Compare commits

...

11 Commits

Author SHA1 Message Date
Daniel Agar 12ba97f4ed EV HGT bias est predict central 2022-11-08 12:13:18 -05:00
Daniel Agar 77042cf6d7 Merge remote-tracking branch 'px4/main' into pr-ekf2_external_vision_control_refactor 2022-11-08 12:10:53 -05:00
Daniel Agar 2ab87d029d increase logging 2022-11-01 21:31:44 -04:00
Daniel Agar 81d622d11b fix EKF2_AID_MASK migration 2022-11-01 10:07:13 -04:00
Daniel Agar 4ffdd2ed63 add protections for EV and flow starting 2022-10-31 17:32:13 -04:00
Daniel Agar 1863641377 [WIP] EV overhaul contd 2022-10-28 10:28:07 -04:00
Daniel Agar 4c22db3b47 ekf2: handle GPS vel/pos timeout in addition to overall reset check
- in a system with good EV + GPS it's possible that horizontal vel/pos
fusion continues successfully, but GPS fusion is failing due to mediocre
yaw alignment
 - GPS always check for yaw failure and act on it if there's
corresponding GPS vel or GPS pos fusion timeout
 - add additional protections to prevent multiple yaw resets/alignments
per update (the controllers won't get the proper heading delta if this
happens)
2022-10-28 10:15:59 -04:00
Daniel Agar 8ab65c84ce ekf2: EV overhaul yaw and position fusion
- new EV position offset estimator
 - yaw_align now strictly means north (no more rotate external vision aid mask)
 - automatically switching between EV yaw, and yaw align north based on
GPS quality
2022-10-28 10:15:17 -04:00
Daniel Agar 7750d610f1 ekf2: update EV height state machine
- respect new EKF2_EV_CTRL parameter for HPOS usage
  - EV hgt rotate EV position before usage (there's often a small offset in frames)
  - EV height reset use proper EV velocity body frame
  - try to keep EV hgt and EV vel state machines consistent
2022-10-28 10:15:03 -04:00
Daniel Agar 897e9f0593 ekf2: move EV vel to new state machine, introduce EKF2_EV_CTRL param 2022-10-28 10:14:49 -04:00
Daniel Agar e52ef945df ekf2: add new EKF2_EV_QMIN parameter 2022-10-28 10:14:44 -04:00
44 changed files with 2072 additions and 1498 deletions
+1
View File
@@ -74,6 +74,7 @@ set(msg_files
EstimatorAidSource2d.msg
EstimatorAidSource3d.msg
EstimatorBias.msg
EstimatorBias3d.msg
EstimatorEventFlags.msg
EstimatorGpsStatus.msg
EstimatorInnovations.msg
+1 -1
View File
@@ -9,4 +9,4 @@ float32 innov # innovation of the last measurement fusion (m)
float32 innov_var # innovation variance of the last measurement fusion (m^2)
float32 innov_test_ratio # normalized innovation squared test ratio
# TOPICS estimator_baro_bias estimator_gnss_hgt_bias estimator_rng_hgt_bias estimator_ev_hgt_bias
# TOPICS estimator_baro_bias estimator_gnss_hgt_bias estimator_rng_hgt_bias
+14
View File
@@ -0,0 +1,14 @@
uint64 timestamp # time since system start (microseconds)
uint64 timestamp_sample # the timestamp of the raw data (microseconds)
uint32 device_id # unique device ID for the sensor that does not change between power cycles
float32[3] bias # estimated barometric altitude bias (m)
float32[3] bias_var # estimated barometric altitude bias variance (m^2)
float32[3] innov # innovation of the last measurement fusion (m)
float32[3] innov_var # innovation variance of the last measurement fusion (m^2)
float32[3] innov_test_ratio # normalized innovation squared test ratio
# TOPICS estimator_bias3d
# TOPICS estimator_ev_pos_bias
+1 -1
View File
@@ -28,4 +28,4 @@ uint8 reset_counter
int8 quality
# TOPICS vehicle_odometry vehicle_mocap_odometry vehicle_visual_odometry
# TOPICS estimator_odometry estimator_visual_odometry_aligned
# TOPICS estimator_odometry
+3
View File
@@ -91,8 +91,11 @@ px4_add_module(
EKF/ekf_helper.cpp
EKF/EKFGSF_yaw.cpp
EKF/estimator_interface.cpp
EKF/ev_control.cpp
EKF/ev_height_control.cpp
EKF/ev_pos_control.cpp
EKF/ev_vel_control.cpp
EKF/ev_yaw_control.cpp
EKF/fake_height_control.cpp
EKF/fake_pos_control.cpp
EKF/gnss_height_control.cpp
+3
View File
@@ -42,8 +42,11 @@ add_library(ecl_EKF
ekf_helper.cpp
EKFGSF_yaw.cpp
estimator_interface.cpp
ev_control.cpp
ev_height_control.cpp
ev_pos_control.cpp
ev_vel_control.cpp
ev_yaw_control.cpp
fake_height_control.cpp
fake_pos_control.cpp
gnss_height_control.cpp
+9 -7
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -57,14 +57,16 @@ class BiasEstimator
{
public:
struct status {
float bias;
float bias_var;
float innov;
float innov_var;
float innov_test_ratio;
float bias{0.f};
float bias_var{0.f};
float innov{0.f};
float innov_var{0.f};
float innov_test_ratio{INFINITY};
};
BiasEstimator() {}
BiasEstimator(float state_init, float state_var_init): _state{state_init}, _state_var{state_var_init} {};
virtual ~BiasEstimator() = default;
void reset()
@@ -107,7 +109,7 @@ private:
float _time_since_last_negative_innov{0.f};
float _time_since_last_positive_innov{0.f};
status _status;
status _status{};
void constrainStateVar();
float computeKalmanGain(float innov_var) const;
+24 -10
View File
@@ -67,7 +67,7 @@ using math::Utilities::updateYawInRotMat;
// maximum sensor intervals in usec
#define BARO_MAX_INTERVAL (uint64_t)2e5 ///< Maximum allowable time interval between pressure altitude measurements (uSec)
#define EV_MAX_INTERVAL (uint64_t)2e5 ///< Maximum allowable time interval between external vision system measurements (uSec)
#define EV_MAX_INTERVAL (uint64_t)1e5 ///< Maximum allowable time interval between external vision system measurements (uSec)
#define GPS_MAX_INTERVAL (uint64_t)5e5 ///< Maximum allowable time interval between GPS measurements (uSec)
#define RNG_MAX_INTERVAL (uint64_t)2e5 ///< Maximum allowable time interval between range finder measurements (uSec)
@@ -78,6 +78,11 @@ using math::Utilities::updateYawInRotMat;
// ground effect compensation
#define GNDEFFECT_TIMEOUT 10E6 ///< Maximum period of time that ground effect protection will be active after it was last turned on (uSec)
enum class PositionFrame : uint8_t {
LOCAL_FRAME_NED = 0,
LOCAL_FRAME_FRD = 1,
};
enum class VelocityFrame : uint8_t {
LOCAL_FRAME_NED = 0,
LOCAL_FRAME_FRD = 1,
@@ -114,6 +119,12 @@ enum HeightSensor : uint8_t {
UNKNOWN = 4
};
enum class PositionSensor : uint8_t {
UNKNOWN = 0,
GNSS = 1,
EV = 2,
};
enum GnssCtrl : uint8_t {
HPOS = (1<<0),
VPOS = (1<<1),
@@ -139,11 +150,11 @@ enum SensorFusionMask : uint16_t {
DEPRECATED_USE_GPS = (1<<0), ///< set to true to use GPS data (DEPRECATED, use gnss_ctrl)
USE_OPT_FLOW = (1<<1), ///< set to true to use optical flow data
INHIBIT_ACC_BIAS = (1<<2), ///< set to true to inhibit estimation of accelerometer delta velocity bias
USE_EXT_VIS_POS = (1<<3), ///< set to true to use external vision position data
USE_EXT_VIS_YAW = (1<<4), ///< set to true to use external vision quaternion data for yaw
DEPRECATED_USE_EXT_VIS_POS = (1<<3), ///< set to true to use external vision position data
DEPRECATED_USE_EXT_VIS_YAW = (1<<4), ///< set to true to use external vision quaternion data for yaw
USE_DRAG = (1<<5), ///< set to true to use the multi-rotor drag model to estimate wind
ROTATE_EXT_VIS = (1<<6), ///< set to true to if the EV observations are in a non NED reference frame and need to be rotated before being used
DEPRECATED_USE_GPS_YAW = (1<<7),///< set to true to use GPS yaw data if available (DEPRECATED, use gnss_ctrl)
DEPRECATED_ROTATE_EXT_VIS = (1<<6), ///< set to true to if the EV observations are in a non NED reference frame and need to be rotated before being used
DEPRECATED_USE_GPS_YAW = (1<<7), ///< set to true to use GPS yaw data if available (DEPRECATED, use gnss_ctrl)
DEPRECATED_USE_EXT_VIS_VEL = (1<<8), ///< set to true to use external vision velocity data
};
@@ -234,9 +245,10 @@ struct extVisionSample {
Vector3f pos{}; ///< XYZ position in external vision's local reference frame (m) - Z must be aligned with down axis
Vector3f vel{}; ///< FRD velocity in reference frame defined in vel_frame variable (m/sec) - Z must be aligned with down axis
Quatf quat{}; ///< quaternion defining rotation from body to earth frame
Vector3f posVar{}; ///< XYZ position variances (m**2)
Vector3f position_var{}; ///< XYZ position variances (m**2)
Vector3f velocity_var{}; ///< XYZ velocity variances ((m/sec)**2)
Vector3f orientation_var{}; ///< orientation variance (rad**2)
PositionFrame pos_frame = PositionFrame::LOCAL_FRAME_FRD;
VelocityFrame vel_frame = VelocityFrame::BODY_FRAME_FRD;
uint8_t reset_counter{};
int8_t quality{}; ///< quality indicator between 0 and 100
@@ -271,6 +283,7 @@ struct parameters {
// measurement source control
int32_t fusion_mode{}; ///< bitmasked integer that selects some aiding sources
int32_t height_sensor_ref{HeightSensor::BARO};
int32_t position_sensor_ref{static_cast<int32_t>(PositionSensor::GNSS)};
int32_t baro_ctrl{1};
int32_t gnss_ctrl{GnssCtrl::HPOS | GnssCtrl::VEL};
int32_t rng_ctrl{RngCtrl::CONDITIONAL};
@@ -313,7 +326,7 @@ struct parameters {
const float initial_wind_uncertainty{1.0f}; ///< 1-sigma initial uncertainty in wind velocity (m/sec)
// position and velocity fusion
float gps_vel_noise{5.0e-1f}; ///< minimum allowed observation noise for gps velocity fusion (m/sec)
float gps_vel_noise{0.5f}; ///< minimum allowed observation noise for gps velocity fusion (m/sec)
float gps_pos_noise{0.5f}; ///< minimum allowed observation noise for gps position fusion (m)
float gps_hgt_bias_nsd{0.13f}; ///< process noise for gnss height bias estimation (m/s/sqrt(Hz))
float pos_noaid_noise{10.0f}; ///< observation noise for non-aiding position fusion (m)
@@ -368,6 +381,7 @@ struct parameters {
// vision position fusion
float ev_vel_noise{0.1f}; ///< minimum allowed observation noise for EV velocity fusion (m/sec)
float ev_pos_noise{0.1f}; ///< minimum allowed observation noise for EV position fusion (m)
float ev_att_noise{0.1f}; ///< minimum allowed observation noise for EV attitude fusion (rad/sec)
int32_t ev_quality_minimum{0}; ///< vision minimum acceptable quality integer
float ev_vel_innov_gate{3.0f}; ///< vision velocity fusion innovation consistency gate size (STD)
@@ -408,11 +422,11 @@ struct parameters {
float acc_bias_learn_gyr_lim{3.0f}; ///< learning is disabled if the magnitude of the IMU angular rate vector is greater than this (rad/sec)
float acc_bias_learn_tc{0.5f}; ///< time constant used to control the decaying envelope filters applied to the accel and gyro magnitudes (sec)
const unsigned reset_timeout_max{7000000}; ///< maximum time we allow horizontal inertial dead reckoning before attempting to reset the states to the measurement or change _control_status if the data is unavailable (uSec)
const unsigned no_aid_timeout_max{1000000}; ///< maximum lapsed time from last fusion of a measurement that constrains horizontal velocity drift before the EKF will determine that the sensor is no longer contributing to aiding (uSec)
const unsigned reset_timeout_max{7'000'000}; ///< maximum time we allow horizontal inertial dead reckoning before attempting to reset the states to the measurement or change _control_status if the data is unavailable (uSec)
const unsigned no_aid_timeout_max{1'000'000}; ///< maximum lapsed time from last fusion of a measurement that constrains horizontal velocity drift before the EKF will determine that the sensor is no longer contributing to aiding (uSec)
const unsigned hgt_fusion_timeout_max{5'000'000}; ///< maximum time we allow height fusion to fail before attempting a reset or stopping the fusion aiding (uSec)
int32_t valid_timeout_max{5000000}; ///< amount of time spent inertial dead reckoning before the estimator reports the state estimates as invalid (uSec)
int32_t valid_timeout_max{5'000'000}; ///< amount of time spent inertial dead reckoning before the estimator reports the state estimates as invalid (uSec)
// static barometer pressure position error coefficient along body axes
float static_pressure_coef_xp{0.0f}; // (-)
+4 -218
View File
@@ -86,10 +86,7 @@ void Ekf::controlFusionModes()
}
if (_gps_buffer) {
_gps_intermittent = !isNewestSampleRecent(_time_last_gps_buffer_push, 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;
_gps_data_ready = _gps_buffer->pop_first_older_than(_imu_sample_delayed.time_us, &_gps_sample_delayed);
if (_gps_data_ready) {
@@ -103,8 +100,6 @@ void Ekf::controlFusionModes()
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_sample_delayed.sacc = fmaxf(_gps_sample_delayed.sacc, _params.gps_vel_noise);
}
}
@@ -161,10 +156,6 @@ void Ekf::controlFusionModes()
}
}
if (_ext_vision_buffer) {
_ev_data_ready = _ext_vision_buffer->pop_first_older_than(_imu_sample_delayed.time_us, &_ev_sample_delayed);
}
if (_airspeed_buffer) {
_tas_data_ready = _airspeed_buffer->pop_first_older_than(_imu_sample_delayed.time_us, &_airspeed_sample_delayed);
}
@@ -181,7 +172,7 @@ void Ekf::controlFusionModes()
controlDragFusion();
controlHeightFusion();
// Additional data odoemtery data from an external estimator can be fused.
// Additional data odometry data from an external estimator can be fused.
controlExternalVisionFusion();
// Additional horizontal velocity data from an auxiliary sensor can be fused
@@ -199,210 +190,6 @@ void Ekf::controlFusionModes()
updateDeadReckoningStatus();
}
void Ekf::controlExternalVisionFusion()
{
// Check for new external vision data
if (_ev_data_ready) {
bool reset = false;
if (_ev_sample_delayed.reset_counter != _ev_sample_delayed_prev.reset_counter) {
reset = true;
}
if (_inhibit_ev_yaw_use) {
stopEvYawFusion();
}
// if the ev data is not in a NED reference frame, then the transformation between EV and EKF navigation frames
// needs to be calculated and the observations rotated into the EKF frame of reference
if ((_params.fusion_mode & SensorFusionMask::ROTATE_EXT_VIS) && ((_params.fusion_mode & SensorFusionMask::USE_EXT_VIS_POS)
|| (_params.ev_ctrl & static_cast<int32_t>(EvCtrl::VEL))) && !_control_status.flags.ev_yaw) {
// rotate EV measurements into the EKF Navigation frame
calcExtVisRotMat();
}
// external vision aiding selection logic
if (_control_status.flags.tilt_align && _control_status.flags.yaw_align) {
// check for a external vision measurement that has fallen behind the fusion time horizon
if (isNewestSampleRecent(_time_last_ext_vision_buffer_push, 2 * EV_MAX_INTERVAL)) {
// turn on use of external vision measurements for position
if (_params.fusion_mode & SensorFusionMask::USE_EXT_VIS_POS && !_control_status.flags.ev_pos) {
startEvPosFusion();
}
}
}
// external vision yaw aiding selection logic
if (!_inhibit_ev_yaw_use && (_params.fusion_mode & SensorFusionMask::USE_EXT_VIS_YAW) && !_control_status.flags.ev_yaw
&& _control_status.flags.tilt_align) {
// don't start using EV data unless data is arriving frequently
if (isNewestSampleRecent(_time_last_ext_vision_buffer_push, 2 * EV_MAX_INTERVAL)) {
if (resetYawToEv()) {
_control_status.flags.yaw_align = true;
startEvYawFusion();
}
}
}
// determine if we should use the horizontal position observations
if (_control_status.flags.ev_pos) {
resetEstimatorAidStatus(_aid_src_ev_pos);
if (reset && _control_status_prev.flags.ev_pos) {
if (!_fuse_hpos_as_odom) {
resetHorizontalPositionToVision();
}
}
Vector3f ev_pos_obs_var;
// correct position and height for offset relative to IMU
const Vector3f pos_offset_body = _params.ev_pos_body - _params.imu_pos_body;
const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
_ev_sample_delayed.pos -= pos_offset_earth;
// Use an incremental position fusion method for EV position data if GPS is also used
if (_params.gnss_ctrl & GnssCtrl::HPOS) {
_fuse_hpos_as_odom = true;
} else {
_fuse_hpos_as_odom = false;
}
if (_fuse_hpos_as_odom) {
if (!_hpos_prev_available) {
// no previous observation available to calculate position change
_hpos_prev_available = true;
} else {
// calculate the change in position since the last measurement
// rotate measurement into body frame is required when fusing with GPS
Vector3f ev_delta_pos = _R_ev_to_ekf * Vector3f(_ev_sample_delayed.pos - _ev_sample_delayed_prev.pos);
// use the change in position since the last measurement
_aid_src_ev_pos.observation[0] = ev_delta_pos(0);
_aid_src_ev_pos.observation[1] = ev_delta_pos(1);
_aid_src_ev_pos.innovation[0] = _state.pos(0) - _hpos_pred_prev(0) - ev_delta_pos(0);
_aid_src_ev_pos.innovation[1] = _state.pos(1) - _hpos_pred_prev(1) - ev_delta_pos(1);
// observation 1-STD error, incremental pos observation is expected to have more uncertainty
Matrix3f ev_pos_var = matrix::diag(_ev_sample_delayed.posVar);
ev_pos_var = _R_ev_to_ekf * ev_pos_var * _R_ev_to_ekf.transpose();
ev_pos_obs_var(0) = fmaxf(ev_pos_var(0, 0), sq(0.5f));
ev_pos_obs_var(1) = fmaxf(ev_pos_var(1, 1), sq(0.5f));
_aid_src_ev_pos.observation_variance[0] = ev_pos_obs_var(0);
_aid_src_ev_pos.observation_variance[1] = ev_pos_obs_var(1);
_aid_src_ev_pos.innovation_variance[0] = P(7, 7) + _aid_src_ev_pos.observation_variance[0];
_aid_src_ev_pos.innovation_variance[1] = P(8, 8) + _aid_src_ev_pos.observation_variance[1];
}
} else {
// use the absolute position
Vector3f ev_pos_meas = _ev_sample_delayed.pos;
Matrix3f ev_pos_var = matrix::diag(_ev_sample_delayed.posVar);
if (_params.fusion_mode & SensorFusionMask::ROTATE_EXT_VIS) {
ev_pos_meas = _R_ev_to_ekf * ev_pos_meas;
ev_pos_var = _R_ev_to_ekf * ev_pos_var * _R_ev_to_ekf.transpose();
}
_aid_src_ev_pos.observation[0] = ev_pos_meas(0);
_aid_src_ev_pos.observation[1] = ev_pos_meas(1);
_aid_src_ev_pos.observation_variance[0] = fmaxf(ev_pos_var(0, 0), sq(0.01f));
_aid_src_ev_pos.observation_variance[1] = fmaxf(ev_pos_var(1, 1), sq(0.01f));
_aid_src_ev_pos.innovation[0] = _state.pos(0) - _aid_src_ev_pos.observation[0];
_aid_src_ev_pos.innovation[1] = _state.pos(1) - _aid_src_ev_pos.observation[1];
_aid_src_ev_pos.innovation_variance[0] = P(7, 7) + _aid_src_ev_pos.observation_variance[0];
_aid_src_ev_pos.innovation_variance[1] = P(8, 8) + _aid_src_ev_pos.observation_variance[1];
// check if we have been deadreckoning too long
if (isTimedOut(_time_last_hor_pos_fuse, _params.reset_timeout_max)) {
resetHorizontalPositionToVision();
}
}
// innovation gate size
const float ev_pos_innov_gate = fmaxf(_params.ev_pos_innov_gate, 1.0f);
setEstimatorAidStatusTestRatio(_aid_src_ev_pos, ev_pos_innov_gate);
_aid_src_ev_pos.timestamp_sample = _ev_sample_delayed.time_us;
_aid_src_ev_pos.fusion_enabled = true;
fuseHorizontalPosition(_aid_src_ev_pos);
}
// determine if we should use the yaw observation
resetEstimatorAidStatus(_aid_src_ev_yaw);
const float measured_hdg = getEulerYaw(_ev_sample_delayed.quat);
const float ev_yaw_obs_var = fmaxf(_ev_sample_delayed.orientation_var(2), 1.e-4f);
if (PX4_ISFINITE(measured_hdg)) {
_aid_src_ev_yaw.timestamp_sample = _ev_sample_delayed.time_us;
_aid_src_ev_yaw.observation = measured_hdg;
_aid_src_ev_yaw.observation_variance = ev_yaw_obs_var;
_aid_src_ev_yaw.fusion_enabled = _control_status.flags.ev_yaw;
if (_control_status.flags.ev_yaw) {
if (reset && _control_status_prev.flags.ev_yaw) {
resetYawToEv();
}
const float innovation = wrap_pi(getEulerYaw(_R_to_earth) - measured_hdg);
fuseYaw(innovation, ev_yaw_obs_var, _aid_src_ev_yaw);
} else {
// populate estimator_aid_src_ev_yaw with delta heading innovations for logging
// use the change in yaw since the last measurement
const float measured_hdg_prev = getEulerYaw(_ev_sample_delayed_prev.quat);
// calculate the change in yaw since the last measurement
const float ev_delta_yaw = wrap_pi(measured_hdg - measured_hdg_prev);
_aid_src_ev_yaw.innovation = wrap_pi(getEulerYaw(_R_to_earth) - _yaw_pred_prev - ev_delta_yaw);
}
}
bool ev_reset = (_ev_sample_delayed.reset_counter != _ev_sample_delayed_prev.reset_counter);
// determine if we should use the horizontal position observations
bool quality_sufficient = (_params.ev_quality_minimum <= 0) || (_ev_sample_delayed.quality >= _params.ev_quality_minimum);
bool starting_conditions_passing = quality_sufficient
&& ((_ev_sample_delayed.time_us - _ev_sample_delayed_prev.time_us) < EV_MAX_INTERVAL)
&& ((_params.ev_quality_minimum <= 0) || (_ev_sample_delayed_prev.quality >= _params.ev_quality_minimum)) // previous quality sufficient
&& ((_params.ev_quality_minimum <= 0) || (_ext_vision_buffer->get_newest().quality >= _params.ev_quality_minimum)) // newest quality sufficient
&& isNewestSampleRecent(_time_last_ext_vision_buffer_push, EV_MAX_INTERVAL);
// EV velocity
controlEvVelFusion(_ev_sample_delayed, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_vel);
// record observation and estimate for use next time
_ev_sample_delayed_prev = _ev_sample_delayed;
_hpos_pred_prev = _state.pos.xy();
_yaw_pred_prev = getEulerYaw(_state.quat_nominal);
} else if ((_control_status.flags.ev_pos || _control_status.flags.ev_vel || _control_status.flags.ev_yaw)
&& !isRecent(_ev_sample_delayed.time_us, (uint64_t)_params.reset_timeout_max)) {
// Turn off EV fusion mode if no data has been received
stopEvFusion();
_warning_events.flags.vision_data_stopped = true;
ECL_WARN("vision data stopped");
}
}
void Ekf::controlGpsYawFusion(const gpsSample &gps_sample, bool gps_checks_passing, bool gps_checks_failing)
{
if (!(_params.gnss_ctrl & GnssCtrl::YAW)
@@ -418,13 +205,14 @@ void Ekf::controlGpsYawFusion(const gpsSample &gps_sample, bool gps_checks_passi
const bool continuing_conditions_passing = !gps_checks_failing;
const bool gps_intermittent = !isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GPS_MAX_INTERVAL);
const bool is_gps_yaw_data_intermittent = !isNewestSampleRecent(_time_last_gps_yaw_buffer_push, 2 * GPS_MAX_INTERVAL);
const bool starting_conditions_passing = continuing_conditions_passing
&& _control_status.flags.tilt_align
&& gps_checks_passing
&& !is_gps_yaw_data_intermittent
&& !_gps_intermittent;
&& !gps_intermittent;
if (_control_status.flags.gps_yaw) {
@@ -576,16 +364,14 @@ void Ekf::controlBetaFusion()
void Ekf::controlDragFusion()
{
if ((_params.fusion_mode & SensorFusionMask::USE_DRAG) && _drag_buffer &&
!_control_status.flags.fake_pos && _control_status.flags.in_air && !_mag_inhibit_yaw_reset_req) {
!_control_status.flags.fake_pos && _control_status.flags.in_air) {
if (!_control_status.flags.wind) {
// reset the wind states and covariances when starting drag accel fusion
_control_status.flags.wind = true;
resetWind();
}
dragSample drag_sample;
if (_drag_buffer->pop_first_older_than(_imu_sample_delayed.time_us, &drag_sample)) {
-2
View File
@@ -204,8 +204,6 @@ bool Ekf::initialiseFilter()
_time_last_hgt_fuse = _imu_sample_delayed.time_us;
_time_last_hor_pos_fuse = _imu_sample_delayed.time_us;
_time_last_hor_vel_fuse = _imu_sample_delayed.time_us;
_time_last_hagl_fuse = _imu_sample_delayed.time_us;
_time_last_flow_terrain_fuse = _imu_sample_delayed.time_us;
// reset the output predictor state history to match the EKF initial values
alignOutputFilter();
+18 -34
View File
@@ -48,6 +48,7 @@
#include "EKFGSF_yaw.h"
#include "bias_estimator.hpp"
#include "height_bias_estimator.hpp"
#include "position_bias_estimator.hpp"
#include <uORB/topics/estimator_aid_source1d.h>
#include <uORB/topics/estimator_aid_source2d.h>
@@ -385,9 +386,6 @@ public:
// return a bitmask integer that describes which state estimates can be used for flight control
void get_ekf_soln_status(uint16_t *status) const;
// return the quaternion defining the rotation from the External Vision to the EKF reference frame
matrix::Quatf getVisionAlignmentQuaternion() const { return Quatf(_R_ev_to_ekf); };
// use the latest IMU data at the current time horizon.
Quatf calculate_quaternion() const;
@@ -413,6 +411,8 @@ public:
const BiasEstimator::status &getRngHgtBiasEstimatorStatus() const { return _rng_hgt_b_est.getStatus(); }
const BiasEstimator::status &getEvHgtBiasEstimatorStatus() const { return _ev_hgt_b_est.getStatus(); }
const BiasEstimator::status &getEvPosBiasEstimatorStatus(int i) const { return _ev_pos_b_est.getStatus(i); }
const auto &aid_src_airspeed() const { return _aid_src_airspeed; }
const auto &aid_src_sideslip() const { return _aid_src_sideslip; }
@@ -472,23 +472,18 @@ private:
bool _filter_initialised{false}; ///< true when the EKF sttes and covariances been initialised
// variables used when position data is being fused using a relative position odometry model
bool _fuse_hpos_as_odom{false}; ///< true when the NE position data is being fused using an odometry assumption
Vector2f _hpos_pred_prev{}; ///< previous value of NE position state used by odometry fusion (m)
float _yaw_pred_prev{}; ///< previous value of yaw state used by odometry fusion (m)
bool _hpos_prev_available{false}; ///< true when previous values of the estimate and measurement are available for use
Dcmf _R_ev_to_ekf; ///< transformation matrix that rotates observations from the EV to the EKF navigation frame, initialized with Identity
bool _inhibit_ev_yaw_use{false}; ///< true when the vision yaw data should not be used (e.g.: NE fusion requires true North)
// booleans true when fresh sensor data is available at the fusion time horizon
bool _gps_data_ready{false}; ///< true when new GPS data has fallen behind the fusion time horizon and is available to be fused
bool _rng_data_ready{false};
bool _flow_data_ready{false}; ///< true when the leading edge of the optical flow integration period has fallen behind the fusion time horizon
bool _ev_data_ready{false}; ///< true when new external vision system data has fallen behind the fusion time horizon and is available to be fused
bool _tas_data_ready{false}; ///< true when new true airspeed data has fallen behind the fusion time horizon and is available to be fused
bool _flow_for_terrain_data_ready{false}; /// same flag as "_flow_data_ready" but used for separate terrain estimator
uint64_t _time_prev_gps_us{0}; ///< time stamp of previous GPS data retrieved from the buffer (uSec)
uint64_t _time_last_horizontal_aiding{0}; ///< amount of time we have been doing inertial only deadreckoning (uSec)
uint64_t _time_last_v_pos_aiding{0};
uint64_t _time_last_v_vel_aiding{0};
@@ -504,7 +499,9 @@ private:
uint64_t _time_last_healthy_rng_data{0};
uint8_t _nb_gps_yaw_reset_available{0}; ///< remaining number of resets allowed before switching to another aiding source
uint8_t _nb_ev_pos_reset_available{0};
uint8_t _nb_ev_vel_reset_available{0};
uint8_t _nb_ev_yaw_reset_available{0};
Vector3f _last_known_pos{}; ///< last known local position vector (m)
@@ -521,14 +518,10 @@ private:
bool _mag_bias_observable{false}; ///< true when there is enough rotation to make magnetometer bias errors observable
bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable
uint64_t _time_yaw_started{0}; ///< last system time in usec that a yaw rotation manoeuvre was detected
uint64_t _mag_use_not_inhibit_us{0}; ///< last system time in usec before magnetometer use was inhibited
float _last_static_yaw{NAN}; ///< last yaw angle recorded when on ground motion checks were passing (rad)
bool _mag_inhibit_yaw_reset_req{false}; ///< true when magnetometer inhibit has been active for long enough to require a yaw reset when conditions improve.
bool _mag_yaw_reset_req{false}; ///< true when a reset of the yaw using the magnetometer data has been requested
bool _mag_decl_cov_reset{false}; ///< true after the fuseDeclination() function has been used to modify the earth field covariances after a magnetic field reset event.
bool _synthetic_mag_z_active{false}; ///< true if we are generating synthetic magnetometer Z measurements
bool _is_yaw_fusion_inhibited{false}; ///< true when yaw sensor use is being inhibited
SquareMatrix24f P{}; ///< state covariance matrix
@@ -597,6 +590,9 @@ private:
// Variables used to publish the WGS-84 location of the EKF local NED origin
float _gps_alt_ref{NAN}; ///< WGS-84 height (m)
uint64_t _last_ev_fail_us{0}; ///< last system time in usec that the EV failed it's checks
uint64_t _last_ev_pass_us{0}; ///< last system time in usec that the EV passed it's checks
// Variables used by the initial filter alignment
bool _is_first_imu_sample{true};
uint32_t _baro_counter{0}; ///< number of baro samples read during initialisation
@@ -635,7 +631,6 @@ private:
// height sensor status
bool _baro_hgt_faulty{false}; ///< true if baro data have been declared faulty TODO: move to fault flags
bool _gps_intermittent{true}; ///< true if data into the buffer is intermittent
// imu fault status
uint64_t _time_bad_vert_accel{0}; ///< last time a bad vertical accel was detected (uSec)
@@ -705,7 +700,6 @@ private:
void resetHorizontalVelocityToZero();
void resetVerticalVelocityTo(float new_vert_vel, float new_vert_vel_var);
void resetHorizontalPositionToVision();
void resetHorizontalPositionToLastKnown();
void resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f &new_horz_pos_var);
@@ -772,19 +766,12 @@ private:
// return true if successful
bool resetMagHeading();
// reset the heading using the external vision measurements
// return true if successful
bool resetYawToEv();
// Return the magnetic declination in radians to be used by the alignment and fusion processing
float getMagDeclination();
// modify output filter to match the the EKF state at the fusion time horizon
void alignOutputFilter();
// update the rotation matrix which transforms EV navigation frame measurements into NED
void calcExtVisRotMat();
// matrix vector multiplication for computing K<24,1> * H<1,24> * P<24,24>
// that is optimized by exploring the sparsity in H
template <size_t ...Idxs>
@@ -869,7 +856,10 @@ private:
// control fusion of external vision observations
void controlExternalVisionFusion();
void controlEvHeightFusion(const extVisionSample &ev_sample, bool starting_conditions_passing, bool ev_reset, bool quality_sufficient, estimator_aid_source1d_s& aid_src);
void controlEvPosFusion(const extVisionSample &ev_sample, bool starting_conditions_passing, bool ev_reset, bool quality_sufficient, estimator_aid_source2d_s& aid_src);
void controlEvVelFusion(const extVisionSample &ev_sample, bool starting_conditions_passing, bool ev_reset, bool quality_sufficient, estimator_aid_source3d_s& aid_src);
void controlEvYawFusion(const extVisionSample &ev_sample, bool starting_conditions_passing, bool ev_reset, bool quality_sufficient, estimator_aid_source1d_s& aid_src);
// control fusion of optical flow observations
void controlOpticalFlowFusion();
@@ -887,12 +877,12 @@ private:
// control fusion of magnetometer observations
void controlMagFusion();
void checkHaglYawResetReq();
bool haglYawResetReq() const;
float getTerrainVPos() const { return isTerrainEstimateValid() ? _terrain_vpos : _last_on_ground_posD; }
void runOnGroundYawReset();
bool canResetMagHeading() const;
void runInAirYawReset();
void runYawReset();
bool resetMagStates();
void selectMagAuto();
void check3DMagFusionSuitability();
@@ -901,7 +891,6 @@ private:
bool canUse3DMagFusion() const;
void checkMagDeclRequired();
void checkMagInhibition();
bool shouldInhibitMag() const;
bool magFieldStrengthDisturbed(const Vector3f &mag) const;
static bool isMeasuredMatchingExpected(float measured, float expected, float gate);
@@ -941,7 +930,6 @@ private:
void controlBaroHeightFusion();
void controlGnssHeightFusion(const gpsSample &gps_sample);
void controlRangeHeightFusion();
void controlEvHeightFusion(const extVisionSample &ev_sample);
bool isConditionalRangeAidSuitable();
@@ -1024,16 +1012,10 @@ private:
void stopAirspeedFusion();
void stopGpsFusion();
void stopGpsPosFusion();
void stopGpsVelFusion();
void startGpsYawFusion(const gpsSample &gps_sample);
void stopGpsYawFusion();
void startEvPosFusion();
void startEvYawFusion();
void stopEvFusion();
void stopEvPosFusion();
void stopEvVelFusion();
void stopEvYawFusion();
@@ -1058,14 +1040,16 @@ private:
EKFGSF_yaw _yawEstimator{};
uint8_t _height_sensor_ref{HeightSensor::UNKNOWN};
uint8_t _position_sensor_ref{static_cast<uint8_t>(PositionSensor::GNSS)};
HeightBiasEstimator _baro_b_est{HeightSensor::BARO, _height_sensor_ref};
HeightBiasEstimator _gps_hgt_b_est{HeightSensor::GNSS, _height_sensor_ref};
HeightBiasEstimator _rng_hgt_b_est{HeightSensor::RANGE, _height_sensor_ref};
HeightBiasEstimator _ev_hgt_b_est{HeightSensor::EV, _height_sensor_ref};
PositionBiasEstimator _ev_pos_b_est{static_cast<uint8_t>(PositionSensor::EV), _position_sensor_ref};
int64_t _ekfgsf_yaw_reset_time{0}; ///< timestamp of last emergency yaw reset (uSec)
uint8_t _ekfgsf_yaw_reset_count{0}; // number of times the yaw has been reset to the EKF-GSF estimate
uint8_t _ekfgsf_yaw_reset_count{0}; // number of times the yaw has been reset to the EKF-GSF estimate in an emergency
void runYawEKFGSF();
+37 -126
View File
@@ -108,22 +108,6 @@ void Ekf::resetVerticalVelocityTo(float new_vert_vel, float new_vert_vel_var)
_time_last_ver_vel_fuse = _imu_sample_delayed.time_us;
}
void Ekf::resetHorizontalPositionToVision()
{
_information_events.flags.reset_pos_to_vision = true;
ECL_INFO("reset position to ev position");
Vector3f _ev_pos = _ev_sample_delayed.pos;
if (_params.fusion_mode & SensorFusionMask::ROTATE_EXT_VIS) {
_ev_pos = _R_ev_to_ekf * _ev_sample_delayed.pos;
}
resetHorizontalPositionTo(Vector2f(_ev_pos), _ev_sample_delayed.posVar.slice<2, 1>(0, 0));
// let the next odometry update know that the previous value of states cannot be used to calculate the change in position
_hpos_prev_available = false;
}
void Ekf::resetHorizontalPositionToLastKnown()
{
_information_events.flags.reset_pos_to_last_known = true;
@@ -154,6 +138,9 @@ void Ekf::resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f
_state_reset_status.posNE_change = delta_horz_pos;
_state_reset_status.posNE_counter++;
_ev_pos_b_est.setBias(_ev_pos_b_est.getBias() - _state_reset_status.posNE_change);
//_gps_pos_b_est.setBias(_gps_pos_b_est.getBias() + _state_reset_status.posNE_change);
// Reset the timout timer
_time_last_hor_pos_fuse = _imu_sample_delayed.time_us;
}
@@ -169,7 +156,6 @@ bool Ekf::isHeightResetRequired() const
return (continuous_bad_accel_hgt || hgt_fusion_timeout);
}
void Ekf::resetVerticalPositionTo(const float new_vert_pos, float new_vert_pos_var)
{
const float old_vert_pos = _state.pos(2);
@@ -242,8 +228,8 @@ void Ekf::alignOutputFilter()
bool Ekf::resetMagHeading()
{
// prevent a reset being performed more than once on the same frame
if (_imu_sample_delayed.time_us == _flt_mag_align_start_time) {
return true;
if ((_flt_mag_align_start_time == _imu_sample_delayed.time_us) || (_control_status_prev.flags.yaw_align != _control_status.flags.yaw_align)) {
return false;
}
const Vector3f mag_init = _mag_lpf.getState();
@@ -287,17 +273,6 @@ bool Ekf::resetMagHeading()
return false;
}
bool Ekf::resetYawToEv()
{
const float yaw_new = getEulerYaw(_ev_sample_delayed.quat);
const float yaw_new_variance = fmaxf(_ev_sample_delayed.orientation_var(2), sq(1.0e-2f));
resetQuatStateYaw(yaw_new, yaw_new_variance);
_R_ev_to_ekf.setIdentity();
return true;
}
// Return the magnetic declination in radians to be used by the alignment and fusion processing
float Ekf::getMagDeclination()
{
@@ -715,7 +690,7 @@ void Ekf::resetMagBiasAndYaw()
_saved_mag_bf_variance.zero();
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
_mag_yaw_reset_req = true;
stopMagFusion();
}
_control_status.flags.mag_fault = false;
@@ -743,6 +718,7 @@ void Ekf::get_innovation_test_status(uint16_t &status, float &mag, float &vel, f
} else if (_control_status.flags.gps_yaw) {
mag = sqrtf(_aid_src_gnss_yaw.test_ratio);
} else {
mag = NAN;
}
@@ -1077,9 +1053,12 @@ void Ekf::initialiseQuatCovariances(Vector3f &rot_vec_var)
void Ekf::stopMagFusion()
{
stopMag3DFusion();
stopMagHdgFusion();
clearMagCov();
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
ECL_INFO("stopping all mag fusion");
stopMag3DFusion();
stopMagHdgFusion();
clearMagCov();
}
}
void Ekf::stopMag3DFusion()
@@ -1149,14 +1128,6 @@ void Ekf::updateGroundEffect()
}
}
// update the rotation matrix which rotates EV measurements into the EKF's navigation frame
void Ekf::calcExtVisRotMat()
{
// Calculate the quaternion delta that rotates from the EV to the EKF reference frame at the EKF fusion time horizon.
const Quatf q_error((_state.quat_nominal * _ev_sample_delayed.quat.inversed()).normalized());
_R_ev_to_ekf = Dcmf(q_error);
}
// Increase the yaw error variance of the quaternions
// Argument is additional yaw variance in rad**2
void Ekf::increaseQuatYawErrVariance(float yaw_variance)
@@ -1249,8 +1220,10 @@ void Ekf::stopAirspeedFusion()
void Ekf::stopGpsFusion()
{
if (_control_status.flags.gps) {
stopGpsPosFusion();
stopGpsVelFusion();
ECL_INFO("stopping GPS position and velocity fusion");
resetEstimatorAidStatus(_aid_src_gnss_pos);
resetEstimatorAidStatus(_aid_src_gnss_vel);
_control_status.flags.gps = false;
}
@@ -1264,23 +1237,6 @@ void Ekf::stopGpsFusion()
_inhibit_ev_yaw_use = false;
}
void Ekf::stopGpsPosFusion()
{
if (_control_status.flags.gps) {
ECL_INFO("stopping GPS position fusion");
_control_status.flags.gps = false;
resetEstimatorAidStatus(_aid_src_gnss_pos);
}
}
void Ekf::stopGpsVelFusion()
{
ECL_INFO("stopping GPS velocity fusion");
resetEstimatorAidStatus(_aid_src_gnss_vel);
}
void Ekf::startGpsYawFusion(const gpsSample &gps_sample)
{
if (!_control_status.flags.gps_yaw && resetYawToGps(gps_sample.yaw)) {
@@ -1303,51 +1259,6 @@ void Ekf::stopGpsYawFusion()
}
}
void Ekf::startEvPosFusion()
{
_control_status.flags.ev_pos = true;
resetHorizontalPositionToVision();
_information_events.flags.starting_vision_pos_fusion = true;
ECL_INFO("starting vision pos fusion");
}
void Ekf::startEvYawFusion()
{
// turn on fusion of external vision yaw measurements and disable all magnetometer fusion
_control_status.flags.ev_yaw = true;
_control_status.flags.mag_dec = false;
stopMagHdgFusion();
stopMag3DFusion();
_information_events.flags.starting_vision_yaw_fusion = true;
ECL_INFO("starting vision yaw fusion");
}
void Ekf::stopEvFusion()
{
stopEvPosFusion();
stopEvVelFusion();
stopEvYawFusion();
}
void Ekf::stopEvPosFusion()
{
if (_control_status.flags.ev_pos) {
ECL_INFO("stopping EV pos fusion");
_control_status.flags.ev_pos = false;
resetEstimatorAidStatus(_aid_src_ev_pos);
}
}
void Ekf::stopEvYawFusion()
{
if (_control_status.flags.ev_yaw) {
ECL_INFO("stopping EV yaw fusion");
_control_status.flags.ev_yaw = false;
}
}
void Ekf::stopAuxVelFusion()
{
ECL_INFO("stopping aux vel fusion");
@@ -1410,32 +1321,27 @@ void Ekf::resetQuatStateYaw(float yaw, float yaw_variance)
// Returns true if the reset was successful
bool Ekf::resetYawToEKFGSF()
{
if (!isYawEmergencyEstimateAvailable()) {
if (!isYawEmergencyEstimateAvailable() || !isTimedOut(_ekfgsf_yaw_reset_time, 5'000'000)) {
return false;
}
resetQuatStateYaw(_yawEstimator.getYaw(), _yawEstimator.getYawVar());
// record a magnetic field alignment event to prevent possibility of the EKF trying to reset the yaw to the mag later in flight
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
_control_status.flags.yaw_align = true;
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
// stop using the magnetometer in the main EKF otherwise it's fusion could drag the yaw around
// and cause another navigation failure
_control_status.flags.mag_fault = true;
_warning_events.flags.emergency_yaw_reset_mag_stopped = true;
} else if (_control_status.flags.gps_yaw) {
_control_status.flags.gps_yaw_fault = true;
_warning_events.flags.emergency_yaw_reset_gps_yaw_stopped = true;
} else if (_control_status.flags.ev_yaw) {
_inhibit_ev_yaw_use = true;
// prevent a reset being performed more than once on the same frame
if ((_flt_mag_align_start_time == _imu_sample_delayed.time_us) || (_control_status_prev.flags.yaw_align != _control_status.flags.yaw_align)) {
return false;
}
// otherwise reset yaw
resetQuatStateYaw(_yawEstimator.getYaw(), _yawEstimator.getYawVar());
_information_events.flags.yaw_aligned_to_imu_gps = true;
ECL_INFO("Yaw aligned using IMU and GPS");
_control_status.flags.yaw_align = true;
_ekfgsf_yaw_reset_time = _imu_sample_delayed.time_us;
_ekfgsf_yaw_reset_count++;
// reset mag states
resetMagStates();
return true;
}
@@ -1472,6 +1378,11 @@ void Ekf::runYawEKFGSF()
const Vector3f imu_gyro_bias = getGyroBias();
_yawEstimator.update(_imu_sample_delayed, _control_status.flags.in_air, TAS, imu_gyro_bias);
// reset when landed
if (!_control_status.flags.in_air) {
_ekfgsf_yaw_reset_count = 0;
}
}
void Ekf::resetGpsDriftCheckFilters()
+1 -1
View File
@@ -496,7 +496,7 @@ bool EstimatorInterface::initialise_interface(uint64_t timestamp)
max_time_delay_ms = math::max(_params.flow_delay_ms, max_time_delay_ms);
}
if ((_params.fusion_mode & (SensorFusionMask::USE_EXT_VIS_POS | SensorFusionMask::USE_EXT_VIS_YAW)) || (_params.ev_ctrl & static_cast<int32_t>(EvCtrl::VEL))) {
if (_params.ev_ctrl > 0) {
max_time_delay_ms = math::max(_params.ev_delay_ms, max_time_delay_ms);
}
+5 -7
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2015-2020 Estimation and Control Library (ECL). All rights reserved.
* Copyright (c) 2015-2022 Estimation and Control Library (ECL). All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -44,9 +44,9 @@
#if defined(MODULE_NAME)
#include <px4_platform_common/log.h>
# define ECL_INFO PX4_DEBUG
# define ECL_WARN PX4_DEBUG
# define ECL_ERR PX4_DEBUG
# define ECL_INFO PX4_INFO // TODO
# define ECL_WARN PX4_WARN // TODO
# define ECL_ERR PX4_ERR // TODO
# define ECL_DEBUG PX4_DEBUG
#else
# define ECL_INFO(X, ...) printf(X "\n", ##__VA_ARGS__)
@@ -256,7 +256,6 @@ public:
const gpsSample &get_gps_sample_delayed() const { return _gps_sample_delayed; }
const rangeSample &get_rng_sample_delayed() { return *(_range_sensor.getSampleAddress()); }
const extVisionSample &get_ev_sample_delayed() const { return _ev_sample_delayed; }
const bool &global_origin_valid() const { return _NED_origin_initialised; }
const MapProjection &global_origin() const { return _pos_ref; }
@@ -303,8 +302,7 @@ protected:
sensor::SensorRangeFinder _range_sensor{};
airspeedSample _airspeed_sample_delayed{};
flowSample _flow_sample_delayed{};
extVisionSample _ev_sample_delayed{};
extVisionSample _ev_sample_delayed_prev{};
extVisionSample _ev_sample_prev{};
dragSample _drag_down_sampled{}; // down sampled drag specific force data (filter prediction rate -> observation rate)
RangeFinderConsistencyCheck _rng_consistency_check;
+97
View File
@@ -0,0 +1,97 @@
/****************************************************************************
*
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ev_control.cpp
* Control functions for ekf external vision control
*/
#include "ekf.h"
void Ekf::controlExternalVisionFusion()
{
_ev_pos_b_est.predict(_dt_ekf_avg);
_ev_hgt_b_est.predict(_dt_ekf_avg);
// Check for new external vision data
extVisionSample ev_sample;
if (_ext_vision_buffer && _ext_vision_buffer->pop_first_older_than(_imu_sample_delayed.time_us, &ev_sample)) {
bool ev_reset = (ev_sample.reset_counter != _ev_sample_prev.reset_counter);
// determine if we should use the horizontal position observations
bool quality_sufficient = (_params.ev_quality_minimum <= 0) || (ev_sample.quality >= _params.ev_quality_minimum);
if (quality_sufficient) {
_last_ev_pass_us = _imu_sample_delayed.time_us;
} else {
_last_ev_fail_us = _imu_sample_delayed.time_us;
}
const bool ev_quality_passing = isTimedOut(_last_ev_fail_us, (uint64_t)1e6);
const bool ev_quality_failing = isTimedOut(_last_ev_pass_us, (uint64_t)1e6);
bool starting_conditions_passing = quality_sufficient
&& ev_quality_passing
&& !ev_quality_failing
&& !ev_reset
&& ((ev_sample.time_us - _ev_sample_prev.time_us) < EV_MAX_INTERVAL)
&& ((_params.ev_quality_minimum <= 0) || (_ev_sample_prev.quality >= _params.ev_quality_minimum)) // previous quality sufficient
&& isNewestSampleRecent(_time_last_ext_vision_buffer_push, EV_MAX_INTERVAL);
controlEvYawFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_yaw);
controlEvVelFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_vel);
controlEvPosFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_pos);
controlEvHeightFusion(ev_sample, starting_conditions_passing, ev_reset, quality_sufficient, _aid_src_ev_hgt);
if (quality_sufficient) {
_ev_sample_prev = ev_sample;
_yaw_pred_prev = getEulerYaw(_state.quat_nominal);
}
} else if ((_control_status.flags.ev_pos || _control_status.flags.ev_vel || _control_status.flags.ev_yaw
|| _control_status.flags.ev_hgt)
&& isTimedOut(_ev_sample_prev.time_us, 2 * EV_MAX_INTERVAL)) {
// Turn off EV fusion mode if no data has been received
stopEvPosFusion();
stopEvVelFusion();
stopEvYawFusion();
stopEvHgtFusion();
_warning_events.flags.vision_data_stopped = true;
ECL_WARN("vision data stopped");
}
}
+127 -93
View File
@@ -38,94 +38,80 @@
#include "ekf.h"
void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample)
void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample, bool starting_conditions_passing, bool ev_reset,
bool quality_sufficient, estimator_aid_source1d_s &aid_src)
{
static constexpr const char *HGT_SRC_NAME = "EV";
static constexpr const char *AID_SRC_NAME = "EV height";
auto &aid_src = _aid_src_ev_hgt;
HeightBiasEstimator &bias_est = _ev_hgt_b_est;
//bias_est.predict(_dt_ekf_avg); // handled by controlExternalVisionFusion()
bias_est.predict(_dt_ekf_avg);
// correct position for offset relative to IMU
const Vector3f pos_offset_body = _params.ev_pos_body - _params.imu_pos_body;
const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
if (_ev_data_ready) {
// rotate measurement into correct earth frame if required
Vector3f pos{ev_sample.pos};
Matrix3f pos_cov{matrix::diag(ev_sample.position_var)};
const float measurement = ev_sample.pos(2);
const float measurement_var = ev_sample.posVar(2);
// rotate EV to the EKF reference frame unless we're operating entirely in vision frame
// TODO: only necessary if there's a roll/pitch offset between VIO and EKF
if (!(_control_status.flags.ev_yaw && _control_status.flags.ev_pos)) {
const float innov_gate = math::max(_params.ev_pos_innov_gate, 1.f);
const Quatf q_error((_state.quat_nominal * ev_sample.quat.inversed()).normalized());
const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var);
if (q_error.isAllFinite()) {
const Dcmf R_ev_to_ekf(q_error);
updateVerticalPositionAidSrcStatus(ev_sample.time_us,
measurement - bias_est.getBias(),
measurement_var + bias_est.getBiasVar(),
innov_gate,
aid_src);
pos = R_ev_to_ekf * ev_sample.pos;
pos_cov = R_ev_to_ekf * matrix::diag(ev_sample.position_var) * R_ev_to_ekf.transpose();
// update the bias estimator before updating the main filter but after
// using its current state to compute the vertical position innovation
if (measurement_valid) {
bias_est.setMaxStateNoise(sqrtf(measurement_var));
bias_est.setProcessNoiseSpectralDensity(_params.ev_hgt_bias_nsd);
bias_est.fuseBias(measurement - _state.pos(2), measurement_var + P(9, 9));
// increase minimum variance to include EV orientation variance
// TODO: do this properly
const float orientation_var_max = math::max(ev_sample.orientation_var(0), ev_sample.orientation_var(1));
pos_cov(2, 2) = math::max(pos_cov(2, 2), orientation_var_max);
}
}
const bool continuing_conditions_passing = ((_params.fusion_mode & SensorFusionMask::USE_EXT_VIS_POS) || (_params.height_sensor_ref == HeightSensor::EV)) // TODO: (_params.ev_ctrl & EvCtrl::VPOS)
&& measurement_valid;
const float measurement = pos(2) - pos_offset_earth(2);
float measurement_var = math::max(pos_cov(2, 2), sq(_params.ev_pos_noise), sq(0.01f));
const bool starting_conditions_passing = continuing_conditions_passing
&& isNewestSampleRecent(_time_last_ext_vision_buffer_push, 2 * EV_MAX_INTERVAL);
// increase minimum variance if GPS active
if (_control_status.flags.gps_hgt) {
measurement_var = math::max(measurement_var, sq(_params.gps_pos_noise));
}
if (_control_status.flags.ev_hgt) {
aid_src.fusion_enabled = true;
const bool measurement_valid = PX4_ISFINITE(measurement) && PX4_ISFINITE(measurement_var);
if (continuing_conditions_passing) {
updateVerticalPositionAidSrcStatus(ev_sample.time_us,
measurement - bias_est.getBias(),
measurement_var + bias_est.getBiasVar(),
math::max(_params.ev_pos_innov_gate, 1.f),
aid_src);
fuseVerticalPosition(aid_src);
// update the bias estimator before updating the main filter but after
// using its current state to compute the vertical position innovation
if (measurement_valid && quality_sufficient) {
bias_est.setMaxStateNoise(sqrtf(measurement_var));
bias_est.setProcessNoiseSpectralDensity(_params.ev_hgt_bias_nsd);
bias_est.fuseBias(measurement - _state.pos(2), measurement_var + P(9, 9));
}
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max);
const bool continuing_conditions_passing = ((_params.ev_ctrl & static_cast<int32_t>(EvCtrl::VPOS))
|| (_params.height_sensor_ref == HeightSensor::EV))
&& measurement_valid;
if (isHeightResetRequired()) {
// All height sources are failing
ECL_WARN("%s height fusion reset required, all height sources failing", HGT_SRC_NAME);
starting_conditions_passing &= continuing_conditions_passing;
_information_events.flags.reset_hgt_to_ev = true;
resetVerticalPositionTo(measurement - bias_est.getBias(), measurement_var);
bias_est.setBias(-_state.pos(2) + measurement);
if (_control_status.flags.ev_hgt) {
aid_src.fusion_enabled = true;
// reset vertical velocity
if (ev_sample.vel.isAllFinite() && (_params.ev_ctrl & static_cast<int32_t>(EvCtrl::VEL))) {
if (continuing_conditions_passing) {
// correct velocity for offset relative to IMU
const Vector3f pos_offset_body = _params.ev_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;
if (ev_reset) {
switch (ev_sample.vel_frame) {
case VelocityFrame::LOCAL_FRAME_NED:
case VelocityFrame::LOCAL_FRAME_FRD: {
const Vector3f reset_vel = ev_sample.vel - vel_offset_earth;
resetVerticalVelocityTo(reset_vel(2), math::max(ev_sample.velocity_var(2), sq(_params.ev_vel_noise)));
}
break;
case VelocityFrame::BODY_FRAME_FRD: {
const Vector3f reset_vel = _R_to_earth * (ev_sample.vel - vel_offset_body);
const Matrix3f reset_vel_cov = _R_to_earth * matrix::diag(ev_sample.velocity_var) * _R_to_earth.transpose();
resetVerticalVelocityTo(reset_vel(2), math::max(reset_vel_cov(2, 2), sq(_params.ev_vel_noise)));
}
break;
}
} else {
resetVerticalVelocityToZero();
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
} else if ((_ev_sample_delayed.reset_counter != _ev_sample_delayed_prev.reset_counter) && !aid_src.fused) {
// fusion failed and EV sample indicates reset
ECL_INFO("%s height reset", HGT_SRC_NAME);
if (quality_sufficient) {
ECL_INFO("reset to %s", AID_SRC_NAME);
if (_height_sensor_ref == HeightSensor::EV) {
_information_events.flags.reset_hgt_to_ev = true;
@@ -138,43 +124,91 @@ void Ekf::controlEvHeightFusion(const extVisionSample &ev_sample)
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
} else if (is_fusion_failing) {
// Some other height source is still working
ECL_WARN("stopping %s height fusion, fusion failing", HGT_SRC_NAME);
} else {
// EV has reset, but quality isn't sufficient
// we have no choice but to stop EV and try to resume once quality is acceptable
stopEvHgtFusion();
return;
}
} else if (quality_sufficient) {
fuseVerticalPosition(aid_src);
} else {
ECL_WARN("stopping %s height fusion, continuing conditions failing", HGT_SRC_NAME);
aid_src.innovation_rejected = true;
}
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.hgt_fusion_timeout_max);
if (isHeightResetRequired() && quality_sufficient) {
// All height sources are failing
ECL_WARN("%s fusion reset required, all height sources failing", AID_SRC_NAME);
_information_events.flags.reset_hgt_to_ev = true;
resetVerticalPositionTo(measurement - bias_est.getBias(), measurement_var);
bias_est.setBias(-_state.pos(2) + measurement);
// reset vertical velocity
if (ev_sample.vel.isAllFinite() && (_params.ev_ctrl & static_cast<int32_t>(EvCtrl::VEL))) {
// correct velocity for offset relative to IMU
const Vector3f vel_offset_body = _ang_rate_delayed_raw % pos_offset_body;
const Vector3f vel_offset_earth = _R_to_earth * vel_offset_body;
switch (ev_sample.vel_frame) {
case VelocityFrame::LOCAL_FRAME_NED:
case VelocityFrame::LOCAL_FRAME_FRD: {
const Vector3f reset_vel = ev_sample.vel - vel_offset_earth;
resetVerticalVelocityTo(reset_vel(2), math::max(ev_sample.velocity_var(2), sq(_params.ev_vel_noise)));
}
break;
case VelocityFrame::BODY_FRAME_FRD: {
const Vector3f reset_vel = _R_to_earth * (ev_sample.vel - vel_offset_body);
const Matrix3f reset_vel_cov = _R_to_earth * matrix::diag(ev_sample.velocity_var) * _R_to_earth.transpose();
resetVerticalVelocityTo(reset_vel(2), math::max(reset_vel_cov(2, 2), sq(_params.ev_vel_noise)));
}
break;
}
} else {
resetVerticalVelocityToZero();
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
} else if (is_fusion_failing) {
// A reset did not fix the issue but all the starting checks are not passing
// This could be a temporary issue, stop the fusion without declaring the sensor faulty
ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME);
stopEvHgtFusion();
}
} else {
if (starting_conditions_passing) {
if (_params.height_sensor_ref == HeightSensor::EV) {
ECL_INFO("starting %s height fusion, resetting height", HGT_SRC_NAME);
_height_sensor_ref = HeightSensor::EV;
_information_events.flags.reset_hgt_to_ev = true;
resetVerticalPositionTo(measurement, measurement_var);
bias_est.reset();
} else {
ECL_INFO("starting %s height fusion", HGT_SRC_NAME);
bias_est.setBias(-_state.pos(2) + measurement);
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
bias_est.setFusionActive();
_control_status.flags.ev_hgt = true;
}
// Stop fusion but do not declare it faulty
ECL_WARN("stopping %s fusion, continuing conditions failing", AID_SRC_NAME);
stopEvHgtFusion();
}
} else if (_control_status.flags.ev_hgt
&& !isNewestSampleRecent(_time_last_ext_vision_buffer_push, 2 * EV_MAX_INTERVAL)) {
// No data anymore. Stop until it comes back.
ECL_WARN("stopping %s height fusion, no data", HGT_SRC_NAME);
stopEvHgtFusion();
} else {
if (starting_conditions_passing) {
// activate fusion, only reset if necessary
if (_params.height_sensor_ref == HeightSensor::EV) {
ECL_INFO("starting %s fusion, resetting state", AID_SRC_NAME);
_information_events.flags.reset_hgt_to_ev = true;
resetVerticalPositionTo(measurement, measurement_var);
_height_sensor_ref = HeightSensor::EV;
bias_est.reset();
} else {
ECL_INFO("starting %s fusion", AID_SRC_NAME);
bias_est.setBias(-_state.pos(2) + measurement);
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
bias_est.setFusionActive();
_control_status.flags.ev_hgt = true;
}
}
}
+299
View File
@@ -0,0 +1,299 @@
/****************************************************************************
*
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ev_pos_control.cpp
* Control functions for ekf external vision position fusion
*/
#include "ekf.h"
void Ekf::controlEvPosFusion(const extVisionSample &ev_sample, bool starting_conditions_passing, bool ev_reset,
bool quality_sufficient, estimator_aid_source2d_s &aid_src)
{
static constexpr const char *AID_SRC_NAME = "EV position";
const bool yaw_alignment_changed = (!_control_status_prev.flags.ev_yaw && _control_status.flags.ev_yaw)
|| (_control_status_prev.flags.yaw_align != _control_status.flags.yaw_align);
// determine if we should use EV position aiding
bool continuing_conditions_passing = (_params.ev_ctrl & static_cast<int32_t>(EvCtrl::HPOS))
&& _control_status.flags.tilt_align
&& PX4_ISFINITE(ev_sample.pos(0))
&& PX4_ISFINITE(ev_sample.pos(1));
// correct position for offset relative to IMU
const Vector3f pos_offset_body = _params.ev_pos_body - _params.imu_pos_body;
const Vector3f pos_offset_earth = _R_to_earth * pos_offset_body;
const bool bias_fusion_was_active = _ev_pos_b_est.fusionActive();
// rotate measurement into correct earth frame if required
Vector3f pos{NAN, NAN, NAN};
Matrix3f pos_cov{};
switch (ev_sample.pos_frame) {
case PositionFrame::LOCAL_FRAME_NED:
if (_control_status.flags.yaw_align) {
pos = ev_sample.pos - pos_offset_earth;
pos_cov = matrix::diag(ev_sample.position_var);
if (_control_status.flags.gps) {
_ev_pos_b_est.setFusionActive();
} else {
_ev_pos_b_est.setFusionInactive();
}
} else {
continuing_conditions_passing = false;
_ev_pos_b_est.setFusionInactive();
_ev_pos_b_est.reset();
}
break;
case PositionFrame::LOCAL_FRAME_FRD:
if (_control_status.flags.ev_yaw) {
// using EV frame
pos = ev_sample.pos - pos_offset_earth;
pos_cov = matrix::diag(ev_sample.position_var);
_ev_pos_b_est.setFusionInactive();
_ev_pos_b_est.reset();
} else {
// rotate EV to the EKF reference frame
const Quatf q_error((_state.quat_nominal * ev_sample.quat.inversed()).normalized());
const Dcmf R_ev_to_ekf = Dcmf(q_error);
pos = R_ev_to_ekf * ev_sample.pos - pos_offset_earth;
pos_cov = R_ev_to_ekf * matrix::diag(ev_sample.position_var) * R_ev_to_ekf.transpose();
// increase minimum variance to include EV orientation variance
// TODO: do this properly
const float orientation_var_max = ev_sample.orientation_var.max();
for (int i = 0; i < 2; i++) {
pos_cov(i, i) = math::max(pos_cov(i, i), orientation_var_max);
}
if (_control_status.flags.gps) {
_ev_pos_b_est.setFusionActive();
} else {
_ev_pos_b_est.setFusionInactive();
}
}
break;
default:
continuing_conditions_passing = false;
_ev_pos_b_est.setFusionInactive();
_ev_pos_b_est.reset();
break;
}
// increase minimum variance if GPS active (position reference)
if (_control_status.flags.gps) {
for (int i = 0; i < 2; i++) {
pos_cov(i, i) = math::max(pos_cov(i, i), sq(_params.gps_pos_noise));
}
}
const Vector2f measurement{pos(0), pos(1)};
const Vector2f measurement_var{
math::max(pos_cov(0, 0), sq(_params.ev_pos_noise), sq(0.01f)),
math::max(pos_cov(1, 1), sq(_params.ev_pos_noise), sq(0.01f))
};
const bool measurement_valid = measurement.isAllFinite() && measurement_var.isAllFinite();
// bias fusion activated (GPS activated)
if (!bias_fusion_was_active && _ev_pos_b_est.fusionActive()) {
if (quality_sufficient) {
// reset the bias estimator
_ev_pos_b_est.setBias(-Vector2f(_state.pos.xy()) + measurement);
} else if (isOtherSourceOfHorizontalAidingThan(_control_status.flags.ev_pos)) {
// otherwise stop EV position, when quality is good again it will restart with reset bias
stopEvPosFusion();
}
}
updateHorizontalPositionAidSrcStatus(ev_sample.time_us,
measurement - _ev_pos_b_est.getBias(), // observation
measurement_var + _ev_pos_b_est.getBiasVar(), // observation variance
math::max(_params.ev_pos_innov_gate, 1.f), // innovation gate
aid_src);
// update the bias estimator before updating the main filter but after
// using its current state to compute the vertical position innovation
if (measurement_valid && quality_sufficient) {
_ev_pos_b_est.setMaxStateNoise(Vector2f(sqrtf(measurement_var(0)), sqrtf(measurement_var(1))));
_ev_pos_b_est.setProcessNoiseSpectralDensity(_params.ev_hgt_bias_nsd); // TODO
_ev_pos_b_est.fuseBias(measurement - Vector2f(_state.pos.xy()), measurement_var + Vector2f(P(7, 7), P(8, 8)));
}
if (!measurement_valid) {
continuing_conditions_passing = false;
}
starting_conditions_passing &= continuing_conditions_passing;
if (_control_status.flags.ev_pos) {
aid_src.fusion_enabled = true;
if (continuing_conditions_passing) {
const bool bias_estimator_change = (bias_fusion_was_active != _ev_pos_b_est.fusionActive());
if (ev_reset || yaw_alignment_changed || bias_estimator_change) {
if (quality_sufficient) {
if (!_control_status.flags.gps) {
ECL_INFO("reset to %s", AID_SRC_NAME);
_information_events.flags.reset_pos_to_vision = true;
resetHorizontalPositionTo(measurement, measurement_var);
_ev_pos_b_est.reset();
} else {
_ev_pos_b_est.setBias(-Vector2f(_state.pos.xy()) + measurement);
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
} else {
// EV has reset, but quality isn't sufficient
// we have no choice but to stop EV and try to resume once quality is acceptable
stopEvPosFusion();
return;
}
} else if (quality_sufficient) {
fuseHorizontalPosition(aid_src);
} else {
aid_src.innovation_rejected = true;
}
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.no_aid_timeout_max); // 1 second
if (is_fusion_failing) {
bool pos_xy_fusion_failing = isTimedOut(_time_last_hor_pos_fuse, _params.no_aid_timeout_max);
if ((_nb_ev_pos_reset_available > 0) && quality_sufficient) {
// Data seems good, attempt a reset
ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME);
if (_control_status.flags.gps && !pos_xy_fusion_failing) {
// reset EV position bias
_ev_pos_b_est.setBias(-Vector2f(_state.pos.xy()) + measurement);
} else {
_information_events.flags.reset_pos_to_vision = true;
if (_control_status.flags.gps) {
resetHorizontalPositionTo(measurement - _ev_pos_b_est.getBias(), measurement_var + _ev_pos_b_est.getBiasVar());
_ev_pos_b_est.setBias(-Vector2f(_state.pos.xy()) + measurement);
} else {
resetHorizontalPositionTo(measurement, measurement_var);
_ev_pos_b_est.reset();
}
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
if (_control_status.flags.in_air) {
_nb_ev_pos_reset_available--;
}
} else if (starting_conditions_passing) {
// Data seems good, but previous reset did not fix the issue
// something else must be wrong, declare the sensor faulty and stop the fusion
//_control_status.flags.ev_pos_fault = true;
ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME);
stopEvPosFusion();
} else {
// A reset did not fix the issue but all the starting checks are not passing
// This could be a temporary issue, stop the fusion without declaring the sensor faulty
ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME);
stopEvPosFusion();
}
}
} else {
// Stop fusion but do not declare it faulty
ECL_WARN("stopping %s fusion, continuing conditions failing", AID_SRC_NAME);
stopEvPosFusion();
}
} else {
if (starting_conditions_passing) {
// activate fusion
// TODO: (_params.position_sensor_ref == PositionSensor::EV)
if (_control_status.flags.gps) {
ECL_INFO("starting %s fusion", AID_SRC_NAME);
_ev_pos_b_est.setBias(-Vector2f(_state.pos.xy()) + measurement);
_ev_pos_b_est.setFusionActive();
} else {
ECL_INFO("starting %s fusion, resetting state", AID_SRC_NAME);
//_position_sensor_ref = PositionSensor::EV;
_information_events.flags.reset_pos_to_vision = true;
resetHorizontalPositionTo(measurement, measurement_var);
_ev_pos_b_est.reset();
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
_nb_ev_pos_reset_available = 3;
_information_events.flags.starting_vision_pos_fusion = true;
_control_status.flags.ev_pos = true;
}
}
}
void Ekf::stopEvPosFusion()
{
if (_control_status.flags.ev_pos) {
resetEstimatorAidStatus(_aid_src_ev_pos);
_control_status.flags.ev_pos = false;
}
}
+1 -1
View File
@@ -214,7 +214,7 @@ void Ekf::controlEvVelFusion(const extVisionSample &ev_sample, bool starting_con
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
_nb_ev_vel_reset_available = 5;
_nb_ev_vel_reset_available = 3;
_information_events.flags.starting_vision_vel_fusion = true;
_control_status.flags.ev_vel = true;
}
+185
View File
@@ -0,0 +1,185 @@
/****************************************************************************
*
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file ev_yaw_control.cpp
* Control functions for ekf external vision yaw fusion
*/
#include "ekf.h"
void Ekf::controlEvYawFusion(const extVisionSample &ev_sample, bool starting_conditions_passing, bool ev_reset,
bool quality_sufficient, estimator_aid_source1d_s &aid_src)
{
static constexpr const char *AID_SRC_NAME = "EV yaw";
resetEstimatorAidStatus(aid_src);
aid_src.timestamp_sample = ev_sample.time_us;
aid_src.observation = getEulerYaw(ev_sample.quat);
aid_src.observation_variance = math::max(ev_sample.orientation_var(2), _params.ev_att_noise, sq(0.01f));
aid_src.innovation = wrap_pi(getEulerYaw(_R_to_earth) - aid_src.observation);
// determine if we should use EV yaw aiding
bool continuing_conditions_passing = (_params.ev_ctrl & static_cast<int32_t>(EvCtrl::YAW))
&& _control_status.flags.tilt_align
&& !_inhibit_ev_yaw_use
&& PX4_ISFINITE(aid_src.observation)
&& PX4_ISFINITE(aid_src.observation_variance);
// if GPS enabled only allow EV yaw if EV is NED
if (_control_status.flags.gps && _control_status.flags.yaw_align
&& (ev_sample.pos_frame != PositionFrame::LOCAL_FRAME_NED)
) {
continuing_conditions_passing = false;
// use delta yaw for innovation logging
aid_src.innovation = wrap_pi(wrap_pi(getEulerYaw(_R_to_earth) - _yaw_pred_prev)
- wrap_pi(getEulerYaw(ev_sample.quat) - getEulerYaw(_ev_sample_prev.quat)));
}
starting_conditions_passing &= continuing_conditions_passing
&& isTimedOut(aid_src.time_last_fuse, (uint32_t)1e6);
if (_control_status.flags.ev_yaw) {
aid_src.fusion_enabled = true;
if (continuing_conditions_passing) {
if (ev_reset) {
if (quality_sufficient) {
ECL_INFO("reset to %s", AID_SRC_NAME);
//_information_events.flags.reset_yaw_to_vision = true; // TODO
resetQuatStateYaw(aid_src.observation, aid_src.observation_variance);
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
} else {
// EV has reset, but quality isn't sufficient
// we have no choice but to stop EV and try to resume once quality is acceptable
stopEvYawFusion();
return;
}
} else if (quality_sufficient) {
fuseYaw(aid_src.innovation, aid_src.observation_variance, aid_src);
} else {
aid_src.innovation_rejected = true;
}
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.no_aid_timeout_max);
if (is_fusion_failing) {
if ((_nb_ev_yaw_reset_available > 0) && quality_sufficient) {
// Data seems good, attempt a reset
//_information_events.flags.reset_yaw_to_vision = true; // TODO
ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME);
resetQuatStateYaw(aid_src.innovation, aid_src.observation_variance);
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
if (_control_status.flags.in_air) {
_nb_ev_yaw_reset_available--;
}
} else if (starting_conditions_passing) {
// Data seems good, but previous reset did not fix the issue
// something else must be wrong, declare the sensor faulty and stop the fusion
//_control_status.flags.ev_yaw_fault = true;
ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME);
stopEvYawFusion();
} else {
// A reset did not fix the issue but all the starting checks are not passing
// This could be a temporary issue, stop the fusion without declaring the sensor faulty
ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME);
stopEvYawFusion();
}
}
} else {
// Stop fusion but do not declare it faulty
ECL_WARN("stopping %s fusion, continuing conditions failing", AID_SRC_NAME);
stopEvYawFusion();
}
} else {
if (starting_conditions_passing) {
// activate fusion
if (ev_sample.pos_frame == PositionFrame::LOCAL_FRAME_NED) {
if (_control_status.flags.yaw_align) {
ECL_INFO("starting %s fusion", AID_SRC_NAME);
} else {
// reset yaw to EV and set yaw_align
ECL_INFO("starting %s fusion, resetting state", AID_SRC_NAME);
resetQuatStateYaw(aid_src.observation, aid_src.observation_variance);
_control_status.flags.yaw_align = true;
}
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
_information_events.flags.starting_vision_yaw_fusion = true;
_control_status.flags.ev_yaw = true;
} else if (ev_sample.pos_frame == PositionFrame::LOCAL_FRAME_FRD) {
// turn on fusion of external vision yaw measurements and disable all other heading fusion
stopMagFusion();
stopGpsYawFusion();
stopGpsFusion();
ECL_INFO("starting %s fusion, resetting state", AID_SRC_NAME);
// reset yaw to EV
resetQuatStateYaw(aid_src.observation, aid_src.observation_variance);
aid_src.time_last_fuse = _imu_sample_delayed.time_us;
_information_events.flags.starting_vision_yaw_fusion = true;
_control_status.flags.yaw_align = false;
_control_status.flags.ev_yaw = true;
}
if (_control_status.flags.ev_yaw) {
_nb_ev_yaw_reset_available = 3;
}
}
}
}
void Ekf::stopEvYawFusion()
{
if (_control_status.flags.ev_yaw) {
resetEstimatorAidStatus(_aid_src_ev_yaw);
_control_status.flags.ev_yaw = false;
}
}
@@ -95,7 +95,6 @@ void Ekf::controlFakePosFusion()
if (starting_conditions_passing) {
ECL_INFO("start fake position fusion");
_control_status.flags.fake_pos = true;
_fuse_hpos_as_odom = false; // TODO: needed?
resetFakePosFusion();
if (_control_status.flags.tilt_align) {
+1 -1
View File
@@ -117,7 +117,7 @@ void Ekf::controlGnssHeightFusion(const gpsSample &gps_sample)
// reset vertical velocity
if (PX4_ISFINITE(gps_sample.vel(2)) && (_params.gnss_ctrl & GnssCtrl::VEL)) {
// use 1.5 as a typical ratio of vacc/hacc
resetVerticalVelocityTo(gps_sample.vel(2), sq(1.5f * gps_sample.sacc));
resetVerticalVelocityTo(gps_sample.vel(2), sq(1.5f * math::max(gps_sample.sacc, _params.gps_vel_noise)));
} else {
resetVerticalVelocityToZero();
+119 -66
View File
@@ -41,11 +41,6 @@
void Ekf::controlGpsFusion()
{
if (!((_params.gnss_ctrl & GnssCtrl::HPOS) || (_params.gnss_ctrl & GnssCtrl::VEL))) {
stopGpsFusion();
return;
}
// Check for new GPS data that has fallen behind the fusion time horizon
if (_gps_data_ready) {
@@ -59,16 +54,19 @@ void Ekf::controlGpsFusion()
controlGpsYawFusion(gps_sample, gps_checks_passing, gps_checks_failing);
// GNSS velocity
const float vel_var = sq(math::max(gps_sample.sacc, _params.gps_vel_noise));
const Vector3f velocity{gps_sample.vel};
const float vel_noise = math::max(gps_sample.sacc, _params.gps_vel_noise);
const float vel_var = sq(vel_noise);
const Vector3f vel_obs_var(vel_var, vel_var, vel_var * sq(1.5f));
updateVelocityAidSrcStatus(gps_sample.time_us,
gps_sample.vel, // observation
velocity, // observation
vel_obs_var, // observation variance
math::max(_params.gps_vel_innov_gate, 1.f), // innovation gate
_aid_src_gnss_vel);
_aid_src_gnss_vel.fusion_enabled = (_params.gnss_ctrl & GnssCtrl::VEL);
// GNSS position
const Vector2f position{gps_sample.pos};
// relax the upper observation noise limit which prevents bad GPS perturbing the position estimate
float pos_noise = math::max(gps_sample.hacc, _params.gps_pos_noise);
@@ -83,17 +81,49 @@ void Ekf::controlGpsFusion()
const float pos_var = sq(pos_noise);
const Vector2f pos_obs_var(pos_var, pos_var);
updateHorizontalPositionAidSrcStatus(gps_sample.time_us,
gps_sample.pos, // observation
position, // observation
pos_obs_var, // observation variance
math::max(_params.gps_pos_innov_gate, 1.f), // innovation gate
_aid_src_gnss_pos);
_aid_src_gnss_pos.fusion_enabled = (_params.gnss_ctrl & GnssCtrl::HPOS);
// update GSF yaw estimator velocity (basic sanity check on GNSS velocity data)
if (gps_checks_passing && !gps_checks_failing) {
_yawEstimator.setVelocity(gps_sample.vel.xy(), gps_sample.sacc);
if (_gps_speed_valid && velocity.isAllFinite()
&& (gps_sample.sacc > FLT_EPSILON) && (gps_sample.sacc <= _params.req_sacc)) {
_yawEstimator.setVelocity(velocity.xy(), vel_noise);
}
// allow GPS to perform yaw align or in flight mag alignment
if (_control_status.flags.tilt_align && _NED_origin_initialised
&& gps_checks_passing && !gps_checks_failing) {
if (!_control_status.flags.yaw_align
|| (_control_status.flags.mag_hdg && !_control_status.flags.mag_aligned_in_flight)
) {
if (resetYawToEKFGSF()) {
// Yaw aligned using IMU and GPS
} else if (resetYawToGps(gps_sample.yaw)) {
ECL_INFO("Yaw aligned using GPS yaw");
} else if (_control_status.flags.ev_yaw && !_control_status.flags.yaw_align && !_control_status.flags.in_air) {
// give mag a chance to start and yaw align if currently blocked by EV yaw
const bool mag_enabled = (_params.mag_fusion_type <= MagFuseType::MAG_3D);
const bool mag_available = (_mag_counter != 0);
if (mag_enabled && mag_available
&& !_control_status.flags.mag_field_disturbed
&& !_control_status.flags.mag_fault) {
stopEvYawFusion();
}
}
}
}
// 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
const bool mandatory_conditions_passing = ((_params.gnss_ctrl & GnssCtrl::HPOS) || (_params.gnss_ctrl & GnssCtrl::VEL))
@@ -102,7 +132,12 @@ void Ekf::controlGpsFusion()
&& _NED_origin_initialised;
const bool continuing_conditions_passing = mandatory_conditions_passing && !gps_checks_failing;
const bool starting_conditions_passing = continuing_conditions_passing && gps_checks_passing;
const bool starting_conditions_passing = continuing_conditions_passing
&& isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GPS_MAX_INTERVAL)
&& _gps_checks_passed
&& gps_checks_passing
&& !gps_checks_failing;
if (_control_status.flags.gps) {
if (mandatory_conditions_passing) {
@@ -112,42 +147,72 @@ void Ekf::controlGpsFusion()
fuseVelocity(_aid_src_gnss_vel);
fuseHorizontalPosition(_aid_src_gnss_pos);
if (shouldResetGpsFusion()) {
const bool was_gps_signal_lost = isTimedOut(_time_prev_gps_us, 1'000'000);
const bool is_vel_fusion_failing = isTimedOut(_aid_src_gnss_vel.time_last_fuse, _params.reset_timeout_max);
const bool is_pos_fusion_failing = isTimedOut(_aid_src_gnss_pos.time_last_fuse, _params.reset_timeout_max);
/* 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.
* The total number of resets allowed per boot cycle is limited.
*/
if (isYawFailure()
&& _control_status.flags.in_air
&& !was_gps_signal_lost
&& _ekfgsf_yaw_reset_count < _params.EKFGSF_reset_count_limit
&& isTimedOut(_ekfgsf_yaw_reset_time, 5'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.
// The total number of resets allowed per boot cycle is limited.
const bool was_gps_signal_lost = isTimedOut(_time_prev_gps_us, 1'000'000);
const bool yaw_failure = isYawFailure() && !was_gps_signal_lost
&& (_ekfgsf_yaw_reset_count < _params.EKFGSF_reset_count_limit)
&& isTimedOut(_ekfgsf_yaw_reset_time, 5'000'000);
const bool should_reset_gps_fusion = shouldResetGpsFusion();
if (should_reset_gps_fusion || (yaw_failure && (is_vel_fusion_failing || is_pos_fusion_failing))) {
bool yaw_reset = false;
if (yaw_failure) {
// 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()) {
ECL_WARN("GPS emergency yaw reset");
_ekfgsf_yaw_reset_count++;
yaw_reset = true;
if (_control_status.flags.mag_hdg || _control_status.flags.mag_3D) {
// stop using the magnetometer in the main EKF otherwise it's fusion could drag the yaw around
// and cause another navigation failure
if (_ekfgsf_yaw_reset_count > 1) {
_control_status.flags.mag_fault = true;
_warning_events.flags.emergency_yaw_reset_mag_stopped = true;
}
}
if (_control_status.flags.gps_yaw) {
_control_status.flags.gps_yaw_fault = true;
_warning_events.flags.emergency_yaw_reset_gps_yaw_stopped = true;
}
if (_control_status.flags.ev_yaw) {
// Stop the vision for yaw fusion and do not allow it to start again
stopEvYawFusion();
_inhibit_ev_yaw_use = true;
}
}
}
ECL_WARN("GPS fusion timeout, resetting velocity and position");
_information_events.flags.reset_vel_to_gps = true;
_information_events.flags.reset_pos_to_gps = true;
resetVelocityTo(gps_sample.vel, vel_obs_var);
resetHorizontalPositionTo(gps_sample.pos, pos_obs_var);
if (should_reset_gps_fusion || is_vel_fusion_failing || yaw_reset) {
// reset velocity
_information_events.flags.reset_vel_to_gps = true;
resetVelocityTo(velocity, vel_obs_var);
_aid_src_gnss_vel.time_last_fuse = _imu_sample_delayed.time_us;
}
if (should_reset_gps_fusion || is_pos_fusion_failing || yaw_reset) {
// reset position
_information_events.flags.reset_pos_to_gps = true;
resetHorizontalPositionTo(position, pos_obs_var);
_aid_src_gnss_pos.time_last_fuse = _imu_sample_delayed.time_us;
}
}
} else {
stopGpsFusion();
_warning_events.flags.gps_quality_poor = true;
ECL_WARN("GPS quality poor - stopping use");
// TODO: move this to EV control logic
// Reset position state to external vision if we are going to use absolute values
if (_control_status.flags.ev_pos && !(_params.fusion_mode & SensorFusionMask::ROTATE_EXT_VIS)) {
resetHorizontalPositionToVision();
}
}
} else { // mandatory conditions are not passing
@@ -158,54 +223,42 @@ void Ekf::controlGpsFusion()
if (starting_conditions_passing) {
// Do not use external vision for yaw if using GPS because yaw needs to be
// defined relative to an NED reference frame
if (_control_status.flags.ev_yaw
|| _mag_inhibit_yaw_reset_req
|| _mag_yaw_reset_req) {
_mag_yaw_reset_req = true;
if (_control_status.flags.ev_yaw) {
// Stop the vision for yaw fusion and do not allow it to start again
stopEvYawFusion();
_inhibit_ev_yaw_use = true;
} else {
ECL_INFO("starting GPS fusion");
_information_events.flags.starting_gps_fusion = true;
// reset position
_information_events.flags.reset_pos_to_gps = true;
resetHorizontalPositionTo(gps_sample.pos, pos_obs_var);
// when already using another velocity source velocity reset is not necessary
if (!isHorizontalAidingActive()) {
_information_events.flags.reset_vel_to_gps = true;
resetVelocityTo(gps_sample.vel, vel_obs_var);
}
_control_status.flags.gps = true;
}
} else if (gps_checks_passing && !_control_status.flags.yaw_align && (_params.mag_fusion_type == MagFuseType::NONE)) {
// If no mag is used, align using the yaw estimator (if available)
if (resetYawToEKFGSF()) {
_information_events.flags.yaw_aligned_to_imu_gps = true;
ECL_INFO("Yaw aligned using IMU and GPS");
// reset position
_information_events.flags.reset_pos_to_gps = true;
resetHorizontalPositionTo(position, pos_obs_var);
_aid_src_gnss_pos.time_last_fuse = _imu_sample_delayed.time_us;
ECL_INFO("reset velocity and position to GPS");
// when already using another velocity source velocity reset is not necessary
if (!isHorizontalAidingActive()
|| isTimedOut(_time_last_hor_vel_fuse, _params.reset_timeout_max)
|| !_control_status_prev.flags.yaw_align
) {
// reset velocity
_information_events.flags.reset_vel_to_gps = true;
_information_events.flags.reset_pos_to_gps = true;
resetVelocityTo(gps_sample.vel, vel_obs_var);
resetHorizontalPositionTo(gps_sample.pos, pos_obs_var);
resetVelocityTo(velocity, vel_obs_var);
_aid_src_gnss_vel.time_last_fuse = _imu_sample_delayed.time_us;
}
_information_events.flags.starting_gps_fusion = true;
ECL_INFO("starting GPS fusion");
_control_status.flags.gps = true;
}
}
} else if (_control_status.flags.gps && !isNewestSampleRecent(_time_last_gps_buffer_push, (uint64_t)10e6)) {
_time_prev_gps_us = _gps_sample_delayed.time_us;
} else if (_control_status.flags.gps && isTimedOut(_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 && !isNewestSampleRecent(_time_last_gps_buffer_push, (uint64_t)1e6)
} else if (_control_status.flags.gps && isTimedOut(_time_prev_gps_us, 2 * GPS_MAX_INTERVAL)
&& isOtherSourceOfHorizontalAidingThan(_control_status.flags.gps)) {
// Handle the case where we are fusing another position source along GPS,
+26 -13
View File
@@ -203,23 +203,36 @@ void Ekf::fuseGpsYaw(const gpsSample& gps_sample)
bool Ekf::resetYawToGps(const float gnss_yaw)
{
// 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_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
if (fabsf(ant_vec_ef(2)) > cosf(math::radians(30.0f))) {
// prevent a reset being performed more than once on the same frame
if ((_flt_mag_align_start_time == _imu_sample_delayed.time_us) || (_control_status_prev.flags.yaw_align != _control_status.flags.yaw_align)) {
return false;
}
// GPS yaw measurement is alreday compensated for antenna offset in the driver
const float measured_yaw = gnss_yaw;
if (PX4_ISFINITE(gnss_yaw) && !_control_status.flags.gps_yaw_fault) {
// 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_ef = _R_to_earth * ant_vec_bf;
const float yaw_variance = sq(fmaxf(_params.gps_heading_noise, 1.e-2f));
resetQuatStateYaw(measured_yaw, yaw_variance);
// check if antenna array vector is within 30 degrees of vertical and therefore unable to provide a reliable heading
if (fabsf(ant_vec_ef(2)) > cosf(math::radians(30.0f))) {
return false;
}
_aid_src_gnss_yaw.time_last_fuse = _imu_sample_delayed.time_us;
_gnss_yaw_signed_test_ratio_lpf.reset(0.f);
// GPS yaw measurement is alreday compensated for antenna offset in the driver
const float measured_yaw = gnss_yaw;
return true;
const float yaw_variance = sq(fmaxf(_params.gps_heading_noise, 1.e-2f));
resetQuatStateYaw(measured_yaw, yaw_variance);
_control_status.flags.yaw_align = true;
_aid_src_gnss_yaw.time_last_fuse = _imu_sample_delayed.time_us;
_gnss_yaw_signed_test_ratio_lpf.reset(0.f);
resetMagStates();
return true;
}
return false;
}
+11 -4
View File
@@ -46,7 +46,6 @@ void Ekf::controlHeightFusion()
controlBaroHeightFusion();
controlGnssHeightFusion(_gps_sample_delayed);
controlRangeHeightFusion();
controlEvHeightFusion(_ev_sample_delayed);
checkHeightSensorRefFallback();
}
@@ -62,6 +61,7 @@ void Ekf::checkHeightSensorRefFallback()
switch (_params.height_sensor_ref) {
default:
/* FALLTHROUGH */
case HeightSensor::UNKNOWN:
fallback_list[0] = HeightSensor::GNSS;
@@ -150,12 +150,18 @@ void Ekf::checkVerticalAccelerationHealth()
// declare a bad vertical acceleration measurement and make the declaration persist
// for a minimum of BADACC_PROBATION seconds
const bool bad_acc_vertical = _fault_status.flags.bad_acc_vertical;
if (_fault_status.flags.bad_acc_vertical) {
_fault_status.flags.bad_acc_vertical = isRecent(_time_bad_vert_accel, BADACC_PROBATION);
} else {
_fault_status.flags.bad_acc_vertical = bad_vert_accel;
}
if (!bad_acc_vertical && _fault_status.flags.bad_acc_vertical) {
ECL_WARN("bad vertical acceleration");
}
}
Likelihood Ekf::estimateInertialNavFallingLikelihood() const
@@ -172,6 +178,7 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const
bool failed_min;
bool failed_lim;
} checks[6] {};
static constexpr size_t NUM_CHECKS = sizeof(checks) / sizeof(checks[0]);
if (_control_status.flags.baro_hgt) {
checks[0] = {ReferenceType::PRESSURE, _aid_src_baro_hgt.innovation, _aid_src_baro_hgt.innovation_variance};
@@ -198,7 +205,7 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const
}
// Compute the check based on innovation ratio for all the sources
for (unsigned i = 0; i < 6; i++) {
for (unsigned i = 0; i < NUM_CHECKS; i++) {
if (checks[i].innov_var < FLT_EPSILON) {
continue;
}
@@ -209,13 +216,13 @@ Likelihood Ekf::estimateInertialNavFallingLikelihood() const
}
// Check all the sources agains each other
for (unsigned i = 0; i < 6; i++) {
for (unsigned i = 0; i < NUM_CHECKS; i++) {
if (checks[i].failed_lim) {
// There is a chance that the inertial nav is falling if one source is failing the test
likelihood_medium = true;
}
for (unsigned j = 0; j < 6; j++) {
for (unsigned j = 0; j < NUM_CHECKS; j++) {
if ((checks[i].ref_type != checks[j].ref_type) && checks[i].failed_lim && checks[j].failed_min) {
// There is a high chance that the inertial nav is failing if two sources are failing the test
+111 -110
View File
@@ -75,7 +75,7 @@ void Ekf::controlMagFusion()
resetEstimatorAidStatus(_aid_src_mag_heading);
_aid_src_mag_heading.timestamp_sample = mag_sample.time_us;
_aid_src_mag_heading.observation = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination();;
_aid_src_mag_heading.observation = -atan2f(mag_earth_pred(1), mag_earth_pred(0)) + getMagDeclination();
_aid_src_mag_heading.innovation = wrap_pi(getEulerYaw(_R_to_earth) - _aid_src_mag_heading.observation);
// compute magnetometer innovations (for estimator_aid_src_mag logging)
@@ -104,17 +104,13 @@ void Ekf::controlMagFusion()
return;
}
_mag_yaw_reset_req |= !_control_status.flags.yaw_align;
_mag_yaw_reset_req |= _mag_inhibit_yaw_reset_req;
if (mag_data_ready && !_control_status.flags.ev_yaw && !_control_status.flags.gps_yaw) {
const bool mag_enabled_previously = _control_status_prev.flags.mag_hdg || _control_status_prev.flags.mag_3D;
// Determine if we should use simple magnetic heading fusion which works better when
// there are large external disturbances or the more accurate 3-axis fusion
switch (_params.mag_fusion_type) {
default:
// FALLTHROUGH
case MagFuseType::AUTO:
selectMagAuto();
@@ -132,18 +128,10 @@ void Ekf::controlMagFusion()
break;
}
const bool mag_enabled = _control_status.flags.mag_hdg || _control_status.flags.mag_3D;
if (!mag_enabled_previously && mag_enabled) {
_mag_yaw_reset_req = true;
}
if (_control_status.flags.in_air) {
checkHaglYawResetReq();
runInAirYawReset();
} else {
runOnGroundYawReset();
if ((_control_status.flags.mag_hdg || _control_status.flags.mag_3D)
&& (!_control_status.flags.yaw_align || _mag_yaw_reset_req || haglYawResetReq())
) {
runYawReset();
}
if (!_control_status.flags.yaw_align) {
@@ -152,43 +140,24 @@ void Ekf::controlMagFusion()
}
checkMagDeclRequired();
checkMagInhibition();
runMagAndMagDeclFusions(mag_sample.mag);
}
}
void Ekf::checkHaglYawResetReq()
bool Ekf::haglYawResetReq() const
{
// We need to reset the yaw angle after climbing away from the ground to enable
// recovery from ground level magnetic interference.
if (!_control_status.flags.mag_aligned_in_flight) {
if (_control_status.flags.in_air && !_control_status.flags.mag_aligned_in_flight && isTerrainEstimateValid()) {
// Check if height has increased sufficiently to be away from ground magnetic anomalies
// and request a yaw reset if not already requested.
static constexpr float mag_anomalies_max_hagl = 1.5f;
const bool above_mag_anomalies = (getTerrainVPos() - _state.pos(2)) > mag_anomalies_max_hagl;
_mag_yaw_reset_req = _mag_yaw_reset_req || above_mag_anomalies;
return above_mag_anomalies;
}
}
void Ekf::runOnGroundYawReset()
{
if (_mag_yaw_reset_req && !_is_yaw_fusion_inhibited) {
const bool has_realigned_yaw = canResetMagHeading() ? resetMagHeading() : false;
if (has_realigned_yaw) {
_mag_yaw_reset_req = false;
_control_status.flags.yaw_align = true;
// Handle the special case where we have not been constraining yaw drift or learning yaw bias due
// to assumed invalid mag field associated with indoor operation with a downwards looking flow sensor.
if (_mag_inhibit_yaw_reset_req) {
_mag_inhibit_yaw_reset_req = false;
// Zero the yaw bias covariance and set the variance to the initial alignment uncertainty
P.uncorrelateCovarianceSetVariance<1>(12, sq(_params.switch_on_gyro_bias * _dt_ekf_avg));
}
}
}
return false;
}
bool Ekf::canResetMagHeading() const
@@ -196,66 +165,48 @@ bool Ekf::canResetMagHeading() const
return !_control_status.flags.mag_field_disturbed && (_params.mag_fusion_type != MagFuseType::NONE);
}
void Ekf::runInAirYawReset()
void Ekf::runYawReset()
{
if (_mag_yaw_reset_req && !_is_yaw_fusion_inhibited) {
bool has_realigned_yaw = false;
// prevent a reset being performed more than once on the same frame
if ((_flt_mag_align_start_time == _imu_sample_delayed.time_us)
|| (_control_status_prev.flags.yaw_align != _control_status.flags.yaw_align)) {
return;
}
// use yaw estimator if available
if (_control_status.flags.gps && isYawEmergencyEstimateAvailable() &&
(_mag_counter != 0) && isNewestSampleRecent(_time_last_mag_buffer_push, 500'000) // mag LPF available
) {
bool has_realigned_yaw = false;
resetQuatStateYaw(_yawEstimator.getYaw(), _yawEstimator.getYawVar());
_information_events.flags.yaw_aligned_to_imu_gps = true;
_ekfgsf_yaw_reset_time = _imu_sample_delayed.time_us;
// if world magnetic model (inclination, declination, strength) available then use it to reset mag states
if (PX4_ISFINITE(_mag_inclination_gps) && PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps)) {
// use predicted earth field to reset states
const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps, _mag_declination_gps)) * Vector3f(_mag_strength_gps, 0, 0);
_state.mag_I = mag_earth_pred;
const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal);
_state.mag_B = _mag_lpf.getState() - (R_to_body * mag_earth_pred);
} else {
// Use the last magnetometer measurements to reset the field states
// calculate initial earth magnetic field states
_state.mag_I = _R_to_earth * _mag_lpf.getState();
_state.mag_B.zero();
}
ECL_DEBUG("resetting mag I: [%.3f, %.3f, %.3f], B: [%.3f, %.3f, %.3f]",
(double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2),
(double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2)
);
resetMagCov();
// use yaw estimator if available
if (isYawEmergencyEstimateAvailable()) {
if (resetYawToEKFGSF()) {
has_realigned_yaw = true;
}
}
if (!has_realigned_yaw && canResetMagHeading()) {
has_realigned_yaw = resetMagHeading();
}
if (!has_realigned_yaw && canResetMagHeading()) {
has_realigned_yaw = resetMagHeading();
}
if (has_realigned_yaw) {
_mag_yaw_reset_req = false;
_control_status.flags.yaw_align = true;
if (has_realigned_yaw) {
_mag_yaw_reset_req = false;
_control_status.flags.yaw_align = true;
if (_control_status.flags.in_air) {
_control_status.flags.mag_aligned_in_flight = true;
// record the time for the magnetic field alignment event
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
// Handle the special case where we have not been constraining yaw drift or learning yaw bias due
// to assumed invalid mag field associated with indoor operation with a downwards looking flow sensor.
if (_mag_inhibit_yaw_reset_req) {
_mag_inhibit_yaw_reset_req = false;
// Zero the yaw bias covariance and set the variance to the initial alignment uncertainty
P.uncorrelateCovarianceSetVariance<1>(12, sq(_params.switch_on_gyro_bias * _dt_ekf_avg));
}
}
// Handle the special case where we have not been constraining yaw drift or learning yaw bias due
// to assumed invalid mag field associated with indoor operation with a downwards looking flow sensor.
if (isTimedOut(_aid_src_mag_heading.time_last_fuse, (uint32_t)5e6)
&& isTimedOut(_aid_src_mag.time_last_fuse, (uint32_t)5e6)
&& isTimedOut(_aid_src_gnss_yaw.time_last_fuse, (uint32_t)5e6)
&& isTimedOut(_aid_src_ev_yaw.time_last_fuse, (uint32_t)5e6)
) {
// Zero the yaw bias covariance and set the variance to the initial alignment uncertainty
P.uncorrelateCovarianceSetVariance<1>(12, sq(_params.switch_on_gyro_bias * _dt_ekf_avg));
}
}
}
@@ -284,7 +235,7 @@ void Ekf::checkYawAngleObservability()
: _accel_lpf_NE.norm() > 2.0f * _params.mag_acc_gate;
_yaw_angle_observable = _yaw_angle_observable
&& (_control_status.flags.gps || _control_status.flags.ev_pos); // Do we have to add ev_vel here?
&& (_control_status.flags.gps || (_control_status.flags.ev_pos && _control_status.flags.yaw_align));
}
void Ekf::checkMagBiasObservability()
@@ -324,20 +275,6 @@ void Ekf::checkMagDeclRequired()
_control_status.flags.mag_dec = (_control_status.flags.mag_3D && (not_using_ne_aiding || user_selected));
}
void Ekf::checkMagInhibition()
{
_is_yaw_fusion_inhibited = shouldInhibitMag();
if (!_is_yaw_fusion_inhibited) {
_mag_use_not_inhibit_us = _imu_sample_delayed.time_us;
}
// If magnetometer use has been inhibited continuously then a yaw reset is required for a valid heading
if (uint32_t(_imu_sample_delayed.time_us - _mag_use_not_inhibit_us) > (uint32_t)5e6) {
_mag_inhibit_yaw_reset_req = true;
}
}
bool Ekf::shouldInhibitMag() const
{
// If the user has selected auto protection against indoor magnetic field errors, only use the magnetometer
@@ -347,9 +284,7 @@ bool Ekf::shouldInhibitMag() const
// has explicitly stopped magnetometer use.
const bool user_selected = (_params.mag_fusion_type == MagFuseType::INDOOR);
const bool heading_not_required_for_navigation = !_control_status.flags.gps
&& !_control_status.flags.ev_pos
&& !_control_status.flags.ev_vel;
const bool heading_not_required_for_navigation = !_control_status.flags.gps;
return (user_selected && heading_not_required_for_navigation) || _control_status.flags.mag_field_disturbed;
}
@@ -384,7 +319,7 @@ void Ekf::runMagAndMagDeclFusions(const Vector3f &mag)
if (_control_status.flags.mag_3D) {
run3DMagAndDeclFusions(mag);
} else if (_control_status.flags.mag_hdg && !_is_yaw_fusion_inhibited) {
} else if (_control_status.flags.mag_hdg && !shouldInhibitMag()) {
// Rotate the measurements into earth frame using the zero yaw angle
Dcmf R_to_earth = updateYawInRotMat(0.f, _R_to_earth);
@@ -408,7 +343,7 @@ void Ekf::run3DMagAndDeclFusions(const Vector3f &mag)
// For the first few seconds after in-flight alignment we allow the magnetic field state estimates to stabilise
// before they are used to constrain heading drift
const bool update_all_states = ((_imu_sample_delayed.time_us - _flt_mag_align_start_time) > (uint64_t)5e6)
&& !_control_status.flags.mag_fault && !_control_status.flags.mag_field_disturbed;
&& !_control_status.flags.mag_fault && !_control_status.flags.mag_field_disturbed;
if (!_mag_decl_cov_reset) {
// After any magnetic field covariance reset event the earth field state
@@ -430,3 +365,69 @@ void Ekf::run3DMagAndDeclFusions(const Vector3f &mag)
}
}
}
bool Ekf::resetMagStates()
{
bool reset = false;
// reinit mag states
const bool mag_available = (_mag_counter != 0) && isNewestSampleRecent(_time_last_mag_buffer_push, 500'000);
// if world magnetic model (inclination, declination, strength) available then use it to reset mag states
if (PX4_ISFINITE(_mag_inclination_gps) && PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps)) {
// use predicted earth field to reset states
const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps,
_mag_declination_gps)) * Vector3f(_mag_strength_gps, 0, 0);
_state.mag_I = mag_earth_pred;
// TODO: ECL_DEBUG
ECL_INFO("resetting mag I to [%.3f, %.3f, %.3f]",
(double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2));
if (mag_available) {
const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal);
_state.mag_B = _mag_lpf.getState() - (R_to_body * mag_earth_pred);
// TODO: ECL_DEBUG
ECL_INFO("resetting mag B to [%.3f, %.3f, %.3f]",
(double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2));
} else {
_state.mag_B.zero();
}
reset = true;
} else if (mag_available) {
// Use the last magnetometer measurements to reset the field states
// calculate initial earth magnetic field states
_state.mag_I = _R_to_earth * _mag_lpf.getState();
_state.mag_B.zero();
// TODO: ECL_DEBUG
ECL_INFO("resetting mag I to [%.3f, %.3f, %.3f]",
(double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2));
reset = true;
}
if (reset) {
resetMagCov();
if (mag_available) {
if (_control_status.flags.in_air) {
// record the start time for the magnetic field alignment
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
_control_status.flags.mag_aligned_in_flight = true;
}
// clear any pending resets
_mag_yaw_reset_req = false;
}
return true;
}
return false;
}
+13 -5
View File
@@ -50,6 +50,7 @@ void Ekf::controlOpticalFlowFusion()
// Accumulate autopilot gyro data across the same time interval as the flow sensor
const Vector3f delta_angle(_imu_sample_delayed.delta_ang - (getGyroBias() * _imu_sample_delayed.delta_ang_dt));
if (_delta_time_of < 0.1f) {
_imu_del_ang_of += delta_angle;
_delta_time_of += _imu_sample_delayed.delta_ang_dt;
@@ -142,10 +143,14 @@ void Ekf::controlOpticalFlowFusion()
const bool preflight_motion_not_ok = !_control_status.flags.in_air
&& ((_imu_sample_delayed.time_us > (_time_good_motion_us + (uint64_t)1E5))
|| (_imu_sample_delayed.time_us < (_time_bad_motion_us + (uint64_t)5E6)));
const bool flight_condition_not_ok = _control_status.flags.in_air && !isTerrainEstimateValid();
const bool starting_conditions_passing = (_flow_sample_delayed.quality >= _params.flow_qual_min)
&& isTerrainEstimateValid();
const bool inhibit_flow_use = ((preflight_motion_not_ok || flight_condition_not_ok) && !is_flow_required)
|| !_control_status.flags.tilt_align;
|| !_control_status.flags.tilt_align;
// Handle cases where we are using optical flow but we should not use it anymore
if (_control_status.flags.opt_flow) {
@@ -160,7 +165,8 @@ void Ekf::controlOpticalFlowFusion()
// optical flow fusion mode selection logic
if ((_params.fusion_mode & SensorFusionMask::USE_OPT_FLOW) // optical flow has been selected by the user
&& !_control_status.flags.opt_flow // we are not yet using flow data
&& !inhibit_flow_use) {
&& !inhibit_flow_use
&& starting_conditions_passing) {
// set the flag and reset the fusion timeout
ECL_INFO("starting optical flow fusion");
@@ -195,7 +201,7 @@ void Ekf::controlOpticalFlowFusion()
if (_imu_sample_delayed.time_us > (_flow_sample_delayed.time_us - uint32_t(1e6f * _flow_sample_delayed.dt) / 2)) {
// Fuse optical flow LOS rate observations into the main filter only if height above ground has been updated recently
// but use a relaxed time criteria to enable it to coast through bad range finder data
if (isRecent(_time_last_hagl_fuse, (uint64_t)10e6)) {
if (isRecent(_time_last_hagl_fuse, (uint64_t)5e6)) {
fuseOptFlow();
_last_known_pos.xy() = _state.pos.xy();
}
@@ -204,8 +210,10 @@ void Ekf::controlOpticalFlowFusion()
}
// handle the case when we have optical flow, are reliant on it, but have not been using it for an extended period
if (isTimedOut(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max)
&& !isOtherSourceOfHorizontalAidingThan(_control_status.flags.opt_flow)) {
if (isTimedOut(_aid_src_optical_flow.time_last_fuse, _params.reset_timeout_max)
&& !isOtherSourceOfHorizontalAidingThan(_control_status.flags.opt_flow)
&& isRecent(_time_last_hagl_fuse, (uint64_t)5e6)
) {
ECL_INFO("reset velocity to flow");
_information_events.flags.reset_vel_to_flow = true;
@@ -0,0 +1,113 @@
/****************************************************************************
*
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/**
* @file position_bias_estimator.hpp
*/
#pragma once
#include "bias_estimator.hpp"
class PositionBiasEstimator
{
public:
PositionBiasEstimator(uint8_t sensor, const uint8_t &sensor_ref):
_sensor(sensor),
_sensor_ref(sensor_ref)
{}
virtual ~PositionBiasEstimator() = default;
bool fusionActive() const { return _is_sensor_fusion_active; }
void setFusionActive() { _is_sensor_fusion_active = true; }
void setFusionInactive() { _is_sensor_fusion_active = false; }
void predict(float dt)
{
if ((_sensor_ref != _sensor) && _is_sensor_fusion_active) {
_bias[0].predict(dt);
_bias[1].predict(dt);
}
}
void fuseBias(Vector2f bias, Vector2f bias_var)
{
if ((_sensor_ref != _sensor) && _is_sensor_fusion_active) {
_bias[0].fuseBias(bias(0), bias_var(0));
_bias[1].fuseBias(bias(1), bias_var(1));
}
}
void setBias(const Vector2f &bias)
{
_bias[0].setBias(bias(0));
_bias[1].setBias(bias(1));
}
void setProcessNoiseSpectralDensity(float nsd)
{
_bias[0].setProcessNoiseSpectralDensity(nsd);
_bias[1].setProcessNoiseSpectralDensity(nsd);
}
// void setBiasStdDev(float state_noise) { _state_var = state_noise * state_noise; }
// void setInnovGate(float gate_size) { _gate_size = gate_size; }
void setMaxStateNoise(const Vector2f &max_noise)
{
_bias[0].setMaxStateNoise(max_noise(0));
_bias[1].setMaxStateNoise(max_noise(1));
}
Vector2f getBias() const { return Vector2f(_bias[0].getBias(), _bias[1].getBias()); }
float getBias(int index) const { return _bias[index].getBias(); }
Vector2f getBiasVar() const { return Vector2f(_bias[0].getBiasVar(), _bias[1].getBiasVar()); }
float getBiasVar(int index) const { return _bias[index].getBiasVar(); }
const BiasEstimator::status &getStatus(int index) const { return _bias[index].getStatus(); }
void reset()
{
_bias[0].reset();
_bias[1].reset();
}
private:
BiasEstimator _bias[2] {};
const uint8_t _sensor;
const uint8_t &_sensor_ref;
bool _is_sensor_fusion_active{false}; // TODO: replace by const ref and remove setter when migrating _control_status.flags from union to bool
};
@@ -163,7 +163,7 @@ bool Ekf::isConditionalRangeAidSuitable()
float range_hagl_max = _params.max_hagl_for_range_aid;
float max_vel_xy = _params.max_vel_for_range_aid;
const float hagl_test_ratio = (_hagl_innov * _hagl_innov / (sq(_params.range_aid_innov_gate) * _hagl_innov_var));
const float hagl_test_ratio = (sq(_hagl_innov) / (sq(_params.range_aid_innov_gate) * _hagl_innov_var));
bool is_hagl_stable = (hagl_test_ratio < 1.f);
@@ -174,7 +174,6 @@ bool Ekf::isConditionalRangeAidSuitable()
}
const float range_hagl = _terrain_vpos - _state.pos(2);
const bool is_in_range = (range_hagl < range_hagl_max);
bool is_below_max_speed = true;
+127 -84
View File
@@ -125,6 +125,7 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode):
_param_ekf2_rng_k_gate(_params->range_kin_consistency_gate),
_param_ekf2_ev_ctrl(_params->ev_ctrl),
_param_ekf2_ev_qmin(_params->ev_quality_minimum),
_param_ekf2_evp_noise(_params->ev_pos_noise),
_param_ekf2_evv_noise(_params->ev_vel_noise),
_param_ekf2_eva_noise(_params->ev_att_noise),
_param_ekf2_evv_gate(_params->ev_vel_innov_gate),
@@ -206,23 +207,67 @@ bool EKF2::multi_init(int imu, int mag)
{
// advertise all topics to ensure consistent uORB instance numbering
_ekf2_timestamps_pub.advertise();
_estimator_baro_bias_pub.advertise();
_estimator_ev_hgt_bias_pub.advertise();
_estimator_event_flags_pub.advertise();
_estimator_gnss_hgt_bias_pub.advertise();
_estimator_gps_status_pub.advertise();
_estimator_innovation_test_ratios_pub.advertise();
_estimator_innovation_variances_pub.advertise();
_estimator_innovations_pub.advertise();
_estimator_optical_flow_vel_pub.advertise();
_estimator_rng_hgt_bias_pub.advertise();
_estimator_sensor_bias_pub.advertise();
_estimator_states_pub.advertise();
_estimator_status_flags_pub.advertise();
_estimator_status_pub.advertise();
_estimator_visual_odometry_aligned_pub.advertise();
_yaw_est_pub.advertise();
// baro advertise
if (_param_ekf2_baro_ctrl.get()) {
_estimator_aid_src_baro_hgt_pub.advertise();
_estimator_baro_bias_pub.advertise();
}
// EV advertise
if (_param_ekf2_ev_ctrl.get() & static_cast<int32_t>(EvCtrl::VPOS)) {
_estimator_aid_src_ev_hgt_pub.advertise();
_estimator_ev_pos_bias_pub.advertise();
}
if (_param_ekf2_ev_ctrl.get() & static_cast<int32_t>(EvCtrl::HPOS)) {
_estimator_aid_src_ev_pos_pub.advertise();
_estimator_ev_pos_bias_pub.advertise();
}
if (_param_ekf2_ev_ctrl.get() & static_cast<int32_t>(EvCtrl::VEL)) {
_estimator_aid_src_ev_vel_pub.advertise();
}
if (_param_ekf2_ev_ctrl.get() & static_cast<int32_t>(EvCtrl::YAW)) {
_estimator_aid_src_ev_yaw_pub.advertise();
}
// GNSS advertise
if (_param_ekf2_gps_ctrl.get() & static_cast<int32_t>(GnssCtrl::VPOS)) {
_estimator_aid_src_gnss_hgt_pub.advertise();
_estimator_gnss_hgt_bias_pub.advertise();
}
if (_param_ekf2_gps_ctrl.get() & static_cast<int32_t>(GnssCtrl::HPOS)) {
_estimator_aid_src_gnss_pos_pub.advertise();
_estimator_gps_status_pub.advertise();
}
if (_param_ekf2_gps_ctrl.get() & static_cast<int32_t>(GnssCtrl::VEL)) {
_estimator_aid_src_gnss_vel_pub.advertise();
}
if (_param_ekf2_gps_ctrl.get() & static_cast<int32_t>(GnssCtrl::YAW)) {
_estimator_aid_src_gnss_yaw_pub.advertise();
}
// RNG advertise
if (_param_ekf2_rng_ctrl.get()) {
_estimator_aid_src_rng_hgt_pub.advertise();
_estimator_rng_hgt_bias_pub.advertise();
}
_attitude_pub.advertise();
_local_position_pub.advertise();
_global_position_pub.advertise();
@@ -591,14 +636,12 @@ void EKF2::Run()
UpdateAirspeedSample(ekf2_timestamps);
UpdateAuxVelSample(ekf2_timestamps);
UpdateBaroSample(ekf2_timestamps);
UpdateExtVisionSample(ekf2_timestamps);
UpdateFlowSample(ekf2_timestamps);
UpdateGpsSample(ekf2_timestamps);
UpdateMagSample(ekf2_timestamps);
UpdateRangeSample(ekf2_timestamps);
vehicle_odometry_s ev_odom;
const bool new_ev_odom = UpdateExtVisionSample(ekf2_timestamps, ev_odom);
// run the EKF update and output
const hrt_abstime ekf_update_start = hrt_absolute_time();
@@ -614,7 +657,7 @@ void EKF2::Run()
PublishBaroBias(now);
PublishGnssHgtBias(now);
PublishRngHgtBias(now);
PublishEvHgtBias(now);
PublishEvPosBias(now);
PublishEventFlags(now);
PublishGpsStatus(now);
PublishInnovations(now);
@@ -638,11 +681,6 @@ void EKF2::Run()
perf_set_elapsed(_ecl_ekf_update_perf, hrt_elapsed_time(&ekf_update_start));
}
// publish external visual odometry after fixed frame alignment if new odometry is received
if (new_ev_odom) {
PublishOdometryAligned(now, ev_odom);
}
// publish ekf2_timestamps
_ekf2_timestamps_pub.publish(ekf2_timestamps);
}
@@ -711,12 +749,32 @@ void EKF2::VerifyParams()
}
// EV EKF2_AID_MASK -> EKF2_EV_CTRL
if ((_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_VEL)) {
if ((_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_VEL)
|| (_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_POS)
|| (_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_YAW)
) {
_param_ekf2_ev_ctrl.set(_param_ekf2_ev_ctrl.get() | static_cast<int32_t>(EvCtrl::VEL));
_param_ekf2_ev_ctrl.commit();
// EKF2_EV_CTRL set VEL bit
if ((_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_VEL)) {
_param_ekf2_ev_ctrl.set(_param_ekf2_ev_ctrl.get() | static_cast<int32_t>(EvCtrl::VEL));
}
// EKF2_EV_CTRL set HPOS/VPOS bits
if ((_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_POS)) {
_param_ekf2_ev_ctrl.set(_param_ekf2_ev_ctrl.get()
| static_cast<int32_t>(EvCtrl::HPOS) | static_cast<int32_t>(EvCtrl::VPOS));
}
// EKF2_EV_CTRL set YAW bit
if ((_param_ekf2_aid_mask.get() & SensorFusionMask::DEPRECATED_USE_EXT_VIS_YAW)) {
_param_ekf2_ev_ctrl.set(_param_ekf2_ev_ctrl.get() | static_cast<int32_t>(EvCtrl::YAW));
}
_param_ekf2_aid_mask.set(_param_ekf2_aid_mask.get() & ~(SensorFusionMask::DEPRECATED_USE_EXT_VIS_VEL));
_param_ekf2_aid_mask.set(_param_ekf2_aid_mask.get() & ~(SensorFusionMask::DEPRECATED_USE_EXT_VIS_POS));
_param_ekf2_aid_mask.set(_param_ekf2_aid_mask.get() & ~(SensorFusionMask::DEPRECATED_USE_EXT_VIS_YAW));
_param_ekf2_ev_ctrl.commit();
_param_ekf2_aid_mask.commit();
mavlink_log_critical(&_mavlink_log_pub, "EKF2 EV use EKF2_EV_CTRL instead of EKF2_AID_MASK\n");
@@ -832,15 +890,35 @@ void EKF2::PublishRngHgtBias(const hrt_abstime &timestamp)
}
}
void EKF2::PublishEvHgtBias(const hrt_abstime &timestamp)
void EKF2::PublishEvPosBias(const hrt_abstime &timestamp)
{
if (_ekf.get_ev_sample_delayed().time_us != 0) {
const BiasEstimator::status &status = _ekf.getEvHgtBiasEstimatorStatus();
if (_ekf.aid_src_ev_hgt().timestamp_sample) {
if (fabsf(status.bias - _last_ev_hgt_bias_published) > 0.001f) {
_estimator_ev_hgt_bias_pub.publish(fillEstimatorBiasMsg(status, _ekf.get_ev_sample_delayed().time_us, timestamp));
estimator_bias3d_s bias{};
_last_ev_hgt_bias_published = status.bias;
// height
BiasEstimator::status bias_est_status[3];
bias_est_status[0] = _ekf.getEvPosBiasEstimatorStatus(0);
bias_est_status[1] = _ekf.getEvPosBiasEstimatorStatus(1);
bias_est_status[2] = _ekf.getEvHgtBiasEstimatorStatus();
for (int i = 0; i < 3; i++) {
bias.bias[i] = bias_est_status[i].bias;
bias.bias_var[i] = bias_est_status[i].bias_var;
bias.innov[i] = bias_est_status[i].innov;
bias.innov_var[i] = bias_est_status[i].innov_var;
bias.innov_test_ratio[i] = bias_est_status[i].innov_test_ratio;
}
const Vector3f bias_vec{bias.bias};
if ((bias_vec - _last_ev_bias_published).longerThan(0.01f)) {
bias.timestamp_sample = _ekf.aid_src_ev_hgt().timestamp_sample;
bias.timestamp = hrt_absolute_time();
_estimator_ev_pos_bias_pub.publish(bias);
_last_ev_bias_published = Vector3f(bias.bias);
}
}
}
@@ -1248,43 +1326,6 @@ void EKF2::PublishOdometry(const hrt_abstime &timestamp)
_odometry_pub.publish(odom);
}
void EKF2::PublishOdometryAligned(const hrt_abstime &timestamp, const vehicle_odometry_s &ev_odom)
{
const Quatf quat_ev2ekf = _ekf.getVisionAlignmentQuaternion(); // rotates from EV to EKF navigation frame
const Dcmf ev_rot_mat(quat_ev2ekf);
vehicle_odometry_s aligned_ev_odom{ev_odom};
// Rotate external position and velocity into EKF navigation frame
const Vector3f aligned_pos = ev_rot_mat * Vector3f(ev_odom.position);
aligned_pos.copyTo(aligned_ev_odom.position);
switch (ev_odom.velocity_frame) {
case vehicle_odometry_s::VELOCITY_FRAME_BODY_FRD: {
const Vector3f aligned_vel = Dcmf(_ekf.getQuaternion()) * Vector3f(ev_odom.velocity);
aligned_vel.copyTo(aligned_ev_odom.velocity);
break;
}
case vehicle_odometry_s::VELOCITY_FRAME_FRD: {
const Vector3f aligned_vel = ev_rot_mat * Vector3f(ev_odom.velocity);
aligned_vel.copyTo(aligned_ev_odom.velocity);
break;
}
}
aligned_ev_odom.velocity_frame = vehicle_odometry_s::VELOCITY_FRAME_NED;
// Compute orientation in EKF navigation frame
Quatf ev_quat_aligned = quat_ev2ekf * Quatf(ev_odom.q);
ev_quat_aligned.normalize();
ev_quat_aligned.copyTo(aligned_ev_odom.q);
aligned_ev_odom.timestamp = _replay_mode ? timestamp : hrt_absolute_time();
_estimator_visual_odometry_aligned_pub.publish(aligned_ev_odom);
}
void EKF2::PublishSensorBias(const hrt_abstime &timestamp)
{
// estimator_sensor_bias
@@ -1738,12 +1779,14 @@ void EKF2::UpdateBaroSample(ekf2_timestamps_s &ekf2_timestamps)
}
}
bool EKF2::UpdateExtVisionSample(ekf2_timestamps_s &ekf2_timestamps, vehicle_odometry_s &ev_odom)
bool EKF2::UpdateExtVisionSample(ekf2_timestamps_s &ekf2_timestamps)
{
// EKF external vision sample
bool new_ev_odom = false;
const unsigned last_generation = _ev_odom_sub.get_last_generation();
vehicle_odometry_s ev_odom;
if (_ev_odom_sub.update(&ev_odom)) {
if (_msg_missed_odometry_perf == nullptr) {
_msg_missed_odometry_perf = perf_alloc(PC_COUNT, MODULE_NAME": vehicle_visual_odometry messages missed");
@@ -1802,38 +1845,38 @@ bool EKF2::UpdateExtVisionSample(ekf2_timestamps_s &ekf2_timestamps, vehicle_odo
}
// check for valid position data
if (Vector3f(ev_odom.position).isAllFinite()) {
bool position_valid = true;
const Vector3f ev_odom_pos(ev_odom.position);
const Vector3f ev_odom_pos_var(ev_odom.position_variance);
// switch (ev_odom.pose_frame) {
// case vehicle_odometry_s::POSE_FRAME_NED:
// ev_data.pos_frame = PositionFrame::LOCAL_FRAME_NED;
// break;
if (ev_odom_pos.isAllFinite()) {
bool position_frame_valid = false;
// case vehicle_odometry_s::POSE_FRAME_FRD:
// ev_data.pos_frame = PositionFrame::LOCAL_FRAME_FRD;
// break;
switch (ev_odom.pose_frame) {
case vehicle_odometry_s::POSE_FRAME_NED:
ev_data.pos_frame = PositionFrame::LOCAL_FRAME_NED;
position_frame_valid = true;
break;
// default:
// position_valid = false;
// break;
// }
case vehicle_odometry_s::POSE_FRAME_FRD:
ev_data.pos_frame = PositionFrame::LOCAL_FRAME_FRD;
position_frame_valid = true;
break;
}
if (position_valid) {
ev_data.pos(0) = ev_odom.position[0];
ev_data.pos(1) = ev_odom.position[1];
ev_data.pos(2) = ev_odom.position[2];
if (position_frame_valid) {
ev_data.pos = ev_odom_pos;
const float evp_noise_var = sq(_param_ekf2_evp_noise.get());
// position measurement error from ev_data or parameters
if (!_param_ekf2_ev_noise_md.get() && Vector3f(ev_odom.position_variance).isAllFinite()) {
ev_data.posVar(0) = fmaxf(evp_noise_var, ev_odom.position_variance[0]);
ev_data.posVar(1) = fmaxf(evp_noise_var, ev_odom.position_variance[1]);
ev_data.posVar(2) = fmaxf(evp_noise_var, ev_odom.position_variance[2]);
if ((_param_ekf2_ev_noise_md.get() == 0) && ev_odom_pos_var.isAllFinite()) {
ev_data.position_var(0) = fmaxf(evp_noise_var, ev_odom_pos_var(0));
ev_data.position_var(1) = fmaxf(evp_noise_var, ev_odom_pos_var(1));
ev_data.position_var(2) = fmaxf(evp_noise_var, ev_odom_pos_var(2));
} else {
ev_data.posVar.setAll(evp_noise_var);
ev_data.position_var.setAll(evp_noise_var);
}
new_ev_odom = true;
+6 -6
View File
@@ -69,6 +69,7 @@
#include <uORB/topics/distance_sensor.h>
#include <uORB/topics/ekf2_timestamps.h>
#include <uORB/topics/estimator_bias.h>
#include <uORB/topics/estimator_bias3d.h>
#include <uORB/topics/estimator_event_flags.h>
#include <uORB/topics/estimator_gps_status.h>
#include <uORB/topics/estimator_innovations.h>
@@ -142,7 +143,7 @@ private:
void PublishBaroBias(const hrt_abstime &timestamp);
void PublishGnssHgtBias(const hrt_abstime &timestamp);
void PublishRngHgtBias(const hrt_abstime &timestamp);
void PublishEvHgtBias(const hrt_abstime &timestamp);
void PublishEvPosBias(const hrt_abstime &timestamp);
estimator_bias_s fillEstimatorBiasMsg(const BiasEstimator::status &status, uint64_t timestamp_sample_us,
uint64_t timestamp, uint32_t device_id = 0);
void PublishEventFlags(const hrt_abstime &timestamp);
@@ -165,7 +166,7 @@ private:
void UpdateAirspeedSample(ekf2_timestamps_s &ekf2_timestamps);
void UpdateAuxVelSample(ekf2_timestamps_s &ekf2_timestamps);
void UpdateBaroSample(ekf2_timestamps_s &ekf2_timestamps);
bool UpdateExtVisionSample(ekf2_timestamps_s &ekf2_timestamps, vehicle_odometry_s &ev_odom);
bool UpdateExtVisionSample(ekf2_timestamps_s &ekf2_timestamps);
bool UpdateFlowSample(ekf2_timestamps_s &ekf2_timestamps);
void UpdateGpsSample(ekf2_timestamps_s &ekf2_timestamps);
void UpdateMagSample(ekf2_timestamps_s &ekf2_timestamps);
@@ -290,7 +291,7 @@ private:
float _last_baro_bias_published{};
float _last_gnss_hgt_bias_published{};
float _last_rng_hgt_bias_published{};
float _last_ev_hgt_bias_published{};
matrix::Vector3f _last_ev_bias_published{};
float _airspeed_scale_factor{1.0f}; ///< scale factor correction applied to airspeed measurements
hrt_abstime _airspeed_validated_timestamp_last{0};
@@ -339,7 +340,7 @@ private:
uORB::PublicationMulti<estimator_bias_s> _estimator_baro_bias_pub{ORB_ID(estimator_baro_bias)};
uORB::PublicationMulti<estimator_bias_s> _estimator_gnss_hgt_bias_pub{ORB_ID(estimator_gnss_hgt_bias)};
uORB::PublicationMulti<estimator_bias_s> _estimator_rng_hgt_bias_pub{ORB_ID(estimator_rng_hgt_bias)};
uORB::PublicationMulti<estimator_bias_s> _estimator_ev_hgt_bias_pub{ORB_ID(estimator_ev_hgt_bias)};
uORB::PublicationMulti<estimator_bias3d_s> _estimator_ev_pos_bias_pub{ORB_ID(estimator_ev_pos_bias)};
uORB::PublicationMultiData<estimator_event_flags_s> _estimator_event_flags_pub{ORB_ID(estimator_event_flags)};
uORB::PublicationMulti<estimator_gps_status_s> _estimator_gps_status_pub{ORB_ID(estimator_gps_status)};
uORB::PublicationMulti<estimator_innovations_s> _estimator_innovation_test_ratios_pub{ORB_ID(estimator_innovation_test_ratios)};
@@ -349,7 +350,6 @@ private:
uORB::PublicationMulti<estimator_states_s> _estimator_states_pub{ORB_ID(estimator_states)};
uORB::PublicationMulti<estimator_status_flags_s> _estimator_status_flags_pub{ORB_ID(estimator_status_flags)};
uORB::PublicationMulti<estimator_status_s> _estimator_status_pub{ORB_ID(estimator_status)};
uORB::PublicationMulti<vehicle_odometry_s> _estimator_visual_odometry_aligned_pub{ORB_ID(estimator_visual_odometry_aligned)};
uORB::PublicationMulti<vehicle_optical_flow_vel_s> _estimator_optical_flow_vel_pub{ORB_ID(estimator_optical_flow_vel)};
uORB::PublicationMulti<yaw_estimator_status_s> _yaw_est_pub{ORB_ID(yaw_estimator_status)};
@@ -524,7 +524,7 @@ private:
(ParamInt<px4::params::EKF2_EV_NOISE_MD>)
_param_ekf2_ev_noise_md, ///< determine source of vision observation noise
(ParamExtInt<px4::params::EKF2_EV_QMIN>) _param_ekf2_ev_qmin,
(ParamFloat<px4::params::EKF2_EVP_NOISE>)
(ParamExtFloat<px4::params::EKF2_EVP_NOISE>)
_param_ekf2_evp_noise, ///< default position observation noise for exernal vision measurements (m)
(ParamExtFloat<px4::params::EKF2_EVV_NOISE>)
_param_ekf2_evv_noise, ///< default velocity observation noise for exernal vision measurements (m/s)
+40 -13
View File
@@ -73,20 +73,35 @@ bool PreFlightChecker::preFlightCheckHorizVelFailed(const estimator_innovations_
{
bool has_failed = false;
if (_is_using_gps_aiding || _is_using_ev_vel_aiding) {
const Vector2f vel_ne_innov = Vector2f(fmaxf(fabsf(innov.gps_hvel[0]), fabsf(innov.ev_hvel[0])),
fmaxf(fabsf(innov.gps_hvel[1]), fabsf(innov.ev_hvel[1])));
Vector2f vel_ne_innov_lpf;
vel_ne_innov_lpf(0) = _filter_vel_n_innov.update(vel_ne_innov(0), alpha, _vel_innov_spike_lim);
vel_ne_innov_lpf(1) = _filter_vel_n_innov.update(vel_ne_innov(1), alpha, _vel_innov_spike_lim);
if (_is_using_gps_aiding) {
const Vector2f vel_ne_innov{fabsf(innov.gps_hvel[0]), fabsf(innov.gps_hvel[1])};
const Vector2f vel_ne_innov_lpf {
_filter_vel_n_innov.update(vel_ne_innov(0), alpha, _vel_innov_spike_lim),
_filter_vel_e_innov.update(vel_ne_innov(1), alpha, _vel_innov_spike_lim)
};
has_failed |= checkInnov2DFailed(vel_ne_innov_lpf, vel_ne_innov, _vel_innov_test_lim, _vel_innov_spike_lim);
}
if (_is_using_ev_vel_aiding) {
const Vector2f vel_ne_innov{fabsf(innov.ev_hvel[0]), fabsf(innov.ev_hvel[1])};
const Vector2f vel_ne_innov_lpf {
_filter_vel_n_innov.update(vel_ne_innov(0), alpha, _vel_innov_spike_lim),
_filter_vel_e_innov.update(vel_ne_innov(1), alpha, _vel_innov_spike_lim)
};
has_failed |= checkInnov2DFailed(vel_ne_innov_lpf, vel_ne_innov, _vel_innov_test_lim, _vel_innov_spike_lim);
}
if (_is_using_flow_aiding) {
const Vector2f flow_innov = Vector2f(innov.flow);
Vector2f flow_innov_lpf;
flow_innov_lpf(0) = _filter_flow_x_innov.update(flow_innov(0), alpha, _flow_innov_spike_lim);
flow_innov_lpf(1) = _filter_flow_y_innov.update(flow_innov(1), alpha, _flow_innov_spike_lim);
const Vector2f flow_innov(innov.flow);
const Vector2f flow_innov_lpf{
_filter_flow_x_innov.update(flow_innov(0), alpha, _flow_innov_spike_lim),
_filter_flow_y_innov.update(flow_innov(1), alpha, _flow_innov_spike_lim)
};
has_failed |= checkInnov2DFailed(flow_innov_lpf, flow_innov, _flow_innov_test_lim, 5.f * _flow_innov_spike_lim);
}
@@ -95,9 +110,21 @@ bool PreFlightChecker::preFlightCheckHorizVelFailed(const estimator_innovations_
bool PreFlightChecker::preFlightCheckVertVelFailed(const estimator_innovations_s &innov, const float alpha)
{
const float vel_d_innov = fmaxf(fabsf(innov.gps_vvel), fabs(innov.ev_vvel)); // only temporary solution
const float vel_d_innov_lpf = _filter_vel_d_innov.update(vel_d_innov, alpha, _vel_innov_spike_lim);
return checkInnovFailed(vel_d_innov_lpf, vel_d_innov, _vel_innov_test_lim, _vel_innov_spike_lim);
bool has_failed = false;
if (_is_using_gps_aiding) {
const float vel_d_innov = fabsf(innov.gps_vvel);
const float vel_d_innov_lpf = _filter_vel_d_innov.update(vel_d_innov, alpha, _vel_innov_spike_lim);
has_failed |= checkInnovFailed(vel_d_innov_lpf, vel_d_innov, _vel_innov_test_lim, _vel_innov_spike_lim);
}
if (_is_using_ev_vel_aiding) {
const float vel_d_innov = fabsf(innov.ev_vvel);
const float vel_d_innov_lpf = _filter_vel_d_innov.update(vel_d_innov, alpha, _vel_innov_spike_lim);
has_failed |= checkInnovFailed(vel_d_innov_lpf, vel_d_innov, _vel_innov_test_lim, _vel_innov_spike_lim);
}
return has_failed;
}
bool PreFlightChecker::preFlightCheckHeightFailed(const estimator_innovations_s &innov, const float alpha)
+9 -9
View File
@@ -603,10 +603,10 @@ PARAM_DEFINE_FLOAT(EKF2_TAS_GATE, 3.0f);
* 0 : Deprecated, use EKF2_GPS_CTRL instead
* 1 : Set to true to use optical flow data if available
* 2 : Set to true to inhibit IMU delta velocity bias estimation
* 3 : Set to true to enable vision position fusion
* 4 : Set to true to enable vision yaw fusion. Cannot be used if bit position 7 is true.
* 3 : Deprecated, use EKF2_EV_CTRL instead
* 4 : Deprecated, use EKF2_EV_CTRL instead
* 5 : Set to true to enable multi-rotor drag specific force fusion
* 6 : set to true if the EV observations are in a non NED reference frame and need to be rotated before being used
* 6 : Deprecated, use EKF2_EV_CTRL instead
* 7 : Deprecated, use EKF2_GPS_CTRL instead
* 3 : Deprecated, use EKF2_EV_CTRL instead
*
@@ -616,10 +616,10 @@ PARAM_DEFINE_FLOAT(EKF2_TAS_GATE, 3.0f);
* @bit 0 unused
* @bit 1 use optical flow
* @bit 2 inhibit IMU bias estimation
* @bit 3 vision position fusion
* @bit 4 vision yaw fusion
* @bit 3 unused
* @bit 4 unused
* @bit 5 multi-rotor drag fusion
* @bit 6 rotate external vision
* @bit 6 unused
* @bit 7 unused
* @bit 8 unused
* @reboot_required true
@@ -841,7 +841,7 @@ PARAM_DEFINE_FLOAT(EKF2_EVV_NOISE, 0.1f);
* @unit rad
* @decimal 2
*/
PARAM_DEFINE_FLOAT(EKF2_EVA_NOISE, 0.05f);
PARAM_DEFINE_FLOAT(EKF2_EVA_NOISE, 0.1f);
/**
* Measurement noise for the optical flow sensor when it's reported quality metric is at the maximum
@@ -1146,10 +1146,10 @@ PARAM_DEFINE_FLOAT(EKF2_RNG_PITCH, 0.0f);
*
* @group EKF2
* @min 0.1
* @max 2
* @max 3
* @unit m/s
*/
PARAM_DEFINE_FLOAT(EKF2_RNG_A_VMAX, 1.0f);
PARAM_DEFINE_FLOAT(EKF2_RNG_A_VMAX, 2.0f);
/**
* Maximum absolute altitude (height above ground level) allowed for conditional range aid mode.
@@ -63,329 +63,329 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
6090000,1,-0.0095,-0.011,-0.022,0.0053,0.0052,-0.011,0.0021,0.00027,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,1.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.5e-07,0.00038,0.00038,0.00016,0.23,0.23,7,0.1,0.1,0.33,1.8e-08,1.8e-08,5.3e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6190000,1,-0.0095,-0.011,-0.022,0.0056,0.0072,-0.005,0.0027,0.00092,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,-1.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-07,0.00041,0.00041,0.00016,0.27,0.27,4.9,0.13,0.13,0.32,1.8e-08,1.8e-08,5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6290000,1,-0.0095,-0.011,-0.022,0.0071,0.0075,-0.012,0.0033,0.0016,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,-1.9e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-07,0.00043,0.00043,0.00016,0.31,0.31,3.2,0.17,0.17,0.3,1.8e-08,1.8e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6390000,0.71,0.0014,-0.014,0.71,0.0048,0.0076,-0.05,0.0025,0.0017,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,4e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00076,0.00034,0.00034,0.00085,0.22,0.22,2.3,0.13,0.13,0.29,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6490000,0.71,0.0014,-0.014,0.71,0.0043,0.0083,-0.052,0.0029,0.0025,-3.7e+02,-1.6e-05,-5.6e-05,4.1e-07,0,0,-8.7e-08,0.21,0.0021,0.44,0,0,0,0,0,0.00051,0.00034,0.00034,0.00056,0.22,0.22,1.5,0.16,0.16,0.26,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6590000,0.71,0.0015,-0.014,0.71,0.0036,0.0085,-0.099,0.0034,0.0033,-3.7e+02,-1.6e-05,-5.6e-05,3.6e-07,0,0,1.7e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00039,0.00034,0.00034,0.00043,0.23,0.23,1.1,0.19,0.19,0.23,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6690000,0.7,0.0015,-0.014,0.71,0.0037,0.0095,-0.076,0.0037,0.0042,-3.7e+02,-1.6e-05,-5.6e-05,3e-07,0,0,-1.5e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00031,0.00034,0.00034,0.00035,0.24,0.24,0.78,0.23,0.23,0.21,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6790000,0.71,0.0015,-0.014,0.71,0.0021,0.0095,-0.11,0.004,0.0052,-3.7e+02,-1.6e-05,-5.6e-05,3.3e-07,0,0,8.5e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00027,0.00034,0.00034,0.0003,0.25,0.25,0.6,0.28,0.28,0.2,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6890000,0.71,0.0015,-0.014,0.71,-0.00021,0.01,-0.12,0.0041,0.0062,-3.7e+02,-1.6e-05,-5.6e-05,3.4e-07,0,0,3.4e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00024,0.00035,0.00035,0.00026,0.26,0.26,0.46,0.33,0.33,0.18,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6990000,0.7,0.0016,-0.014,0.71,-0.00055,0.011,-0.12,0.004,0.0072,-3.7e+02,-1.6e-05,-5.6e-05,1.6e-07,0,0,-2.7e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00021,0.00035,0.00035,0.00023,0.28,0.28,0.36,0.38,0.38,0.16,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7090000,0.7,0.0016,-0.014,0.71,-0.0014,0.011,-0.13,0.0039,0.0083,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-08,0,0,-6.3e-06,0.21,0.0021,0.44,0,0,0,0,0,0.0002,0.00036,0.00036,0.00022,0.3,0.3,0.29,0.44,0.44,0.16,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7190000,0.7,0.0016,-0.014,0.71,-0.0034,0.011,-0.15,0.0037,0.0093,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-07,0,0,-4.1e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00018,0.00036,0.00036,0.0002,0.32,0.32,0.24,0.51,0.51,0.15,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7290000,0.7,0.0016,-0.014,0.71,-0.0052,0.011,-0.15,0.0033,0.01,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,0,0,-1.1e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00017,0.00037,0.00037,0.00018,0.34,0.34,0.2,0.58,0.58,0.14,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7390000,0.7,0.0017,-0.014,0.71,-0.0056,0.012,-0.16,0.0027,0.011,-3.7e+02,-1.6e-05,-5.6e-05,-1.3e-07,0,0,-1.2e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00016,0.00038,0.00038,0.00017,0.37,0.37,0.18,0.66,0.66,0.13,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7490000,0.7,0.0017,-0.014,0.71,-0.0076,0.013,-0.16,0.002,0.013,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,0,0,-2e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.00039,0.00039,0.00016,0.4,0.4,0.15,0.76,0.76,0.12,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7590000,0.7,0.0017,-0.014,0.71,-0.0098,0.014,-0.17,0.0011,0.014,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-08,0,0,-2.9e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00039,0.00039,0.00015,0.43,0.43,0.14,0.85,0.85,0.12,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7690000,0.7,0.0018,-0.014,0.71,-0.012,0.015,-0.16,2.3e-05,0.015,-3.7e+02,-1.6e-05,-5.6e-05,-4.5e-08,0,0,-4.9e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.0004,0.0004,0.00015,0.47,0.47,0.13,0.96,0.96,0.11,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7790000,0.7,0.0019,-0.014,0.71,-0.014,0.016,-0.16,-0.0013,0.017,-3.7e+02,-1.6e-05,-5.6e-05,-3.7e-07,0,0,-6.9e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00041,0.00041,0.00014,0.51,0.51,0.12,1.1,1.1,0.11,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
7890000,0.7,0.0019,-0.014,0.71,-0.017,0.018,-0.16,-0.0028,0.018,-3.7e+02,-1.6e-05,-5.6e-05,-2.7e-07,0,0,-9.5e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00042,0.00042,0.00014,0.55,0.55,0.11,1.2,1.2,0.1,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
7990000,0.7,0.0019,-0.014,0.71,-0.019,0.019,-0.16,-0.0046,0.02,-3.7e+02,-1.6e-05,-5.6e-05,-1.6e-07,0,0,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00043,0.00043,0.00013,0.6,0.59,0.1,1.3,1.3,0.099,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
8090000,0.7,0.0019,-0.014,0.71,-0.021,0.02,-0.17,-0.0066,0.022,-3.7e+02,-1.6e-05,-5.6e-05,6.1e-08,0,0,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00045,0.00045,0.00013,0.65,0.65,0.1,1.5,1.5,0.097,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
8190000,0.7,0.0019,-0.014,0.71,-0.024,0.021,-0.18,-0.0088,0.023,-3.7e+02,-1.6e-05,-5.6e-05,-2.1e-07,0,0,-0.00013,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00046,0.00046,0.00012,0.69,0.69,0.099,1.7,1.7,0.094,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
8290000,0.7,0.002,-0.014,0.71,-0.026,0.022,-0.17,-0.011,0.025,-3.7e+02,-1.6e-05,-5.6e-05,-4e-07,0,0,-0.00017,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00047,0.00047,0.00012,0.75,0.75,0.097,1.9,1.9,0.091,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0
8390000,0.7,0.002,-0.014,0.71,-0.029,0.023,-0.17,-0.014,0.028,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,0,0,-0.00021,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00048,0.00048,0.00012,0.81,0.81,0.097,2.1,2.1,0.091,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0
8490000,0.7,0.002,-0.014,0.71,-0.031,0.025,-0.17,-0.017,0.029,-3.7e+02,-1.6e-05,-5.6e-05,-3e-07,0,0,-0.00025,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00049,0.00049,0.00012,0.87,0.87,0.096,2.3,2.3,0.089,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0
8590000,0.7,0.002,-0.014,0.71,-0.034,0.027,-0.17,-0.021,0.032,-3.7e+02,-1.6e-05,-5.6e-05,-6.2e-07,0,0,-0.00029,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00051,0.00051,0.00011,0.94,0.94,0.095,2.5,2.5,0.088,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
8690000,0.7,0.0021,-0.014,0.71,-0.037,0.028,-0.16,-0.024,0.033,-3.7e+02,-1.6e-05,-5.6e-05,-2.5e-07,0,0,-0.00034,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00052,0.00052,0.00011,0.99,0.99,0.096,2.7,2.7,0.088,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
8790000,0.7,0.0021,-0.014,0.71,-0.04,0.03,-0.15,-0.028,0.036,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,0,0,-0.00041,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00054,0.00054,0.00011,1.1,1.1,0.095,3,3,0.087,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,3.1e-06,0,0,0,0,0,0,0,0
8890000,0.7,0.0021,-0.014,0.71,-0.043,0.03,-0.15,-0.032,0.038,-3.7e+02,-1.6e-05,-5.6e-05,-6.2e-07,0,0,-0.00045,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00055,0.00055,0.00011,1.1,1.1,0.095,3.3,3.3,0.086,1.3e-08,1.3e-08,4.5e-09,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0
8990000,0.7,0.0021,-0.014,0.71,-0.045,0.031,-0.14,-0.036,0.04,-3.7e+02,-1.6e-05,-5.6e-05,-9.6e-07,0,0,-0.0005,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00056,0.00056,0.00011,1.2,1.2,0.096,3.6,3.6,0.087,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0
9090000,0.7,0.0022,-0.014,0.71,-0.048,0.031,-0.14,-0.04,0.042,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-06,0,0,-0.00053,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00057,0.00057,0.00011,1.3,1.3,0.095,3.9,3.9,0.086,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0
9190000,0.7,0.0022,-0.014,0.71,-0.05,0.032,-0.14,-0.045,0.045,-3.7e+02,-1.6e-05,-5.6e-05,-5.2e-07,0,0,-0.00057,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.00059,0.00059,0.0001,1.4,1.4,0.094,4.3,4.3,0.085,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.7e-06,0,0,0,0,0,0,0,0
9290000,0.7,0.0022,-0.014,0.71,-0.051,0.033,-0.14,-0.048,0.046,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,0,0,-0.00061,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.0006,0.0006,0.0001,1.4,1.4,0.093,4.5,4.5,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0
9390000,0.7,0.0022,-0.014,0.71,-0.053,0.035,-0.14,-0.054,0.049,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-07,0,0,-0.00064,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00062,0.00061,0.0001,1.5,1.5,0.093,5,5,0.086,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0
9490000,0.7,0.0022,-0.014,0.71,-0.054,0.035,-0.13,-0.057,0.05,-3.7e+02,-1.6e-05,-5.6e-05,1.3e-08,0,0,-0.00068,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00062,0.00062,0.0001,1.6,1.6,0.091,5.2,5.2,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.3e-06,0,0,0,0,0,0,0,0
9590000,0.7,0.0022,-0.014,0.71,-0.058,0.036,-0.13,-0.062,0.053,-3.7e+02,-1.6e-05,-5.6e-05,1.4e-07,0,0,-0.00072,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00064,0.00064,0.0001,1.7,1.7,0.089,5.8,5.8,0.085,1.3e-08,1.3e-08,4.2e-09,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0
9690000,0.7,0.0022,-0.014,0.71,-0.058,0.037,-0.12,-0.065,0.053,-3.7e+02,-1.6e-05,-5.6e-05,-4.4e-07,0,0,-0.00077,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00064,0.00064,0.0001,1.7,1.7,0.089,6,6,0.086,1.3e-08,1.3e-08,4.2e-09,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0
9790000,0.7,0.0022,-0.014,0.71,-0.06,0.039,-0.11,-0.071,0.056,-3.7e+02,-1.6e-05,-5.6e-05,-9.9e-08,0,0,-0.00082,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00066,0.00066,0.0001,1.8,1.8,0.087,6.6,6.6,0.085,1.3e-08,1.3e-08,4.1e-09,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0
9890000,0.7,0.0022,-0.014,0.71,-0.06,0.039,-0.11,-0.073,0.056,-3.7e+02,-1.6e-05,-5.6e-05,-1.8e-07,0,0,-0.00085,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00066,0.00066,9.9e-05,1.8,1.8,0.084,6.8,6.8,0.085,1.2e-08,1.2e-08,4.1e-09,4e-06,4e-06,1.8e-06,0,0,0,0,0,0,0,0
9990000,0.7,0.0023,-0.014,0.71,-0.063,0.04,-0.1,-0.079,0.06,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,0,0,-0.00088,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00068,0.00068,9.9e-05,2,2,0.083,7.4,7.4,0.086,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0
10090000,0.7,0.0023,-0.014,0.71,-0.061,0.039,-0.097,-0.079,0.059,-3.7e+02,-1.5e-05,-5.6e-05,-3.7e-07,0,0,-0.00091,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00067,0.00067,9.8e-05,2,2,0.08,7.5,7.5,0.085,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0
10190000,0.7,0.0023,-0.014,0.71,-0.064,0.042,-0.096,-0.086,0.063,-3.7e+02,-1.5e-05,-5.6e-05,-1.2e-06,0,0,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00069,0.00069,9.8e-05,2.1,2.1,0.078,8.3,8.3,0.084,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
10290000,0.7,0.0022,-0.014,0.71,-0.062,0.04,-0.084,-0.085,0.061,-3.7e+02,-1.5e-05,-5.6e-05,-1.7e-06,0,0,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00068,0.00068,9.8e-05,2.1,2.1,0.076,8.3,8.3,0.085,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
10390000,0.7,0.0022,-0.014,0.71,0.0091,-0.019,0.0096,0.00085,-0.0017,-3.7e+02,-1.5e-05,-5.6e-05,-1.7e-06,-6.6e-10,4.8e-10,-0.001,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0007,0.0007,9.7e-05,0.25,0.25,0.56,0.25,0.25,0.078,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0
10490000,0.7,0.0023,-0.014,0.71,0.0074,-0.017,0.023,0.0017,-0.0036,-3.7e+02,-1.5e-05,-5.6e-05,-2.2e-06,-1.7e-08,1.2e-08,-0.001,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00073,0.00073,9.7e-05,0.26,0.26,0.55,0.26,0.26,0.08,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
10590000,0.7,0.0024,-0.014,0.71,0.0069,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-1.5e-05,-5.6e-05,-2.2e-06,-2.7e-06,4.5e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00073,0.00073,9.7e-05,0.14,0.14,0.27,0.13,0.13,0.073,1.2e-08,1.2e-08,3.7e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
10690000,0.7,0.0024,-0.014,0.71,0.0044,-0.0059,0.03,0.0024,-0.0015,-3.7e+02,-1.5e-05,-5.6e-05,-2.4e-06,-2.7e-06,4.7e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00076,0.00076,9.7e-05,0.15,0.15,0.26,0.14,0.14,0.078,1.2e-08,1.2e-08,3.7e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10790000,0.7,0.0024,-0.014,0.71,0.004,-0.0032,0.024,0.0026,-0.00073,-3.7e+02,-1.5e-05,-5.5e-05,-2.4e-06,-4.3e-06,2.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00074,0.00073,9.7e-05,0.11,0.11,0.17,0.091,0.091,0.072,1.1e-08,1.1e-08,3.6e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10890000,0.7,0.0024,-0.014,0.71,0.0023,-0.0019,0.02,0.0029,-0.00095,-3.7e+02,-1.5e-05,-5.5e-05,-2.5e-06,-4.3e-06,2.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00076,0.00076,9.6e-05,0.13,0.13,0.16,0.098,0.098,0.075,1.1e-08,1.1e-08,3.5e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10990000,0.7,0.0023,-0.014,0.71,0.0052,0.0032,0.014,0.0046,-0.0022,-3.7e+02,-1.4e-05,-5.5e-05,-2e-06,-8.3e-06,8.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0007,0.00069,9.7e-05,0.1,0.1,0.12,0.073,0.073,0.071,1.1e-08,1.1e-08,3.5e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
11090000,0.7,0.0023,-0.014,0.71,0.0035,0.0056,0.019,0.0051,-0.0018,-3.7e+02,-1.4e-05,-5.5e-05,-1.5e-06,-8.3e-06,8.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00072,0.00072,9.6e-05,0.13,0.13,0.11,0.08,0.08,0.074,1.1e-08,1.1e-08,3.4e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
11190000,0.7,0.0022,-0.014,0.71,0.0087,0.0081,0.0077,0.0066,-0.0028,-3.7e+02,-1.3e-05,-5.5e-05,-2e-06,-9.5e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00062,0.00062,9.6e-05,0.1,0.1,0.084,0.063,0.063,0.069,9.4e-09,9.5e-09,3.4e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11290000,0.7,0.0023,-0.014,0.71,0.0082,0.011,0.0074,0.0075,-0.0018,-3.7e+02,-1.3e-05,-5.5e-05,-2.7e-06,-9.5e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00064,0.00064,9.6e-05,0.13,0.13,0.078,0.071,0.071,0.072,9.4e-09,9.5e-09,3.3e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11390000,0.7,0.0023,-0.014,0.71,0.0037,0.009,0.0017,0.0054,-0.002,-3.7e+02,-1.4e-05,-5.5e-05,-3.2e-06,-5.3e-06,1.2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00054,0.00054,9.6e-05,0.1,0.1,0.063,0.058,0.058,0.068,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11490000,0.7,0.0023,-0.014,0.71,0.00095,0.012,0.0025,0.0056,-0.00092,-3.7e+02,-1.4e-05,-5.5e-05,-4.2e-06,-5.3e-06,1.2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00056,0.00056,9.6e-05,0.13,0.13,0.058,0.066,0.066,0.069,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11590000,0.7,0.0022,-0.014,0.71,-0.0029,0.01,-0.0034,0.0044,-0.0014,-3.7e+02,-1.4e-05,-5.6e-05,-4.4e-06,-1e-06,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00046,0.00046,9.6e-05,0.1,0.1,0.049,0.054,0.054,0.066,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11690000,0.7,0.0022,-0.014,0.71,-0.006,0.013,-0.008,0.0039,-0.00027,-3.7e+02,-1.4e-05,-5.6e-05,-4.7e-06,-9.5e-07,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00047,0.00047,9.6e-05,0.12,0.12,0.046,0.063,0.063,0.066,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11790000,0.7,0.0022,-0.014,0.71,-0.011,0.013,-0.0098,0.0017,0.00056,-3.7e+02,-1.4e-05,-5.6e-05,-4.8e-06,1.4e-07,9.7e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00039,0.00039,9.6e-05,0.096,0.096,0.039,0.052,0.052,0.063,6.6e-09,6.6e-09,3e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11890000,0.7,0.0022,-0.014,0.71,-0.013,0.014,-0.011,0.00052,0.0019,-3.7e+02,-1.4e-05,-5.6e-05,-5.3e-06,8.2e-08,9.7e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0004,0.0004,9.6e-05,0.12,0.12,0.037,0.061,0.061,0.063,6.6e-09,6.6e-09,2.9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11990000,0.7,0.0022,-0.014,0.71,-0.014,0.014,-0.016,-0.0004,0.0023,-3.7e+02,-1.4e-05,-5.6e-05,-5.1e-06,1.5e-06,1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00034,0.00034,9.6e-05,0.09,0.09,0.033,0.051,0.051,0.061,5.9e-09,5.9e-09,2.9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12090000,0.7,0.0022,-0.014,0.71,-0.016,0.016,-0.022,-0.0019,0.0038,-3.7e+02,-1.4e-05,-5.6e-05,-4.7e-06,1.7e-06,1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00035,0.00035,9.6e-05,0.11,0.11,0.031,0.06,0.06,0.061,5.9e-09,5.9e-09,2.8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12190000,0.7,0.0018,-0.014,0.71,-0.0089,0.013,-0.017,0.0014,0.0019,-3.7e+02,-1.3e-05,-5.7e-05,-4.5e-06,4.4e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0003,0.0003,9.5e-05,0.085,0.085,0.028,0.051,0.051,0.059,5.4e-09,5.4e-09,2.8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12290000,0.7,0.0018,-0.014,0.71,-0.012,0.015,-0.016,0.00035,0.0033,-3.7e+02,-1.3e-05,-5.7e-05,-4.3e-06,4.1e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00031,0.00031,9.6e-05,0.1,0.1,0.028,0.059,0.059,0.059,5.4e-09,5.4e-09,2.7e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12390000,0.7,0.0015,-0.014,0.71,-0.0059,0.011,-0.015,0.0029,0.0017,-3.7e+02,-1.3e-05,-5.8e-05,-4.6e-06,5.9e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00027,0.00027,9.5e-05,0.079,0.079,0.026,0.05,0.05,0.057,5e-09,5e-09,2.6e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0
12490000,0.7,0.0015,-0.014,0.71,-0.0072,0.013,-0.018,0.0023,0.0029,-3.7e+02,-1.3e-05,-5.8e-05,-5.1e-06,5.9e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00028,0.00028,9.5e-05,0.092,0.092,0.026,0.059,0.059,0.057,5e-09,5e-09,2.6e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0
12590000,0.7,0.0016,-0.014,0.71,-0.015,0.011,-0.023,-0.0028,0.0015,-3.7e+02,-1.3e-05,-5.8e-05,-5e-06,7.3e-06,1.7e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00025,0.00025,9.5e-05,0.073,0.073,0.025,0.05,0.05,0.055,4.7e-09,4.7e-09,2.5e-09,3.6e-06,3.6e-06,9.8e-07,0,0,0,0,0,0,0,0
12690000,0.7,0.0016,-0.014,0.71,-0.015,0.012,-0.027,-0.0043,0.0026,-3.7e+02,-1.3e-05,-5.8e-05,-5.2e-06,7.5e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00026,0.00026,9.5e-05,0.085,0.085,0.025,0.058,0.058,0.055,4.7e-09,4.7e-09,2.5e-09,3.6e-06,3.6e-06,9.8e-07,0,0,0,0,0,0,0,0
12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0092,-0.03,-0.0077,0.0013,-3.7e+02,-1.4e-05,-5.8e-05,-5e-06,8e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00023,0.00023,9.5e-05,0.068,0.068,0.024,0.049,0.049,0.053,4.4e-09,4.4e-09,2.4e-09,3.6e-06,3.6e-06,9.7e-07,0,0,0,0,0,0,0,0
12890000,0.7,0.0016,-0.013,0.71,-0.021,0.0091,-0.03,-0.0097,0.0022,-3.7e+02,-1.4e-05,-5.8e-05,-4.8e-06,7.4e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00024,0.00024,9.5e-05,0.079,0.079,0.025,0.058,0.058,0.054,4.4e-09,4.4e-09,2.4e-09,3.6e-06,3.6e-06,9.6e-07,0,0,0,0,0,0,0,0
12990000,0.7,0.0012,-0.014,0.71,-0.0088,0.0066,-0.03,-0.0011,0.0012,-3.7e+02,-1.3e-05,-5.9e-05,-4.2e-06,7.3e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00022,9.5e-05,0.064,0.064,0.025,0.049,0.049,0.052,4.2e-09,4.2e-09,2.3e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0
13090000,0.7,0.0012,-0.014,0.71,-0.0096,0.0068,-0.03,-0.002,0.0018,-3.7e+02,-1.3e-05,-5.9e-05,-4.7e-06,6.9e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00023,0.00023,9.5e-05,0.073,0.073,0.025,0.057,0.057,0.052,4.2e-09,4.2e-09,2.3e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0
13190000,0.7,0.00099,-0.014,0.71,-0.00038,0.0062,-0.027,0.0044,0.0012,-3.7e+02,-1.2e-05,-5.9e-05,-4.6e-06,5.6e-06,2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.06,0.06,0.025,0.049,0.049,0.051,4e-09,4e-09,2.2e-09,3.6e-06,3.6e-06,9.1e-07,0,0,0,0,0,0,0,0
13290000,0.7,0.001,-0.014,0.71,-0.00066,0.007,-0.024,0.0043,0.0018,-3.7e+02,-1.2e-05,-5.9e-05,-4.1e-06,4.3e-06,2.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00022,9.4e-05,0.068,0.069,0.027,0.057,0.057,0.051,4e-09,4e-09,2.2e-09,3.6e-06,3.6e-06,9.1e-07,0,0,0,0,0,0,0,0
13390000,0.7,0.00085,-0.014,0.71,0.00026,0.006,-0.02,0.0033,0.0011,-3.7e+02,-1.2e-05,-5.9e-05,-3.6e-06,2.6e-06,2.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.056,0.056,0.026,0.049,0.049,0.05,3.8e-09,3.8e-09,2.1e-09,3.6e-06,3.6e-06,8.8e-07,0,0,0,0,0,0,0,0
13490000,0.7,0.00087,-0.014,0.71,-0.00025,0.0059,-0.019,0.0033,0.0017,-3.7e+02,-1.2e-05,-5.9e-05,-3.1e-06,1.8e-06,2.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00021,9.4e-05,0.064,0.064,0.028,0.057,0.057,0.05,3.8e-09,3.8e-09,2.1e-09,3.6e-06,3.6e-06,8.7e-07,0,0,0,0,0,0,0,0
13590000,0.7,0.00081,-0.014,0.71,7.7e-05,0.0061,-0.021,0.0024,0.001,-3.7e+02,-1.2e-05,-5.9e-05,-3.4e-06,1.5e-06,2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.4e-05,0.053,0.053,0.028,0.049,0.049,0.05,3.6e-09,3.6e-09,2e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0
13690000,0.7,0.00079,-0.014,0.71,0.00075,0.0078,-0.025,0.0024,0.0017,-3.7e+02,-1.1e-05,-5.9e-05,-2.7e-06,1.8e-06,2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.061,0.061,0.029,0.056,0.056,0.05,3.6e-09,3.6e-09,2e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0
13790000,0.7,0.00067,-0.014,0.71,0.0014,0.0036,-0.027,0.0035,-0.00062,-3.7e+02,-1.1e-05,-6e-05,-2.7e-06,-3.4e-07,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.3e-05,0.051,0.051,0.029,0.048,0.048,0.049,3.4e-09,3.4e-09,1.9e-09,3.6e-06,3.6e-06,7.9e-07,0,0,0,0,0,0,0,0
13890000,0.7,0.00063,-0.014,0.71,0.0019,0.0035,-0.031,0.0036,-0.00029,-3.7e+02,-1.1e-05,-6e-05,-2.3e-06,-3.5e-08,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.3e-05,0.058,0.058,0.03,0.056,0.056,0.05,3.4e-09,3.4e-09,1.9e-09,3.6e-06,3.6e-06,7.8e-07,0,0,0,0,0,0,0,0
13990000,0.7,0.00056,-0.014,0.71,0.0022,0.001,-0.03,0.0045,-0.002,-3.7e+02,-1.1e-05,-6e-05,-2.2e-06,-2.7e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.049,0.049,0.03,0.048,0.048,0.05,3.2e-09,3.2e-09,1.8e-09,3.6e-06,3.6e-06,7.4e-07,0,0,0,0,0,0,0,0
14090000,0.7,0.00054,-0.014,0.71,0.0023,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-1.1e-05,-6e-05,-1.5e-06,-2.6e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.055,0.055,0.031,0.056,0.056,0.05,3.2e-09,3.2e-09,1.8e-09,3.6e-06,3.6e-06,7.3e-07,0,0,0,0,0,0,0,0
14190000,0.7,0.00044,-0.014,0.71,0.0057,0.00062,-0.033,0.0068,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-1.1e-06,-2.4e-06,1.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.047,0.047,0.031,0.048,0.048,0.05,3.1e-09,3.1e-09,1.8e-09,3.6e-06,3.6e-06,6.9e-07,0,0,0,0,0,0,0,0
14290000,0.7,0.00045,-0.014,0.71,0.0065,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-8.2e-07,-3e-06,1.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.053,0.053,0.032,0.055,0.055,0.051,3.1e-09,3.1e-09,1.7e-09,3.6e-06,3.6e-06,6.7e-07,0,0,0,0,0,0,0,0
14390000,0.7,0.00036,-0.014,0.71,0.0083,0.0023,-0.034,0.0087,-0.0013,-3.7e+02,-1.1e-05,-6e-05,-1.5e-07,-3.1e-06,1.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00019,0.00019,9.2e-05,0.045,0.045,0.031,0.048,0.048,0.05,2.9e-09,2.9e-09,1.7e-09,3.6e-06,3.6e-06,6.3e-07,0,0,0,0,0,0,0,0
14490000,0.7,0.00034,-0.013,0.71,0.0083,0.0035,-0.037,0.0095,-0.001,-3.7e+02,-1e-05,-6e-05,7.6e-08,-2.6e-06,1.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.2e-05,0.051,0.051,0.032,0.055,0.055,0.051,2.9e-09,2.9e-09,1.6e-09,3.6e-06,3.6e-06,6.2e-07,0,0,0,0,0,0,0,0
14590000,0.7,0.00033,-0.013,0.71,0.0049,0.0019,-0.038,0.006,-0.0025,-3.7e+02,-1.1e-05,-6.1e-05,1.4e-07,-6.3e-06,1.6e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.2e-05,0.044,0.044,0.031,0.047,0.047,0.051,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.8e-07,0,0,0,0,0,0,0,0
14690000,0.7,0.00029,-0.013,0.71,0.0062,-0.0011,-0.034,0.0066,-0.0024,-3.7e+02,-1.1e-05,-6.1e-05,6.2e-07,-7.4e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.2e-05,0.049,0.049,0.032,0.054,0.054,0.051,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.6e-07,0,0,0,0,0,0,0,0
14790000,0.7,0.00031,-0.013,0.71,0.003,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-1.1e-05,-6.1e-05,7.8e-07,-1.1e-05,2.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.1e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-09,2.6e-09,1.5e-09,3.6e-06,3.6e-06,5.3e-07,0,0,0,0,0,0,0,0
14890000,0.7,0.00031,-0.013,0.71,0.0046,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-1.1e-05,-6.1e-05,1.1e-06,-1.1e-05,2.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.1e-05,0.048,0.048,0.031,0.054,0.054,0.052,2.6e-09,2.6e-09,1.5e-09,3.6e-06,3.6e-06,5.1e-07,0,0,0,0,0,0,0,0
14990000,0.7,0.0003,-0.013,0.71,0.0034,-0.0019,-0.029,0.0031,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,1e-06,-1.2e-05,2.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.042,0.042,0.03,0.047,0.047,0.051,2.4e-09,2.4e-09,1.5e-09,3.5e-06,3.5e-06,4.8e-07,0,0,0,0,0,0,0,0
15090000,0.7,0.00023,-0.013,0.71,0.0038,-0.0021,-0.032,0.0035,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.1e-06,-1.1e-05,2.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.047,0.047,0.031,0.054,0.054,0.052,2.4e-09,2.4e-09,1.4e-09,3.5e-06,3.5e-06,4.6e-07,0,0,0,0,0,0,0,0
15190000,0.7,0.00025,-0.013,0.71,0.0032,-0.00083,-0.029,0.0028,-0.0024,-3.7e+02,-1.2e-05,-6.1e-05,1e-06,-1.1e-05,2.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.041,0.041,0.03,0.047,0.047,0.052,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4.3e-07,0,0,0,0,0,0,0,0
15290000,0.7,0.0002,-0.013,0.71,0.0038,-0.00068,-0.027,0.0031,-0.0025,-3.7e+02,-1.2e-05,-6.1e-05,1.4e-06,-1.2e-05,2.6e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9e-05,0.046,0.046,0.03,0.054,0.054,0.052,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4.2e-07,0,0,0,0,0,0,0,0
15390000,0.7,0.00021,-0.013,0.71,0.003,-0.00032,-0.025,0.00054,-0.002,-3.7e+02,-1.2e-05,-6.1e-05,2e-06,-1.3e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00018,0.00018,9e-05,0.04,0.04,0.029,0.047,0.047,0.051,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.9e-07,0,0,0,0,0,0,0,0
15490000,0.7,0.00023,-0.013,0.71,0.0043,-0.00071,-0.025,0.00091,-0.0021,-3.7e+02,-1.2e-05,-6.1e-05,1.7e-06,-1.2e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9e-05,0.045,0.045,0.029,0.053,0.053,0.053,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.7e-07,0,0,0,0,0,0,0,0
15590000,0.7,0.00024,-0.013,0.71,0.0024,-0.0007,-0.023,-0.0013,-0.0017,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.2e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,9e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-09,1.9e-09,1.3e-09,3.5e-06,3.5e-06,3.5e-07,0,0,0,0,0,0,0,0
15690000,0.7,0.00025,-0.013,0.71,0.0027,-0.00088,-0.024,-0.0011,-0.0018,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.2e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00018,8.9e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-09,1.9e-09,1.2e-09,3.5e-06,3.5e-06,3.3e-07,0,0,0,0,0,0,0,0
15790000,0.7,0.00021,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00098,-0.0028,-3.7e+02,-1.2e-05,-6.1e-05,1.6e-06,-1.5e-05,3.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,8.9e-05,0.039,0.039,0.027,0.046,0.046,0.051,1.8e-09,1.8e-09,1.2e-09,3.4e-06,3.4e-06,3.1e-07,0,0,0,0,0,0,0,0
15890000,0.7,0.00016,-0.013,0.71,0.0042,-0.003,-0.024,-0.00058,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.7e-06,-1.5e-05,3.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,8.9e-05,0.044,0.044,0.027,0.053,0.053,0.052,1.8e-09,1.8e-09,1.2e-09,3.4e-06,3.4e-06,3e-07,0,0,0,0,0,0,0,0
15990000,0.7,0.0001,-0.013,0.71,0.004,-0.0039,-0.02,-0.00066,-0.0039,-3.7e+02,-1.2e-05,-6.1e-05,2.1e-06,-1.8e-05,3.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.9e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.7e-09,1.7e-09,1.2e-09,3.4e-06,3.4e-06,2.8e-07,0,0,0,0,0,0,0,0
16090000,0.71,0.0001,-0.013,0.71,0.0058,-0.0042,-0.016,-0.00019,-0.0043,-3.7e+02,-1.2e-05,-6.1e-05,2.7e-06,-1.9e-05,3.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,8.8e-05,0.043,0.043,0.025,0.053,0.053,0.052,1.7e-09,1.7e-09,1.1e-09,3.4e-06,3.4e-06,2.7e-07,0,0,0,0,0,0,0,0
16190000,0.71,0.00013,-0.013,0.71,0.0057,-0.0034,-0.015,-0.0004,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,2.8e-06,-1.8e-05,3.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.8e-05,0.038,0.038,0.025,0.046,0.046,0.051,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.5e-07,0,0,0,0,0,0,0,0
16290000,0.71,0.00014,-0.013,0.71,0.0074,-0.0042,-0.016,0.00026,-0.0039,-3.7e+02,-1.2e-05,-6.1e-05,3.4e-06,-1.7e-05,3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.8e-05,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.4e-07,0,0,0,0,0,0,0,0
16390000,0.71,0.00013,-0.013,0.71,0.0063,-0.0044,-0.015,-6.7e-05,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,3.3e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.8e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-09,1.4e-09,1.1e-09,3.3e-06,3.4e-06,2.2e-07,0,0,0,0,0,0,0,0
16490000,0.71,0.00015,-0.013,0.71,0.0055,-0.004,-0.018,0.00049,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,3.4e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.7e-05,0.042,0.042,0.023,0.052,0.052,0.052,1.4e-09,1.4e-09,1e-09,3.3e-06,3.4e-06,2.1e-07,0,0,0,0,0,0,0,0
16590000,0.71,0.00041,-0.013,0.71,0.0019,-0.0012,-0.018,-0.0025,-7.8e-05,-3.7e+02,-1.3e-05,-6e-05,3.5e-06,-9e-06,4.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00016,0.00016,8.7e-05,0.037,0.037,0.022,0.046,0.046,0.051,1.3e-09,1.3e-09,1e-09,3.3e-06,3.3e-06,2e-07,0,0,0,0,0,0,0,0
16690000,0.71,0.0004,-0.013,0.71,0.0021,-0.00073,-0.015,-0.0023,-0.00018,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-9.6e-06,4.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00017,0.00016,8.7e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.3e-09,1.3e-09,9.9e-10,3.3e-06,3.3e-06,1.9e-07,0,0,0,0,0,0,0,0
16790000,0.71,0.00055,-0.013,0.71,-0.0013,0.0015,-0.014,-0.0047,0.0025,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-3.9e-06,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.7e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.2e-09,1.2e-09,9.7e-10,3.3e-06,3.3e-06,1.8e-07,0,0,0,0,0,0,0,0
16890000,0.71,0.00056,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0048,0.0027,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-4.3e-06,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.6e-05,0.041,0.041,0.021,0.052,0.052,0.051,1.2e-09,1.2e-09,9.5e-10,3.3e-06,3.3e-06,1.7e-07,0,0,0,0,0,0,0,0
16990000,0.71,0.0005,-0.013,0.71,-0.0016,0.00033,-0.011,-0.0052,0.00086,-3.7e+02,-1.3e-05,-6e-05,2.9e-06,-8.4e-06,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00015,0.00015,8.6e-05,0.036,0.036,0.02,0.046,0.046,0.05,1.1e-09,1.1e-09,9.2e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0
17090000,0.71,0.00047,-0.013,0.71,-0.00076,0.0013,-0.01,-0.0053,0.00091,-3.7e+02,-1.3e-05,-6e-05,3e-06,-8.3e-06,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00016,0.00016,8.6e-05,0.04,0.04,0.02,0.052,0.052,0.05,1.1e-09,1.1e-09,9e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0
17190000,0.71,0.00046,-0.013,0.71,-0.00031,0.0013,-0.011,-0.0057,-0.00054,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.6e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.5e-10,9.6e-10,8.9e-10,3.2e-06,3.2e-06,1.5e-07,0,0,0,0,0,0,0,0
17290000,0.71,0.00043,-0.013,0.71,0.0018,0.0023,-0.0067,-0.0056,-0.00038,-3.7e+02,-1.4e-05,-6e-05,3e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.5e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.5e-10,9.6e-10,8.7e-10,3.2e-06,3.2e-06,1.4e-07,0,0,0,0,0,0,0,0
17390000,0.71,0.0004,-0.013,0.71,0.0024,0.0015,-0.0047,-0.0047,-0.0016,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00014,8.5e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.7e-10,8.7e-10,8.5e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
17490000,0.71,0.00039,-0.013,0.71,0.003,0.001,-0.003,-0.0044,-0.0015,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00015,0.00015,8.5e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.7e-10,8.7e-10,8.3e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
17590000,0.71,0.0003,-0.013,0.71,0.0042,-0.00014,0.0025,-0.0037,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.4e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.5e-05,0.034,0.034,0.017,0.046,0.046,0.048,7.9e-10,7.9e-10,8.1e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0
17690000,0.71,0.00027,-0.012,0.71,0.0051,0.00056,0.0019,-0.0032,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.6e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.038,0.038,0.017,0.052,0.052,0.048,7.9e-10,7.9e-10,7.9e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0
17790000,0.71,0.00018,-0.013,0.71,0.0077,0.00029,0.00056,-0.0021,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.9e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.033,0.033,0.016,0.045,0.045,0.048,7.1e-10,7.1e-10,7.8e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
17890000,0.71,0.00019,-0.013,0.71,0.0092,-0.00047,0.00065,-0.0012,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.9e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.4e-05,0.037,0.037,0.016,0.052,0.052,0.048,7.1e-10,7.1e-10,7.6e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
17990000,0.71,0.00014,-0.013,0.71,0.011,-0.0022,0.0019,-0.00053,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.4e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-10,6.4e-10,7.5e-10,3.1e-06,3.1e-06,1e-07,0,0,0,0,0,0,0,0
18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0024,0.0043,0.00061,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.3e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-10,6.4e-10,7.3e-10,3.1e-06,3.1e-06,9.7e-08,0,0,0,0,0,0,0,0
18190000,0.71,0.00011,-0.013,0.71,0.012,-0.0013,0.0056,0.0015,-0.0017,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.3e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-10,5.8e-10,7.2e-10,3.1e-06,3.1e-06,9.2e-08,0,0,0,0,0,0,0,0
18290000,0.71,4.9e-05,-0.012,0.71,0.012,-0.0019,0.0068,0.0027,-0.0018,-3.7e+02,-1.3e-05,-6.1e-05,4.1e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-10,5.8e-10,7e-10,3.1e-06,3.1e-06,8.9e-08,0,0,0,0,0,0,0,0
18390000,0.71,6.5e-05,-0.013,0.71,0.014,-0.0002,0.0079,0.0032,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.3e-10,5.3e-10,6.9e-10,3.1e-06,3.1e-06,8.4e-08,0,0,0,0,0,0,0,0
18490000,0.71,8e-05,-0.012,0.71,0.014,0.00021,0.0076,0.0047,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.5e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.2e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.3e-10,5.3e-10,6.7e-10,3.1e-06,3.1e-06,8.2e-08,0,0,0,0,0,0,0,0
18590000,0.71,8.5e-05,-0.012,0.71,0.013,0.00045,0.0057,0.0035,-0.0012,-3.7e+02,-1.4e-05,-6.1e-05,4.9e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-10,4.8e-10,6.6e-10,3.1e-06,3.1e-06,7.8e-08,0,0,0,0,0,0,0,0
18690000,0.71,5.4e-05,-0.012,0.71,0.014,-0.00024,0.0038,0.0049,-0.0011,-3.7e+02,-1.4e-05,-6.1e-05,4.8e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00013,0.00012,8.2e-05,0.034,0.034,0.013,0.051,0.051,0.045,4.8e-10,4.8e-10,6.5e-10,3.1e-06,3.1e-06,7.5e-08,0,0,0,0,0,0,0,0
18790000,0.71,8.4e-05,-0.012,0.71,0.012,6.5e-05,0.0035,0.0038,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,4.6e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.4e-10,4.4e-10,6.3e-10,3.1e-06,3.1e-06,7.2e-08,0,0,0,0,0,0,0,0
18890000,0.71,0.00011,-0.012,0.71,0.013,0.00056,0.0041,0.005,-0.00085,-3.7e+02,-1.4e-05,-6.1e-05,5e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.4e-10,4.4e-10,6.2e-10,3.1e-06,3.1e-06,7e-08,0,0,0,0,0,0,0,0
18990000,0.71,9.4e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.0007,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.029,0.029,0.012,0.045,0.045,0.044,4e-10,4e-10,6.1e-10,3e-06,3e-06,6.6e-08,0,0,0,0,0,0,0,0
19090000,0.71,7.9e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0078,-0.0005,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.032,0.032,0.012,0.051,0.051,0.044,4e-10,4e-10,6e-10,3e-06,3e-06,6.5e-08,0,0,0,0,0,0,0,0
19190000,0.71,8.1e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0086,-0.00045,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00011,8.1e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-10,3.6e-10,5.9e-10,3e-06,3e-06,6.2e-08,0,0,0,0,0,0,0,0
19290000,0.71,0.0001,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00027,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00012,8e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-10,3.6e-10,5.7e-10,3e-06,3e-06,6e-08,0,0,0,0,0,0,0,0
19390000,0.71,0.00012,-0.012,0.71,0.013,0.00039,0.012,0.008,-0.00028,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.028,0.028,0.012,0.045,0.045,0.043,3.3e-10,3.3e-10,5.6e-10,3e-06,3e-06,5.8e-08,0,0,0,0,0,0,0,0
19490000,0.71,0.00014,-0.012,0.71,0.012,-0.00033,0.0088,0.0092,-0.00028,-3.7e+02,-1.4e-05,-6.1e-05,5.6e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-10,3.3e-10,5.5e-10,3e-06,3e-06,5.6e-08,0,0,0,0,0,0,0,0
19590000,0.71,0.00019,-0.012,0.71,0.0097,-0.0013,0.0081,0.0075,-0.0003,-3.7e+02,-1.4e-05,-6.1e-05,5.9e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-10,3e-10,5.4e-10,3e-06,3e-06,5.4e-08,0,0,0,0,0,0,0,0
19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0035,0.0096,0.0085,-0.00055,-3.7e+02,-1.4e-05,-6.1e-05,5.7e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-10,3e-10,5.3e-10,3e-06,3e-06,5.2e-08,0,0,0,0,0,0,0,0
19790000,0.71,0.00026,-0.012,0.71,0.0078,-0.0044,0.01,0.0068,-0.00044,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,5.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19890000,0.71,0.0002,-0.012,0.71,0.0065,-0.0047,0.011,0.0076,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,6.2e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-10,2.7e-10,5.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19990000,0.71,0.00019,-0.012,0.71,0.0041,-0.0053,0.014,0.0062,-0.00076,-3.7e+02,-1.4e-05,-6.1e-05,6.7e-06,-1.7e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-10,2.5e-10,5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20090000,0.71,0.00018,-0.012,0.71,0.0039,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-1.4e-05,-6.1e-05,7.1e-06,-1.7e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.028,0.028,0.01,0.05,0.05,0.042,2.5e-10,2.5e-10,4.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20190000,0.71,0.00029,-0.012,0.71,0.0015,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.6e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.9e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-10,2.3e-10,4.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20290000,0.71,0.00025,-0.012,0.71,0.00038,-0.0096,0.015,0.0043,-0.002,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-1.6e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.8e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-10,2.3e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20390000,0.71,0.00027,-0.012,0.71,-0.0021,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-1.4e-05,7.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.8e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-10,2.1e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20490000,0.71,0.00032,-0.012,0.71,-0.0025,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.4e-05,7.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.027,0.027,0.0096,0.049,0.049,0.041,2.1e-10,2.1e-10,4.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20590000,0.71,0.00034,-0.012,0.71,-0.0022,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-1.4e-05,-6e-05,7.1e-06,-1.3e-05,7.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.024,0.024,0.0094,0.044,0.044,0.04,2e-10,2e-10,4.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20690000,0.71,0.00037,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.3e-05,7.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.026,0.026,0.0093,0.049,0.049,0.04,2e-10,2e-10,4.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20790000,0.71,0.0004,-0.012,0.71,-0.0033,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.7e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20890000,0.71,0.00038,-0.012,0.71,-0.0037,-0.014,0.014,0.001,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-1.1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,0.0001,0.0001,7.7e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.015,0.0027,-0.0031,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-8.7e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.7e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-10,1.7e-10,4.2e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21090000,0.71,0.00039,-0.012,0.71,-0.0041,-0.017,0.015,0.0023,-0.0047,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-8.7e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.9e-05,9.9e-05,7.7e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-10,1.7e-10,4.1e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21190000,0.71,0.00042,-0.012,0.71,-0.0033,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.6e-06,-6.3e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.7e-05,9.7e-05,7.7e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21290000,0.71,0.00046,-0.012,0.71,-0.0039,-0.018,0.016,0.0034,-0.0054,-3.7e+02,-1.4e-05,-6e-05,7.9e-06,-6.3e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.6e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.6e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21390000,0.71,0.00051,-0.012,0.71,-0.0047,-0.017,0.016,0.0029,-0.0034,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-2.6e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.6e-05,9.6e-05,7.6e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-10,1.4e-10,3.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21490000,0.71,0.00052,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-2.6e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.7e-05,9.6e-05,7.6e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-10,1.4e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21590000,0.71,0.00054,-0.012,0.71,-0.0058,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,8e-07,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-10,1.3e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21690000,0.71,0.00055,-0.012,0.71,-0.0057,-0.016,0.017,0.0013,-0.0048,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,7.8e-07,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-10,1.3e-10,3.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21790000,0.71,0.00057,-0.012,0.71,-0.0063,-0.011,0.015,9e-05,-0.00075,-3.7e+02,-1.4e-05,-5.9e-05,7.6e-06,6e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.4e-05,9.4e-05,7.5e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21890000,0.71,0.00057,-0.012,0.71,-0.0063,-0.012,0.016,-0.00054,-0.0019,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,5.9e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.4e-05,9.4e-05,7.5e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21990000,0.71,0.00062,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.3e-05,9.3e-05,7.5e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-10,1.2e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22090000,0.71,0.00064,-0.012,0.71,-0.0071,-0.0082,0.015,-0.0021,0.00064,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.4e-05,9.3e-05,7.5e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-10,1.2e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22190000,0.71,0.00061,-0.012,0.71,-0.0069,-0.0073,0.015,-0.0018,0.00059,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.2e-05,9.2e-05,7.5e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-10,1.1e-10,3.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22290000,0.71,0.00065,-0.012,0.71,-0.0082,-0.0081,0.015,-0.0025,-0.00018,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.3e-05,9.2e-05,7.4e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-10,1.1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22390000,0.71,0.00062,-0.012,0.71,-0.0088,-0.0075,0.017,-0.0022,-0.00017,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.2e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.1e-05,9.1e-05,7.4e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-10,1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22490000,0.71,0.00063,-0.012,0.71,-0.0095,-0.0075,0.018,-0.0031,-0.00094,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.2e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.2e-05,9.2e-05,7.4e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-10,1e-10,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22590000,0.71,0.00061,-0.012,0.71,-0.0092,-0.007,0.017,-0.0034,0.00014,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.3e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.1e-05,9e-05,7.4e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-11,9.7e-11,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22690000,0.71,0.00064,-0.012,0.71,-0.01,-0.0067,0.018,-0.0043,-0.00054,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.3e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.1e-05,9.1e-05,7.4e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-11,9.7e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22790000,0.71,0.00063,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00043,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.4e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.4e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-11,9.2e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22890000,0.71,0.00064,-0.012,0.71,-0.012,-0.0051,0.021,-0.0066,-0.00097,-3.7e+02,-1.4e-05,-5.9e-05,6.9e-06,1.4e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-11,9.2e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22990000,0.71,0.00062,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00086,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.9e-05,8.9e-05,7.3e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-11,8.7e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23090000,0.71,0.00059,-0.012,0.71,-0.013,-0.0056,0.022,-0.0086,-0.0014,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,9e-05,9e-05,7.3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-11,8.7e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23190000,0.71,0.00065,-0.012,0.71,-0.014,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.9e-05,7.3e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-11,8.2e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23290000,0.71,0.00059,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.9e-05,7.3e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-11,8.2e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23390000,0.71,0.00068,-0.012,0.71,-0.016,-0.008,0.022,-0.016,-0.0018,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,1.5e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.8e-05,8.8e-05,7.3e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.8e-05,7.3e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0076,-0.044,-0.017,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,1.8e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.8e-05,8.7e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,1.8e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.8e-05,8.8e-05,7.2e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23790000,0.71,0.005,0.00066,0.71,-0.089,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.005,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23990000,0.71,0.00097,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2.2e-05,6.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.6e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-11,6.7e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24090000,0.71,0.0023,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.2e-05,6.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.8e-11,6.8e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.4e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.6e-05,8.6e-05,7.1e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-11,6.4e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2.4e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.6e-05,8.6e-05,7.1e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-11,6.5e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24390000,0.71,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.1e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24490000,0.71,0.0047,-0.0017,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.1e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.6e-05,8.5e-05,7.1e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.068,-0.56,-0.081,-0.045,-3.7e+02,-1.3e-05,-5.9e-05,6.4e-06,2e-05,4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-11,5.9e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-1.3e-05,-5.9e-05,6.5e-06,2e-05,4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-11,5.9e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24790000,0.71,0.0049,0.0015,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.4e-05,3.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.4e-05,8.4e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-11,5.7e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-1.3e-05,-5.9e-05,6.2e-06,2.4e-05,4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.4e-05,8.4e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-11,5.7e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-1.3e-05,-5.9e-05,6e-06,3.4e-05,2.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.3e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.5e-11,5.5e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3.4e-05,2.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.4e-05,8.3e-05,7e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.5e-11,5.5e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3e-05,1.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.2e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-11,5.3e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3e-05,1.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.3e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-11,5.3e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-1.2e-05,-5.9e-05,5.9e-06,3.3e-05,3.5e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.2e-05,8.2e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,3.2e-05,3.6e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.2e-05,8.2e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,2.9e-05,-5.8e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.1e-05,8.1e-05,7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-11,4.9e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,2.9e-05,-5.5e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8.1e-05,8.1e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-11,4.9e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,3.8e-05,-3.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3.7e-05,-3.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8.1e-05,8e-05,6.9e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-1.1e-05,-5.9e-05,6.1e-06,3.3e-05,-4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-1.1e-05,-5.9e-05,5.9e-06,3.4e-05,-4.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-11,4.6e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-1.1e-05,-5.9e-05,6e-06,4.5e-05,-8.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.9e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-11,4.4e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-1.1e-05,-5.9e-05,5.9e-06,4.6e-05,-8.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.9e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-11,4.5e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-1e-05,-5.9e-05,5.9e-06,3.3e-05,-9.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.8e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-1e-05,-5.9e-05,5.8e-06,3.3e-05,-9.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-9.5e-06,-5.9e-05,5.5e-06,4.3e-05,-0.00013,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.7e-05,6.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-9.5e-06,-5.9e-05,5.6e-06,4.2e-05,-0.00013,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-9e-06,-6e-05,5.4e-06,2e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.8e-05,0.015,0.014,0.008,0.039,0.039,0.035,4.1e-11,4.1e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-9e-06,-6e-05,5.5e-06,2e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.9e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4.1e-11,4.1e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-7.9e-06,-6e-05,5.4e-06,2.9e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.6e-05,7.6e-05,6.9e-05,0.015,0.014,0.008,0.039,0.039,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-7.9e-06,-6e-05,5.3e-06,2.9e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.6e-05,6.8e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-7.8e-06,-5.9e-05,5.4e-06,3.9e-05,-0.0002,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.6e-05,7.6e-05,6.8e-05,0.016,0.015,0.0081,0.045,0.045,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-7.8e-06,-5.9e-05,5.4e-06,3.9e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.8e-05,0.017,0.016,0.0081,0.05,0.049,0.035,4e-11,4e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27390000,0.71,0.037,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-7.2e-06,-5.9e-05,5.5e-06,5.9e-05,-0.00021,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.7e-05,0.017,0.016,0.0081,0.052,0.052,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27490000,0.71,0.031,0.063,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-7.2e-06,-5.9e-05,5.4e-06,5.8e-05,-0.00021,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-7.5e-06,-5.9e-05,5.5e-06,5.7e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.017,0.0082,0.06,0.059,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-7.5e-06,-5.9e-05,5.4e-06,5.6e-05,-0.00019,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.7e-05,6.7e-05,0.019,0.018,0.0083,0.065,0.065,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-7.6e-06,-5.8e-05,5.3e-06,5.8e-05,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.019,0.018,0.0082,0.068,0.067,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-7.6e-06,-5.8e-05,5.2e-06,5.6e-05,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.019,0.0083,0.074,0.073,0.035,3.9e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-8e-06,-5.8e-05,5.3e-06,5.1e-05,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.019,0.0083,0.076,0.076,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-8e-06,-5.8e-05,5.1e-06,5e-05,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0084,0.083,0.082,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-8.2e-06,-5.8e-05,5.1e-06,4.7e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.09,-4.4,-2.4,-3.7e+02,-8.2e-06,-5.8e-05,4.9e-06,4.5e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0086,0.092,0.092,0.036,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-8.2e-06,-5.8e-05,4.8e-06,4.3e-05,-0.00013,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.7e-05,6.5e-05,0.022,0.021,0.0087,0.1,0.099,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28490000,0.71,0.0026,0.0045,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,4e-05,-0.00012,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.023,0.022,0.0088,0.11,0.11,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28590000,0.71,0.00085,0.001,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,3.7e-05,-0.00012,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.023,0.0089,0.12,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28690000,0.71,0.00014,8.3e-05,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-8.2e-06,-5.8e-05,4.6e-06,3.2e-05,-0.0001,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.025,0.025,0.009,0.13,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28790000,0.71,-0.00015,-0.00017,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-8.9e-06,-5.8e-05,4.6e-06,1.3e-06,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28890000,0.71,-0.00017,5.3e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-8.9e-06,-5.8e-05,4.6e-06,-3e-06,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.8e-05,6.5e-05,0.025,0.025,0.009,0.14,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28990000,0.71,2.5e-05,0.0005,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-9.8e-06,-5.8e-05,4.5e-06,-2.4e-05,-0.00025,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.8e-05,6.4e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.7e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29090000,0.71,0.00018,0.0009,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-9.8e-06,-5.8e-05,4.4e-06,-2.9e-05,-0.00023,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-11,3.7e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29190000,0.71,0.0004,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-1e-05,-5.8e-05,4.4e-06,-4.9e-05,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29290000,0.71,0.00075,0.0022,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-1e-05,-5.8e-05,4.3e-06,-5.4e-05,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.026,0.0091,0.16,0.16,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29390000,0.71,0.0013,0.0037,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-1.1e-05,-5.8e-05,4.1e-06,-7e-05,-0.00029,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.009,0.16,0.16,0.036,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-1.1e-05,-5.7e-05,4.1e-06,-7.4e-05,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-1.1e-05,-5.7e-05,4e-06,-9.8e-05,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.009,0.17,0.16,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-1.1e-05,-5.7e-05,3.9e-06,-0.0001,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.93,-8.5,-4.1,-3.7e+02,-1.2e-05,-5.7e-05,3.9e-06,-0.00012,-0.00029,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.3e-05,0.025,0.025,0.0091,0.18,0.17,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29890000,0.71,0.0029,0.0074,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-1.2e-05,-5.7e-05,3.7e-06,-0.00013,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29990000,0.71,0.003,0.0076,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-1.2e-05,-5.7e-05,3.6e-06,-0.00015,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.19,0.18,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
6390000,0.71,0.0014,-0.014,0.71,0.0048,0.0076,-0.05,0.0025,0.0017,-3.7e+02,-1.6e-05,-5.6e-05,2.1e-06,0,0,4e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00077,0.00034,0.00034,0.00085,0.22,0.22,2.3,0.13,0.13,0.29,1.4e-08,1.5e-08,1e-06,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6490000,0.71,0.0014,-0.014,0.71,0.0043,0.0083,-0.052,0.0029,0.0025,-3.7e+02,-1.6e-05,-5.6e-05,-2.3e-06,0,0,-8.7e-08,0.21,0.0021,0.44,0,0,0,0,0,0.00053,0.00034,0.00034,0.00058,0.22,0.22,1.5,0.16,0.16,0.26,1.4e-08,1.5e-08,9.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6590000,0.71,0.0015,-0.014,0.71,0.0036,0.0085,-0.099,0.0034,0.0034,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-05,0,0,1.7e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00042,0.00034,0.00034,0.00046,0.23,0.23,1.1,0.19,0.19,0.23,1.4e-08,1.4e-08,9.7e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6690000,0.7,0.0015,-0.014,0.71,0.0037,0.0095,-0.076,0.0037,0.0043,-3.7e+02,-1.6e-05,-5.6e-05,-2.4e-05,0,0,-1.5e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00038,0.00034,0.00034,0.00041,0.24,0.24,0.78,0.23,0.23,0.21,1.4e-08,1.4e-08,9.4e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6790000,0.71,0.0015,-0.014,0.71,0.0021,0.0095,-0.11,0.004,0.0052,-3.7e+02,-1.6e-05,-5.6e-05,-1.6e-05,0,0,8.5e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00037,0.00034,0.00034,0.00039,0.25,0.25,0.6,0.28,0.28,0.2,1.4e-08,1.4e-08,8.9e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6890000,0.71,0.0015,-0.014,0.71,-0.00016,0.01,-0.12,0.0041,0.0062,-3.7e+02,-1.6e-05,-5.6e-05,-1.3e-05,0,0,3.4e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00036,0.00035,0.00035,0.00037,0.26,0.26,0.46,0.33,0.33,0.18,1.4e-08,1.4e-08,8.3e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
6990000,0.7,0.0016,-0.014,0.71,-0.00035,0.011,-0.12,0.0041,0.0072,-3.7e+02,-1.6e-05,-5.6e-05,-4.1e-05,0,0,-2.7e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00036,0.00035,0.00035,0.00036,0.28,0.28,0.36,0.38,0.38,0.16,1.4e-08,1.4e-08,7.5e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7090000,0.7,0.0016,-0.014,0.71,-0.00097,0.01,-0.13,0.004,0.0083,-3.7e+02,-1.6e-05,-5.6e-05,-6.7e-05,0,0,-6.3e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00037,0.00036,0.00036,0.00037,0.3,0.3,0.29,0.44,0.44,0.16,1.4e-08,1.4e-08,6.8e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7190000,0.7,0.0016,-0.014,0.71,-0.0028,0.01,-0.15,0.0039,0.0093,-3.7e+02,-1.6e-05,-5.6e-05,-7.1e-05,0,0,-4.1e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00037,0.00036,0.00036,0.00036,0.32,0.32,0.24,0.51,0.51,0.15,1.4e-08,1.4e-08,6e-07,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
7290000,0.7,0.0016,-0.014,0.71,-0.0046,0.011,-0.15,0.0035,0.01,-3.7e+02,-1.6e-05,-5.6e-05,-6.2e-05,0,0,-1.1e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00037,0.00037,0.00037,0.00036,0.35,0.34,0.2,0.58,0.58,0.14,1.4e-08,1.4e-08,5.3e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7390000,0.7,0.0016,-0.014,0.71,-0.005,0.012,-0.16,0.0029,0.011,-3.7e+02,-1.6e-05,-5.6e-05,-5.3e-05,0,0,-1.2e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00037,0.00038,0.00038,0.00036,0.37,0.37,0.18,0.66,0.66,0.13,1.4e-08,1.4e-08,4.7e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7490000,0.7,0.0017,-0.014,0.71,-0.0069,0.012,-0.16,0.0023,0.013,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-05,0,0,-2e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00037,0.00039,0.00039,0.00035,0.4,0.4,0.15,0.76,0.76,0.12,1.4e-08,1.4e-08,4e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7590000,0.7,0.0017,-0.014,0.71,-0.0093,0.014,-0.17,0.0014,0.014,-3.7e+02,-1.6e-05,-5.6e-05,-3e-05,0,0,-2.9e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00036,0.00039,0.00039,0.00034,0.43,0.43,0.14,0.85,0.85,0.12,1.4e-08,1.4e-08,3.5e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7690000,0.7,0.0018,-0.014,0.71,-0.011,0.014,-0.16,0.00029,0.015,-3.7e+02,-1.6e-05,-5.6e-05,-2.8e-05,0,0,-4.9e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00036,0.0004,0.0004,0.00034,0.47,0.47,0.13,0.96,0.96,0.11,1.4e-08,1.4e-08,3.1e-07,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
7790000,0.7,0.0018,-0.014,0.71,-0.013,0.015,-0.16,-0.00078,0.016,-3.7e+02,-1.6e-05,-5.6e-05,-4.3e-05,0,0,-6.9e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00035,0.00041,0.00041,0.00033,0.51,0.51,0.12,1.1,1.1,0.11,1.4e-08,1.4e-08,2.6e-07,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
7890000,0.7,0.0018,-0.014,0.71,-0.016,0.017,-0.16,-0.0024,0.018,-3.7e+02,-1.6e-05,-5.6e-05,-3.2e-05,0,0,-9.5e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00033,0.00042,0.00042,0.00032,0.55,0.55,0.11,1.2,1.2,0.1,1.4e-08,1.4e-08,2.3e-07,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
7990000,0.7,0.0019,-0.014,0.71,-0.018,0.018,-0.16,-0.0042,0.02,-3.7e+02,-1.6e-05,-5.6e-05,-2.3e-05,0,0,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00032,0.00043,0.00043,0.00031,0.6,0.59,0.1,1.3,1.3,0.099,1.4e-08,1.4e-08,2e-07,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
8090000,0.7,0.0019,-0.014,0.71,-0.021,0.02,-0.17,-0.0064,0.022,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-05,0,0,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00032,0.00045,0.00045,0.0003,0.65,0.65,0.1,1.5,1.5,0.097,1.4e-08,1.4e-08,1.7e-07,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
8190000,0.7,0.0019,-0.014,0.71,-0.024,0.021,-0.18,-0.0083,0.023,-3.7e+02,-1.6e-05,-5.6e-05,-1.9e-05,0,0,-0.00013,0.21,0.0021,0.44,0,0,0,0,0,0.00031,0.00046,0.00046,0.00029,0.69,0.69,0.099,1.7,1.7,0.094,1.4e-08,1.4e-08,1.5e-07,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
8290000,0.7,0.0019,-0.014,0.71,-0.025,0.021,-0.17,-0.011,0.025,-3.7e+02,-1.6e-05,-5.6e-05,-2.2e-05,0,0,-0.00017,0.21,0.0021,0.44,0,0,0,0,0,0.0003,0.00047,0.00047,0.00028,0.75,0.75,0.097,1.9,1.9,0.091,1.4e-08,1.4e-08,1.3e-07,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0
8390000,0.7,0.002,-0.014,0.71,-0.028,0.023,-0.17,-0.014,0.027,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-05,0,0,-0.00021,0.21,0.0021,0.44,0,0,0,0,0,0.00029,0.00048,0.00048,0.00028,0.81,0.81,0.097,2.1,2.1,0.091,1.4e-08,1.4e-08,1.2e-07,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0
8490000,0.7,0.002,-0.014,0.71,-0.03,0.024,-0.17,-0.017,0.029,-3.7e+02,-1.6e-05,-5.6e-05,-1.6e-05,0,0,-0.00025,0.21,0.0021,0.44,0,0,0,0,0,0.00028,0.00049,0.00049,0.00027,0.87,0.87,0.096,2.3,2.3,0.089,1.4e-08,1.4e-08,1.1e-07,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0
8590000,0.7,0.002,-0.014,0.71,-0.033,0.026,-0.17,-0.02,0.031,-3.7e+02,-1.6e-05,-5.6e-05,-2e-05,0,0,-0.00029,0.21,0.0021,0.44,0,0,0,0,0,0.00027,0.00051,0.00051,0.00026,0.94,0.94,0.095,2.5,2.5,0.088,1.4e-08,1.4e-08,9.3e-08,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
8690000,0.7,0.0021,-0.014,0.71,-0.037,0.027,-0.16,-0.023,0.033,-3.7e+02,-1.6e-05,-5.6e-05,-1.1e-05,0,0,-0.00034,0.21,0.0021,0.44,0,0,0,0,0,0.00027,0.00052,0.00052,0.00025,0.99,0.99,0.096,2.7,2.7,0.088,1.4e-08,1.4e-08,8.4e-08,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
8790000,0.7,0.002,-0.014,0.71,-0.04,0.029,-0.15,-0.027,0.035,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-05,0,0,-0.00041,0.21,0.0021,0.44,0,0,0,0,0,0.00026,0.00054,0.00054,0.00025,1.1,1.1,0.095,3,3,0.087,1.4e-08,1.4e-08,7.5e-08,4e-06,4e-06,3.1e-06,0,0,0,0,0,0,0,0
8890000,0.7,0.002,-0.014,0.71,-0.042,0.029,-0.15,-0.031,0.037,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-05,0,0,-0.00045,0.21,0.0021,0.44,0,0,0,0,0,0.00025,0.00055,0.00055,0.00024,1.1,1.1,0.095,3.3,3.3,0.086,1.3e-08,1.3e-08,6.7e-08,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0
8990000,0.7,0.0021,-0.014,0.71,-0.044,0.03,-0.14,-0.035,0.039,-3.7e+02,-1.6e-05,-5.6e-05,-1.8e-05,0,0,-0.0005,0.21,0.0021,0.44,0,0,0,0,0,0.00025,0.00056,0.00056,0.00023,1.2,1.2,0.096,3.6,3.6,0.087,1.3e-08,1.3e-08,6.1e-08,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0
9090000,0.7,0.0021,-0.014,0.71,-0.046,0.03,-0.14,-0.038,0.041,-3.7e+02,-1.6e-05,-5.6e-05,-1.9e-05,0,0,-0.00053,0.21,0.0021,0.44,0,0,0,0,0,0.00024,0.00057,0.00057,0.00023,1.3,1.3,0.095,3.9,3.9,0.086,1.3e-08,1.3e-08,5.5e-08,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0
9190000,0.7,0.0022,-0.014,0.71,-0.049,0.031,-0.14,-0.044,0.044,-3.7e+02,-1.6e-05,-5.6e-05,-9.9e-06,0,0,-0.00057,0.21,0.0021,0.44,0,0,0,0,0,0.00023,0.00059,0.00059,0.00022,1.4,1.4,0.094,4.3,4.3,0.085,1.3e-08,1.3e-08,5e-08,4e-06,4e-06,2.7e-06,0,0,0,0,0,0,0,0
9290000,0.7,0.0022,-0.014,0.71,-0.05,0.032,-0.14,-0.047,0.045,-3.7e+02,-1.6e-05,-5.6e-05,-8.5e-06,0,0,-0.00061,0.21,0.0021,0.44,0,0,0,0,0,0.00023,0.0006,0.0006,0.00022,1.4,1.4,0.093,4.5,4.5,0.085,1.3e-08,1.3e-08,4.5e-08,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0
9390000,0.7,0.0021,-0.014,0.71,-0.052,0.034,-0.14,-0.053,0.048,-3.7e+02,-1.6e-05,-5.6e-05,-8.2e-06,0,0,-0.00064,0.21,0.0021,0.44,0,0,0,0,0,0.00023,0.00062,0.00061,0.00021,1.5,1.5,0.093,5,5,0.086,1.3e-08,1.3e-08,4.2e-08,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0
9490000,0.7,0.0021,-0.014,0.71,-0.054,0.034,-0.13,-0.056,0.049,-3.7e+02,-1.6e-05,-5.6e-05,-2.9e-06,0,0,-0.00068,0.21,0.0021,0.44,0,0,0,0,0,0.00022,0.00062,0.00062,0.00021,1.6,1.6,0.091,5.2,5.2,0.085,1.3e-08,1.3e-08,3.8e-08,4e-06,4e-06,2.3e-06,0,0,0,0,0,0,0,0
9590000,0.7,0.0022,-0.014,0.71,-0.057,0.036,-0.13,-0.062,0.053,-3.7e+02,-1.6e-05,-5.6e-05,-1.7e-06,0,0,-0.00072,0.21,0.0021,0.44,0,0,0,0,0,0.00021,0.00064,0.00064,0.0002,1.7,1.7,0.089,5.8,5.8,0.085,1.3e-08,1.3e-08,3.5e-08,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0
9690000,0.7,0.0022,-0.014,0.71,-0.058,0.037,-0.12,-0.064,0.052,-3.7e+02,-1.6e-05,-5.6e-05,-6e-06,0,0,-0.00077,0.21,0.0021,0.44,0,0,0,0,0,0.00021,0.00064,0.00064,0.0002,1.7,1.7,0.089,6,6,0.086,1.3e-08,1.3e-08,3.2e-08,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0
9790000,0.7,0.0022,-0.014,0.71,-0.059,0.039,-0.11,-0.071,0.056,-3.7e+02,-1.6e-05,-5.6e-05,-3.1e-06,0,0,-0.00082,0.21,0.0021,0.44,0,0,0,0,0,0.00021,0.00066,0.00066,0.00019,1.8,1.8,0.087,6.6,6.6,0.085,1.3e-08,1.3e-08,3e-08,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0
9890000,0.7,0.0022,-0.014,0.71,-0.059,0.039,-0.11,-0.072,0.056,-3.7e+02,-1.6e-05,-5.6e-05,-3.4e-06,0,0,-0.00085,0.21,0.0021,0.44,0,0,0,0,0,0.0002,0.00066,0.00066,0.00019,1.8,1.8,0.084,6.8,6.8,0.085,1.2e-08,1.2e-08,2.7e-08,4e-06,4e-06,1.8e-06,0,0,0,0,0,0,0,0
9990000,0.7,0.0023,-0.014,0.71,-0.062,0.04,-0.1,-0.078,0.059,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-06,0,0,-0.00088,0.21,0.0021,0.44,0,0,0,0,0,0.0002,0.00068,0.00068,0.00019,2,2,0.083,7.4,7.4,0.086,1.2e-08,1.2e-08,2.5e-08,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0
10090000,0.7,0.0023,-0.014,0.71,-0.061,0.038,-0.097,-0.079,0.059,-3.7e+02,-1.5e-05,-5.6e-05,-4.1e-06,0,0,-0.00091,0.21,0.0021,0.44,0,0,0,0,0,0.00019,0.00067,0.00067,0.00018,2,2,0.08,7.5,7.5,0.085,1.2e-08,1.2e-08,2.3e-08,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0
10190000,0.7,0.0023,-0.014,0.71,-0.062,0.041,-0.096,-0.084,0.062,-3.7e+02,-1.5e-05,-5.6e-05,-8.4e-06,0,0,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,0.00019,0.00069,0.00069,0.00018,2.1,2.1,0.078,8.3,8.3,0.084,1.2e-08,1.2e-08,2.2e-08,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
10290000,0.7,0.0022,-0.014,0.71,-0.061,0.039,-0.084,-0.084,0.06,-3.7e+02,-1.5e-05,-5.6e-05,-1.1e-05,0,0,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,0.00019,0.00068,0.00068,0.00018,2.1,2.1,0.076,8.3,8.3,0.085,1.2e-08,1.2e-08,2e-08,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
10390000,0.7,0.0022,-0.014,0.71,0.0091,-0.019,0.0096,0.00085,-0.0017,-3.7e+02,-1.5e-05,-5.6e-05,-1e-05,-6.6e-10,4.8e-10,-0.001,0.21,0.0021,0.44,0,0,0,0,0,0.00018,0.0007,0.0007,0.00017,0.25,0.25,0.56,0.25,0.25,0.078,1.2e-08,1.2e-08,1.9e-08,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0
10490000,0.7,0.0022,-0.014,0.71,0.0075,-0.017,0.023,0.0017,-0.0036,-3.7e+02,-1.5e-05,-5.6e-05,-1.2e-05,-1.7e-08,1.3e-08,-0.001,0.21,0.0021,0.44,0,0,0,0,0,0.00018,0.00073,0.00073,0.00017,0.26,0.26,0.55,0.26,0.26,0.08,1.2e-08,1.2e-08,1.8e-08,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
10590000,0.7,0.0023,-0.014,0.71,0.0071,-0.0067,0.026,0.0018,-0.00082,-3.7e+02,-1.5e-05,-5.6e-05,-1.1e-05,-2.7e-06,4.3e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00018,0.00074,0.00074,0.00017,0.14,0.14,0.27,0.13,0.13,0.073,1.2e-08,1.2e-08,1.6e-08,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
10690000,0.7,0.0024,-0.014,0.71,0.0046,-0.0062,0.03,0.0024,-0.0015,-3.7e+02,-1.5e-05,-5.6e-05,-1.1e-05,-2.7e-06,4.5e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00017,0.00076,0.00076,0.00016,0.15,0.15,0.26,0.14,0.14,0.078,1.2e-08,1.2e-08,1.5e-08,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10790000,0.7,0.0024,-0.014,0.71,0.0042,-0.0034,0.024,0.0027,-0.00073,-3.7e+02,-1.5e-05,-5.5e-05,-1.1e-05,-4.4e-06,2.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00017,0.00074,0.00074,0.00016,0.11,0.11,0.17,0.091,0.091,0.072,1.1e-08,1.1e-08,1.4e-08,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10890000,0.7,0.0023,-0.014,0.71,0.0025,-0.0022,0.02,0.003,-0.00098,-3.7e+02,-1.5e-05,-5.5e-05,-1e-05,-4.4e-06,2e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00017,0.00076,0.00076,0.00016,0.13,0.13,0.16,0.098,0.098,0.075,1.1e-08,1.1e-08,1.3e-08,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
10990000,0.7,0.0023,-0.014,0.71,0.0054,0.0029,0.014,0.0046,-0.0023,-3.7e+02,-1.4e-05,-5.5e-05,-8.2e-06,-8.5e-06,8.7e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00017,0.0007,0.0007,0.00016,0.1,0.1,0.12,0.073,0.073,0.071,1.1e-08,1.1e-08,1.3e-08,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
11090000,0.7,0.0023,-0.014,0.71,0.0037,0.0054,0.019,0.0051,-0.0019,-3.7e+02,-1.4e-05,-5.5e-05,-6.2e-06,-8.5e-06,8.8e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00016,0.00072,0.00072,0.00015,0.13,0.13,0.11,0.08,0.08,0.074,1.1e-08,1.1e-08,1.2e-08,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
11190000,0.7,0.0022,-0.014,0.71,0.0089,0.0079,0.0077,0.0066,-0.0028,-3.7e+02,-1.3e-05,-5.5e-05,-7.3e-06,-9.7e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00016,0.00062,0.00062,0.00015,0.1,0.1,0.084,0.063,0.063,0.069,9.4e-09,9.5e-09,1.1e-08,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11290000,0.7,0.0023,-0.014,0.71,0.0085,0.01,0.0074,0.0075,-0.0019,-3.7e+02,-1.3e-05,-5.5e-05,-9.3e-06,-9.8e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00016,0.00064,0.00064,0.00015,0.13,0.13,0.078,0.071,0.071,0.072,9.4e-09,9.5e-09,1.1e-08,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11390000,0.7,0.0023,-0.014,0.71,0.004,0.0087,0.0017,0.0054,-0.002,-3.7e+02,-1.4e-05,-5.5e-05,-1.1e-05,-5.8e-06,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00016,0.00054,0.00054,0.00015,0.1,0.1,0.063,0.058,0.058,0.068,8.4e-09,8.4e-09,1e-08,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11490000,0.7,0.0023,-0.014,0.71,0.0013,0.011,0.0025,0.0057,-0.00099,-3.7e+02,-1.4e-05,-5.5e-05,-1.3e-05,-5.9e-06,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.00056,0.00056,0.00015,0.13,0.13,0.058,0.066,0.066,0.069,8.4e-09,8.4e-09,9.4e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
11590000,0.7,0.0022,-0.014,0.71,-0.0026,0.0098,-0.0034,0.0044,-0.0014,-3.7e+02,-1.4e-05,-5.6e-05,-1.3e-05,-1.8e-06,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.00046,0.00046,0.00014,0.1,0.1,0.049,0.054,0.054,0.066,7.4e-09,7.4e-09,9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11690000,0.7,0.0021,-0.014,0.71,-0.0056,0.013,-0.008,0.004,-0.00035,-3.7e+02,-1.4e-05,-5.6e-05,-1.4e-05,-1.7e-06,1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.00047,0.00047,0.00014,0.12,0.12,0.046,0.063,0.063,0.066,7.4e-09,7.4e-09,8.5e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11790000,0.7,0.0022,-0.014,0.71,-0.011,0.013,-0.0098,0.0017,0.00053,-3.7e+02,-1.4e-05,-5.6e-05,-1.3e-05,-7.4e-07,8.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.00039,0.00039,0.00014,0.096,0.096,0.039,0.052,0.052,0.063,6.6e-09,6.6e-09,8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11890000,0.7,0.0022,-0.014,0.71,-0.013,0.014,-0.011,0.00058,0.0018,-3.7e+02,-1.4e-05,-5.6e-05,-1.4e-05,-8.5e-07,8.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.0004,0.0004,0.00014,0.12,0.12,0.037,0.061,0.061,0.063,6.6e-09,6.6e-09,7.6e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
11990000,0.7,0.0022,-0.014,0.71,-0.014,0.014,-0.016,-0.00037,0.0023,-3.7e+02,-1.4e-05,-5.6e-05,-1.3e-05,5.7e-07,9.4e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.00034,0.00034,0.00014,0.09,0.09,0.033,0.051,0.051,0.061,5.9e-09,5.9e-09,7.2e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12090000,0.7,0.0022,-0.014,0.71,-0.015,0.016,-0.022,-0.0019,0.0037,-3.7e+02,-1.4e-05,-5.6e-05,-1.2e-05,8.4e-07,9.3e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00035,0.00035,0.00014,0.11,0.11,0.031,0.06,0.06,0.061,5.9e-09,5.9e-09,6.9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12190000,0.7,0.0018,-0.014,0.71,-0.0087,0.013,-0.017,0.0014,0.0019,-3.7e+02,-1.3e-05,-5.7e-05,-1.1e-05,3.6e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.0003,0.0003,0.00013,0.085,0.085,0.028,0.051,0.051,0.059,5.4e-09,5.4e-09,6.5e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12290000,0.7,0.0018,-0.014,0.71,-0.011,0.014,-0.016,0.00038,0.0033,-3.7e+02,-1.3e-05,-5.7e-05,-1e-05,3.4e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00031,0.00031,0.00013,0.1,0.1,0.028,0.059,0.059,0.059,5.4e-09,5.4e-09,6.2e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
12390000,0.7,0.0015,-0.014,0.71,-0.0058,0.011,-0.015,0.0029,0.0017,-3.7e+02,-1.3e-05,-5.8e-05,-1.1e-05,5.1e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00027,0.00027,0.00013,0.079,0.079,0.026,0.05,0.05,0.057,5e-09,5e-09,5.9e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0
12490000,0.7,0.0015,-0.014,0.71,-0.007,0.013,-0.018,0.0023,0.0029,-3.7e+02,-1.3e-05,-5.8e-05,-1.1e-05,5e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00028,0.00028,0.00013,0.092,0.092,0.026,0.059,0.059,0.057,5e-09,5e-09,5.6e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0
12590000,0.7,0.0015,-0.014,0.71,-0.014,0.011,-0.024,-0.0028,0.0015,-3.7e+02,-1.3e-05,-5.8e-05,-1.1e-05,6.5e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00025,0.00025,0.00013,0.073,0.073,0.025,0.05,0.05,0.055,4.7e-09,4.7e-09,5.4e-09,3.6e-06,3.6e-06,9.8e-07,0,0,0,0,0,0,0,0
12690000,0.7,0.0016,-0.014,0.71,-0.015,0.012,-0.027,-0.0043,0.0026,-3.7e+02,-1.3e-05,-5.8e-05,-1.1e-05,6.7e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00026,0.00026,0.00013,0.085,0.085,0.025,0.058,0.058,0.055,4.7e-09,4.7e-09,5.1e-09,3.6e-06,3.6e-06,9.8e-07,0,0,0,0,0,0,0,0
12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0091,-0.03,-0.0077,0.0013,-3.7e+02,-1.4e-05,-5.8e-05,-1.1e-05,7.2e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00023,0.00023,0.00013,0.068,0.068,0.024,0.049,0.049,0.053,4.4e-09,4.4e-09,4.9e-09,3.6e-06,3.6e-06,9.7e-07,0,0,0,0,0,0,0,0
12890000,0.7,0.0016,-0.013,0.71,-0.021,0.009,-0.03,-0.0097,0.0022,-3.7e+02,-1.4e-05,-5.8e-05,-1e-05,6.6e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00024,0.00024,0.00012,0.079,0.079,0.025,0.058,0.058,0.054,4.4e-09,4.4e-09,4.7e-09,3.6e-06,3.6e-06,9.6e-07,0,0,0,0,0,0,0,0
12990000,0.7,0.0012,-0.014,0.71,-0.0087,0.0065,-0.03,-0.0011,0.0012,-3.7e+02,-1.3e-05,-5.9e-05,-8.6e-06,6.6e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00022,0.00022,0.00012,0.064,0.064,0.025,0.049,0.049,0.052,4.2e-09,4.2e-09,4.5e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0
13090000,0.7,0.0012,-0.014,0.71,-0.0094,0.0067,-0.03,-0.002,0.0018,-3.7e+02,-1.3e-05,-5.9e-05,-9.3e-06,6.2e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00023,0.00023,0.00012,0.073,0.073,0.025,0.057,0.057,0.052,4.2e-09,4.2e-09,4.3e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0
13190000,0.7,0.00099,-0.014,0.71,-0.00029,0.0061,-0.027,0.0044,0.0012,-3.7e+02,-1.2e-05,-5.9e-05,-9e-06,4.9e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00021,0.00021,0.00012,0.06,0.06,0.025,0.049,0.049,0.051,4e-09,4e-09,4.1e-09,3.6e-06,3.6e-06,9.1e-07,0,0,0,0,0,0,0,0
13290000,0.7,0.001,-0.014,0.71,-0.00056,0.0069,-0.024,0.0043,0.0018,-3.7e+02,-1.2e-05,-5.9e-05,-7.8e-06,3.7e-06,2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00022,0.00022,0.00012,0.069,0.069,0.027,0.057,0.057,0.051,4e-09,4e-09,4e-09,3.6e-06,3.6e-06,9.1e-07,0,0,0,0,0,0,0,0
13390000,0.7,0.00085,-0.014,0.71,0.00032,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-1.2e-05,-5.9e-05,-6.7e-06,2.1e-06,2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00021,0.00021,0.00012,0.056,0.056,0.026,0.049,0.049,0.05,3.8e-09,3.8e-09,3.8e-09,3.6e-06,3.6e-06,8.8e-07,0,0,0,0,0,0,0,0
13490000,0.7,0.00087,-0.014,0.71,-0.00019,0.0058,-0.019,0.0033,0.0017,-3.7e+02,-1.2e-05,-5.9e-05,-5.8e-06,1.3e-06,2.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00022,0.00021,0.00012,0.064,0.064,0.028,0.057,0.057,0.05,3.8e-09,3.8e-09,3.6e-09,3.6e-06,3.6e-06,8.7e-07,0,0,0,0,0,0,0,0
13590000,0.7,0.00081,-0.014,0.71,0.00014,0.006,-0.021,0.0024,0.001,-3.7e+02,-1.2e-05,-5.9e-05,-6.2e-06,1e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.0002,0.0002,0.00012,0.053,0.053,0.028,0.049,0.049,0.05,3.6e-09,3.6e-09,3.5e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0
13690000,0.7,0.00078,-0.014,0.71,0.0008,0.0078,-0.025,0.0024,0.0017,-3.7e+02,-1.2e-05,-5.9e-05,-5e-06,1.4e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00021,0.00021,0.00012,0.061,0.061,0.029,0.056,0.056,0.05,3.6e-09,3.6e-09,3.4e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0
13790000,0.7,0.00067,-0.014,0.71,0.0015,0.0036,-0.027,0.0035,-0.00062,-3.7e+02,-1.1e-05,-6e-05,-4.8e-06,-7.2e-07,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.0002,0.0002,0.00011,0.051,0.051,0.029,0.048,0.048,0.049,3.4e-09,3.4e-09,3.2e-09,3.6e-06,3.6e-06,7.9e-07,0,0,0,0,0,0,0,0
13890000,0.7,0.00063,-0.014,0.71,0.0019,0.0035,-0.031,0.0036,-0.00029,-3.7e+02,-1.1e-05,-6e-05,-4.1e-06,-3.6e-07,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00021,0.00021,0.00011,0.058,0.058,0.03,0.056,0.056,0.05,3.4e-09,3.4e-09,3.1e-09,3.6e-06,3.6e-06,7.8e-07,0,0,0,0,0,0,0,0
13990000,0.7,0.00056,-0.014,0.71,0.0023,0.00099,-0.03,0.0044,-0.002,-3.7e+02,-1.1e-05,-6e-05,-3.8e-06,-3e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.0002,0.0002,0.00011,0.049,0.049,0.03,0.048,0.048,0.05,3.2e-09,3.2e-09,3e-09,3.6e-06,3.6e-06,7.4e-07,0,0,0,0,0,0,0,0
14090000,0.7,0.00054,-0.014,0.71,0.0023,0.0011,-0.031,0.0046,-0.0019,-3.7e+02,-1.1e-05,-6e-05,-2.7e-06,-2.8e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.0002,0.0002,0.00011,0.055,0.055,0.031,0.056,0.056,0.05,3.2e-09,3.2e-09,2.9e-09,3.6e-06,3.6e-06,7.3e-07,0,0,0,0,0,0,0,0
14190000,0.7,0.00044,-0.014,0.71,0.0057,0.00059,-0.033,0.0068,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-2.1e-06,-2.6e-06,1.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.0002,0.0002,0.00011,0.047,0.047,0.031,0.048,0.048,0.05,3.1e-09,3.1e-09,2.8e-09,3.6e-06,3.6e-06,6.9e-07,0,0,0,0,0,0,0,0
14290000,0.7,0.00045,-0.014,0.71,0.0065,0.0013,-0.032,0.0074,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-1.6e-06,-3.2e-06,1.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.0002,0.0002,0.00011,0.053,0.053,0.032,0.055,0.055,0.051,3.1e-09,3.1e-09,2.7e-09,3.6e-06,3.6e-06,6.7e-07,0,0,0,0,0,0,0,0
14390000,0.7,0.00036,-0.014,0.71,0.0083,0.0023,-0.034,0.0087,-0.0013,-3.7e+02,-1.1e-05,-6e-05,-5.3e-07,-3.2e-06,1.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00019,0.00019,0.00011,0.045,0.045,0.031,0.048,0.048,0.05,2.9e-09,2.9e-09,2.6e-09,3.6e-06,3.6e-06,6.3e-07,0,0,0,0,0,0,0,0
14490000,0.7,0.00034,-0.013,0.71,0.0083,0.0035,-0.037,0.0095,-0.001,-3.7e+02,-1.1e-05,-6e-05,-1.8e-07,-2.6e-06,1.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.0002,0.0002,0.00011,0.051,0.051,0.032,0.055,0.055,0.051,2.9e-09,2.9e-09,2.5e-09,3.6e-06,3.6e-06,6.2e-07,0,0,0,0,0,0,0,0
14590000,0.7,0.00033,-0.013,0.71,0.0049,0.0019,-0.038,0.006,-0.0025,-3.7e+02,-1.1e-05,-6.1e-05,-9.5e-08,-6.3e-06,1.6e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00019,0.00019,0.00011,0.044,0.044,0.031,0.047,0.047,0.051,2.7e-09,2.7e-09,2.4e-09,3.6e-06,3.6e-06,5.8e-07,0,0,0,0,0,0,0,0
14690000,0.7,0.00029,-0.013,0.71,0.0062,-0.0011,-0.034,0.0066,-0.0024,-3.7e+02,-1.1e-05,-6.1e-05,6.2e-07,-7.4e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.0002,0.0002,0.00011,0.049,0.049,0.032,0.054,0.054,0.051,2.7e-09,2.7e-09,2.3e-09,3.6e-06,3.6e-06,5.6e-07,0,0,0,0,0,0,0,0
14790000,0.7,0.00031,-0.013,0.71,0.003,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-1.1e-05,-6.1e-05,8.4e-07,-1.1e-05,2.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00019,0.00019,0.00011,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-09,2.6e-09,2.2e-09,3.6e-06,3.6e-06,5.3e-07,0,0,0,0,0,0,0,0
14890000,0.7,0.00031,-0.013,0.71,0.0045,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-1.1e-05,-6.1e-05,1.3e-06,-1.1e-05,2.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.0002,0.0002,0.00011,0.048,0.048,0.031,0.054,0.054,0.052,2.6e-09,2.6e-09,2.2e-09,3.6e-06,3.6e-06,5.1e-07,0,0,0,0,0,0,0,0
14990000,0.7,0.0003,-0.013,0.71,0.0034,-0.0019,-0.029,0.0031,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,1.2e-06,-1.2e-05,2.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00019,0.00019,0.0001,0.042,0.042,0.03,0.047,0.047,0.051,2.4e-09,2.4e-09,2.1e-09,3.5e-06,3.5e-06,4.8e-07,0,0,0,0,0,0,0,0
15090000,0.7,0.00023,-0.013,0.71,0.0038,-0.0021,-0.032,0.0035,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.2e-06,-1.1e-05,2.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00019,0.00019,0.0001,0.047,0.047,0.031,0.054,0.054,0.052,2.4e-09,2.4e-09,2e-09,3.5e-06,3.5e-06,4.6e-07,0,0,0,0,0,0,0,0
15190000,0.7,0.00025,-0.013,0.71,0.0032,-0.00083,-0.029,0.0028,-0.0024,-3.7e+02,-1.2e-05,-6.1e-05,1.2e-06,-1.1e-05,2.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00019,0.00019,0.0001,0.041,0.041,0.03,0.047,0.047,0.052,2.3e-09,2.3e-09,2e-09,3.5e-06,3.5e-06,4.3e-07,0,0,0,0,0,0,0,0
15290000,0.7,0.00021,-0.013,0.71,0.0037,-0.00068,-0.027,0.0031,-0.0025,-3.7e+02,-1.2e-05,-6.1e-05,1.6e-06,-1.2e-05,2.6e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00019,0.00019,0.0001,0.046,0.046,0.03,0.054,0.054,0.052,2.3e-09,2.3e-09,1.9e-09,3.5e-06,3.5e-06,4.2e-07,0,0,0,0,0,0,0,0
15390000,0.7,0.00021,-0.013,0.71,0.003,-0.00032,-0.025,0.00052,-0.002,-3.7e+02,-1.2e-05,-6.1e-05,2.5e-06,-1.2e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00018,0.00018,0.0001,0.04,0.04,0.029,0.047,0.047,0.051,2.1e-09,2.1e-09,1.8e-09,3.5e-06,3.5e-06,3.9e-07,0,0,0,0,0,0,0,0
15490000,0.7,0.00023,-0.013,0.71,0.0043,-0.00071,-0.025,0.0009,-0.0021,-3.7e+02,-1.2e-05,-6.1e-05,2.1e-06,-1.2e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00019,0.00019,0.0001,0.045,0.045,0.029,0.053,0.053,0.053,2.1e-09,2.1e-09,1.8e-09,3.5e-06,3.5e-06,3.7e-07,0,0,0,0,0,0,0,0
15590000,0.7,0.00024,-0.013,0.71,0.0024,-0.00069,-0.023,-0.0013,-0.0017,-3.7e+02,-1.2e-05,-6.1e-05,1.8e-06,-1.2e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00018,0.00018,0.0001,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-09,1.9e-09,1.7e-09,3.5e-06,3.5e-06,3.5e-07,0,0,0,0,0,0,0,0
15690000,0.7,0.00025,-0.013,0.71,0.0027,-0.00087,-0.024,-0.0011,-0.0018,-3.7e+02,-1.2e-05,-6.1e-05,1.8e-06,-1.2e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00019,0.00018,0.0001,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-09,1.9e-09,1.7e-09,3.5e-06,3.5e-06,3.3e-07,0,0,0,0,0,0,0,0
15790000,0.7,0.00021,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00099,-0.0028,-3.7e+02,-1.2e-05,-6.1e-05,1.8e-06,-1.5e-05,3.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00018,0.00018,9.9e-05,0.039,0.039,0.027,0.046,0.046,0.051,1.8e-09,1.8e-09,1.6e-09,3.4e-06,3.4e-06,3.1e-07,0,0,0,0,0,0,0,0
15890000,0.7,0.00016,-0.013,0.71,0.0041,-0.003,-0.024,-0.00059,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,2e-06,-1.5e-05,3.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00018,0.00018,9.9e-05,0.044,0.044,0.027,0.053,0.053,0.052,1.8e-09,1.8e-09,1.6e-09,3.4e-06,3.4e-06,3e-07,0,0,0,0,0,0,0,0
15990000,0.7,0.0001,-0.013,0.71,0.004,-0.0039,-0.02,-0.00067,-0.0039,-3.7e+02,-1.2e-05,-6.1e-05,2.5e-06,-1.8e-05,3.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00017,0.00017,9.8e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.7e-09,1.7e-09,1.5e-09,3.4e-06,3.4e-06,2.8e-07,0,0,0,0,0,0,0,0
16090000,0.71,0.0001,-0.013,0.71,0.0057,-0.0041,-0.016,-0.0002,-0.0043,-3.7e+02,-1.2e-05,-6.1e-05,3.3e-06,-1.8e-05,3.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00018,0.00018,9.8e-05,0.043,0.043,0.025,0.053,0.053,0.052,1.7e-09,1.7e-09,1.5e-09,3.4e-06,3.4e-06,2.7e-07,0,0,0,0,0,0,0,0
16190000,0.71,0.00013,-0.013,0.71,0.0057,-0.0034,-0.015,-0.00041,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,3.4e-06,-1.7e-05,3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00017,0.00017,9.7e-05,0.038,0.038,0.025,0.046,0.046,0.051,1.5e-09,1.5e-09,1.4e-09,3.4e-06,3.4e-06,2.5e-07,0,0,0,0,0,0,0,0
16290000,0.71,0.00014,-0.013,0.71,0.0073,-0.0042,-0.016,0.00025,-0.0038,-3.7e+02,-1.2e-05,-6.1e-05,4.1e-06,-1.7e-05,3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00017,0.00017,9.7e-05,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-09,1.5e-09,1.4e-09,3.4e-06,3.4e-06,2.4e-07,0,0,0,0,0,0,0,0
16390000,0.71,0.00013,-0.013,0.71,0.0062,-0.0044,-0.015,-8e-05,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,3.9e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00017,0.00017,9.6e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-09,1.4e-09,1.4e-09,3.3e-06,3.4e-06,2.2e-07,0,0,0,0,0,0,0,0
16490000,0.71,0.00015,-0.013,0.71,0.0054,-0.0039,-0.018,0.00048,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,4.1e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00017,0.00017,9.6e-05,0.042,0.042,0.023,0.052,0.052,0.052,1.4e-09,1.4e-09,1.3e-09,3.3e-06,3.4e-06,2.1e-07,0,0,0,0,0,0,0,0
16590000,0.71,0.00041,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0025,-7.2e-05,-3.7e+02,-1.3e-05,-6e-05,4.2e-06,-8.7e-06,4.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.00016,0.00016,9.5e-05,0.037,0.037,0.022,0.046,0.046,0.051,1.3e-09,1.3e-09,1.3e-09,3.3e-06,3.3e-06,2e-07,0,0,0,0,0,0,0,0
16690000,0.71,0.0004,-0.013,0.71,0.002,-0.00071,-0.015,-0.0023,-0.00017,-3.7e+02,-1.3e-05,-6e-05,3.9e-06,-9.3e-06,4.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00017,0.00016,9.4e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.3e-09,1.3e-09,1.2e-09,3.3e-06,3.3e-06,1.9e-07,0,0,0,0,0,0,0,0
16790000,0.71,0.00055,-0.013,0.71,-0.0014,0.0015,-0.014,-0.0047,0.0025,-3.7e+02,-1.3e-05,-6e-05,3.9e-06,-3.7e-06,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00016,0.00016,9.4e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.2e-09,1.2e-09,1.2e-09,3.3e-06,3.3e-06,1.8e-07,0,0,0,0,0,0,0,0
16890000,0.71,0.00056,-0.013,0.71,-0.0016,0.0024,-0.011,-0.0048,0.0027,-3.7e+02,-1.3e-05,-6e-05,3.7e-06,-4.1e-06,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00016,0.00016,9.4e-05,0.041,0.041,0.021,0.052,0.052,0.051,1.2e-09,1.2e-09,1.2e-09,3.3e-06,3.3e-06,1.7e-07,0,0,0,0,0,0,0,0
16990000,0.71,0.0005,-0.013,0.71,-0.0016,0.00035,-0.01,-0.0052,0.00086,-3.7e+02,-1.3e-05,-6e-05,3.4e-06,-8.1e-06,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00015,0.00015,9.3e-05,0.036,0.036,0.02,0.046,0.046,0.05,1.1e-09,1.1e-09,1.1e-09,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0
17090000,0.71,0.00047,-0.013,0.71,-0.00079,0.0013,-0.01,-0.0054,0.00092,-3.7e+02,-1.3e-05,-6e-05,3.4e-06,-8.1e-06,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00016,0.00016,9.3e-05,0.04,0.04,0.02,0.052,0.052,0.05,1.1e-09,1.1e-09,1.1e-09,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0
17190000,0.71,0.00045,-0.013,0.71,-0.00034,0.0013,-0.011,-0.0057,-0.00053,-3.7e+02,-1.3e-05,-6e-05,3.7e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00015,0.00015,9.2e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.5e-10,9.6e-10,1.1e-09,3.2e-06,3.2e-06,1.5e-07,0,0,0,0,0,0,0,0
17290000,0.71,0.00043,-0.013,0.71,0.0018,0.0023,-0.0067,-0.0056,-0.00037,-3.7e+02,-1.3e-05,-6e-05,3.4e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00015,0.00015,9.2e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.5e-10,9.6e-10,1.1e-09,3.2e-06,3.2e-06,1.4e-07,0,0,0,0,0,0,0,0
17390000,0.71,0.0004,-0.013,0.71,0.0024,0.0015,-0.0047,-0.0047,-0.0016,-3.7e+02,-1.3e-05,-6e-05,3.8e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00015,0.00014,9.1e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.7e-10,8.7e-10,1e-09,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
17490000,0.71,0.00039,-0.013,0.71,0.003,0.0011,-0.003,-0.0044,-0.0015,-3.7e+02,-1.3e-05,-6e-05,3.8e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00015,0.00015,9.1e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.7e-10,8.7e-10,1e-09,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
17590000,0.71,0.0003,-0.013,0.71,0.0042,-0.00012,0.0025,-0.0037,-0.0026,-3.7e+02,-1.3e-05,-6.1e-05,3.9e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00014,0.00014,9e-05,0.034,0.034,0.017,0.046,0.046,0.048,7.8e-10,7.9e-10,9.8e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0
17690000,0.71,0.00027,-0.012,0.71,0.0051,0.00059,0.0019,-0.0033,-0.0026,-3.7e+02,-1.3e-05,-6.1e-05,4e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00014,0.00014,9e-05,0.038,0.038,0.017,0.052,0.052,0.048,7.8e-10,7.9e-10,9.5e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0
17790000,0.71,0.00018,-0.013,0.71,0.0077,0.00031,0.00056,-0.0021,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.7e-06,-1.8e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00014,0.00014,9e-05,0.033,0.033,0.016,0.045,0.045,0.048,7.1e-10,7.1e-10,9.3e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
17890000,0.71,0.00019,-0.013,0.71,0.0092,-0.00045,0.00065,-0.0012,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,5e-06,-1.8e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00014,0.00014,8.9e-05,0.037,0.037,0.016,0.052,0.052,0.048,7.1e-10,7.1e-10,9e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
17990000,0.71,0.00013,-0.013,0.71,0.011,-0.0022,0.0019,-0.00054,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,4.9e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00013,0.00013,8.9e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-10,6.4e-10,8.8e-10,3.1e-06,3.1e-06,1e-07,0,0,0,0,0,0,0,0
18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0024,0.0043,0.00059,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.5e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00014,0.00014,8.8e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-10,6.4e-10,8.6e-10,3.1e-06,3.1e-06,9.7e-08,0,0,0,0,0,0,0,0
18190000,0.71,0.00011,-0.013,0.71,0.012,-0.0013,0.0056,0.0015,-0.0017,-3.7e+02,-1.3e-05,-6.1e-05,4.7e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00013,0.00013,8.8e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-10,5.8e-10,8.4e-10,3.1e-06,3.1e-06,9.2e-08,0,0,0,0,0,0,0,0
18290000,0.71,4.8e-05,-0.012,0.71,0.012,-0.0018,0.0068,0.0027,-0.0018,-3.7e+02,-1.3e-05,-6.1e-05,4.6e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00013,0.00013,8.8e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-10,5.8e-10,8.2e-10,3.1e-06,3.1e-06,8.9e-08,0,0,0,0,0,0,0,0
18390000,0.71,6.4e-05,-0.013,0.71,0.014,-0.00018,0.0079,0.0032,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.9e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00013,0.00013,8.7e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.3e-10,5.3e-10,8e-10,3.1e-06,3.1e-06,8.4e-08,0,0,0,0,0,0,0,0
18490000,0.71,7.9e-05,-0.012,0.71,0.014,0.00023,0.0076,0.0047,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,5e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00013,0.00013,8.7e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.3e-10,5.3e-10,7.8e-10,3.1e-06,3.1e-06,8.2e-08,0,0,0,0,0,0,0,0
18590000,0.71,8.3e-05,-0.012,0.71,0.013,0.00047,0.0057,0.0035,-0.0012,-3.7e+02,-1.3e-05,-6.1e-05,5.4e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00012,0.00012,8.6e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-10,4.8e-10,7.6e-10,3.1e-06,3.1e-06,7.8e-08,0,0,0,0,0,0,0,0
18690000,0.71,5.2e-05,-0.012,0.71,0.014,-0.00022,0.0038,0.0049,-0.0011,-3.7e+02,-1.3e-05,-6.1e-05,5.3e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00013,0.00012,8.6e-05,0.034,0.034,0.013,0.051,0.051,0.045,4.8e-10,4.8e-10,7.4e-10,3.1e-06,3.1e-06,7.5e-08,0,0,0,0,0,0,0,0
18790000,0.71,8.3e-05,-0.012,0.71,0.012,8.7e-05,0.0035,0.0037,-0.0009,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00012,0.00012,8.6e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.4e-10,4.4e-10,7.3e-10,3.1e-06,3.1e-06,7.2e-08,0,0,0,0,0,0,0,0
18890000,0.71,0.00011,-0.012,0.71,0.013,0.00058,0.0041,0.005,-0.00084,-3.7e+02,-1.4e-05,-6.1e-05,5.6e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00012,0.00012,8.5e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.4e-10,4.4e-10,7.1e-10,3.1e-06,3.1e-06,7e-08,0,0,0,0,0,0,0,0
18990000,0.71,9.3e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.0007,-3.7e+02,-1.4e-05,-6.1e-05,5.7e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00012,0.00012,8.5e-05,0.029,0.029,0.012,0.045,0.045,0.044,4e-10,4e-10,6.9e-10,3e-06,3e-06,6.6e-08,0,0,0,0,0,0,0,0
19090000,0.71,7.7e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0078,-0.00049,-3.7e+02,-1.4e-05,-6.1e-05,5.7e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00012,0.00012,8.5e-05,0.032,0.032,0.012,0.051,0.051,0.044,4e-10,4e-10,6.8e-10,3e-06,3e-06,6.5e-08,0,0,0,0,0,0,0,0
19190000,0.71,8e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0086,-0.00044,-3.7e+02,-1.4e-05,-6.1e-05,5.9e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00012,0.00011,8.4e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-10,3.6e-10,6.6e-10,3e-06,3e-06,6.2e-08,0,0,0,0,0,0,0,0
19290000,0.71,0.0001,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00025,-3.7e+02,-1.4e-05,-6.1e-05,5.7e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00012,0.00012,8.4e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-10,3.6e-10,6.5e-10,3e-06,3e-06,6e-08,0,0,0,0,0,0,0,0
19390000,0.71,0.00011,-0.012,0.71,0.013,0.00041,0.012,0.008,-0.00027,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00011,0.00011,8.4e-05,0.028,0.028,0.012,0.045,0.045,0.043,3.3e-10,3.3e-10,6.4e-10,3e-06,3e-06,5.8e-08,0,0,0,0,0,0,0,0
19490000,0.71,0.00014,-0.012,0.71,0.012,-0.0003,0.0088,0.0092,-0.00027,-3.7e+02,-1.4e-05,-6.1e-05,6.1e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00011,0.00011,8.3e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-10,3.3e-10,6.2e-10,3e-06,3e-06,5.6e-08,0,0,0,0,0,0,0,0
19590000,0.71,0.00019,-0.012,0.71,0.0097,-0.0013,0.0081,0.0075,-0.00029,-3.7e+02,-1.4e-05,-6.1e-05,6.5e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00011,0.00011,8.3e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-10,3e-10,6.1e-10,3e-06,3e-06,5.4e-08,0,0,0,0,0,0,0,0
19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0035,0.0096,0.0084,-0.00054,-3.7e+02,-1.4e-05,-6.1e-05,6.3e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00011,0.00011,8.3e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-10,3e-10,5.9e-10,3e-06,3e-06,5.2e-08,0,0,0,0,0,0,0,0
19790000,0.71,0.00025,-0.012,0.71,0.0077,-0.0043,0.01,0.0068,-0.00043,-3.7e+02,-1.4e-05,-6.1e-05,6.3e-06,-1.7e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00011,0.00011,8.3e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,5.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19890000,0.71,0.0002,-0.012,0.71,0.0065,-0.0046,0.011,0.0076,-0.0009,-3.7e+02,-1.4e-05,-6.1e-05,6.7e-06,-1.7e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00011,0.00011,8.2e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-10,2.7e-10,5.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19990000,0.71,0.00019,-0.012,0.71,0.0041,-0.0053,0.014,0.0061,-0.00075,-3.7e+02,-1.4e-05,-6.1e-05,7.2e-06,-1.7e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00011,0.00011,8.2e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-10,2.5e-10,5.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20090000,0.71,0.00018,-0.012,0.71,0.0038,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-1.4e-05,-6.1e-05,7.7e-06,-1.7e-05,7.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00011,0.00011,8.2e-05,0.028,0.028,0.01,0.05,0.05,0.042,2.5e-10,2.5e-10,5.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20190000,0.71,0.00029,-0.012,0.71,0.0015,-0.0079,0.017,0.0042,-0.0011,-3.7e+02,-1.4e-05,-6e-05,7.9e-06,-1.5e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.0001,0.0001,8.1e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-10,2.3e-10,5.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20290000,0.71,0.00025,-0.012,0.71,0.00036,-0.0095,0.015,0.0043,-0.0019,-3.7e+02,-1.4e-05,-6e-05,8e-06,-1.6e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00011,0.00011,8.1e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-10,2.3e-10,5.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20390000,0.71,0.00027,-0.012,0.71,-0.0021,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-1.4e-05,-6e-05,8e-06,-1.4e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.0001,0.0001,8.1e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-10,2.1e-10,5.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20490000,0.71,0.00032,-0.012,0.71,-0.0026,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-1.4e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.0001,0.0001,8.1e-05,0.027,0.027,0.0096,0.049,0.049,0.041,2.1e-10,2.1e-10,5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20590000,0.71,0.00034,-0.012,0.71,-0.0022,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-1.2e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.0001,0.0001,8e-05,0.024,0.024,0.0094,0.044,0.044,0.04,2e-10,2e-10,4.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20690000,0.71,0.00037,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-1.2e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.0001,0.0001,8e-05,0.026,0.026,0.0093,0.049,0.049,0.04,2e-10,2e-10,4.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20790000,0.71,0.0004,-0.012,0.71,-0.0033,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.0001,0.0001,8e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-10,1.8e-10,4.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20890000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.014,0.001,-0.0038,-3.7e+02,-1.4e-05,-6e-05,8.1e-06,-1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.0001,0.0001,7.9e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-10,1.8e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.015,0.0027,-0.0031,-3.7e+02,-1.4e-05,-6e-05,8.1e-06,-8.3e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,9.8e-05,9.8e-05,7.9e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-10,1.7e-10,4.6e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21090000,0.71,0.00038,-0.012,0.71,-0.0041,-0.017,0.015,0.0022,-0.0046,-3.7e+02,-1.4e-05,-6e-05,8.2e-06,-8.3e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,9.9e-05,9.9e-05,7.9e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-10,1.7e-10,4.5e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
21190000,0.71,0.00042,-0.012,0.71,-0.0034,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-1.4e-05,-6e-05,8.1e-06,-6e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,9.7e-05,9.7e-05,7.9e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-10,1.6e-10,4.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21290000,0.71,0.00046,-0.012,0.71,-0.0039,-0.018,0.016,0.0034,-0.0054,-3.7e+02,-1.4e-05,-6e-05,8.4e-06,-5.9e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,9.8e-05,9.8e-05,7.8e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.6e-10,1.6e-10,4.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21390000,0.71,0.00051,-0.012,0.71,-0.0047,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-1.4e-05,-6e-05,8.2e-06,-2.2e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,9.6e-05,9.6e-05,7.8e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-10,1.4e-10,4.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21490000,0.71,0.00052,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0051,-3.7e+02,-1.4e-05,-6e-05,8.3e-06,-2.3e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,9.7e-05,9.6e-05,7.8e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-10,1.4e-10,4.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21590000,0.71,0.00054,-0.012,0.71,-0.0058,-0.015,0.015,0.0019,-0.0031,-3.7e+02,-1.4e-05,-6e-05,8.2e-06,1.1e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,9.5e-05,9.5e-05,7.8e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-10,1.3e-10,4.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21690000,0.71,0.00055,-0.012,0.71,-0.0057,-0.016,0.017,0.0013,-0.0047,-3.7e+02,-1.4e-05,-6e-05,8.3e-06,1.1e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,9.6e-05,9.5e-05,7.8e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-10,1.3e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21790000,0.71,0.00057,-0.012,0.71,-0.0063,-0.011,0.015,8.5e-05,-0.00073,-3.7e+02,-1.4e-05,-5.9e-05,8e-06,6.3e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,9.4e-05,9.4e-05,7.7e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.3e-10,1.3e-10,3.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21890000,0.71,0.00057,-0.012,0.71,-0.0063,-0.012,0.016,-0.00055,-0.0019,-3.7e+02,-1.4e-05,-5.9e-05,8e-06,6.2e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,9.4e-05,9.4e-05,7.7e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-10,1.3e-10,3.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21990000,0.71,0.00062,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-1.4e-05,-5.9e-05,7.9e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.3e-05,9.3e-05,7.7e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-10,1.2e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22090000,0.71,0.00063,-0.012,0.71,-0.0071,-0.0082,0.015,-0.0021,0.00065,-3.7e+02,-1.4e-05,-5.9e-05,7.9e-06,1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.4e-05,9.3e-05,7.7e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-10,1.2e-10,3.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22190000,0.71,0.0006,-0.012,0.71,-0.0069,-0.0073,0.015,-0.0018,0.0006,-3.7e+02,-1.4e-05,-5.9e-05,7.9e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.2e-05,9.2e-05,7.6e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-10,1.1e-10,3.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22290000,0.71,0.00064,-0.012,0.71,-0.0082,-0.008,0.015,-0.0025,-0.00017,-3.7e+02,-1.4e-05,-5.9e-05,7.7e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.3e-05,9.2e-05,7.6e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-10,1.1e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22390000,0.71,0.00062,-0.012,0.71,-0.0088,-0.0075,0.017,-0.0022,-0.00016,-3.7e+02,-1.4e-05,-5.9e-05,7.8e-06,1.2e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.1e-05,9.1e-05,7.6e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-10,1e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22490000,0.71,0.00062,-0.012,0.71,-0.0095,-0.0074,0.018,-0.0031,-0.00093,-3.7e+02,-1.4e-05,-5.9e-05,7.7e-06,1.2e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.2e-05,9.2e-05,7.6e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-10,1e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22590000,0.71,0.00061,-0.012,0.71,-0.0092,-0.007,0.017,-0.0034,0.00015,-3.7e+02,-1.4e-05,-5.9e-05,7.7e-06,1.4e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.1e-05,9e-05,7.5e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-11,9.7e-11,3.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22690000,0.71,0.00064,-0.012,0.71,-0.01,-0.0067,0.018,-0.0043,-0.00053,-3.7e+02,-1.4e-05,-5.9e-05,7.8e-06,1.4e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.1e-05,9.1e-05,7.5e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-11,9.7e-11,3.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22790000,0.71,0.00062,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00042,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9e-05,9e-05,7.5e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-11,9.2e-11,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22890000,0.71,0.00063,-0.012,0.71,-0.012,-0.0051,0.021,-0.0066,-0.00096,-3.7e+02,-1.4e-05,-5.9e-05,7.2e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9e-05,9e-05,7.5e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-11,9.2e-11,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
22990000,0.71,0.00062,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00085,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.5e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,8.9e-05,8.9e-05,7.5e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-11,8.7e-11,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23090000,0.71,0.00058,-0.012,0.71,-0.013,-0.0056,0.022,-0.0086,-0.0014,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.5e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9e-05,9e-05,7.5e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-11,8.7e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23190000,0.71,0.00065,-0.012,0.71,-0.014,-0.0065,0.024,-0.012,-0.0012,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.5e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,8.9e-05,8.9e-05,7.4e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-11,8.2e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23290000,0.71,0.00059,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.5e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,8.9e-05,8.9e-05,7.4e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-11,8.2e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23390000,0.71,0.00068,-0.012,0.71,-0.016,-0.008,0.022,-0.016,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.9e-06,1.6e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.8e-05,8.8e-05,7.4e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-11,7.8e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.6e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.9e-05,8.8e-05,7.4e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-11,7.8e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0076,-0.044,-0.017,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,1.8e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.8e-05,8.7e-05,7.4e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-11,7.4e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,1.8e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.8e-05,8.8e-05,7.3e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-11,7.4e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23790000,0.71,0.005,0.00066,0.71,-0.089,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,2.1e-05,6.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.7e-05,8.7e-05,7.3e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-11,7.1e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.0049,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,2.1e-05,6.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.7e-05,8.7e-05,7.3e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-11,7.1e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
23990000,0.71,0.00097,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,2.2e-05,6.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.7e-05,8.6e-05,7.3e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-11,6.7e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24090000,0.71,0.0023,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,2.2e-05,6.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.7e-05,8.7e-05,7.3e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.8e-11,6.8e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-1.4e-05,-5.9e-05,6.8e-06,2.4e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.6e-05,8.6e-05,7.3e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-11,6.4e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,2.5e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.6e-05,8.6e-05,7.2e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-11,6.5e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24390000,0.71,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-1.3e-05,-5.9e-05,6.6e-06,2.2e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.5e-05,8.5e-05,7.2e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-11,6.2e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24490000,0.71,0.0047,-0.0017,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-1.3e-05,-5.9e-05,6.5e-06,2.2e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.6e-05,8.5e-05,7.2e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-11,6.2e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.068,-0.56,-0.081,-0.045,-3.7e+02,-1.3e-05,-5.9e-05,6.6e-06,2.1e-05,4.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.5e-05,8.5e-05,7.2e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-11,5.9e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-1.3e-05,-5.9e-05,6.7e-06,2e-05,4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.5e-05,8.5e-05,7.2e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-11,5.9e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.094,-0.72,-0.1,-0.063,-3.7e+02,-1.3e-05,-5.9e-05,6.5e-06,2.5e-05,3.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.4e-05,8.4e-05,7.2e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-11,5.7e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-1.3e-05,-5.9e-05,6.4e-06,2.5e-05,3.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.4e-05,8.4e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-11,5.7e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-1.3e-05,-5.9e-05,6.2e-06,3.4e-05,2.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.3e-05,8.3e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.5e-11,5.5e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-1.3e-05,-5.9e-05,6e-06,3.4e-05,2.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.4e-05,8.3e-05,7.1e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.5e-11,5.5e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-1.3e-05,-5.9e-05,6.1e-06,3.1e-05,1.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.3e-05,8.2e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.3e-11,5.3e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-1.3e-05,-5.9e-05,6.1e-06,3.1e-05,1.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.3e-05,8.3e-05,7.1e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-11,5.3e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3.3e-05,3.3e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.2e-05,8.2e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-11,5.1e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3.3e-05,3.4e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.2e-05,8.2e-05,7.1e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-11,5.1e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3e-05,-6e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.1e-05,8.1e-05,7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-11,4.9e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3e-05,-5.7e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.1e-05,8.1e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-11,4.9e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-1.2e-05,-5.9e-05,6.2e-06,3.8e-05,-3.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8e-05,8e-05,7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-11,4.7e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-1.2e-05,-5.9e-05,6.3e-06,3.8e-05,-3.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.1e-05,8e-05,7e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-1.1e-05,-5.9e-05,6.3e-06,3.4e-05,-4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8e-05,8e-05,7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-11,4.6e-11,2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-1.1e-05,-5.9e-05,6.1e-06,3.5e-05,-4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8e-05,8e-05,7e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-11,4.6e-11,2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-1.1e-05,-5.9e-05,6.1e-06,4.7e-05,-8.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.9e-05,7.9e-05,7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-11,4.4e-11,2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-1.1e-05,-5.9e-05,6e-06,4.7e-05,-8.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.9e-05,7.9e-05,7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-11,4.5e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-1e-05,-5.9e-05,6e-06,3.4e-05,-9.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.8e-05,7.8e-05,7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-11,4.3e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-1e-05,-5.9e-05,6e-06,3.4e-05,-9.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.9e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-11,4.3e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-9.5e-06,-5.9e-05,5.6e-06,4.4e-05,-0.00013,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.8e-05,7.7e-05,6.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-11,4.2e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-9.5e-06,-5.9e-05,5.7e-06,4.4e-05,-0.00013,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.8e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-9e-06,-6e-05,5.5e-06,2.2e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.7e-05,7.7e-05,6.9e-05,0.015,0.014,0.008,0.039,0.039,0.035,4.1e-11,4.1e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-9e-06,-6e-05,5.6e-06,2.1e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,7.7e-05,7.7e-05,6.9e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4.1e-11,4.1e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-7.9e-06,-6e-05,5.5e-06,3.1e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.6e-05,7.6e-05,6.9e-05,0.015,0.014,0.008,0.039,0.039,0.035,4e-11,4e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-7.9e-06,-6e-05,5.4e-06,3.1e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.6e-05,6.9e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-7.8e-06,-5.9e-05,5.5e-06,4.1e-05,-0.0002,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.6e-05,7.6e-05,6.9e-05,0.016,0.015,0.0081,0.045,0.045,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-7.8e-06,-5.9e-05,5.5e-06,4.1e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.6e-05,6.8e-05,0.017,0.016,0.0081,0.05,0.049,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27390000,0.71,0.037,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-7.2e-06,-5.9e-05,5.6e-06,6.1e-05,-0.00021,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.8e-05,0.017,0.016,0.0081,0.052,0.052,0.035,3.9e-11,3.9e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27490000,0.71,0.031,0.063,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-7.2e-06,-5.9e-05,5.5e-06,6e-05,-0.00021,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.8e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-11,3.9e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-7.5e-06,-5.9e-05,5.6e-06,5.9e-05,-0.00019,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.017,0.0082,0.06,0.059,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27690000,0.71,0.026,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-7.5e-06,-5.9e-05,5.4e-06,5.9e-05,-0.00019,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.7e-05,6.7e-05,0.019,0.018,0.0083,0.065,0.065,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-7.6e-06,-5.8e-05,5.3e-06,6e-05,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.019,0.018,0.0082,0.068,0.067,0.035,3.8e-11,3.8e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-7.6e-06,-5.8e-05,5.3e-06,5.8e-05,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.02,0.019,0.0083,0.074,0.073,0.035,3.9e-11,3.8e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-8e-06,-5.8e-05,5.4e-06,5.3e-05,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.02,0.019,0.0083,0.076,0.076,0.035,3.8e-11,3.8e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-8e-06,-5.8e-05,5.1e-06,5.2e-05,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.021,0.02,0.0084,0.083,0.082,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-8.2e-06,-5.8e-05,5.2e-06,4.9e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.7e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.09,-4.4,-2.4,-3.7e+02,-8.2e-06,-5.8e-05,5e-06,4.7e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0086,0.092,0.092,0.036,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-8.2e-06,-5.8e-05,4.8e-06,4.5e-05,-0.00013,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.7e-05,6.6e-05,0.022,0.021,0.0087,0.1,0.099,0.036,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28490000,0.71,0.0026,0.0045,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-8.2e-06,-5.8e-05,4.8e-06,4.2e-05,-0.00012,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.8e-05,7.7e-05,6.5e-05,0.023,0.022,0.0088,0.11,0.11,0.036,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28590000,0.71,0.00085,0.001,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-8.2e-06,-5.8e-05,4.8e-06,3.8e-05,-0.00011,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.023,0.0089,0.12,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28690000,0.71,0.00015,8e-05,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,3.4e-05,-0.0001,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.025,0.025,0.009,0.13,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28790000,0.71,-0.00014,-0.00017,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-8.9e-06,-5.8e-05,4.7e-06,2.9e-06,-0.00017,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28890000,0.71,-0.00016,5.2e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-8.9e-06,-5.8e-05,4.6e-06,-1.4e-06,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.8e-05,6.5e-05,0.025,0.025,0.009,0.14,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
28990000,0.71,3.1e-05,0.0005,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-9.8e-06,-5.8e-05,4.5e-06,-2.3e-05,-0.00025,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.8e-05,6.5e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.7e-11,3.6e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29090000,0.71,0.00018,0.0009,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-9.8e-06,-5.8e-05,4.4e-06,-2.8e-05,-0.00023,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.9e-05,7.8e-05,6.5e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29190000,0.71,0.0004,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-1e-05,-5.8e-05,4.5e-06,-4.8e-05,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.5e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-11,3.6e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29290000,0.71,0.00076,0.0022,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-1e-05,-5.8e-05,4.4e-06,-5.3e-05,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.5e-05,0.025,0.026,0.0091,0.16,0.16,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
29390000,0.71,0.0013,0.0037,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-1.1e-05,-5.8e-05,4.1e-06,-6.9e-05,-0.00029,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.009,0.16,0.16,0.036,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-1.1e-05,-5.8e-05,4.1e-06,-7.4e-05,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-1.1e-05,-5.7e-05,4e-06,-9.7e-05,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.009,0.17,0.16,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-1.1e-05,-5.7e-05,3.9e-06,-0.0001,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.93,-8.5,-4.1,-3.7e+02,-1.2e-05,-5.7e-05,3.9e-06,-0.00012,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.025,0.0091,0.18,0.17,0.037,3.5e-11,3.4e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29890000,0.71,0.0029,0.0074,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-1.2e-05,-5.7e-05,3.8e-06,-0.00013,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,8e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.5e-11,3.4e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29990000,0.71,0.003,0.0076,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-1.2e-05,-5.7e-05,3.6e-06,-0.00015,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,8e-05,7.8e-05,6.4e-05,0.025,0.025,0.009,0.19,0.18,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30090000,0.71,0.003,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00015,-0.00024,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.026,0.0091,0.2,0.2,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30190000,0.71,0.0031,0.0074,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00017,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.2,0.19,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30290000,0.71,0.003,0.0072,0.71,-2,-1,0.86,-9.6,-4.6,-3.7e+02,-1.2e-05,-5.7e-05,3.4e-06,-0.00017,-0.00024,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.21,0.21,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30390000,0.71,0.003,0.0071,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00018,-0.00023,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.21,0.2,0.036,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30490000,0.71,0.0029,0.0068,0.71,-2,-1,0.83,-10,-4.8,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00019,-0.00022,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.22,0.22,0.037,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30590000,0.71,0.0028,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00019,-0.00022,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.3e-11,3.2e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.0002,-0.00021,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.23,0.23,0.037,3.3e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30790000,0.71,0.0026,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00021,-0.0002,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30890000,0.71,0.0025,0.0055,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00021,-0.00019,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.24,0.24,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30990000,0.71,0.0024,0.005,0.71,-1.8,-0.96,0.76,-11,-5.3,-3.7e+02,-1.3e-05,-5.7e-05,3.1e-06,-0.00022,-0.00018,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31090000,0.71,0.0022,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-1.3e-05,-5.7e-05,3e-06,-0.00023,-0.00017,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.25,0.24,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31190000,0.71,0.0022,0.0043,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00024,-0.00014,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.1e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31290000,0.71,0.002,0.0038,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00024,-0.00013,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.1e-05,0.026,0.027,0.0089,0.26,0.25,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30590000,0.71,0.0028,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00019,-0.00022,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.7e-05,6.3e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.3e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.0002,-0.00021,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.23,0.23,0.037,3.3e-11,3.2e-11,1.2e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30790000,0.71,0.0027,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00021,-0.0002,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30890000,0.71,0.0025,0.0055,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00021,-0.00019,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.24,0.24,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
30990000,0.71,0.0025,0.005,0.71,-1.8,-0.96,0.76,-11,-5.3,-3.7e+02,-1.3e-05,-5.7e-05,3.1e-06,-0.00022,-0.00018,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.2e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31090000,0.71,0.0022,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-1.3e-05,-5.7e-05,3e-06,-0.00023,-0.00017,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.25,0.24,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31190000,0.71,0.0022,0.0043,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00024,-0.00014,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31290000,0.71,0.002,0.0038,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00025,-0.00013,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.0089,0.26,0.25,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31390000,0.71,0.0018,0.0033,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00025,-0.00011,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31490000,0.71,0.0016,0.0027,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00026,-0.0001,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.027,0.0088,0.26,0.26,0.037,3.1e-11,3.1e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31590000,0.71,0.0016,0.0023,0.71,-1.7,-0.91,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-8.3e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31690000,0.71,0.0013,0.0017,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-7.1e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31790000,0.71,0.0011,0.0011,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00028,-5.3e-05,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31890000,0.71,0.00087,0.00038,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00029,-4e-05,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31990000,0.71,0.00074,-8.2e-05,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.0003,-2.1e-05,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
32090000,0.71,0.00045,-0.0008,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.0003,-6.3e-06,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
32190000,0.71,0.00024,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00031,1.4e-05,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-11,2.9e-11,9.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32290000,0.71,9.8e-06,-0.0023,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00032,3e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.3,0.3,0.037,3e-11,2.9e-11,9.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32390000,0.71,-0.00017,-0.0029,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00032,3.9e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-11,2.9e-11,9.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32490000,0.71,-0.00029,-0.0032,0.71,-1.4,-0.81,0.72,-14,-6.6,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00033,5.1e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-11,2.9e-11,9.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32590000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,5.8e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0084,0.31,0.31,0.036,2.9e-11,2.9e-11,9.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32690000,0.71,-0.00033,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,6.4e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,5.9e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32790000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00034,7.3e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0084,0.32,0.31,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32890000,0.71,-0.0002,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00034,8.4e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.9e-11,2.9e-11,9.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32990000,0.71,-7.3e-05,-0.0033,0.71,-1.3,-0.77,0.7,-15,-7,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00035,9.7e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.32,0.32,0.036,2.8e-11,2.8e-11,9.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33090000,0.71,-0.00011,-0.0033,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.0001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-11,2.8e-11,9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.00011,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.33,0.33,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33290000,0.65,0.015,-0.0015,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00036,0.00011,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,8e-05,7.4e-05,6.1e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33390000,0.55,0.013,-0.0017,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,7.9e-05,7.5e-05,6.5e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-11,2.8e-11,8.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33490000,0.41,0.0069,0.00072,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5e-05,7.8e-05,7.7e-05,7e-05,0.026,0.026,0.0081,0.36,0.35,0.036,2.8e-11,2.8e-11,8.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33590000,0.25,0.00099,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.7e-05,7.6e-05,7.8e-05,7.3e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33690000,0.087,-0.0023,-0.0049,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.5e-05,7.5e-05,8e-05,7.6e-05,0.028,0.028,0.0076,0.36,0.36,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33790000,-0.082,-0.0038,-0.0067,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.4e-05,7.2e-05,8e-05,7.6e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-11,2.7e-11,8.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33890000,-0.25,-0.0049,-0.0074,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.6e-05,7.2e-05,8.1e-05,7.5e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-11,2.8e-11,8.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33990000,-0.39,-0.0031,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.8e-05,6.9e-05,7.8e-05,7.2e-05,0.032,0.032,0.007,0.37,0.37,0.035,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34090000,-0.5,-0.0021,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.6e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.1e-05,6.9e-05,7.8e-05,6.9e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34190000,-0.57,-0.0014,-0.011,0.82,-0.92,-0.54,0.74,-16,-7.8,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,6.5e-05,7.3e-05,6.7e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
31490000,0.71,0.0016,0.0027,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00026,-9.9e-05,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.027,0.0088,0.26,0.26,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31590000,0.71,0.0016,0.0024,0.71,-1.7,-0.91,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-8.2e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3.1e-11,3e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31690000,0.71,0.0013,0.0017,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-7e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31790000,0.71,0.0011,0.0011,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00028,-5.2e-05,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31890000,0.71,0.00088,0.00038,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00029,-3.9e-05,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
31990000,0.71,0.00074,-7.4e-05,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.0003,-2e-05,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
32090000,0.71,0.00046,-0.00079,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.0003,-4.9e-06,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
32190000,0.71,0.00025,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00031,1.6e-05,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-11,2.9e-11,9.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32290000,0.71,1.3e-05,-0.0023,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00032,3.2e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.3,0.3,0.037,3e-11,2.9e-11,9.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32390000,0.71,-0.00017,-0.0029,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00032,4.1e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-11,2.9e-11,9.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32490000,0.71,-0.00029,-0.0032,0.71,-1.4,-0.81,0.72,-14,-6.6,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00033,5.2e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-11,2.9e-11,9.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32590000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,5.9e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0084,0.31,0.31,0.036,2.9e-11,2.9e-11,9.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32690000,0.71,-0.00033,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,6.5e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-11,2.9e-11,9.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32790000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00034,7.4e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.4e-05,6e-05,0.025,0.025,0.0084,0.32,0.31,0.036,2.9e-11,2.9e-11,9.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32890000,0.71,-0.0002,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00034,8.5e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
32990000,0.71,-7e-05,-0.0033,0.71,-1.3,-0.76,0.7,-15,-7,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00035,9.8e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.32,0.32,0.036,2.8e-11,2.8e-11,9.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33090000,0.71,-0.0001,-0.0033,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.0001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-11,2.8e-11,9.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.00011,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.33,0.33,0.036,2.8e-11,2.8e-11,9.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33290000,0.65,0.015,-0.0015,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00036,0.00011,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,8e-05,7.4e-05,6.1e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-11,2.8e-11,9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33390000,0.55,0.013,-0.0017,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,7.9e-05,7.5e-05,6.5e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33490000,0.41,0.0069,0.00073,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.1e-05,7.8e-05,7.7e-05,7e-05,0.026,0.026,0.0081,0.36,0.35,0.036,2.8e-11,2.8e-11,8.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33590000,0.25,0.00099,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.7e-05,7.6e-05,7.8e-05,7.3e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.8e-11,2.8e-11,8.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33690000,0.087,-0.0023,-0.0049,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.5e-05,7.5e-05,8e-05,7.5e-05,0.028,0.028,0.0076,0.36,0.36,0.036,2.8e-11,2.8e-11,8.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33790000,-0.082,-0.0038,-0.0067,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.5e-05,7.2e-05,8e-05,7.6e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-11,2.7e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33890000,-0.25,-0.0049,-0.0074,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.6e-05,7.2e-05,8.1e-05,7.5e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-11,2.8e-11,8.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
33990000,-0.39,-0.0031,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.9e-05,6.9e-05,7.8e-05,7.2e-05,0.032,0.032,0.007,0.37,0.37,0.035,2.7e-11,2.7e-11,8.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34090000,-0.5,-0.002,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.6e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.2e-05,6.9e-05,7.8e-05,6.9e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-11,2.7e-11,8.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34190000,-0.57,-0.0014,-0.011,0.82,-0.92,-0.54,0.74,-16,-7.8,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,6.5e-05,7.3e-05,6.7e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34290000,-0.61,-0.0023,-0.0086,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,6.5e-05,7.3e-05,6.5e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34390000,-0.64,-0.0025,-0.0061,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00044,0.00019,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,6e-05,6.7e-05,6.4e-05,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-11,2.7e-11,8.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34490000,-0.65,-0.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00043,0.00019,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,6.1e-05,6.7e-05,6.3e-05,0.049,0.05,0.0064,0.4,0.4,0.035,2.7e-11,2.7e-11,8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00027,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-11,2.7e-11,8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.37,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00027,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-11,2.7e-11,7.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34790000,-0.67,-0.0021,-0.0018,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00064,0.00038,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34890000,-0.68,-0.0021,-0.0017,0.74,-0.7,-0.32,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00064,0.00038,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.059,0.061,0.0062,0.42,0.42,0.034,2.6e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34990000,-0.68,-0.0085,-0.0045,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.058,0.058,0.0068,0.42,0.42,0.034,2.6e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34390000,-0.64,-0.0025,-0.0061,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00044,0.00019,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,6e-05,6.7e-05,6.4e-05,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34490000,-0.65,-0.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00044,0.00019,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,6.1e-05,6.7e-05,6.3e-05,0.049,0.05,0.0064,0.4,0.4,0.035,2.7e-11,2.7e-11,8.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00028,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.3e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-11,2.7e-11,8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.37,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00028,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-11,2.7e-11,8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34790000,-0.67,-0.0021,-0.0018,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00064,0.00038,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-11,2.7e-11,7.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34890000,-0.68,-0.0021,-0.0017,0.74,-0.71,-0.32,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00064,0.00038,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.059,0.061,0.0062,0.42,0.42,0.034,2.6e-11,2.7e-11,7.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34990000,-0.68,-0.0085,-0.0045,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.2e-05,0.058,0.058,0.0068,0.42,0.42,0.034,2.6e-11,2.7e-11,7.8e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35090000,-0.68,-0.0085,-0.0045,0.73,0.43,0.31,-0.19,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.063,0.063,0.0068,0.43,0.43,0.034,2.7e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35190000,-0.68,-0.0085,-0.0045,0.73,0.45,0.34,-0.18,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.068,0.068,0.0067,0.44,0.44,0.034,2.7e-11,2.7e-11,7.6e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35290000,-0.68,-0.0086,-0.0046,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.073,0.074,0.0066,0.46,0.45,0.033,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35390000,-0.68,-0.0086,-0.0046,0.73,0.5,0.41,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.079,0.08,0.0066,0.47,0.47,0.034,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35490000,-0.68,-0.0087,-0.0046,0.73,0.52,0.44,-0.18,-17,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.085,0.087,0.0065,0.49,0.49,0.034,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35590000,-0.68,-0.0056,-0.0045,0.73,0.41,0.36,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6.1e-05,0.068,0.069,0.0062,0.48,0.48,0.033,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35690000,-0.68,-0.0057,-0.0045,0.73,0.43,0.38,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6e-05,0.073,0.075,0.0061,0.49,0.49,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35190000,-0.68,-0.0085,-0.0045,0.73,0.45,0.34,-0.18,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.068,0.068,0.0067,0.44,0.44,0.034,2.7e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35290000,-0.68,-0.0086,-0.0046,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.073,0.074,0.0066,0.46,0.45,0.033,2.7e-11,2.7e-11,7.6e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35390000,-0.68,-0.0086,-0.0046,0.73,0.5,0.41,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.079,0.08,0.0066,0.47,0.47,0.034,2.7e-11,2.7e-11,7.6e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35490000,-0.68,-0.0087,-0.0046,0.73,0.52,0.44,-0.18,-17,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.085,0.087,0.0065,0.49,0.49,0.034,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35590000,-0.68,-0.0056,-0.0045,0.73,0.41,0.36,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6.1e-05,0.068,0.069,0.0062,0.48,0.48,0.033,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35690000,-0.68,-0.0056,-0.0045,0.73,0.43,0.38,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6.1e-05,0.073,0.075,0.0061,0.49,0.49,0.033,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35790000,-0.68,-0.0034,-0.0044,0.73,0.35,0.32,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3e-06,-0.00079,0.00053,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.061,0.062,0.0059,0.49,0.48,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35890000,-0.68,-0.0034,-0.0045,0.73,0.37,0.35,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,3.1e-06,-0.00079,0.00053,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.066,0.068,0.0059,0.5,0.5,0.033,2.7e-11,2.7e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35990000,-0.68,-0.0016,-0.0044,0.73,0.3,0.29,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.3e-06,-0.00087,0.0006,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.8e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
36090000,-0.68,-0.0016,-0.0044,0.73,0.31,0.31,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00087,0.0006,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-11,2.8e-11,7.1e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
36190000,-0.68,-0.00014,-0.0043,0.73,0.26,0.27,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00097,0.00068,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-11,2.8e-11,7.1e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36290000,-0.68,-0.00021,-0.0042,0.73,0.27,0.28,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.7e-06,-0.00097,0.00068,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.06,0.062,0.0056,0.52,0.52,0.032,2.7e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36390000,-0.68,0.00084,-0.0041,0.73,0.22,0.24,-0.21,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.9e-06,-0.0011,0.00077,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36490000,-0.68,0.00079,-0.0041,0.73,0.23,0.26,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.1e-06,-0.0011,0.00077,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.059,0.061,0.0055,0.53,0.52,0.032,2.8e-11,2.8e-11,6.9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
35890000,-0.68,-0.0034,-0.0045,0.73,0.37,0.35,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,3.1e-06,-0.00079,0.00053,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.066,0.068,0.0059,0.5,0.5,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
35990000,-0.68,-0.0015,-0.0044,0.73,0.3,0.29,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.3e-06,-0.00087,0.0006,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.8e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
36090000,-0.68,-0.0016,-0.0044,0.73,0.31,0.31,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00087,0.0006,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-11,2.8e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
36190000,-0.68,-0.00014,-0.0042,0.73,0.26,0.27,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00097,0.00068,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-11,2.8e-11,7.1e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36290000,-0.68,-0.0002,-0.0042,0.73,0.27,0.28,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.7e-06,-0.00097,0.00068,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.06,0.062,0.0056,0.52,0.52,0.032,2.7e-11,2.8e-11,7.1e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36390000,-0.68,0.00085,-0.0041,0.73,0.22,0.24,-0.21,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.9e-06,-0.0011,0.00077,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36490000,-0.68,0.00079,-0.0041,0.73,0.23,0.26,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.1e-06,-0.0011,0.00077,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.059,0.061,0.0055,0.53,0.52,0.032,2.8e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36590000,-0.68,0.0016,-0.004,0.73,0.19,0.22,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.3e-06,-0.0012,0.00086,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,6e-05,0.053,0.054,0.0055,0.52,0.52,0.031,2.8e-11,2.8e-11,6.9e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36690000,-0.68,0.0016,-0.004,0.74,0.19,0.23,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.4e-06,-0.0012,0.00086,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,5.9e-05,0.058,0.06,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36790000,-0.68,0.0022,-0.0039,0.74,0.16,0.2,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.5e-06,-0.0013,0.00095,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,5.9e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
36890000,-0.68,0.0022,-0.0039,0.74,0.16,0.21,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.6e-06,-0.0013,0.00095,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,5.9e-05,0.057,0.059,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
36990000,-0.68,0.0026,-0.0037,0.74,0.13,0.18,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.8e-06,-0.0015,0.001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,1.9e-05,2e-05,5.9e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
37090000,-0.68,0.0026,-0.0037,0.74,0.13,0.19,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5e-06,-0.0015,0.001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,2e-05,2.1e-05,5.9e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
37190000,-0.68,0.0029,-0.0036,0.74,0.11,0.16,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.2e-06,-0.0016,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.9e-05,2e-05,5.9e-05,0.05,0.052,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.6e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
36690000,-0.68,0.0016,-0.004,0.74,0.19,0.23,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.4e-06,-0.0012,0.00086,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,6e-05,0.058,0.06,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.9e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
36790000,-0.68,0.0022,-0.0039,0.74,0.16,0.2,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.5e-06,-0.0013,0.00095,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,6e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
36890000,-0.68,0.0022,-0.0039,0.74,0.16,0.21,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.7e-06,-0.0013,0.00095,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,5.9e-05,0.057,0.059,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.8e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
36990000,-0.68,0.0026,-0.0037,0.74,0.13,0.18,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.8e-06,-0.0015,0.001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,1.9e-05,2e-05,5.9e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.8e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
37090000,-0.68,0.0026,-0.0037,0.74,0.13,0.19,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5e-06,-0.0015,0.001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2e-05,2.1e-05,5.9e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
37190000,-0.68,0.0029,-0.0036,0.74,0.11,0.16,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.2e-06,-0.0016,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.9e-05,2e-05,5.9e-05,0.05,0.052,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.7e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
37290000,-0.68,0.0029,-0.0036,0.74,0.11,0.17,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.4e-06,-0.0016,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.9e-05,2e-05,5.9e-05,0.055,0.057,0.0059,0.56,0.56,0.031,2.8e-11,2.9e-11,6.6e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
37390000,-0.68,0.0032,-0.0034,0.74,0.088,0.14,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.5e-06,-0.0017,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.05,0.051,0.0059,0.56,0.56,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37490000,-0.68,0.0032,-0.0034,0.74,0.087,0.15,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.6e-06,-0.0017,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37590000,-0.68,0.0033,-0.0033,0.74,0.069,0.12,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.8e-06,-0.0017,0.0012,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.049,0.05,0.0061,0.57,0.57,0.031,2.9e-11,2.9e-11,6.4e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37690000,-0.68,0.0033,-0.0034,0.74,0.066,0.13,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.9e-06,-0.0017,0.0012,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-11,2.9e-11,6.4e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37390000,-0.68,0.0032,-0.0034,0.74,0.088,0.14,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.5e-06,-0.0017,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.05,0.051,0.0059,0.56,0.56,0.031,2.9e-11,2.9e-11,6.6e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37490000,-0.68,0.0031,-0.0034,0.74,0.087,0.15,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.7e-06,-0.0017,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37590000,-0.68,0.0033,-0.0033,0.74,0.069,0.12,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.8e-06,-0.0017,0.0012,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.049,0.05,0.0061,0.57,0.57,0.031,2.9e-11,2.9e-11,6.5e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37690000,-0.68,0.0033,-0.0033,0.74,0.066,0.13,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6e-06,-0.0017,0.0012,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-11,2.9e-11,6.5e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
37790000,-0.68,0.0034,-0.0033,0.74,0.052,0.11,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.1e-06,-0.0018,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.048,0.048,0.0063,0.58,0.58,0.03,2.9e-11,2.9e-11,6.4e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
37890000,-0.68,0.0034,-0.0033,0.74,0.05,0.11,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.3e-06,-0.0018,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.052,0.053,0.0064,0.59,0.59,0.03,2.9e-11,2.9e-11,6.3e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
37890000,-0.68,0.0034,-0.0033,0.74,0.05,0.11,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.3e-06,-0.0018,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.052,0.053,0.0064,0.59,0.59,0.03,2.9e-11,2.9e-11,6.4e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
37990000,-0.68,0.0034,-0.0033,0.74,0.037,0.097,-0.15,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.5e-06,-0.0019,0.0013,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.047,0.047,0.0065,0.59,0.59,0.031,2.9e-11,2.9e-11,6.3e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
38090000,-0.68,0.0034,-0.0033,0.74,0.034,0.1,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.6e-06,-0.0019,0.0013,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
38190000,-0.68,0.0034,-0.0032,0.74,0.022,0.085,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.8e-06,-0.002,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38090000,-0.68,0.0034,-0.0033,0.74,0.034,0.1,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.6e-06,-0.0019,0.0013,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-11,3e-11,6.3e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
38190000,-0.68,0.0034,-0.0032,0.74,0.022,0.085,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.8e-06,-0.002,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-11,3e-11,6.3e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38290000,-0.68,0.0034,-0.0032,0.74,0.019,0.086,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.9e-06,-0.002,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.049,0.05,0.0068,0.61,0.61,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38390000,-0.68,0.0034,-0.0031,0.74,0.012,0.074,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.1e-06,-0.002,0.0013,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38490000,-0.68,0.0034,-0.0031,0.74,0.0091,0.076,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.2e-06,-0.002,0.0013,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.8e-05,0.048,0.048,0.007,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38590000,-0.68,0.0034,-0.003,0.74,0.0051,0.065,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.4e-06,-0.002,0.0013,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.8e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38690000,-0.68,0.0033,-0.003,0.74,0.0012,0.065,-0.097,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.5e-06,-0.0021,0.0013,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38790000,-0.68,0.0033,-0.003,0.74,-0.0034,0.054,-0.089,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.7e-06,-0.0021,0.0013,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38390000,-0.68,0.0034,-0.0031,0.74,0.012,0.074,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.1e-06,-0.002,0.0013,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38490000,-0.68,0.0034,-0.0031,0.74,0.009,0.076,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.3e-06,-0.002,0.0013,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.048,0.048,0.007,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
38590000,-0.68,0.0034,-0.003,0.74,0.0051,0.065,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.4e-06,-0.002,0.0013,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38690000,-0.68,0.0033,-0.003,0.74,0.0012,0.065,-0.097,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.6e-06,-0.0021,0.0013,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.8e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-11,3e-11,6.1e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38790000,-0.68,0.0033,-0.003,0.74,-0.0035,0.054,-0.089,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.7e-06,-0.0021,0.0013,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
38890000,-0.67,0.0031,-0.003,0.74,-0.013,0.043,0.41,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.8e-06,-0.0021,0.0013,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.045,0.045,0.0075,0.64,0.64,0.032,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
1 Timestamp state[0] state[1] state[2] state[3] state[4] state[5] state[6] state[7] state[8] state[9] state[10] state[11] state[12] state[13] state[14] state[15] state[16] state[17] state[18] state[19] state[20] state[21] state[22] state[23] variance[0] variance[1] variance[2] variance[3] variance[4] variance[5] variance[6] variance[7] variance[8] variance[9] variance[10] variance[11] variance[12] variance[13] variance[14] variance[15] variance[16] variance[17] variance[18] variance[19] variance[20] variance[21] variance[22] variance[23]
63 6090000 1 -0.0095 -0.011 -0.022 0.0053 0.0052 -0.011 0.0021 0.00027 -3.7e+02 -1.6e-05 -5.6e-05 4.3e-07 0 0 1.4e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.5e-07 0.00038 0.00038 0.00016 0.23 0.23 7 0.1 0.1 0.33 1.8e-08 1.8e-08 5.3e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
64 6190000 1 -0.0095 -0.011 -0.022 0.0056 0.0072 -0.005 0.0027 0.00092 -3.7e+02 -1.6e-05 -5.6e-05 4.3e-07 0 0 -1.1e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.6e-07 0.00041 0.00041 0.00016 0.27 0.27 4.9 0.13 0.13 0.32 1.8e-08 1.8e-08 5e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
65 6290000 1 -0.0095 -0.011 -0.022 0.0071 0.0075 -0.012 0.0033 0.0016 -3.7e+02 -1.6e-05 -5.6e-05 4.3e-07 0 0 -1.9e-07 0.19 9.3e-10 0.4 0 0 0 0 0 1.6e-07 0.00043 0.00043 0.00016 0.31 0.31 3.2 0.17 0.17 0.3 1.8e-08 1.8e-08 4.8e-09 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
66 6390000 0.71 0.0014 -0.014 0.71 0.0048 0.0076 -0.05 0.0025 0.0017 -3.7e+02 -1.6e-05 -5.6e-05 4.3e-07 2.1e-06 0 0 4e-07 0.21 0.0021 0.44 0 0 0 0 0 0.00076 0.00077 0.00034 0.00034 0.00085 0.22 0.22 2.3 0.13 0.13 0.29 1.4e-08 1.5e-08 4.8e-09 1e-06 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
67 6490000 0.71 0.0014 -0.014 0.71 0.0043 0.0083 -0.052 0.0029 0.0025 -3.7e+02 -1.6e-05 -5.6e-05 4.1e-07 -2.3e-06 0 0 -8.7e-08 0.21 0.0021 0.44 0 0 0 0 0 0.00051 0.00053 0.00034 0.00034 0.00056 0.00058 0.22 0.22 1.5 0.16 0.16 0.26 1.4e-08 1.5e-08 4.8e-09 9.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
68 6590000 0.71 0.0015 -0.014 0.71 0.0036 0.0085 -0.099 0.0034 0.0033 0.0034 -3.7e+02 -1.6e-05 -5.6e-05 3.6e-07 -1.2e-05 0 0 1.7e-06 0.21 0.0021 0.44 0 0 0 0 0 0.00039 0.00042 0.00034 0.00034 0.00043 0.00046 0.23 0.23 1.1 0.19 0.19 0.23 1.4e-08 1.4e-08 4.8e-09 9.7e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
69 6690000 0.7 0.0015 -0.014 0.71 0.0037 0.0095 -0.076 0.0037 0.0042 0.0043 -3.7e+02 -1.6e-05 -5.6e-05 3e-07 -2.4e-05 0 0 -1.5e-06 0.21 0.0021 0.44 0 0 0 0 0 0.00031 0.00038 0.00034 0.00034 0.00035 0.00041 0.24 0.24 0.78 0.23 0.23 0.21 1.4e-08 1.4e-08 4.8e-09 9.4e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
70 6790000 0.71 0.0015 -0.014 0.71 0.0021 0.0095 -0.11 0.004 0.0052 -3.7e+02 -1.6e-05 -5.6e-05 3.3e-07 -1.6e-05 0 0 8.5e-07 0.21 0.0021 0.44 0 0 0 0 0 0.00027 0.00037 0.00034 0.00034 0.0003 0.00039 0.25 0.25 0.6 0.28 0.28 0.2 1.4e-08 1.4e-08 4.8e-09 8.9e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
71 6890000 0.71 0.0015 -0.014 0.71 -0.00021 -0.00016 0.01 -0.12 0.0041 0.0062 -3.7e+02 -1.6e-05 -5.6e-05 3.4e-07 -1.3e-05 0 0 3.4e-07 0.21 0.0021 0.44 0 0 0 0 0 0.00024 0.00036 0.00035 0.00035 0.00026 0.00037 0.26 0.26 0.46 0.33 0.33 0.18 1.4e-08 1.4e-08 4.8e-09 8.3e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
72 6990000 0.7 0.0016 -0.014 0.71 -0.00055 -0.00035 0.011 -0.12 0.004 0.0041 0.0072 -3.7e+02 -1.6e-05 -5.6e-05 1.6e-07 -4.1e-05 0 0 -2.7e-06 0.21 0.0021 0.44 0 0 0 0 0 0.00021 0.00036 0.00035 0.00035 0.00023 0.00036 0.28 0.28 0.36 0.38 0.38 0.16 1.4e-08 1.4e-08 4.8e-09 7.5e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
73 7090000 0.7 0.0016 -0.014 0.71 -0.0014 -0.00097 0.011 0.01 -0.13 0.0039 0.004 0.0083 -3.7e+02 -1.6e-05 -5.6e-05 -5.1e-08 -6.7e-05 0 0 -6.3e-06 0.21 0.0021 0.44 0 0 0 0 0 0.0002 0.00037 0.00036 0.00036 0.00022 0.00037 0.3 0.3 0.29 0.44 0.44 0.16 1.4e-08 1.4e-08 4.7e-09 6.8e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
74 7190000 0.7 0.0016 -0.014 0.71 -0.0034 -0.0028 0.011 0.01 -0.15 0.0037 0.0039 0.0093 -3.7e+02 -1.6e-05 -5.6e-05 -1.4e-07 -7.1e-05 0 0 -4.1e-06 0.21 0.0021 0.44 0 0 0 0 0 0.00018 0.00037 0.00036 0.00036 0.0002 0.00036 0.32 0.32 0.24 0.51 0.51 0.15 1.4e-08 1.4e-08 4.7e-09 6e-07 4e-06 4e-06 4e-06 0 0 0 0 0 0 0 0
75 7290000 0.7 0.0016 -0.014 0.71 -0.0052 -0.0046 0.011 -0.15 0.0033 0.0035 0.01 -3.7e+02 -1.6e-05 -5.6e-05 -1.5e-07 -6.2e-05 0 0 -1.1e-05 0.21 0.0021 0.44 0 0 0 0 0 0.00017 0.00037 0.00037 0.00037 0.00018 0.00036 0.34 0.35 0.34 0.2 0.58 0.58 0.14 1.4e-08 1.4e-08 4.7e-09 5.3e-07 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
76 7390000 0.7 0.0017 0.0016 -0.014 0.71 -0.0056 -0.005 0.012 -0.16 0.0027 0.0029 0.011 -3.7e+02 -1.6e-05 -5.6e-05 -1.3e-07 -5.3e-05 0 0 -1.2e-05 0.21 0.0021 0.44 0 0 0 0 0 0.00016 0.00037 0.00038 0.00038 0.00017 0.00036 0.37 0.37 0.18 0.66 0.66 0.13 1.4e-08 1.4e-08 4.7e-09 4.7e-07 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
77 7490000 0.7 0.0017 -0.014 0.71 -0.0076 -0.0069 0.013 0.012 -0.16 0.002 0.0023 0.013 -3.7e+02 -1.6e-05 -5.6e-05 -1.5e-07 -4.7e-05 0 0 -2e-05 0.21 0.0021 0.44 0 0 0 0 0 0.00015 0.00037 0.00039 0.00039 0.00016 0.00035 0.4 0.4 0.15 0.76 0.76 0.12 1.4e-08 1.4e-08 4.7e-09 4e-07 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
78 7590000 0.7 0.0017 -0.014 0.71 -0.0098 -0.0093 0.014 -0.17 0.0011 0.0014 0.014 -3.7e+02 -1.6e-05 -5.6e-05 -1.4e-08 -3e-05 0 0 -2.9e-05 0.21 0.0021 0.44 0 0 0 0 0 0.00014 0.00036 0.00039 0.00039 0.00015 0.00034 0.43 0.43 0.14 0.85 0.85 0.12 1.4e-08 1.4e-08 4.7e-09 3.5e-07 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
79 7690000 0.7 0.0018 -0.014 0.71 -0.012 -0.011 0.015 0.014 -0.16 2.3e-05 0.00029 0.015 -3.7e+02 -1.6e-05 -5.6e-05 -4.5e-08 -2.8e-05 0 0 -4.9e-05 0.21 0.0021 0.44 0 0 0 0 0 0.00014 0.00036 0.0004 0.0004 0.00015 0.00034 0.47 0.47 0.13 0.96 0.96 0.11 1.4e-08 1.4e-08 4.7e-09 3.1e-07 4e-06 4e-06 3.9e-06 0 0 0 0 0 0 0 0
80 7790000 0.7 0.0019 0.0018 -0.014 0.71 -0.014 -0.013 0.016 0.015 -0.16 -0.0013 -0.00078 0.017 0.016 -3.7e+02 -1.6e-05 -5.6e-05 -3.7e-07 -4.3e-05 0 0 -6.9e-05 0.21 0.0021 0.44 0 0 0 0 0 0.00013 0.00035 0.00041 0.00041 0.00014 0.00033 0.51 0.51 0.12 1.1 1.1 0.11 1.4e-08 1.4e-08 4.7e-09 2.6e-07 4e-06 4e-06 3.8e-06 0 0 0 0 0 0 0 0
81 7890000 0.7 0.0019 0.0018 -0.014 0.71 -0.017 -0.016 0.018 0.017 -0.16 -0.0028 -0.0024 0.018 -3.7e+02 -1.6e-05 -5.6e-05 -2.7e-07 -3.2e-05 0 0 -9.5e-05 0.21 0.0021 0.44 0 0 0 0 0 0.00013 0.00033 0.00042 0.00042 0.00014 0.00032 0.55 0.55 0.11 1.2 1.2 0.1 1.4e-08 1.4e-08 4.7e-09 2.3e-07 4e-06 4e-06 3.8e-06 0 0 0 0 0 0 0 0
82 7990000 0.7 0.0019 -0.014 0.71 -0.019 -0.018 0.019 0.018 -0.16 -0.0046 -0.0042 0.02 -3.7e+02 -1.6e-05 -5.6e-05 -1.6e-07 -2.3e-05 0 0 -0.00011 0.21 0.0021 0.44 0 0 0 0 0 0.00012 0.00032 0.00043 0.00043 0.00013 0.00031 0.6 0.59 0.1 1.3 1.3 0.099 1.4e-08 1.4e-08 4.7e-09 2e-07 4e-06 4e-06 3.8e-06 0 0 0 0 0 0 0 0
83 8090000 0.7 0.0019 -0.014 0.71 -0.021 0.02 -0.17 -0.0066 -0.0064 0.022 -3.7e+02 -1.6e-05 -5.6e-05 6.1e-08 -1.2e-05 0 0 -0.00011 0.21 0.0021 0.44 0 0 0 0 0 0.00012 0.00032 0.00045 0.00045 0.00013 0.0003 0.65 0.65 0.1 1.5 1.5 0.097 1.4e-08 1.4e-08 4.7e-09 1.7e-07 4e-06 4e-06 3.7e-06 0 0 0 0 0 0 0 0
84 8190000 0.7 0.0019 -0.014 0.71 -0.024 0.021 -0.18 -0.0088 -0.0083 0.023 -3.7e+02 -1.6e-05 -5.6e-05 -2.1e-07 -1.9e-05 0 0 -0.00013 0.21 0.0021 0.44 0 0 0 0 0 0.00012 0.00031 0.00046 0.00046 0.00012 0.00029 0.69 0.69 0.099 1.7 1.7 0.094 1.4e-08 1.4e-08 4.6e-09 1.5e-07 4e-06 4e-06 3.7e-06 0 0 0 0 0 0 0 0
85 8290000 0.7 0.002 0.0019 -0.014 0.71 -0.026 -0.025 0.022 0.021 -0.17 -0.011 0.025 -3.7e+02 -1.6e-05 -5.6e-05 -4e-07 -2.2e-05 0 0 -0.00017 0.21 0.0021 0.44 0 0 0 0 0 0.00011 0.0003 0.00047 0.00047 0.00012 0.00028 0.75 0.75 0.097 1.9 1.9 0.091 1.4e-08 1.4e-08 4.6e-09 1.3e-07 4e-06 4e-06 3.6e-06 0 0 0 0 0 0 0 0
86 8390000 0.7 0.002 -0.014 0.71 -0.029 -0.028 0.023 -0.17 -0.014 0.028 0.027 -3.7e+02 -1.6e-05 -5.6e-05 -1.5e-07 -1.4e-05 0 0 -0.00021 0.21 0.0021 0.44 0 0 0 0 0 0.00011 0.00029 0.00048 0.00048 0.00012 0.00028 0.81 0.81 0.097 2.1 2.1 0.091 1.4e-08 1.4e-08 4.6e-09 1.2e-07 4e-06 4e-06 3.5e-06 0 0 0 0 0 0 0 0
87 8490000 0.7 0.002 -0.014 0.71 -0.031 -0.03 0.025 0.024 -0.17 -0.017 0.029 -3.7e+02 -1.6e-05 -5.6e-05 -3e-07 -1.6e-05 0 0 -0.00025 0.21 0.0021 0.44 0 0 0 0 0 0.00011 0.00028 0.00049 0.00049 0.00012 0.00027 0.87 0.87 0.096 2.3 2.3 0.089 1.4e-08 1.4e-08 4.6e-09 1.1e-07 4e-06 4e-06 3.4e-06 0 0 0 0 0 0 0 0
88 8590000 0.7 0.002 -0.014 0.71 -0.034 -0.033 0.027 0.026 -0.17 -0.021 -0.02 0.032 0.031 -3.7e+02 -1.6e-05 -5.6e-05 -6.2e-07 -2e-05 0 0 -0.00029 0.21 0.0021 0.44 0 0 0 0 0 0.00011 0.00027 0.00051 0.00051 0.00011 0.00026 0.94 0.94 0.095 2.5 2.5 0.088 1.4e-08 1.4e-08 4.6e-09 9.3e-08 4e-06 4e-06 3.3e-06 0 0 0 0 0 0 0 0
89 8690000 0.7 0.0021 -0.014 0.71 -0.037 0.028 0.027 -0.16 -0.024 -0.023 0.033 -3.7e+02 -1.6e-05 -5.6e-05 -2.5e-07 -1.1e-05 0 0 -0.00034 0.21 0.0021 0.44 0 0 0 0 0 0.00011 0.00027 0.00052 0.00052 0.00011 0.00025 0.99 0.99 0.096 2.7 2.7 0.088 1.4e-08 1.4e-08 4.5e-09 8.4e-08 4e-06 4e-06 3.3e-06 0 0 0 0 0 0 0 0
90 8790000 0.7 0.0021 0.002 -0.014 0.71 -0.04 0.03 0.029 -0.15 -0.028 -0.027 0.036 0.035 -3.7e+02 -1.6e-05 -5.6e-05 -4.7e-07 -1.4e-05 0 0 -0.00041 0.21 0.0021 0.44 0 0 0 0 0 0.0001 0.00026 0.00054 0.00054 0.00011 0.00025 1.1 1.1 0.095 3 3 0.087 1.4e-08 1.4e-08 4.5e-09 7.5e-08 4e-06 4e-06 3.1e-06 0 0 0 0 0 0 0 0
91 8890000 0.7 0.0021 0.002 -0.014 0.71 -0.043 -0.042 0.03 0.029 -0.15 -0.032 -0.031 0.038 0.037 -3.7e+02 -1.6e-05 -5.6e-05 -6.2e-07 -1.5e-05 0 0 -0.00045 0.21 0.0021 0.44 0 0 0 0 0 0.0001 0.00025 0.00055 0.00055 0.00011 0.00024 1.1 1.1 0.095 3.3 3.3 0.086 1.3e-08 1.3e-08 4.5e-09 6.7e-08 4e-06 4e-06 3e-06 0 0 0 0 0 0 0 0
92 8990000 0.7 0.0021 -0.014 0.71 -0.045 -0.044 0.031 0.03 -0.14 -0.036 -0.035 0.04 0.039 -3.7e+02 -1.6e-05 -5.6e-05 -9.6e-07 -1.8e-05 0 0 -0.0005 0.21 0.0021 0.44 0 0 0 0 0 0.0001 0.00025 0.00056 0.00056 0.00011 0.00023 1.2 1.2 0.096 3.6 3.6 0.087 1.3e-08 1.3e-08 4.4e-09 6.1e-08 4e-06 4e-06 2.9e-06 0 0 0 0 0 0 0 0
93 9090000 0.7 0.0022 0.0021 -0.014 0.71 -0.048 -0.046 0.031 0.03 -0.14 -0.04 -0.038 0.042 0.041 -3.7e+02 -1.6e-05 -5.6e-05 -1.2e-06 -1.9e-05 0 0 -0.00053 0.21 0.0021 0.44 0 0 0 0 0 0.0001 0.00024 0.00057 0.00057 0.00011 0.00023 1.3 1.3 0.095 3.9 3.9 0.086 1.3e-08 1.3e-08 4.4e-09 5.5e-08 4e-06 4e-06 2.8e-06 0 0 0 0 0 0 0 0
94 9190000 0.7 0.0022 -0.014 0.71 -0.05 -0.049 0.032 0.031 -0.14 -0.045 -0.044 0.045 0.044 -3.7e+02 -1.6e-05 -5.6e-05 -5.2e-07 -9.9e-06 0 0 -0.00057 0.21 0.0021 0.44 0 0 0 0 0 9.9e-05 0.00023 0.00059 0.00059 0.0001 0.00022 1.4 1.4 0.094 4.3 4.3 0.085 1.3e-08 1.3e-08 4.4e-09 5e-08 4e-06 4e-06 2.7e-06 0 0 0 0 0 0 0 0
95 9290000 0.7 0.0022 -0.014 0.71 -0.051 -0.05 0.033 0.032 -0.14 -0.048 -0.047 0.046 0.045 -3.7e+02 -1.6e-05 -5.6e-05 -4.7e-07 -8.5e-06 0 0 -0.00061 0.21 0.0021 0.44 0 0 0 0 0 9.9e-05 0.00023 0.0006 0.0006 0.0001 0.00022 1.4 1.4 0.093 4.5 4.5 0.085 1.3e-08 1.3e-08 4.3e-09 4.5e-08 4e-06 4e-06 2.5e-06 0 0 0 0 0 0 0 0
96 9390000 0.7 0.0022 0.0021 -0.014 0.71 -0.053 -0.052 0.035 0.034 -0.14 -0.054 -0.053 0.049 0.048 -3.7e+02 -1.6e-05 -5.6e-05 -5.1e-07 -8.2e-06 0 0 -0.00064 0.21 0.0021 0.44 0 0 0 0 0 9.8e-05 0.00023 0.00062 0.00061 0.0001 0.00021 1.5 1.5 0.093 5 5 0.086 1.3e-08 1.3e-08 4.3e-09 4.2e-08 4e-06 4e-06 2.4e-06 0 0 0 0 0 0 0 0
97 9490000 0.7 0.0022 0.0021 -0.014 0.71 -0.054 0.035 0.034 -0.13 -0.057 -0.056 0.05 0.049 -3.7e+02 -1.6e-05 -5.6e-05 1.3e-08 -2.9e-06 0 0 -0.00068 0.21 0.0021 0.44 0 0 0 0 0 9.8e-05 0.00022 0.00062 0.00062 0.0001 0.00021 1.6 1.6 0.091 5.2 5.2 0.085 1.3e-08 1.3e-08 4.3e-09 3.8e-08 4e-06 4e-06 2.3e-06 0 0 0 0 0 0 0 0
98 9590000 0.7 0.0022 -0.014 0.71 -0.058 -0.057 0.036 -0.13 -0.062 0.053 -3.7e+02 -1.6e-05 -5.6e-05 1.4e-07 -1.7e-06 0 0 -0.00072 0.21 0.0021 0.44 0 0 0 0 0 9.7e-05 0.00021 0.00064 0.00064 0.0001 0.0002 1.7 1.7 0.089 5.8 5.8 0.085 1.3e-08 1.3e-08 4.2e-09 3.5e-08 4e-06 4e-06 2.1e-06 0 0 0 0 0 0 0 0
99 9690000 0.7 0.0022 -0.014 0.71 -0.058 0.037 -0.12 -0.065 -0.064 0.053 0.052 -3.7e+02 -1.6e-05 -5.6e-05 -4.4e-07 -6e-06 0 0 -0.00077 0.21 0.0021 0.44 0 0 0 0 0 9.7e-05 0.00021 0.00064 0.00064 0.0001 0.0002 1.7 1.7 0.089 6 6 0.086 1.3e-08 1.3e-08 4.2e-09 3.2e-08 4e-06 4e-06 2e-06 0 0 0 0 0 0 0 0
100 9790000 0.7 0.0022 -0.014 0.71 -0.06 -0.059 0.039 -0.11 -0.071 0.056 -3.7e+02 -1.6e-05 -5.6e-05 -9.9e-08 -3.1e-06 0 0 -0.00082 0.21 0.0021 0.44 0 0 0 0 0 9.7e-05 0.00021 0.00066 0.00066 0.0001 0.00019 1.8 1.8 0.087 6.6 6.6 0.085 1.3e-08 1.3e-08 4.1e-09 3e-08 4e-06 4e-06 1.9e-06 0 0 0 0 0 0 0 0
101 9890000 0.7 0.0022 -0.014 0.71 -0.06 -0.059 0.039 -0.11 -0.073 -0.072 0.056 -3.7e+02 -1.6e-05 -5.6e-05 -1.8e-07 -3.4e-06 0 0 -0.00085 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.0002 0.00066 0.00066 9.9e-05 0.00019 1.8 1.8 0.084 6.8 6.8 0.085 1.2e-08 1.2e-08 4.1e-09 2.7e-08 4e-06 4e-06 1.8e-06 0 0 0 0 0 0 0 0
102 9990000 0.7 0.0023 -0.014 0.71 -0.063 -0.062 0.04 -0.1 -0.079 -0.078 0.06 0.059 -3.7e+02 -1.6e-05 -5.6e-05 -4.7e-07 -5.1e-06 0 0 -0.00088 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.0002 0.00068 0.00068 9.9e-05 0.00019 2 2 0.083 7.4 7.4 0.086 1.2e-08 1.2e-08 4e-09 2.5e-08 4e-06 4e-06 1.7e-06 0 0 0 0 0 0 0 0
103 10090000 0.7 0.0023 -0.014 0.71 -0.061 0.039 0.038 -0.097 -0.079 0.059 -3.7e+02 -1.5e-05 -5.6e-05 -3.7e-07 -4.1e-06 0 0 -0.00091 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00019 0.00067 0.00067 9.8e-05 0.00018 2 2 0.08 7.5 7.5 0.085 1.2e-08 1.2e-08 4e-09 2.3e-08 4e-06 4e-06 1.6e-06 0 0 0 0 0 0 0 0
104 10190000 0.7 0.0023 -0.014 0.71 -0.064 -0.062 0.042 0.041 -0.096 -0.086 -0.084 0.063 0.062 -3.7e+02 -1.5e-05 -5.6e-05 -1.2e-06 -8.4e-06 0 0 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00019 0.00069 0.00069 9.8e-05 0.00018 2.1 2.1 0.078 8.3 8.3 0.084 1.2e-08 1.2e-08 3.9e-09 2.2e-08 4e-06 4e-06 1.4e-06 0 0 0 0 0 0 0 0
105 10290000 0.7 0.0022 -0.014 0.71 -0.062 -0.061 0.04 0.039 -0.084 -0.085 -0.084 0.061 0.06 -3.7e+02 -1.5e-05 -5.6e-05 -1.7e-06 -1.1e-05 0 0 -0.00098 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00019 0.00068 0.00068 9.8e-05 0.00018 2.1 2.1 0.076 8.3 8.3 0.085 1.2e-08 1.2e-08 3.9e-09 2e-08 4e-06 4e-06 1.4e-06 0 0 0 0 0 0 0 0
106 10390000 0.7 0.0022 -0.014 0.71 0.0091 -0.019 0.0096 0.00085 -0.0017 -3.7e+02 -1.5e-05 -5.6e-05 -1.7e-06 -1e-05 -6.6e-10 4.8e-10 -0.001 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00018 0.0007 0.0007 9.7e-05 0.00017 0.25 0.25 0.56 0.25 0.25 0.078 1.2e-08 1.2e-08 3.8e-09 1.9e-08 4e-06 4e-06 1.3e-06 0 0 0 0 0 0 0 0
107 10490000 0.7 0.0023 0.0022 -0.014 0.71 0.0074 0.0075 -0.017 0.023 0.0017 -0.0036 -3.7e+02 -1.5e-05 -5.6e-05 -2.2e-06 -1.2e-05 -1.7e-08 1.2e-08 1.3e-08 -0.001 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00018 0.00073 0.00073 9.7e-05 0.00017 0.26 0.26 0.55 0.26 0.26 0.08 1.2e-08 1.2e-08 3.8e-09 1.8e-08 4e-06 4e-06 1.2e-06 0 0 0 0 0 0 0 0
108 10590000 0.7 0.0024 0.0023 -0.014 0.71 0.0069 0.0071 -0.0065 -0.0067 0.026 0.0018 -0.00081 -0.00082 -3.7e+02 -1.5e-05 -5.6e-05 -2.2e-06 -1.1e-05 -2.7e-06 4.5e-07 4.3e-07 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00018 0.00073 0.00074 0.00073 0.00074 9.7e-05 0.00017 0.14 0.14 0.27 0.13 0.13 0.073 1.2e-08 1.2e-08 3.7e-09 1.6e-08 4e-06 4e-06 1.2e-06 0 0 0 0 0 0 0 0
109 10690000 0.7 0.0024 -0.014 0.71 0.0044 0.0046 -0.0059 -0.0062 0.03 0.0024 -0.0015 -3.7e+02 -1.5e-05 -5.6e-05 -2.4e-06 -1.1e-05 -2.7e-06 4.7e-07 4.5e-07 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00017 0.00076 0.00076 9.7e-05 0.00016 0.15 0.15 0.26 0.14 0.14 0.078 1.2e-08 1.2e-08 3.7e-09 1.5e-08 4e-06 4e-06 1.1e-06 0 0 0 0 0 0 0 0
110 10790000 0.7 0.0024 -0.014 0.71 0.004 0.0042 -0.0032 -0.0034 0.024 0.0026 0.0027 -0.00073 -3.7e+02 -1.5e-05 -5.5e-05 -2.4e-06 -1.1e-05 -4.3e-06 -4.4e-06 2.1e-06 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00017 0.00074 0.00073 0.00074 9.7e-05 0.00016 0.11 0.11 0.17 0.091 0.091 0.072 1.1e-08 1.1e-08 3.6e-09 1.4e-08 4e-06 4e-06 1.1e-06 0 0 0 0 0 0 0 0
111 10890000 0.7 0.0024 0.0023 -0.014 0.71 0.0023 0.0025 -0.0019 -0.0022 0.02 0.0029 0.003 -0.00095 -0.00098 -3.7e+02 -1.5e-05 -5.5e-05 -2.5e-06 -1e-05 -4.3e-06 -4.4e-06 2.1e-06 2e-06 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00017 0.00076 0.00076 9.6e-05 0.00016 0.13 0.13 0.16 0.098 0.098 0.075 1.1e-08 1.1e-08 3.5e-09 1.3e-08 4e-06 4e-06 1.1e-06 0 0 0 0 0 0 0 0
112 10990000 0.7 0.0023 -0.014 0.71 0.0052 0.0054 0.0032 0.0029 0.014 0.0046 -0.0022 -0.0023 -3.7e+02 -1.4e-05 -5.5e-05 -2e-06 -8.2e-06 -8.3e-06 -8.5e-06 8.9e-06 8.7e-06 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00017 0.0007 0.00069 0.0007 9.7e-05 0.00016 0.1 0.1 0.12 0.073 0.073 0.071 1.1e-08 1.1e-08 3.5e-09 1.3e-08 3.9e-06 3.9e-06 1.1e-06 0 0 0 0 0 0 0 0
113 11090000 0.7 0.0023 -0.014 0.71 0.0035 0.0037 0.0056 0.0054 0.019 0.0051 -0.0018 -0.0019 -3.7e+02 -1.4e-05 -5.5e-05 -1.5e-06 -6.2e-06 -8.3e-06 -8.5e-06 8.9e-06 8.8e-06 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00016 0.00072 0.00072 9.6e-05 0.00015 0.13 0.13 0.11 0.08 0.08 0.074 1.1e-08 1.1e-08 3.4e-09 1.2e-08 3.9e-06 3.9e-06 1.1e-06 0 0 0 0 0 0 0 0
114 11190000 0.7 0.0022 -0.014 0.71 0.0087 0.0089 0.0081 0.0079 0.0077 0.0066 -0.0028 -3.7e+02 -1.3e-05 -5.5e-05 -2e-06 -7.3e-06 -9.5e-06 -9.7e-06 1.5e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00016 0.00062 0.00062 9.6e-05 0.00015 0.1 0.1 0.084 0.063 0.063 0.069 9.4e-09 9.5e-09 3.4e-09 1.1e-08 3.8e-06 3.8e-06 1e-06 0 0 0 0 0 0 0 0
115 11290000 0.7 0.0023 -0.014 0.71 0.0082 0.0085 0.011 0.01 0.0074 0.0075 -0.0018 -0.0019 -3.7e+02 -1.3e-05 -5.5e-05 -2.7e-06 -9.3e-06 -9.5e-06 -9.8e-06 1.5e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00016 0.00064 0.00064 9.6e-05 0.00015 0.13 0.13 0.078 0.071 0.071 0.072 9.4e-09 9.5e-09 3.3e-09 1.1e-08 3.8e-06 3.8e-06 1e-06 0 0 0 0 0 0 0 0
116 11390000 0.7 0.0023 -0.014 0.71 0.0037 0.004 0.009 0.0087 0.0017 0.0054 -0.002 -3.7e+02 -1.4e-05 -5.5e-05 -3.2e-06 -1.1e-05 -5.3e-06 -5.8e-06 1.2e-05 1.1e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00016 0.00054 0.00054 9.6e-05 0.00015 0.1 0.1 0.063 0.058 0.058 0.068 8.4e-09 8.4e-09 3.2e-09 1e-08 3.8e-06 3.8e-06 1e-06 0 0 0 0 0 0 0 0
117 11490000 0.7 0.0023 -0.014 0.71 0.00095 0.0013 0.012 0.011 0.0025 0.0056 0.0057 -0.00092 -0.00099 -3.7e+02 -1.4e-05 -5.5e-05 -4.2e-06 -1.3e-05 -5.3e-06 -5.9e-06 1.2e-05 1.1e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00015 0.00056 0.00056 9.6e-05 0.00015 0.13 0.13 0.058 0.066 0.066 0.069 8.4e-09 8.4e-09 3.2e-09 9.4e-09 3.8e-06 3.8e-06 1e-06 0 0 0 0 0 0 0 0
118 11590000 0.7 0.0022 -0.014 0.71 -0.0029 -0.0026 0.01 0.0098 -0.0034 0.0044 -0.0014 -3.7e+02 -1.4e-05 -5.6e-05 -4.4e-06 -1.3e-05 -1e-06 -1.8e-06 1.1e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00015 0.00046 0.00046 9.6e-05 0.00014 0.1 0.1 0.049 0.054 0.054 0.066 7.4e-09 7.4e-09 3.1e-09 9e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
119 11690000 0.7 0.0022 0.0021 -0.014 0.71 -0.006 -0.0056 0.013 -0.008 0.0039 0.004 -0.00027 -0.00035 -3.7e+02 -1.4e-05 -5.6e-05 -4.7e-06 -1.4e-05 -9.5e-07 -1.7e-06 1.1e-05 1e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00015 0.00047 0.00047 9.6e-05 0.00014 0.12 0.12 0.046 0.063 0.063 0.066 7.4e-09 7.4e-09 3.1e-09 8.5e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
120 11790000 0.7 0.0022 -0.014 0.71 -0.011 0.013 -0.0098 0.0017 0.00056 0.00053 -3.7e+02 -1.4e-05 -5.6e-05 -4.8e-06 -1.3e-05 1.4e-07 -7.4e-07 9.7e-06 8.9e-06 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00015 0.00039 0.00039 9.6e-05 0.00014 0.096 0.096 0.039 0.052 0.052 0.063 6.6e-09 6.6e-09 3e-09 8e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
121 11890000 0.7 0.0022 -0.014 0.71 -0.013 0.014 -0.011 0.00052 0.00058 0.0019 0.0018 -3.7e+02 -1.4e-05 -5.6e-05 -5.3e-06 -1.4e-05 8.2e-08 -8.5e-07 9.7e-06 8.9e-06 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00015 0.0004 0.0004 9.6e-05 0.00014 0.12 0.12 0.037 0.061 0.061 0.063 6.6e-09 6.6e-09 2.9e-09 7.6e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
122 11990000 0.7 0.0022 -0.014 0.71 -0.014 0.014 -0.016 -0.0004 -0.00037 0.0023 -3.7e+02 -1.4e-05 -5.6e-05 -5.1e-06 -1.3e-05 1.5e-06 5.7e-07 1e-05 9.4e-06 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.7e-05 0.00015 0.00034 0.00034 9.6e-05 0.00014 0.09 0.09 0.033 0.051 0.051 0.061 5.9e-09 5.9e-09 2.9e-09 7.2e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
123 12090000 0.7 0.0022 -0.014 0.71 -0.016 -0.015 0.016 -0.022 -0.0019 0.0038 0.0037 -3.7e+02 -1.4e-05 -5.6e-05 -4.7e-06 -1.2e-05 1.7e-06 8.4e-07 1e-05 9.3e-06 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.7e-05 0.00014 0.00035 0.00035 9.6e-05 0.00014 0.11 0.11 0.031 0.06 0.06 0.061 5.9e-09 5.9e-09 2.8e-09 6.9e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
124 12190000 0.7 0.0018 -0.014 0.71 -0.0089 -0.0087 0.013 -0.017 0.0014 0.0019 -3.7e+02 -1.3e-05 -5.7e-05 -4.5e-06 -1.1e-05 4.4e-06 3.6e-06 1.6e-05 1.5e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00014 0.0003 0.0003 9.5e-05 0.00013 0.085 0.085 0.028 0.051 0.051 0.059 5.4e-09 5.4e-09 2.8e-09 6.5e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
125 12290000 0.7 0.0018 -0.014 0.71 -0.012 -0.011 0.015 0.014 -0.016 0.00035 0.00038 0.0033 -3.7e+02 -1.3e-05 -5.7e-05 -4.3e-06 -1e-05 4.1e-06 3.4e-06 1.6e-05 1.5e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.7e-05 0.00014 0.00031 0.00031 9.6e-05 0.00013 0.1 0.1 0.028 0.059 0.059 0.059 5.4e-09 5.4e-09 2.7e-09 6.2e-09 3.7e-06 3.7e-06 1e-06 0 0 0 0 0 0 0 0
126 12390000 0.7 0.0015 -0.014 0.71 -0.0059 -0.0058 0.011 -0.015 0.0029 0.0017 -3.7e+02 -1.3e-05 -5.8e-05 -4.6e-06 -1.1e-05 5.9e-06 5.1e-06 1.9e-05 1.8e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.7e-05 0.00014 0.00027 0.00027 9.5e-05 0.00013 0.079 0.079 0.026 0.05 0.05 0.057 5e-09 5e-09 2.6e-09 5.9e-09 3.6e-06 3.6e-06 1e-06 0 0 0 0 0 0 0 0
127 12490000 0.7 0.0015 -0.014 0.71 -0.0072 -0.007 0.013 -0.018 0.0023 0.0029 -3.7e+02 -1.3e-05 -5.8e-05 -5.1e-06 -1.1e-05 5.9e-06 5e-06 1.9e-05 1.8e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00014 0.00028 0.00028 9.5e-05 0.00013 0.092 0.092 0.026 0.059 0.059 0.057 5e-09 5e-09 2.6e-09 5.6e-09 3.6e-06 3.6e-06 1e-06 0 0 0 0 0 0 0 0
128 12590000 0.7 0.0016 0.0015 -0.014 0.71 -0.015 -0.014 0.011 -0.023 -0.024 -0.0028 0.0015 -3.7e+02 -1.3e-05 -5.8e-05 -5e-06 -1.1e-05 7.3e-06 6.5e-06 1.7e-05 1.6e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.7e-05 0.00014 0.00025 0.00025 9.5e-05 0.00013 0.073 0.073 0.025 0.05 0.05 0.055 4.7e-09 4.7e-09 2.5e-09 5.4e-09 3.6e-06 3.6e-06 9.8e-07 0 0 0 0 0 0 0 0
129 12690000 0.7 0.0016 -0.014 0.71 -0.015 0.012 -0.027 -0.0043 0.0026 -3.7e+02 -1.3e-05 -5.8e-05 -5.2e-06 -1.1e-05 7.5e-06 6.7e-06 1.6e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.7e-05 0.00013 0.00026 0.00026 9.5e-05 0.00013 0.085 0.085 0.025 0.058 0.058 0.055 4.7e-09 4.7e-09 2.5e-09 5.1e-09 3.6e-06 3.6e-06 9.8e-07 0 0 0 0 0 0 0 0
130 12790000 0.7 0.0016 -0.013 0.71 -0.02 0.0092 0.0091 -0.03 -0.0077 0.0013 -3.7e+02 -1.4e-05 -5.8e-05 -5e-06 -1.1e-05 8e-06 7.2e-06 1.6e-05 1.5e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00013 0.00023 0.00023 9.5e-05 0.00013 0.068 0.068 0.024 0.049 0.049 0.053 4.4e-09 4.4e-09 2.4e-09 4.9e-09 3.6e-06 3.6e-06 9.7e-07 0 0 0 0 0 0 0 0
131 12890000 0.7 0.0016 -0.013 0.71 -0.021 0.0091 0.009 -0.03 -0.0097 0.0022 -3.7e+02 -1.4e-05 -5.8e-05 -4.8e-06 -1e-05 7.4e-06 6.6e-06 1.6e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.7e-05 0.00013 0.00024 0.00024 9.5e-05 0.00012 0.079 0.079 0.025 0.058 0.058 0.054 4.4e-09 4.4e-09 2.4e-09 4.7e-09 3.6e-06 3.6e-06 9.6e-07 0 0 0 0 0 0 0 0
132 12990000 0.7 0.0012 -0.014 0.71 -0.0088 -0.0087 0.0066 0.0065 -0.03 -0.0011 0.0012 -3.7e+02 -1.3e-05 -5.9e-05 -4.2e-06 -8.6e-06 7.3e-06 6.6e-06 1.8e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00013 0.00022 0.00022 9.5e-05 0.00012 0.064 0.064 0.025 0.049 0.049 0.052 4.2e-09 4.2e-09 2.3e-09 4.5e-09 3.6e-06 3.6e-06 9.4e-07 0 0 0 0 0 0 0 0
133 13090000 0.7 0.0012 -0.014 0.71 -0.0096 -0.0094 0.0068 0.0067 -0.03 -0.002 0.0018 -3.7e+02 -1.3e-05 -5.9e-05 -4.7e-06 -9.3e-06 6.9e-06 6.2e-06 1.8e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00013 0.00023 0.00023 9.5e-05 0.00012 0.073 0.073 0.025 0.057 0.057 0.052 4.2e-09 4.2e-09 2.3e-09 4.3e-09 3.6e-06 3.6e-06 9.4e-07 0 0 0 0 0 0 0 0
134 13190000 0.7 0.00099 -0.014 0.71 -0.00038 -0.00029 0.0062 0.0061 -0.027 0.0044 0.0012 -3.7e+02 -1.2e-05 -5.9e-05 -4.6e-06 -9e-06 5.6e-06 4.9e-06 2e-05 1.9e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00013 0.00021 0.00021 9.4e-05 0.00012 0.06 0.06 0.025 0.049 0.049 0.051 4e-09 4e-09 2.2e-09 4.1e-09 3.6e-06 3.6e-06 9.1e-07 0 0 0 0 0 0 0 0
135 13290000 0.7 0.001 -0.014 0.71 -0.00066 -0.00056 0.007 0.0069 -0.024 0.0043 0.0018 -3.7e+02 -1.2e-05 -5.9e-05 -4.1e-06 -7.8e-06 4.3e-06 3.7e-06 2.1e-05 2e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00013 0.00022 0.00022 9.4e-05 0.00012 0.068 0.069 0.069 0.027 0.057 0.057 0.051 4e-09 4e-09 2.2e-09 4e-09 3.6e-06 3.6e-06 9.1e-07 0 0 0 0 0 0 0 0
136 13390000 0.7 0.00085 -0.014 0.71 0.00026 0.00032 0.006 0.0059 -0.02 0.0033 0.0011 -3.7e+02 -1.2e-05 -5.9e-05 -3.6e-06 -6.7e-06 2.6e-06 2.1e-06 2.1e-05 2e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00012 0.00021 0.00021 9.4e-05 0.00012 0.056 0.056 0.026 0.049 0.049 0.05 3.8e-09 3.8e-09 2.1e-09 3.8e-09 3.6e-06 3.6e-06 8.8e-07 0 0 0 0 0 0 0 0
137 13490000 0.7 0.00087 -0.014 0.71 -0.00025 -0.00019 0.0059 0.0058 -0.019 0.0033 0.0017 -3.7e+02 -1.2e-05 -5.9e-05 -3.1e-06 -5.8e-06 1.8e-06 1.3e-06 2.1e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00012 0.00022 0.00021 9.4e-05 0.00012 0.064 0.064 0.028 0.057 0.057 0.05 3.8e-09 3.8e-09 2.1e-09 3.6e-09 3.6e-06 3.6e-06 8.7e-07 0 0 0 0 0 0 0 0
138 13590000 0.7 0.00081 -0.014 0.71 7.7e-05 0.00014 0.0061 0.006 -0.021 0.0024 0.001 -3.7e+02 -1.2e-05 -5.9e-05 -3.4e-06 -6.2e-06 1.5e-06 1e-06 2e-05 1.9e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00012 0.0002 0.0002 9.4e-05 0.00012 0.053 0.053 0.028 0.049 0.049 0.05 3.6e-09 3.6e-09 2e-09 3.5e-09 3.6e-06 3.6e-06 8.3e-07 0 0 0 0 0 0 0 0
139 13690000 0.7 0.00079 0.00078 -0.014 0.71 0.00075 0.0008 0.0078 -0.025 0.0024 0.0017 -3.7e+02 -1.1e-05 -1.2e-05 -5.9e-05 -2.7e-06 -5e-06 1.8e-06 1.4e-06 2e-05 1.9e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00012 0.00021 0.00021 9.4e-05 0.00012 0.061 0.061 0.029 0.056 0.056 0.05 3.6e-09 3.6e-09 2e-09 3.4e-09 3.6e-06 3.6e-06 8.3e-07 0 0 0 0 0 0 0 0
140 13790000 0.7 0.00067 -0.014 0.71 0.0014 0.0015 0.0036 -0.027 0.0035 -0.00062 -3.7e+02 -1.1e-05 -6e-05 -2.7e-06 -4.8e-06 -3.4e-07 -7.2e-07 1.8e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00012 0.0002 0.0002 9.3e-05 0.00011 0.051 0.051 0.029 0.048 0.048 0.049 3.4e-09 3.4e-09 1.9e-09 3.2e-09 3.6e-06 3.6e-06 7.9e-07 0 0 0 0 0 0 0 0
141 13890000 0.7 0.00063 -0.014 0.71 0.0019 0.0035 -0.031 0.0036 -0.00029 -3.7e+02 -1.1e-05 -6e-05 -2.3e-06 -4.1e-06 -3.5e-08 -3.6e-07 1.8e-05 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 9.6e-05 0.00012 0.00021 0.00021 9.3e-05 0.00011 0.058 0.058 0.03 0.056 0.056 0.05 3.4e-09 3.4e-09 1.9e-09 3.1e-09 3.6e-06 3.6e-06 7.8e-07 0 0 0 0 0 0 0 0
142 13990000 0.7 0.00056 -0.014 0.71 0.0022 0.0023 0.001 0.00099 -0.03 0.0045 0.0044 -0.002 -3.7e+02 -1.1e-05 -6e-05 -2.2e-06 -3.8e-06 -2.7e-06 -3e-06 1.7e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.5e-05 0.00012 0.0002 0.0002 9.3e-05 0.00011 0.049 0.049 0.03 0.048 0.048 0.05 3.2e-09 3.2e-09 1.8e-09 3e-09 3.6e-06 3.6e-06 7.4e-07 0 0 0 0 0 0 0 0
143 14090000 0.7 0.00054 -0.014 0.71 0.0023 0.0012 0.0011 -0.031 0.0047 0.0046 -0.0019 -3.7e+02 -1.1e-05 -6e-05 -1.5e-06 -2.7e-06 -2.6e-06 -2.8e-06 1.7e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.5e-05 0.00012 0.0002 0.0002 9.3e-05 0.00011 0.055 0.055 0.031 0.056 0.056 0.05 3.2e-09 3.2e-09 1.8e-09 2.9e-09 3.6e-06 3.6e-06 7.3e-07 0 0 0 0 0 0 0 0
144 14190000 0.7 0.00044 -0.014 0.71 0.0057 0.00062 0.00059 -0.033 0.0068 -0.0016 -3.7e+02 -1.1e-05 -6e-05 -1.1e-06 -2.1e-06 -2.4e-06 -2.6e-06 1.4e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.5e-05 0.00012 0.0002 0.0002 9.3e-05 0.00011 0.047 0.047 0.031 0.048 0.048 0.05 3.1e-09 3.1e-09 1.8e-09 2.8e-09 3.6e-06 3.6e-06 6.9e-07 0 0 0 0 0 0 0 0
145 14290000 0.7 0.00045 -0.014 0.71 0.0065 0.0014 0.0013 -0.032 0.0074 -0.0016 -3.7e+02 -1.1e-05 -6e-05 -8.2e-07 -1.6e-06 -3e-06 -3.2e-06 1.5e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.5e-05 0.00012 0.0002 0.0002 9.3e-05 0.00011 0.053 0.053 0.032 0.055 0.055 0.051 3.1e-09 3.1e-09 1.7e-09 2.7e-09 3.6e-06 3.6e-06 6.7e-07 0 0 0 0 0 0 0 0
146 14390000 0.7 0.00036 -0.014 0.71 0.0083 0.0023 -0.034 0.0087 -0.0013 -3.7e+02 -1.1e-05 -6e-05 -1.5e-07 -5.3e-07 -3.1e-06 -3.2e-06 1.2e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.5e-05 0.00011 0.00019 0.00019 9.2e-05 0.00011 0.045 0.045 0.031 0.048 0.048 0.05 2.9e-09 2.9e-09 1.7e-09 2.6e-09 3.6e-06 3.6e-06 6.3e-07 0 0 0 0 0 0 0 0
147 14490000 0.7 0.00034 -0.013 0.71 0.0083 0.0035 -0.037 0.0095 -0.001 -3.7e+02 -1e-05 -1.1e-05 -6e-05 7.6e-08 -1.8e-07 -2.6e-06 1.2e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.4e-05 0.00011 0.0002 0.0002 9.2e-05 0.00011 0.051 0.051 0.032 0.055 0.055 0.051 2.9e-09 2.9e-09 1.6e-09 2.5e-09 3.6e-06 3.6e-06 6.2e-07 0 0 0 0 0 0 0 0
148 14590000 0.7 0.00033 -0.013 0.71 0.0049 0.0019 -0.038 0.006 -0.0025 -3.7e+02 -1.1e-05 -6.1e-05 1.4e-07 -9.5e-08 -6.3e-06 1.6e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.4e-05 0.00011 0.00019 0.00019 9.2e-05 0.00011 0.044 0.044 0.031 0.047 0.047 0.051 2.7e-09 2.7e-09 1.6e-09 2.4e-09 3.6e-06 3.6e-06 5.8e-07 0 0 0 0 0 0 0 0
149 14690000 0.7 0.00029 -0.013 0.71 0.0062 -0.0011 -0.034 0.0066 -0.0024 -3.7e+02 -1.1e-05 -6.1e-05 6.2e-07 -7.4e-06 1.7e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.4e-05 0.00011 0.0002 0.0002 9.2e-05 0.00011 0.049 0.049 0.032 0.054 0.054 0.051 2.7e-09 2.7e-09 1.6e-09 2.3e-09 3.6e-06 3.6e-06 5.6e-07 0 0 0 0 0 0 0 0
150 14790000 0.7 0.00031 -0.013 0.71 0.003 -0.0026 -0.03 0.0037 -0.0034 -3.7e+02 -1.1e-05 -6.1e-05 7.8e-07 8.4e-07 -1.1e-05 2.2e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.4e-05 0.00011 0.00019 0.00019 9.1e-05 0.00011 0.043 0.043 0.031 0.047 0.047 0.051 2.6e-09 2.6e-09 1.5e-09 2.2e-09 3.6e-06 3.6e-06 5.3e-07 0 0 0 0 0 0 0 0
151 14890000 0.7 0.00031 -0.013 0.71 0.0046 0.0045 -0.0017 -0.033 0.0041 -0.0036 -3.7e+02 -1.1e-05 -6.1e-05 1.1e-06 1.3e-06 -1.1e-05 2.2e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.4e-05 0.00011 0.0002 0.0002 9.1e-05 0.00011 0.048 0.048 0.031 0.054 0.054 0.052 2.6e-09 2.6e-09 1.5e-09 2.2e-09 3.6e-06 3.6e-06 5.1e-07 0 0 0 0 0 0 0 0
152 14990000 0.7 0.0003 -0.013 0.71 0.0034 -0.0019 -0.029 0.0031 -0.0029 -3.7e+02 -1.2e-05 -6.1e-05 1e-06 1.2e-06 -1.2e-05 2.4e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.3e-05 0.00011 0.00019 0.00019 9.1e-05 0.0001 0.042 0.042 0.03 0.047 0.047 0.051 2.4e-09 2.4e-09 1.5e-09 2.1e-09 3.5e-06 3.5e-06 4.8e-07 0 0 0 0 0 0 0 0
153 15090000 0.7 0.00023 -0.013 0.71 0.0038 -0.0021 -0.032 0.0035 -0.0031 -3.7e+02 -1.2e-05 -6.1e-05 1.1e-06 1.2e-06 -1.1e-05 2.4e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.3e-05 0.00011 0.00019 0.00019 9.1e-05 0.0001 0.047 0.047 0.031 0.054 0.054 0.052 2.4e-09 2.4e-09 1.4e-09 2e-09 3.5e-06 3.5e-06 4.6e-07 0 0 0 0 0 0 0 0
154 15190000 0.7 0.00025 -0.013 0.71 0.0032 -0.00083 -0.029 0.0028 -0.0024 -3.7e+02 -1.2e-05 -6.1e-05 1e-06 1.2e-06 -1.1e-05 2.5e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.3e-05 0.00011 0.00019 0.00019 9.1e-05 0.0001 0.041 0.041 0.03 0.047 0.047 0.052 2.3e-09 2.3e-09 1.4e-09 2e-09 3.5e-06 3.5e-06 4.3e-07 0 0 0 0 0 0 0 0
155 15290000 0.7 0.0002 0.00021 -0.013 0.71 0.0038 0.0037 -0.00068 -0.027 0.0031 -0.0025 -3.7e+02 -1.2e-05 -6.1e-05 1.4e-06 1.6e-06 -1.2e-05 2.6e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.3e-05 0.00011 0.00019 0.00019 9e-05 0.0001 0.046 0.046 0.03 0.054 0.054 0.052 2.3e-09 2.3e-09 1.4e-09 1.9e-09 3.5e-06 3.5e-06 4.2e-07 0 0 0 0 0 0 0 0
156 15390000 0.7 0.00021 -0.013 0.71 0.003 -0.00032 -0.025 0.00054 0.00052 -0.002 -3.7e+02 -1.2e-05 -6.1e-05 2e-06 2.5e-06 -1.3e-05 -1.2e-05 2.8e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.3e-05 0.00011 0.00018 0.00018 9e-05 0.0001 0.04 0.04 0.029 0.047 0.047 0.051 2.1e-09 2.1e-09 1.3e-09 1.8e-09 3.5e-06 3.5e-06 3.9e-07 0 0 0 0 0 0 0 0
157 15490000 0.7 0.00023 -0.013 0.71 0.0043 -0.00071 -0.025 0.00091 0.0009 -0.0021 -3.7e+02 -1.2e-05 -6.1e-05 1.7e-06 2.1e-06 -1.2e-05 2.8e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.2e-05 0.00011 0.00019 0.00019 9e-05 0.0001 0.045 0.045 0.029 0.053 0.053 0.053 2.1e-09 2.1e-09 1.3e-09 1.8e-09 3.5e-06 3.5e-06 3.7e-07 0 0 0 0 0 0 0 0
158 15590000 0.7 0.00024 -0.013 0.71 0.0024 -0.0007 -0.00069 -0.023 -0.0013 -0.0017 -3.7e+02 -1.2e-05 -6.1e-05 1.5e-06 1.8e-06 -1.2e-05 3e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.2e-05 0.00011 0.00018 0.00018 9e-05 0.0001 0.039 0.039 0.028 0.046 0.046 0.052 1.9e-09 1.9e-09 1.3e-09 1.7e-09 3.5e-06 3.5e-06 3.5e-07 0 0 0 0 0 0 0 0
159 15690000 0.7 0.00025 -0.013 0.71 0.0027 -0.00088 -0.00087 -0.024 -0.0011 -0.0018 -3.7e+02 -1.2e-05 -6.1e-05 1.5e-06 1.8e-06 -1.2e-05 3e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.2e-05 0.0001 0.00019 0.00018 8.9e-05 0.0001 0.044 0.044 0.028 0.053 0.053 0.052 1.9e-09 1.9e-09 1.2e-09 1.7e-09 3.5e-06 3.5e-06 3.3e-07 0 0 0 0 0 0 0 0
160 15790000 0.7 0.00021 -0.013 0.71 0.0032 -0.0025 -0.026 -0.00098 -0.00099 -0.0028 -3.7e+02 -1.2e-05 -6.1e-05 1.6e-06 1.8e-06 -1.5e-05 3.1e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.2e-05 0.0001 0.00018 0.00018 8.9e-05 9.9e-05 0.039 0.039 0.027 0.046 0.046 0.051 1.8e-09 1.8e-09 1.2e-09 1.6e-09 3.4e-06 3.4e-06 3.1e-07 0 0 0 0 0 0 0 0
161 15890000 0.7 0.00016 -0.013 0.71 0.0042 0.0041 -0.003 -0.024 -0.00058 -0.00059 -0.0031 -3.7e+02 -1.2e-05 -6.1e-05 1.7e-06 2e-06 -1.5e-05 3.1e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.1e-05 0.0001 0.00018 0.00018 8.9e-05 9.9e-05 0.044 0.044 0.027 0.053 0.053 0.052 1.8e-09 1.8e-09 1.2e-09 1.6e-09 3.4e-06 3.4e-06 3e-07 0 0 0 0 0 0 0 0
162 15990000 0.7 0.0001 -0.013 0.71 0.004 -0.0039 -0.02 -0.00066 -0.00067 -0.0039 -3.7e+02 -1.2e-05 -6.1e-05 2.1e-06 2.5e-06 -1.8e-05 3.3e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.1e-05 0.0001 0.00017 0.00017 8.9e-05 9.8e-05 0.038 0.038 0.026 0.046 0.046 0.051 1.7e-09 1.7e-09 1.2e-09 1.5e-09 3.4e-06 3.4e-06 2.8e-07 0 0 0 0 0 0 0 0
163 16090000 0.71 0.0001 -0.013 0.71 0.0058 0.0057 -0.0042 -0.0041 -0.016 -0.00019 -0.0002 -0.0043 -3.7e+02 -1.2e-05 -6.1e-05 2.7e-06 3.3e-06 -1.9e-05 -1.8e-05 3.3e-05 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 9.1e-05 0.0001 0.00018 0.00018 8.8e-05 9.8e-05 0.043 0.043 0.025 0.053 0.053 0.052 1.7e-09 1.7e-09 1.1e-09 1.5e-09 3.4e-06 3.4e-06 2.7e-07 0 0 0 0 0 0 0 0
164 16190000 0.71 0.00013 -0.013 0.71 0.0057 -0.0034 -0.015 -0.0004 -0.00041 -0.0035 -3.7e+02 -1.2e-05 -6.1e-05 2.8e-06 3.4e-06 -1.8e-05 -1.7e-05 3.6e-05 3.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 9.1e-05 0.0001 0.00017 0.00017 8.8e-05 9.7e-05 0.038 0.038 0.025 0.046 0.046 0.051 1.5e-09 1.5e-09 1.1e-09 1.4e-09 3.4e-06 3.4e-06 2.5e-07 0 0 0 0 0 0 0 0
165 16290000 0.71 0.00014 -0.013 0.71 0.0074 0.0073 -0.0042 -0.016 0.00026 0.00025 -0.0039 -0.0038 -3.7e+02 -1.2e-05 -6.1e-05 3.4e-06 4.1e-06 -1.7e-05 3.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 9e-05 0.0001 0.00017 0.00017 8.8e-05 9.7e-05 0.042 0.042 0.024 0.053 0.053 0.052 1.5e-09 1.5e-09 1.1e-09 1.4e-09 3.4e-06 3.4e-06 2.4e-07 0 0 0 0 0 0 0 0
166 16390000 0.71 0.00013 -0.013 0.71 0.0063 0.0062 -0.0044 -0.015 -6.7e-05 -8e-05 -0.0031 -3.7e+02 -1.2e-05 -6.1e-05 3.3e-06 3.9e-06 -1.6e-05 3.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 9e-05 0.0001 0.00017 0.00017 8.8e-05 9.6e-05 0.037 0.037 0.023 0.046 0.046 0.051 1.4e-09 1.4e-09 1.1e-09 1.4e-09 3.3e-06 3.4e-06 2.2e-07 0 0 0 0 0 0 0 0
167 16490000 0.71 0.00015 -0.013 0.71 0.0055 0.0054 -0.004 -0.0039 -0.018 0.00049 0.00048 -0.0035 -3.7e+02 -1.2e-05 -6.1e-05 3.4e-06 4.1e-06 -1.6e-05 3.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 9e-05 0.0001 0.00017 0.00017 8.7e-05 9.6e-05 0.042 0.042 0.023 0.052 0.052 0.052 1.4e-09 1.4e-09 1e-09 1.3e-09 3.3e-06 3.4e-06 2.1e-07 0 0 0 0 0 0 0 0
168 16590000 0.71 0.00041 -0.013 0.71 0.0019 0.0018 -0.0012 -0.018 -0.0025 -7.8e-05 -7.2e-05 -3.7e+02 -1.3e-05 -6e-05 3.5e-06 4.2e-06 -9e-06 -8.7e-06 4.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 9e-05 9.9e-05 0.00016 0.00016 8.7e-05 9.5e-05 0.037 0.037 0.022 0.046 0.046 0.051 1.3e-09 1.3e-09 1e-09 1.3e-09 3.3e-06 3.3e-06 2e-07 0 0 0 0 0 0 0 0
169 16690000 0.71 0.0004 -0.013 0.71 0.0021 0.002 -0.00073 -0.00071 -0.015 -0.0023 -0.00018 -0.00017 -3.7e+02 -1.3e-05 -6e-05 3.3e-06 3.9e-06 -9.6e-06 -9.3e-06 4.7e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.9e-05 9.8e-05 0.00017 0.00016 8.7e-05 9.4e-05 0.041 0.041 0.022 0.052 0.052 0.051 1.3e-09 1.3e-09 9.9e-10 1.2e-09 3.3e-06 3.3e-06 1.9e-07 0 0 0 0 0 0 0 0
170 16790000 0.71 0.00055 -0.013 0.71 -0.0013 -0.0014 0.0015 -0.014 -0.0047 0.0025 -3.7e+02 -1.3e-05 -6e-05 3.3e-06 3.9e-06 -3.9e-06 -3.7e-06 5.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.9e-05 9.8e-05 0.00016 0.00016 8.7e-05 9.4e-05 0.036 0.036 0.021 0.046 0.046 0.05 1.2e-09 1.2e-09 9.7e-10 1.2e-09 3.3e-06 3.3e-06 1.8e-07 0 0 0 0 0 0 0 0
171 16890000 0.71 0.00056 -0.013 0.71 -0.0016 0.0023 0.0024 -0.011 -0.0048 0.0027 -3.7e+02 -1.3e-05 -6e-05 3.2e-06 3.7e-06 -4.3e-06 -4.1e-06 5.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.9e-05 9.8e-05 0.00016 0.00016 8.6e-05 9.4e-05 0.041 0.041 0.021 0.052 0.052 0.051 1.2e-09 1.2e-09 9.5e-10 1.2e-09 3.3e-06 3.3e-06 1.7e-07 0 0 0 0 0 0 0 0
172 16990000 0.71 0.0005 -0.013 0.71 -0.0016 0.00033 0.00035 -0.011 -0.01 -0.0052 0.00086 -3.7e+02 -1.3e-05 -6e-05 2.9e-06 3.4e-06 -8.4e-06 -8.1e-06 5.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.9e-05 9.7e-05 0.00015 0.00015 8.6e-05 9.3e-05 0.036 0.036 0.02 0.046 0.046 0.05 1.1e-09 1.1e-09 9.2e-10 1.1e-09 3.3e-06 3.3e-06 1.6e-07 0 0 0 0 0 0 0 0
173 17090000 0.71 0.00047 -0.013 0.71 -0.00076 -0.00079 0.0013 -0.01 -0.0053 -0.0054 0.00091 0.00092 -3.7e+02 -1.3e-05 -6e-05 3e-06 3.4e-06 -8.3e-06 -8.1e-06 5.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.8e-05 9.6e-05 0.00016 0.00016 8.6e-05 9.3e-05 0.04 0.04 0.02 0.052 0.052 0.05 1.1e-09 1.1e-09 9e-10 1.1e-09 3.3e-06 3.3e-06 1.6e-07 0 0 0 0 0 0 0 0
174 17190000 0.71 0.00046 0.00045 -0.013 0.71 -0.00031 -0.00034 0.0013 -0.011 -0.0057 -0.00054 -0.00053 -3.7e+02 -1.3e-05 -6e-05 3.2e-06 3.7e-06 -1.2e-05 5.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.8e-05 9.6e-05 0.00015 0.00015 8.6e-05 9.2e-05 0.035 0.035 0.019 0.046 0.046 0.049 9.5e-10 9.6e-10 8.9e-10 1.1e-09 3.2e-06 3.2e-06 1.5e-07 0 0 0 0 0 0 0 0
175 17290000 0.71 0.00043 -0.013 0.71 0.0018 0.0023 -0.0067 -0.0056 -0.00038 -0.00037 -3.7e+02 -1.4e-05 -1.3e-05 -6e-05 3e-06 3.4e-06 -1.2e-05 5.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.8e-05 9.5e-05 0.00015 0.00015 8.5e-05 9.2e-05 0.039 0.039 0.019 0.052 0.052 0.049 9.5e-10 9.6e-10 8.7e-10 1.1e-09 3.2e-06 3.2e-06 1.4e-07 0 0 0 0 0 0 0 0
176 17390000 0.71 0.0004 -0.013 0.71 0.0024 0.0015 -0.0047 -0.0047 -0.0016 -3.7e+02 -1.3e-05 -6e-05 3.3e-06 3.8e-06 -1.6e-05 5.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.8e-05 9.5e-05 0.00015 0.00014 8.5e-05 9.1e-05 0.034 0.034 0.018 0.046 0.046 0.048 8.7e-10 8.7e-10 8.5e-10 1e-09 3.2e-06 3.2e-06 1.3e-07 0 0 0 0 0 0 0 0
177 17490000 0.71 0.00039 -0.013 0.71 0.003 0.001 0.0011 -0.003 -0.0044 -0.0015 -3.7e+02 -1.3e-05 -6e-05 3.3e-06 3.8e-06 -1.6e-05 5.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.7e-05 9.5e-05 0.00015 0.00015 8.5e-05 9.1e-05 0.038 0.038 0.018 0.052 0.052 0.049 8.7e-10 8.7e-10 8.3e-10 1e-09 3.2e-06 3.2e-06 1.3e-07 0 0 0 0 0 0 0 0
178 17590000 0.71 0.0003 -0.013 0.71 0.0042 -0.00014 -0.00012 0.0025 -0.0037 -0.0026 -3.7e+02 -1.4e-05 -1.3e-05 -6.1e-05 3.4e-06 3.9e-06 -1.9e-05 5.9e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.7e-05 9.4e-05 0.00014 0.00014 8.5e-05 9e-05 0.034 0.034 0.017 0.046 0.046 0.048 7.9e-10 7.8e-10 7.9e-10 8.1e-10 9.8e-10 3.2e-06 3.2e-06 1.2e-07 0 0 0 0 0 0 0 0
179 17690000 0.71 0.00027 -0.012 0.71 0.0051 0.00056 0.00059 0.0019 -0.0032 -0.0033 -0.0026 -3.7e+02 -1.4e-05 -1.3e-05 -6.1e-05 3.6e-06 4e-06 -1.9e-05 5.9e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.7e-05 9.3e-05 0.00014 0.00014 8.4e-05 9e-05 0.038 0.038 0.017 0.052 0.052 0.048 7.9e-10 7.8e-10 7.9e-10 7.9e-10 9.5e-10 3.2e-06 3.2e-06 1.2e-07 0 0 0 0 0 0 0 0
180 17790000 0.71 0.00018 -0.013 0.71 0.0077 0.00029 0.00031 0.00056 -0.0021 -0.0022 -3.7e+02 -1.3e-05 -6.1e-05 4.2e-06 4.7e-06 -1.9e-05 -1.8e-05 5.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.7e-05 9.3e-05 0.00014 0.00014 8.4e-05 9e-05 0.033 0.033 0.016 0.045 0.045 0.048 7.1e-10 7.1e-10 7.8e-10 9.3e-10 3.2e-06 3.2e-06 1.1e-07 0 0 0 0 0 0 0 0
181 17890000 0.71 0.00019 -0.013 0.71 0.0092 -0.00047 -0.00045 0.00065 -0.0012 -0.0022 -3.7e+02 -1.3e-05 -6.1e-05 4.4e-06 5e-06 -1.9e-05 -1.8e-05 5.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.6e-05 9.3e-05 0.00014 0.00014 8.4e-05 8.9e-05 0.037 0.037 0.016 0.052 0.052 0.048 7.1e-10 7.1e-10 7.6e-10 9e-10 3.2e-06 3.2e-06 1.1e-07 0 0 0 0 0 0 0 0
182 17990000 0.71 0.00014 0.00013 -0.013 0.71 0.011 -0.0022 0.0019 -0.00053 -0.00054 -0.0019 -3.7e+02 -1.3e-05 -6.1e-05 4.4e-06 4.9e-06 -1.8e-05 5.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.6e-05 9.2e-05 0.00013 0.00013 8.4e-05 8.9e-05 0.032 0.032 0.016 0.045 0.045 0.047 6.4e-10 6.4e-10 7.5e-10 8.8e-10 3.1e-06 3.1e-06 1e-07 0 0 0 0 0 0 0 0
183 18090000 0.71 0.00014 -0.013 0.71 0.012 -0.0024 0.0043 0.00061 0.00059 -0.0022 -3.7e+02 -1.3e-05 -6.1e-05 4e-06 4.5e-06 -1.8e-05 5.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.6e-05 9.2e-05 0.00014 0.00014 8.3e-05 8.8e-05 0.036 0.036 0.016 0.051 0.051 0.047 6.4e-10 6.4e-10 7.3e-10 8.6e-10 3.1e-06 3.1e-06 9.7e-08 0 0 0 0 0 0 0 0
184 18190000 0.71 0.00011 -0.013 0.71 0.012 -0.0013 0.0056 0.0015 -0.0017 -3.7e+02 -1.3e-05 -6.1e-05 4.2e-06 4.7e-06 -1.7e-05 5.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.6e-05 9.1e-05 0.00013 0.00013 8.3e-05 8.8e-05 0.032 0.032 0.015 0.045 0.045 0.047 5.8e-10 5.8e-10 7.2e-10 8.4e-10 3.1e-06 3.1e-06 9.2e-08 0 0 0 0 0 0 0 0
185 18290000 0.71 4.9e-05 4.8e-05 -0.012 0.71 0.012 -0.0019 -0.0018 0.0068 0.0027 -0.0018 -3.7e+02 -1.3e-05 -6.1e-05 4.1e-06 4.6e-06 -1.7e-05 5.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.5e-05 9.1e-05 0.00013 0.00013 8.3e-05 8.8e-05 0.035 0.035 0.015 0.051 0.051 0.046 5.8e-10 5.8e-10 7e-10 8.2e-10 3.1e-06 3.1e-06 8.9e-08 0 0 0 0 0 0 0 0
186 18390000 0.71 6.5e-05 6.4e-05 -0.013 0.71 0.014 -0.0002 -0.00018 0.0079 0.0032 -0.0014 -3.7e+02 -1.3e-05 -6.1e-05 4.4e-06 4.9e-06 -1.7e-05 5.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.5e-05 9e-05 0.00013 0.00013 8.3e-05 8.7e-05 0.031 0.031 0.014 0.045 0.045 0.046 5.3e-10 5.3e-10 6.9e-10 8e-10 3.1e-06 3.1e-06 8.4e-08 0 0 0 0 0 0 0 0
187 18490000 0.71 8e-05 7.9e-05 -0.012 0.71 0.014 0.00021 0.00023 0.0076 0.0047 -0.0014 -3.7e+02 -1.3e-05 -6.1e-05 4.5e-06 5e-06 -1.7e-05 5.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.5e-05 9e-05 0.00013 0.00013 8.2e-05 8.7e-05 0.034 0.034 0.014 0.051 0.051 0.046 5.3e-10 5.3e-10 6.7e-10 7.8e-10 3.1e-06 3.1e-06 8.2e-08 0 0 0 0 0 0 0 0
188 18590000 0.71 8.5e-05 8.3e-05 -0.012 0.71 0.013 0.00045 0.00047 0.0057 0.0035 -0.0012 -3.7e+02 -1.4e-05 -1.3e-05 -6.1e-05 4.9e-06 5.4e-06 -1.7e-05 5.9e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.5e-05 9e-05 0.00012 0.00012 8.2e-05 8.6e-05 0.03 0.03 0.014 0.045 0.045 0.045 4.8e-10 4.8e-10 6.6e-10 7.6e-10 3.1e-06 3.1e-06 7.8e-08 0 0 0 0 0 0 0 0
189 18690000 0.71 5.4e-05 5.2e-05 -0.012 0.71 0.014 -0.00024 -0.00022 0.0038 0.0049 -0.0011 -3.7e+02 -1.4e-05 -1.3e-05 -6.1e-05 4.8e-06 5.3e-06 -1.7e-05 5.9e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.4e-05 8.9e-05 0.00013 0.00012 8.2e-05 8.6e-05 0.034 0.034 0.013 0.051 0.051 0.045 4.8e-10 4.8e-10 6.5e-10 7.4e-10 3.1e-06 3.1e-06 7.5e-08 0 0 0 0 0 0 0 0
190 18790000 0.71 8.4e-05 8.3e-05 -0.012 0.71 0.012 6.5e-05 8.7e-05 0.0035 0.0038 0.0037 -0.00091 -0.0009 -3.7e+02 -1.4e-05 -6.1e-05 4.6e-06 5.2e-06 -1.7e-05 6.3e-05 6.2e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.4e-05 8.9e-05 0.00012 0.00012 8.2e-05 8.6e-05 0.03 0.03 0.013 0.045 0.045 0.045 4.4e-10 4.4e-10 6.3e-10 7.3e-10 3.1e-06 3.1e-06 7.2e-08 0 0 0 0 0 0 0 0
191 18890000 0.71 0.00011 -0.012 0.71 0.013 0.00056 0.00058 0.0041 0.005 -0.00085 -0.00084 -3.7e+02 -1.4e-05 -6.1e-05 5e-06 5.6e-06 -1.7e-05 6.3e-05 6.2e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.4e-05 8.9e-05 0.00012 0.00012 8.1e-05 8.5e-05 0.033 0.033 0.013 0.051 0.051 0.045 4.4e-10 4.4e-10 6.2e-10 7.1e-10 3.1e-06 3.1e-06 7e-08 0 0 0 0 0 0 0 0
192 18990000 0.71 9.4e-05 9.3e-05 -0.012 0.71 0.014 0.0015 0.0028 0.0063 -0.0007 -3.7e+02 -1.4e-05 -6.1e-05 5.2e-06 5.7e-06 -1.7e-05 6.2e-05 6.1e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.4e-05 8.8e-05 0.00012 0.00012 8.1e-05 8.5e-05 0.029 0.029 0.012 0.045 0.045 0.044 4e-10 4e-10 6.1e-10 6.9e-10 3e-06 3e-06 6.6e-08 0 0 0 0 0 0 0 0
193 19090000 0.71 7.9e-05 7.7e-05 -0.012 0.71 0.015 0.0021 0.0058 0.0078 -0.0005 -0.00049 -3.7e+02 -1.4e-05 -6.1e-05 5.2e-06 5.7e-06 -1.7e-05 6.2e-05 6.1e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.4e-05 8.8e-05 0.00012 0.00012 8.1e-05 8.5e-05 0.032 0.032 0.012 0.051 0.051 0.044 4e-10 4e-10 6e-10 6.8e-10 3e-06 3e-06 6.5e-08 0 0 0 0 0 0 0 0
194 19190000 0.71 8.1e-05 8e-05 -0.012 0.71 0.015 0.0021 0.0058 0.0086 -0.00045 -0.00044 -3.7e+02 -1.4e-05 -6.1e-05 5.3e-06 5.9e-06 -1.7e-05 6.1e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.3e-05 8.8e-05 0.00012 0.00011 8.1e-05 8.4e-05 0.028 0.028 0.012 0.045 0.045 0.044 3.6e-10 3.6e-10 5.9e-10 6.6e-10 3e-06 3e-06 6.2e-08 0 0 0 0 0 0 0 0
195 19290000 0.71 0.0001 -0.012 0.71 0.015 0.0013 0.0086 0.01 -0.00027 -0.00025 -3.7e+02 -1.4e-05 -6.1e-05 5.2e-06 5.7e-06 -1.7e-05 6.1e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.3e-05 8.7e-05 0.00012 0.00012 8e-05 8.4e-05 0.031 0.031 0.012 0.05 0.05 0.044 3.6e-10 3.6e-10 5.7e-10 6.5e-10 3e-06 3e-06 6e-08 0 0 0 0 0 0 0 0
196 19390000 0.71 0.00012 0.00011 -0.012 0.71 0.013 0.00039 0.00041 0.012 0.008 -0.00028 -0.00027 -3.7e+02 -1.4e-05 -6.1e-05 5.3e-06 5.8e-06 -1.8e-05 6.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.3e-05 8.7e-05 0.00011 0.00011 8e-05 8.4e-05 0.028 0.028 0.012 0.045 0.045 0.043 3.3e-10 3.3e-10 5.6e-10 6.4e-10 3e-06 3e-06 5.8e-08 0 0 0 0 0 0 0 0
197 19490000 0.71 0.00014 -0.012 0.71 0.012 -0.00033 -0.0003 0.0088 0.0092 -0.00028 -0.00027 -3.7e+02 -1.4e-05 -6.1e-05 5.6e-06 6.1e-06 -1.8e-05 6.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.3e-05 8.7e-05 0.00011 0.00011 8e-05 8.3e-05 0.03 0.03 0.011 0.05 0.05 0.043 3.3e-10 3.3e-10 5.5e-10 6.2e-10 3e-06 3e-06 5.6e-08 0 0 0 0 0 0 0 0
198 19590000 0.71 0.00019 -0.012 0.71 0.0097 -0.0013 0.0081 0.0075 -0.0003 -0.00029 -3.7e+02 -1.4e-05 -6.1e-05 5.9e-06 6.5e-06 -1.8e-05 6.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.2e-05 8.6e-05 0.00011 0.00011 8e-05 8.3e-05 0.027 0.027 0.011 0.044 0.044 0.042 3e-10 3e-10 5.4e-10 6.1e-10 3e-06 3e-06 5.4e-08 0 0 0 0 0 0 0 0
199 19690000 0.71 0.00019 -0.012 0.71 0.01 -0.0035 0.0096 0.0085 0.0084 -0.00055 -0.00054 -3.7e+02 -1.4e-05 -6.1e-05 5.7e-06 6.3e-06 -1.8e-05 6.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.2e-05 8.6e-05 0.00011 0.00011 8e-05 8.3e-05 0.029 0.029 0.011 0.05 0.05 0.042 3e-10 3e-10 5.3e-10 5.9e-10 3e-06 3e-06 5.2e-08 0 0 0 0 0 0 0 0
200 19790000 0.71 0.00026 0.00025 -0.012 0.71 0.0078 0.0077 -0.0044 -0.0043 0.01 0.0068 -0.00044 -0.00043 -3.7e+02 -1.4e-05 -6.1e-05 5.8e-06 6.3e-06 -1.8e-05 -1.7e-05 7.1e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.2e-05 8.6e-05 0.00011 0.00011 7.9e-05 8.3e-05 0.026 0.026 0.011 0.044 0.044 0.042 2.7e-10 2.7e-10 5.2e-10 5.8e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
201 19890000 0.71 0.0002 -0.012 0.71 0.0065 -0.0047 -0.0046 0.011 0.0076 -0.00091 -0.0009 -3.7e+02 -1.4e-05 -6.1e-05 6.2e-06 6.7e-06 -1.8e-05 -1.7e-05 7.1e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.2e-05 8.5e-05 0.00011 0.00011 7.9e-05 8.2e-05 0.029 0.029 0.011 0.05 0.05 0.042 2.7e-10 2.7e-10 5.1e-10 5.7e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
202 19990000 0.71 0.00019 -0.012 0.71 0.0041 -0.0053 0.014 0.0062 0.0061 -0.00076 -0.00075 -3.7e+02 -1.4e-05 -6.1e-05 6.7e-06 7.2e-06 -1.7e-05 7.3e-05 7.2e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.1e-05 8.5e-05 0.00011 0.00011 7.9e-05 8.2e-05 0.026 0.026 0.01 0.044 0.044 0.041 2.5e-10 2.5e-10 5e-10 5.6e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
203 20090000 0.71 0.00018 -0.012 0.71 0.0039 0.0038 -0.0073 0.014 0.0065 -0.0014 -3.7e+02 -1.4e-05 -6.1e-05 7.1e-06 7.7e-06 -1.7e-05 7.3e-05 7.2e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.1e-05 8.5e-05 0.00011 0.00011 7.9e-05 8.2e-05 0.028 0.028 0.01 0.05 0.05 0.042 2.5e-10 2.5e-10 4.9e-10 5.5e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
204 20190000 0.71 0.00029 -0.012 0.71 0.0015 -0.008 -0.0079 0.017 0.0042 -0.0011 -3.7e+02 -1.4e-05 -6e-05 7.3e-06 7.9e-06 -1.6e-05 -1.5e-05 7.6e-05 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.1e-05 8.4e-05 0.0001 0.0001 7.9e-05 8.1e-05 0.025 0.025 0.01 0.044 0.044 0.041 2.3e-10 2.3e-10 4.8e-10 5.4e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
205 20290000 0.71 0.00025 -0.012 0.71 0.00038 0.00036 -0.0096 -0.0095 0.015 0.0043 -0.002 -0.0019 -3.7e+02 -1.4e-05 -6e-05 7.4e-06 8e-06 -1.6e-05 7.6e-05 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.1e-05 8.4e-05 0.00011 0.00011 7.8e-05 8.1e-05 0.027 0.027 0.0099 0.049 0.049 0.041 2.3e-10 2.3e-10 4.7e-10 5.2e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
206 20390000 0.71 0.00027 -0.012 0.71 -0.0021 -0.01 0.017 0.0024 -0.0015 -3.7e+02 -1.4e-05 -6e-05 7.4e-06 8e-06 -1.4e-05 7.8e-05 7.7e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8.1e-05 8.4e-05 0.0001 0.0001 7.8e-05 8.1e-05 0.024 0.024 0.0097 0.044 0.044 0.041 2.1e-10 2.1e-10 4.7e-10 5.2e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
207 20490000 0.71 0.00032 -0.012 0.71 -0.0025 -0.0026 -0.011 0.016 0.0022 -0.0026 -3.7e+02 -1.4e-05 -6e-05 7.2e-06 7.8e-06 -1.4e-05 7.8e-05 7.7e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8e-05 8.3e-05 0.0001 0.0001 7.8e-05 8.1e-05 0.027 0.027 0.0096 0.049 0.049 0.041 2.1e-10 2.1e-10 4.6e-10 5e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
208 20590000 0.71 0.00034 -0.012 0.71 -0.0022 -0.011 0.013 0.0019 -0.0021 -3.7e+02 -1.4e-05 -6e-05 7.1e-06 7.7e-06 -1.3e-05 -1.2e-05 7.8e-05 7.7e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8e-05 8.3e-05 0.0001 0.0001 7.8e-05 8e-05 0.024 0.024 0.0094 0.044 0.044 0.04 2e-10 2e-10 4.5e-10 4.9e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
209 20690000 0.71 0.00037 -0.012 0.71 -0.0022 -0.012 0.015 0.0016 -0.0032 -3.7e+02 -1.4e-05 -6e-05 7.2e-06 7.8e-06 -1.3e-05 -1.2e-05 7.8e-05 7.7e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8e-05 8.3e-05 0.0001 0.0001 7.8e-05 8e-05 0.026 0.026 0.0093 0.049 0.049 0.04 2e-10 2e-10 4.4e-10 4.9e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
210 20790000 0.71 0.0004 -0.012 0.71 -0.0033 -0.011 0.015 0.0014 -0.0025 -3.7e+02 -1.4e-05 -6e-05 7.3e-06 7.8e-06 -1.1e-05 -1e-05 7.7e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 8e-05 8.3e-05 0.0001 0.0001 7.7e-05 8e-05 0.023 0.023 0.0091 0.043 0.043 0.04 1.8e-10 1.8e-10 4.3e-10 4.8e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
211 20890000 0.71 0.00038 -0.012 0.71 -0.0037 -0.0038 -0.014 0.014 0.001 -0.0038 -3.7e+02 -1.4e-05 -6e-05 7.5e-06 8.1e-06 -1.1e-05 -1e-05 7.7e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.9e-05 8.2e-05 0.0001 0.0001 7.7e-05 7.9e-05 0.025 0.025 0.0091 0.049 0.049 0.04 1.8e-10 1.8e-10 4.3e-10 4.7e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
212 20990000 0.71 0.00039 -0.012 0.71 -0.004 -0.014 0.015 0.0027 -0.0031 -3.7e+02 -1.4e-05 -6e-05 7.5e-06 8.1e-06 -8.7e-06 -8.3e-06 7.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.9e-05 8.2e-05 9.8e-05 9.8e-05 7.7e-05 7.9e-05 0.023 0.023 0.0089 0.043 0.043 0.039 1.7e-10 1.7e-10 4.2e-10 4.6e-10 2.9e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
213 21090000 0.71 0.00039 0.00038 -0.012 0.71 -0.0041 -0.017 0.015 0.0023 0.0022 -0.0047 -0.0046 -3.7e+02 -1.4e-05 -6e-05 7.7e-06 8.2e-06 -8.7e-06 -8.3e-06 7.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.9e-05 8.2e-05 9.9e-05 9.9e-05 7.7e-05 7.9e-05 0.025 0.025 0.0089 0.048 0.048 0.039 1.7e-10 1.7e-10 4.1e-10 4.5e-10 2.9e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
214 21190000 0.71 0.00042 -0.012 0.71 -0.0033 -0.0034 -0.016 0.014 0.0037 -0.0038 -3.7e+02 -1.4e-05 -6e-05 7.6e-06 8.1e-06 -6.3e-06 -6e-06 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.9e-05 8.1e-05 9.7e-05 9.7e-05 7.7e-05 7.9e-05 0.022 0.022 0.0087 0.043 0.043 0.039 1.5e-10 1.6e-10 4e-10 4.4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
215 21290000 0.71 0.00046 -0.012 0.71 -0.0039 -0.018 0.016 0.0034 -0.0054 -3.7e+02 -1.4e-05 -6e-05 7.9e-06 8.4e-06 -6.3e-06 -5.9e-06 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.9e-05 8.1e-05 9.8e-05 9.8e-05 7.6e-05 7.8e-05 0.024 0.024 0.0086 0.048 0.048 0.039 1.6e-10 1.6e-10 4e-10 4.3e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
216 21390000 0.71 0.00051 -0.012 0.71 -0.0047 -0.017 0.016 0.0029 0.0028 -0.0034 -3.7e+02 -1.4e-05 -6e-05 7.7e-06 8.2e-06 -2.6e-06 -2.2e-06 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.9e-05 8.1e-05 9.6e-05 9.6e-05 7.6e-05 7.8e-05 0.022 0.022 0.0085 0.043 0.043 0.039 1.4e-10 1.4e-10 3.9e-10 4.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
217 21490000 0.71 0.00052 -0.012 0.71 -0.0053 -0.018 0.015 0.0023 -0.0052 -0.0051 -3.7e+02 -1.4e-05 -6e-05 7.8e-06 8.3e-06 -2.6e-06 -2.3e-06 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.8e-05 8.1e-05 9.7e-05 9.6e-05 7.6e-05 7.8e-05 0.023 0.023 0.0085 0.048 0.048 0.038 1.4e-10 1.4e-10 3.8e-10 4.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
218 21590000 0.71 0.00054 -0.012 0.71 -0.0058 -0.015 0.015 0.0019 -0.0032 -0.0031 -3.7e+02 -1.4e-05 -6e-05 7.7e-06 8.2e-06 8e-07 1.1e-06 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.8e-05 8e-05 9.5e-05 9.5e-05 7.6e-05 7.8e-05 0.021 0.021 0.0083 0.043 0.043 0.038 1.3e-10 1.3e-10 3.8e-10 4.1e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
219 21690000 0.71 0.00055 -0.012 0.71 -0.0057 -0.016 0.017 0.0013 -0.0048 -0.0047 -3.7e+02 -1.4e-05 -6e-05 7.8e-06 8.3e-06 7.8e-07 1.1e-06 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.8e-05 8e-05 9.5e-05 9.6e-05 9.5e-05 7.6e-05 7.8e-05 0.023 0.023 0.0084 0.048 0.048 0.038 1.3e-10 1.3e-10 3.7e-10 4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
220 21790000 0.71 0.00057 -0.012 0.71 -0.0063 -0.011 0.015 9e-05 8.5e-05 -0.00075 -0.00073 -3.7e+02 -1.4e-05 -5.9e-05 7.6e-06 8e-06 6e-06 6.3e-06 7.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.8e-05 8e-05 9.4e-05 9.4e-05 7.5e-05 7.7e-05 0.021 0.021 0.0082 0.042 0.042 0.038 1.3e-10 1.3e-10 3.6e-10 3.9e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
221 21890000 0.71 0.00057 -0.012 0.71 -0.0063 -0.012 0.016 -0.00054 -0.00055 -0.0019 -3.7e+02 -1.4e-05 -5.9e-05 7.5e-06 8e-06 5.9e-06 6.2e-06 7.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.7e-05 8e-05 9.4e-05 9.4e-05 7.5e-05 7.7e-05 0.022 0.022 0.0082 0.047 0.047 0.038 1.3e-10 1.3e-10 3.6e-10 3.9e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
222 21990000 0.71 0.00062 -0.012 0.71 -0.0068 -0.0091 0.016 -0.0015 0.0015 -3.7e+02 -1.4e-05 -5.9e-05 7.5e-06 7.9e-06 1e-05 1.1e-05 7.7e-05 7.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.7e-05 7.9e-05 9.3e-05 9.3e-05 7.5e-05 7.7e-05 0.02 0.02 0.0081 0.042 0.042 0.038 1.2e-10 1.2e-10 3.5e-10 3.8e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
223 22090000 0.71 0.00064 0.00063 -0.012 0.71 -0.0071 -0.0082 0.015 -0.0021 0.00064 0.00065 -3.7e+02 -1.4e-05 -5.9e-05 7.4e-06 7.9e-06 1e-05 7.7e-05 7.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.7e-05 7.9e-05 9.4e-05 9.3e-05 7.5e-05 7.7e-05 0.022 0.022 0.0081 0.047 0.047 0.038 1.2e-10 1.2e-10 3.5e-10 3.7e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
224 22190000 0.71 0.00061 0.0006 -0.012 0.71 -0.0069 -0.0073 0.015 -0.0018 0.00059 0.0006 -3.7e+02 -1.4e-05 -5.9e-05 7.4e-06 7.9e-06 1.1e-05 7.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.7e-05 7.9e-05 9.2e-05 9.2e-05 7.5e-05 7.6e-05 0.02 0.02 0.008 0.042 0.042 0.037 1.1e-10 1.1e-10 3.4e-10 3.7e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
225 22290000 0.71 0.00065 0.00064 -0.012 0.71 -0.0082 -0.0081 -0.008 0.015 -0.0025 -0.00018 -0.00017 -3.7e+02 -1.4e-05 -5.9e-05 7.3e-06 7.7e-06 1.1e-05 7.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.7e-05 7.9e-05 9.3e-05 9.2e-05 7.4e-05 7.6e-05 0.021 0.021 0.008 0.047 0.047 0.037 1.1e-10 1.1e-10 3.3e-10 3.6e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
226 22390000 0.71 0.00062 -0.012 0.71 -0.0088 -0.0075 0.017 -0.0022 -0.00017 -0.00016 -3.7e+02 -1.4e-05 -5.9e-05 7.4e-06 7.8e-06 1.2e-05 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.7e-05 7.9e-05 9.1e-05 9.1e-05 7.4e-05 7.6e-05 0.019 0.019 0.0079 0.042 0.042 0.037 1e-10 1e-10 3.3e-10 3.5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
227 22490000 0.71 0.00063 0.00062 -0.012 0.71 -0.0095 -0.0075 -0.0074 0.018 -0.0031 -0.00094 -0.00093 -3.7e+02 -1.4e-05 -5.9e-05 7.3e-06 7.7e-06 1.2e-05 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.6e-05 7.8e-05 9.2e-05 9.2e-05 7.4e-05 7.6e-05 0.021 0.021 0.0079 0.047 0.047 0.037 1e-10 1e-10 3.2e-10 3.5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
228 22590000 0.71 0.00061 -0.012 0.71 -0.0092 -0.007 0.017 -0.0034 0.00014 0.00015 -3.7e+02 -1.4e-05 -5.9e-05 7.3e-06 7.7e-06 1.3e-05 1.4e-05 7.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.6e-05 7.8e-05 9.1e-05 9e-05 7.4e-05 7.5e-05 0.019 0.019 0.0078 0.042 0.042 0.036 9.7e-11 9.7e-11 3.2e-10 3.4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
229 22690000 0.71 0.00064 -0.012 0.71 -0.01 -0.0067 0.018 -0.0043 -0.00054 -0.00053 -3.7e+02 -1.4e-05 -5.9e-05 7.4e-06 7.8e-06 1.3e-05 1.4e-05 7.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.6e-05 7.8e-05 9.1e-05 9.1e-05 7.4e-05 7.5e-05 0.02 0.02 0.0079 0.046 0.046 0.037 9.7e-11 9.7e-11 3.1e-10 3.4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
230 22790000 0.71 0.00063 0.00062 -0.012 0.71 -0.011 -0.0055 0.019 -0.0055 -0.00043 -0.00042 -3.7e+02 -1.4e-05 -5.9e-05 7e-06 7.3e-06 1.4e-05 7.4e-05 7.3e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.6e-05 7.8e-05 9e-05 9e-05 7.4e-05 7.5e-05 0.019 0.019 0.0078 0.042 0.042 0.036 9.2e-11 9.2e-11 3.1e-10 3.3e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
231 22890000 0.71 0.00064 0.00063 -0.012 0.71 -0.012 -0.0051 0.021 -0.0066 -0.00097 -0.00096 -3.7e+02 -1.4e-05 -5.9e-05 6.9e-06 7.2e-06 1.4e-05 7.4e-05 7.3e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.6e-05 7.7e-05 9e-05 9e-05 7.3e-05 7.5e-05 0.02 0.02 0.0078 0.046 0.046 0.036 9.2e-11 9.2e-11 3e-10 3.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
232 22990000 0.71 0.00062 -0.012 0.71 -0.012 -0.0056 0.022 -0.0074 -0.00086 -0.00085 -3.7e+02 -1.4e-05 -5.9e-05 7e-06 7.3e-06 1.4e-05 1.5e-05 7.3e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.6e-05 7.7e-05 8.9e-05 8.9e-05 7.3e-05 7.5e-05 0.018 0.018 0.0078 0.041 0.041 0.036 8.7e-11 8.7e-11 3e-10 3.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
233 23090000 0.71 0.00059 0.00058 -0.012 0.71 -0.013 -0.0056 0.022 -0.0086 -0.0014 -3.7e+02 -1.4e-05 -5.9e-05 6.7e-06 7e-06 1.4e-05 1.5e-05 7.3e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.5e-05 7.7e-05 9e-05 9e-05 7.3e-05 7.5e-05 0.02 0.02 0.0078 0.046 0.046 0.036 8.7e-11 8.7e-11 2.9e-10 3.1e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
234 23190000 0.71 0.00065 -0.012 0.71 -0.014 -0.0066 -0.0065 0.024 -0.012 -0.0013 -0.0012 -3.7e+02 -1.4e-05 -5.9e-05 6.7e-06 7e-06 1.5e-05 7.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.5e-05 7.7e-05 8.9e-05 8.9e-05 7.3e-05 7.4e-05 0.018 0.018 0.0077 0.041 0.041 0.036 8.2e-11 8.2e-11 2.9e-10 3.1e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
235 23290000 0.71 0.00059 -0.012 0.71 -0.015 -0.0078 0.024 -0.013 -0.002 -3.7e+02 -1.4e-05 -5.9e-05 6.7e-06 7e-06 1.5e-05 7.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.5e-05 7.7e-05 8.9e-05 8.9e-05 7.3e-05 7.4e-05 0.019 0.019 0.0078 0.046 0.046 0.036 8.2e-11 8.2e-11 2.9e-10 3e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
236 23390000 0.71 0.00068 -0.012 0.71 -0.016 -0.008 0.022 -0.016 -0.0018 -0.0017 -3.7e+02 -1.4e-05 -5.9e-05 6.6e-06 6.9e-06 1.5e-05 1.6e-05 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.5e-05 7.6e-05 8.8e-05 8.8e-05 7.3e-05 7.4e-05 0.018 0.018 0.0077 0.041 0.041 0.036 7.8e-11 7.8e-11 2.8e-10 3e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
237 23490000 0.71 0.0031 -0.0096 0.71 -0.023 -0.0089 -0.012 -0.018 -0.0026 -3.7e+02 -1.4e-05 -5.9e-05 6.7e-06 7e-06 1.5e-05 1.6e-05 7.6e-05 7.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.5e-05 7.6e-05 8.9e-05 8.8e-05 7.3e-05 7.4e-05 0.019 0.019 0.0078 0.045 0.045 0.036 7.8e-11 7.8e-11 2.8e-10 2.9e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
238 23590000 0.71 0.0083 -0.0018 0.71 -0.034 -0.0076 -0.044 -0.017 -0.0013 -3.7e+02 -1.4e-05 -5.9e-05 6.6e-06 6.8e-06 1.8e-05 7.3e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.4e-05 7.6e-05 8.8e-05 8.7e-05 7.2e-05 7.4e-05 0.017 0.017 0.0077 0.041 0.041 0.035 7.4e-11 7.4e-11 2.7e-10 2.9e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
239 23690000 0.71 0.0079 0.004 0.71 -0.065 -0.016 -0.094 -0.021 -0.0024 -3.7e+02 -1.4e-05 -5.9e-05 6.5e-06 6.8e-06 1.8e-05 7.3e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.4e-05 7.6e-05 8.8e-05 8.8e-05 7.2e-05 7.3e-05 0.019 0.019 0.0078 0.045 0.045 0.036 7.4e-11 7.4e-11 2.7e-10 2.8e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
240 23790000 0.71 0.005 0.00066 0.71 -0.089 -0.027 -0.15 -0.021 -0.0017 -3.7e+02 -1.4e-05 -5.9e-05 6.6e-06 6.8e-06 2e-05 2.1e-05 6.8e-05 6.7e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.4e-05 7.6e-05 8.7e-05 8.7e-05 7.2e-05 7.3e-05 0.017 0.017 0.0077 0.041 0.041 0.035 7.1e-11 7.1e-11 2.6e-10 2.8e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
241 23890000 0.71 0.0024 -0.0054 0.71 -0.11 -0.036 -0.2 -0.03 -0.005 -0.0049 -3.7e+02 -1.4e-05 -5.9e-05 6.5e-06 6.7e-06 2e-05 2.1e-05 6.8e-05 6.7e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.4e-05 7.5e-05 8.7e-05 8.7e-05 7.2e-05 7.3e-05 0.019 0.019 0.0078 0.045 0.045 0.035 7.1e-11 7.1e-11 2.6e-10 2.7e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
242 23990000 0.71 0.00097 -0.01 0.71 -0.11 -0.04 -0.25 -0.034 -0.0082 -3.7e+02 -1.4e-05 -5.9e-05 6.5e-06 6.8e-06 2.2e-05 6.4e-05 6.3e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.4e-05 7.5e-05 8.7e-05 8.6e-05 7.2e-05 7.3e-05 0.017 0.017 0.0077 0.041 0.041 0.035 6.7e-11 6.7e-11 2.6e-10 2.7e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
243 24090000 0.71 0.0023 -0.0088 0.71 -0.11 -0.04 -0.3 -0.045 -0.012 -3.7e+02 -1.4e-05 -5.9e-05 6.6e-06 6.8e-06 2.2e-05 6.4e-05 6.3e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.4e-05 7.5e-05 8.7e-05 8.7e-05 7.2e-05 7.3e-05 0.018 0.018 0.0078 0.045 0.045 0.035 6.8e-11 6.8e-11 2.5e-10 2.7e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
244 24190000 0.71 0.0033 -0.0065 0.71 -0.11 -0.041 -0.35 -0.046 -0.014 -3.7e+02 -1.4e-05 -5.9e-05 6.6e-06 6.8e-06 2.4e-05 5.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.4e-05 7.5e-05 8.6e-05 8.6e-05 7.1e-05 7.3e-05 0.017 0.017 0.0077 0.04 0.04 0.035 6.4e-11 6.4e-11 2.5e-10 2.6e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
245 24290000 0.71 0.0038 -0.0057 0.71 -0.12 -0.045 -0.41 -0.058 -0.018 -3.7e+02 -1.4e-05 -5.9e-05 6.5e-06 6.7e-06 2.4e-05 2.5e-05 5.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.3e-05 7.5e-05 8.6e-05 8.6e-05 7.1e-05 7.2e-05 0.018 0.018 0.0078 0.045 0.045 0.036 6.5e-11 6.5e-11 2.5e-10 2.6e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
246 24390000 0.71 0.0039 -0.0059 0.71 -0.13 -0.052 -0.46 -0.064 -0.03 -3.7e+02 -1.3e-05 -5.9e-05 6.3e-06 6.6e-06 2.1e-05 2.2e-05 5.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.3e-05 7.4e-05 8.5e-05 8.5e-05 7.1e-05 7.2e-05 0.017 0.017 0.0078 0.04 0.04 0.035 6.2e-11 6.2e-11 2.4e-10 2.5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
247 24490000 0.71 0.0047 -0.0017 0.71 -0.14 -0.057 -0.51 -0.077 -0.035 -3.7e+02 -1.3e-05 -5.9e-05 6.3e-06 6.5e-06 2.1e-05 2.2e-05 5.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.3e-05 7.4e-05 8.6e-05 8.5e-05 7.1e-05 7.2e-05 0.018 0.018 0.0078 0.045 0.045 0.035 6.2e-11 6.2e-11 2.4e-10 2.5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
248 24590000 0.71 0.0052 0.0019 0.71 -0.16 -0.068 -0.56 -0.081 -0.045 -3.7e+02 -1.3e-05 -5.9e-05 6.4e-06 6.6e-06 2e-05 2.1e-05 4.8e-05 4.7e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.3e-05 7.4e-05 8.5e-05 8.5e-05 7.1e-05 7.2e-05 0.017 0.017 0.0078 0.04 0.04 0.035 5.9e-11 5.9e-11 2.4e-10 2.5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
249 24690000 0.71 0.0052 0.0028 0.71 -0.18 -0.082 -0.64 -0.098 -0.052 -3.7e+02 -1.3e-05 -5.9e-05 6.5e-06 6.7e-06 2e-05 4.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.3e-05 7.4e-05 8.5e-05 8.5e-05 7.1e-05 7.2e-05 0.018 0.018 0.0078 0.044 0.044 0.035 5.9e-11 5.9e-11 2.3e-10 2.4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
250 24790000 0.71 0.0049 0.0015 0.0014 0.71 -0.2 -0.095 -0.094 -0.72 -0.1 -0.063 -3.7e+02 -1.3e-05 -5.9e-05 6.3e-06 6.5e-06 2.4e-05 2.5e-05 3.9e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.3e-05 7.4e-05 8.4e-05 8.4e-05 7.1e-05 7.2e-05 0.016 0.016 0.0078 0.04 0.04 0.035 5.7e-11 5.7e-11 2.3e-10 2.4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
251 24890000 0.71 0.0067 0.0031 0.71 -0.22 -0.11 -0.75 -0.13 -0.073 -3.7e+02 -1.3e-05 -5.9e-05 6.2e-06 6.4e-06 2.4e-05 2.5e-05 4e-05 3.9e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.2e-05 7.4e-05 8.4e-05 8.4e-05 7.1e-05 0.018 0.018 0.0078 0.044 0.044 0.035 5.7e-11 5.7e-11 2.3e-10 2.4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
252 24990000 0.71 0.0085 0.0047 0.71 -0.24 -0.11 -0.81 -0.13 -0.081 -3.7e+02 -1.3e-05 -5.9e-05 6e-06 6.2e-06 3.4e-05 2.5e-05 2.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.2e-05 7.3e-05 8.3e-05 8.3e-05 7e-05 7.1e-05 0.016 0.016 0.0078 0.04 0.04 0.035 5.5e-11 5.5e-11 2.2e-10 2.3e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
253 25090000 0.71 0.0088 0.0041 0.71 -0.27 -0.12 -0.85 -0.15 -0.093 -3.7e+02 -1.3e-05 -5.9e-05 5.9e-06 6e-06 3.4e-05 2.4e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.2e-05 7.3e-05 8.4e-05 8.3e-05 7e-05 7.1e-05 0.018 0.018 0.0079 0.044 0.044 0.035 5.5e-11 5.5e-11 2.2e-10 2.3e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
254 25190000 0.71 0.0082 0.0027 0.71 -0.29 -0.14 -0.91 -0.17 -0.12 -3.7e+02 -1.3e-05 -5.9e-05 5.9e-06 6.1e-06 3e-05 3.1e-05 1.9e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.2e-05 7.3e-05 8.3e-05 8.2e-05 7e-05 7.1e-05 0.016 0.016 0.0078 0.04 0.04 0.035 5.2e-11 5.3e-11 5.3e-11 2.2e-10 2.3e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
255 25290000 0.71 0.01 0.0095 0.71 -0.32 -0.15 -0.96 -0.2 -0.13 -3.7e+02 -1.3e-05 -5.9e-05 5.9e-06 6.1e-06 3e-05 3.1e-05 1.9e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.2e-05 7.3e-05 8.3e-05 8.3e-05 7e-05 7.1e-05 0.017 0.017 0.0079 0.044 0.044 0.035 5.3e-11 5.3e-11 2.1e-10 2.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
256 25390000 0.71 0.011 0.016 0.71 -0.35 -0.17 -1 -0.22 -0.15 -3.7e+02 -1.2e-05 -5.9e-05 5.9e-06 6.1e-06 3.3e-05 3.5e-06 3.3e-06 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.2e-05 7.3e-05 8.2e-05 8.2e-05 7e-05 7.1e-05 0.016 0.016 0.0078 0.04 0.04 0.035 5.1e-11 5.1e-11 2.1e-10 2.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
257 25490000 0.71 0.012 0.017 0.71 -0.4 -0.19 -1.1 -0.25 -0.17 -3.7e+02 -1.2e-05 -5.9e-05 6e-06 6.1e-06 3.2e-05 3.3e-05 3.6e-06 3.4e-06 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.2e-05 7.3e-05 8.2e-05 8.2e-05 7e-05 7.1e-05 0.017 0.017 0.0079 0.044 0.044 0.035 5.1e-11 5.1e-11 2.1e-10 2.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
258 25590000 0.71 0.011 0.015 0.71 -0.44 -0.22 -1.1 -0.28 -0.21 -3.7e+02 -1.2e-05 -5.9e-05 6e-06 6.1e-06 2.9e-05 3e-05 -5.8e-06 -6e-06 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.2e-05 8.1e-05 8.1e-05 7e-05 0.016 0.016 0.0079 0.04 0.04 0.035 4.9e-11 4.9e-11 2.1e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
259 25690000 0.71 0.015 0.022 0.71 -0.49 -0.24 -1.2 -0.33 -0.23 -3.7e+02 -1.2e-05 -5.9e-05 6e-06 6.1e-06 2.9e-05 3e-05 -5.5e-06 -5.7e-06 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.1e-05 7.2e-05 8.1e-05 8.1e-05 7e-05 0.017 0.017 0.0079 0.044 0.044 0.035 4.9e-11 4.9e-11 2e-10 2.1e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
260 25790000 0.71 0.017 0.028 0.71 -0.53 -0.27 -1.2 -0.34 -0.26 -3.7e+02 -1.2e-05 -5.9e-05 6e-06 6.2e-06 3.8e-05 -3.1e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.1e-05 7.2e-05 8e-05 8e-05 6.9e-05 7e-05 0.016 0.016 0.0079 0.04 0.04 0.035 4.7e-11 4.7e-11 2e-10 2.1e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
261 25890000 0.71 0.017 0.028 0.71 -0.6 -0.3 -1.3 -0.4 -0.29 -3.7e+02 -1.2e-05 -5.9e-05 6.1e-06 6.3e-06 3.7e-05 3.8e-05 -3.1e-05 -3.2e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.1e-05 7.2e-05 8.1e-05 8e-05 6.9e-05 7e-05 0.017 0.017 0.008 0.044 0.044 0.035 4.7e-11 4.7e-11 2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
262 25990000 0.71 0.016 0.025 0.71 -0.66 -0.33 -1.3 -0.44 -0.34 -3.7e+02 -1.1e-05 -5.9e-05 6.1e-06 6.3e-06 3.3e-05 3.4e-05 -4.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.1e-05 7.2e-05 8e-05 8e-05 6.9e-05 7e-05 0.015 0.015 0.0079 0.039 0.039 0.035 4.6e-11 4.6e-11 1.9e-10 2e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
263 26090000 0.7 0.021 0.035 0.71 -0.72 -0.36 -1.3 -0.51 -0.38 -3.7e+02 -1.1e-05 -5.9e-05 5.9e-06 6.1e-06 3.4e-05 3.5e-05 -4.7e-05 -4.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7.1e-05 7.2e-05 8e-05 8e-05 6.9e-05 7e-05 0.017 0.016 0.008 0.043 0.043 0.035 4.6e-11 4.6e-11 1.9e-10 2e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
264 26190000 0.7 0.023 0.045 0.71 -0.78 -0.39 -1.3 -0.53 -0.42 -3.7e+02 -1.1e-05 -5.9e-05 6e-06 6.1e-06 4.5e-05 4.7e-05 -8.6e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7e-05 7.1e-05 7.9e-05 7.9e-05 6.9e-05 7e-05 0.015 0.015 0.0079 0.039 0.039 0.035 4.4e-11 4.4e-11 1.9e-10 2e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
265 26290000 0.7 0.024 0.047 0.71 -0.87 -0.44 -1.3 -0.62 -0.46 -3.7e+02 -1.1e-05 -5.9e-05 5.9e-06 6e-06 4.6e-05 4.7e-05 -8.5e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7e-05 7.1e-05 7.9e-05 7.9e-05 6.9e-05 7e-05 0.016 0.016 0.008 0.043 0.043 0.035 4.5e-11 4.5e-11 1.9e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
266 26390000 0.7 0.023 0.043 0.71 -0.95 -0.49 -1.3 -0.68 -0.55 -3.7e+02 -1e-05 -5.9e-05 5.9e-06 6e-06 3.3e-05 3.4e-05 -9.9e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7e-05 7.1e-05 7.8e-05 7.8e-05 6.9e-05 7e-05 0.015 0.015 0.0079 0.039 0.039 0.035 4.3e-11 4.3e-11 1.8e-10 1.9e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
267 26490000 0.7 0.031 0.059 0.71 -1 -0.53 -1.3 -0.78 -0.6 -3.7e+02 -1e-05 -5.9e-05 5.8e-06 6e-06 3.3e-05 3.4e-05 -9.8e-05 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7e-05 7.1e-05 7.9e-05 7.8e-05 6.9e-05 0.016 0.016 0.008 0.043 0.043 0.035 4.3e-11 4.3e-11 1.8e-10 1.9e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
268 26590000 0.7 0.037 0.075 0.71 -1.1 -0.59 -1.3 -0.82 -0.67 -3.7e+02 -9.5e-06 -5.9e-05 5.5e-06 5.6e-06 4.3e-05 4.4e-05 -0.00013 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7e-05 7.1e-05 7.8e-05 7.7e-05 6.9e-05 0.015 0.015 0.008 0.039 0.039 0.035 4.2e-11 4.2e-11 1.8e-10 1.9e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
269 26690000 0.7 0.038 0.078 0.71 -1.3 -0.65 -1.3 -0.94 -0.73 -3.7e+02 -9.5e-06 -5.9e-05 5.6e-06 5.7e-06 4.2e-05 4.4e-05 -0.00013 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7e-05 7.1e-05 7.8e-05 7.8e-05 6.9e-05 0.016 0.016 0.008 0.043 0.043 0.035 4.2e-11 4.2e-11 1.8e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
270 26790000 0.7 0.036 0.072 0.71 -1.4 -0.73 -1.3 -1 -0.85 -3.7e+02 -9e-06 -6e-05 5.4e-06 5.5e-06 2e-05 2.2e-05 -0.00016 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7e-05 7.1e-05 7.7e-05 7.7e-05 6.8e-05 6.9e-05 0.015 0.014 0.008 0.039 0.039 0.035 4.1e-11 4.1e-11 1.8e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
271 26890000 0.7 0.045 0.094 0.7 -1.5 -0.79 -1.3 -1.2 -0.93 -3.7e+02 -9e-06 -6e-05 5.5e-06 5.6e-06 2e-05 2.1e-05 -0.00016 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7e-05 7.1e-05 7.7e-05 7.7e-05 6.9e-05 0.016 0.015 0.0081 0.043 0.043 0.035 4.1e-11 4.1e-11 1.7e-10 1.8e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
272 26990000 0.7 0.051 0.12 0.7 -1.7 -0.87 -1.3 -1.2 -1 -3.7e+02 -7.9e-06 -6e-05 5.4e-06 5.5e-06 2.9e-05 3.1e-05 -0.00021 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7e-05 7.6e-05 7.6e-05 6.9e-05 0.015 0.014 0.008 0.039 0.039 0.035 4e-11 4e-11 1.7e-10 1.8e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
273 27090000 0.7 0.052 0.12 0.7 -1.9 -0.96 -1.3 -1.4 -1.1 -3.7e+02 -7.9e-06 -6e-05 5.3e-06 5.4e-06 2.9e-05 3.1e-05 -0.00021 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 7e-05 7.7e-05 7.6e-05 6.8e-05 6.9e-05 0.016 0.015 0.0081 0.043 0.043 0.035 4e-11 4e-11 1.7e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
274 27190000 0.71 0.048 0.11 0.7 -2.1 -1 -1.2 -1.6 -1.2 -3.7e+02 -7.8e-06 -5.9e-05 5.4e-06 5.5e-06 3.9e-05 4.1e-05 -0.0002 -0.0013 0.21 0.0021 0.44 0 0 0 0 0 6.9e-05 7e-05 7.6e-05 7.6e-05 6.8e-05 6.9e-05 0.016 0.015 0.0081 0.045 0.045 0.035 4e-11 4e-11 1.7e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
275 27290000 0.71 0.043 0.094 0.7 -2.2 -1.1 -1.2 -1.8 -1.3 -3.7e+02 -7.8e-06 -5.9e-05 5.4e-06 5.5e-06 3.9e-05 4.1e-05 -0.0002 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.9e-05 7e-05 7.7e-05 7.6e-05 6.8e-05 0.017 0.016 0.0081 0.05 0.049 0.035 4e-11 4e-11 1.6e-10 1.7e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
276 27390000 0.71 0.037 0.078 0.7 -2.3 -1.1 -1.2 -2 -1.4 -3.7e+02 -7.2e-06 -5.9e-05 5.5e-06 5.6e-06 5.9e-05 6.1e-05 -0.00021 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.9e-05 7.7e-05 7.6e-05 6.7e-05 6.8e-05 0.017 0.016 0.0081 0.052 0.052 0.035 3.9e-11 3.9e-11 1.6e-10 1.7e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
277 27490000 0.71 0.031 0.063 0.7 -2.4 -1.2 -1.2 -2.3 -1.5 -3.7e+02 -7.2e-06 -5.9e-05 5.4e-06 5.5e-06 5.8e-05 6e-05 -0.00021 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.8e-05 6.9e-05 7.7e-05 7.6e-05 6.7e-05 6.8e-05 0.018 0.018 0.0082 0.057 0.057 0.035 3.9e-11 3.9e-11 1.6e-10 1.7e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
278 27590000 0.71 0.026 0.05 0.7 -2.5 -1.2 -1.2 -2.5 -1.6 -3.7e+02 -7.5e-06 -5.9e-05 5.5e-06 5.6e-06 5.7e-05 5.9e-05 -0.0002 -0.00019 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.8e-05 6.9e-05 7.7e-05 7.6e-05 6.7e-05 0.018 0.017 0.0082 0.06 0.059 0.035 3.9e-11 3.9e-11 1.6e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
279 27690000 0.71 0.025 0.026 0.048 0.7 -2.5 -1.2 -1.2 -2.8 -1.7 -3.7e+02 -7.5e-06 -5.9e-05 5.4e-06 5.6e-05 5.9e-05 -0.00019 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.8e-05 7.7e-05 7.7e-05 6.7e-05 0.019 0.018 0.0083 0.065 0.065 0.035 3.9e-11 3.9e-11 1.6e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
280 27790000 0.71 0.026 0.05 0.7 -2.6 -1.2 -1.2 -3 -1.8 -3.7e+02 -7.6e-06 -5.8e-05 5.3e-06 5.8e-05 6e-05 -0.00018 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.7e-05 6.8e-05 7.7e-05 7.6e-05 6.6e-05 6.7e-05 0.019 0.018 0.0082 0.068 0.067 0.035 3.8e-11 3.8e-11 1.5e-10 1.6e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
281 27890000 0.71 0.025 0.048 0.7 -2.6 -1.2 -1.2 -3.3 -2 -3.7e+02 -7.6e-06 -5.8e-05 5.2e-06 5.3e-06 5.6e-05 5.8e-05 -0.00018 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.7e-05 6.8e-05 7.7e-05 7.6e-05 6.6e-05 6.7e-05 0.02 0.019 0.0083 0.074 0.073 0.035 3.9e-11 3.8e-11 1.5e-10 1.6e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
282 27990000 0.71 0.024 0.045 0.7 -2.7 -1.2 -1.2 -3.6 -2.1 -3.7e+02 -8e-06 -5.8e-05 5.3e-06 5.4e-06 5.1e-05 5.3e-05 -0.00016 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.7e-05 6.8e-05 7.7e-05 7.6e-05 6.6e-05 6.7e-05 0.02 0.019 0.0083 0.076 0.076 0.035 3.8e-11 3.8e-11 1.5e-10 1.6e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
283 28090000 0.71 0.03 0.058 0.7 -2.7 -1.3 -1.2 -3.9 -2.2 -3.7e+02 -8e-06 -5.8e-05 5.1e-06 5e-05 5.2e-05 -0.00016 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.7e-05 6.8e-05 7.7e-05 7.6e-05 6.6e-05 6.7e-05 0.021 0.02 0.0084 0.083 0.082 0.035 3.8e-11 3.8e-11 1.5e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
284 28190000 0.71 0.035 0.071 0.7 -2.8 -1.3 -0.95 -4.2 -2.3 -3.7e+02 -8.2e-06 -5.8e-05 5.1e-06 5.2e-06 4.7e-05 4.9e-05 -0.00014 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.7e-05 7.7e-05 7.6e-05 6.6e-05 6.7e-05 0.02 0.02 0.0084 0.085 0.085 0.035 3.8e-11 3.7e-11 1.5e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
285 28290000 0.71 0.028 0.054 0.7 -2.8 -1.3 -0.09 -4.4 -2.4 -3.7e+02 -8.2e-06 -5.8e-05 4.9e-06 5e-06 4.5e-05 4.7e-05 -0.00014 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.7e-05 7.7e-05 7.6e-05 6.6e-05 0.021 0.02 0.0086 0.092 0.092 0.036 3.8e-11 3.7e-11 1.5e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
286 28390000 0.71 0.011 0.023 0.7 -2.8 -1.3 0.77 -4.7 -2.6 -3.7e+02 -8.2e-06 -5.8e-05 4.8e-06 4.3e-05 4.5e-05 -0.00013 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.6e-05 6.7e-05 7.7e-05 7.7e-05 6.5e-05 6.6e-05 0.022 0.021 0.0087 0.1 0.099 0.036 3.8e-11 3.8e-11 1.4e-10 1.5e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
287 28490000 0.71 0.0026 0.0045 0.7 -2.7 -1.3 1.1 -5 -2.7 -3.7e+02 -8.2e-06 -5.8e-05 4.7e-06 4.8e-06 4e-05 4.2e-05 -0.00012 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.6e-05 6.7e-05 7.8e-05 7.7e-05 6.5e-05 0.023 0.022 0.0088 0.11 0.11 0.036 3.8e-11 3.8e-11 1.4e-10 1.5e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
288 28590000 0.71 0.00085 0.001 0.7 -2.6 -1.3 0.96 -5.3 -2.8 -3.7e+02 -8.2e-06 -5.8e-05 4.7e-06 4.8e-06 3.7e-05 3.8e-05 -0.00012 -0.00011 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.6e-05 7.8e-05 7.7e-05 6.5e-05 0.024 0.023 0.0089 0.12 0.12 0.036 3.8e-11 3.8e-11 1.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
289 28690000 0.71 0.00014 0.00015 8.3e-05 8e-05 0.7 -2.6 -1.2 0.96 -5.5 -2.9 -3.7e+02 -8.2e-06 -5.8e-05 4.6e-06 4.7e-06 3.2e-05 3.4e-05 -0.0001 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.6e-05 7.8e-05 7.7e-05 6.5e-05 0.025 0.025 0.009 0.13 0.12 0.036 3.8e-11 3.8e-11 1.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
290 28790000 0.71 -0.00015 -0.00014 -0.00017 0.71 -2.5 -1.2 0.97 -5.8 -3 -3.7e+02 -8.9e-06 -5.8e-05 4.6e-06 4.7e-06 1.3e-06 2.9e-06 -0.00018 -0.00017 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.5e-05 6.6e-05 7.8e-05 7.7e-05 6.5e-05 0.024 0.024 0.0089 0.13 0.13 0.036 3.7e-11 3.7e-11 1.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
291 28890000 0.71 -0.00017 -0.00016 5.3e-05 5.2e-05 0.71 -2.5 -1.2 0.96 -6.1 -3.2 -3.7e+02 -8.9e-06 -5.8e-05 4.6e-06 -3e-06 -1.4e-06 -0.00016 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.5e-05 6.6e-05 7.8e-05 7.8e-05 6.5e-05 0.025 0.025 0.009 0.14 0.13 0.036 3.7e-11 3.7e-11 1.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
292 28990000 0.71 2.5e-05 3.1e-05 0.0005 0.71 -2.4 -1.2 0.95 -6.4 -3.3 -3.7e+02 -9.8e-06 -5.8e-05 4.5e-06 -2.4e-05 -2.3e-05 -0.00025 -0.0012 0.21 0.0021 0.44 0 0 0 0 0 6.5e-05 6.6e-05 7.8e-05 7.8e-05 6.4e-05 6.5e-05 0.024 0.024 0.009 0.14 0.14 0.036 3.7e-11 3.6e-11 1.3e-10 1.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
293 29090000 0.71 0.00018 0.0009 0.71 -2.4 -1.2 0.94 -6.7 -3.4 -3.7e+02 -9.8e-06 -5.8e-05 4.4e-06 -2.9e-05 -2.8e-05 -0.00023 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.5e-05 6.6e-05 7.9e-05 7.8e-05 6.4e-05 6.5e-05 0.025 0.025 0.009 0.15 0.15 0.036 3.7e-11 3.7e-11 1.3e-10 1.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
294 29190000 0.71 0.0004 0.0013 0.71 -2.3 -1.1 0.93 -7 -3.5 -3.7e+02 -1e-05 -5.8e-05 4.4e-06 4.5e-06 -4.9e-05 -4.8e-05 -0.00027 -0.00026 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.5e-05 7.9e-05 7.8e-05 6.4e-05 6.5e-05 0.024 0.024 0.009 0.15 0.15 0.036 3.6e-11 3.6e-11 1.3e-10 1.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
295 29290000 0.71 0.00075 0.00076 0.0022 0.71 -2.3 -1.1 0.96 -7.2 -3.6 -3.7e+02 -1e-05 -5.8e-05 4.3e-06 4.4e-06 -5.4e-05 -5.3e-05 -0.00025 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.5e-05 7.9e-05 7.8e-05 6.4e-05 6.5e-05 0.025 0.026 0.0091 0.16 0.16 0.036 3.6e-11 3.6e-11 1.3e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
296 29390000 0.71 0.0013 0.0037 0.71 -2.3 -1.1 0.97 -7.5 -3.7 -3.7e+02 -1.1e-05 -5.8e-05 4.1e-06 -7e-05 -6.9e-05 -0.00029 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.5e-05 7.9e-05 7.8e-05 6.4e-05 0.024 0.025 0.009 0.16 0.16 0.036 3.6e-11 3.5e-11 1.3e-10 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
297 29490000 0.71 0.0018 0.0048 0.71 -2.2 -1.1 0.97 -7.7 -3.8 -3.7e+02 -1.1e-05 -5.7e-05 -5.8e-05 4.1e-06 -7.4e-05 -0.00028 -0.00027 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.5e-05 7.9e-05 7.8e-05 6.4e-05 0.026 0.026 0.0091 0.17 0.17 0.037 3.6e-11 3.5e-11 1.3e-10 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
298 29590000 0.71 0.0022 0.0059 0.71 -2.2 -1.1 0.96 -8 -3.9 -3.7e+02 -1.1e-05 -5.7e-05 4e-06 -9.8e-05 -9.7e-05 -0.00028 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 6.5e-05 7.9e-05 7.8e-05 6.4e-05 0.024 0.025 0.009 0.17 0.16 0.036 3.5e-11 3.5e-11 1.3e-10 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
299 29690000 0.71 0.0025 0.0066 0.71 -2.2 -1.1 0.95 -8.2 -4 -3.7e+02 -1.1e-05 -5.7e-05 3.9e-06 -0.0001 -0.00027 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 6.5e-05 7.9e-05 7.8e-05 6.4e-05 0.026 0.026 0.0091 0.18 0.18 0.036 3.5e-11 3.5e-11 1.3e-10 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
300 29790000 0.71 0.0028 0.0071 0.71 -2.1 -1.1 0.93 -8.5 -4.1 -3.7e+02 -1.2e-05 -5.7e-05 3.9e-06 -0.00012 -0.00029 -0.00028 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 6.5e-05 7.9e-05 7.8e-05 6.3e-05 6.4e-05 0.025 0.025 0.0091 0.18 0.17 0.037 3.5e-11 3.4e-11 1.2e-10 1.3e-10 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
301 29890000 0.71 0.0029 0.0074 0.71 -2.1 -1.1 0.92 -8.7 -4.2 -3.7e+02 -1.2e-05 -5.7e-05 3.7e-06 3.8e-06 -0.00013 -0.00026 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 6.5e-05 8e-05 7.8e-05 6.3e-05 6.4e-05 0.026 0.026 0.0091 0.19 0.19 0.037 3.5e-11 3.4e-11 1.2e-10 1.3e-10 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
302 29990000 0.71 0.003 0.0076 0.71 -2.1 -1.1 0.9 -9 -4.3 -3.7e+02 -1.2e-05 -5.7e-05 3.6e-06 -0.00015 -0.00026 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 6.5e-05 8e-05 7.8e-05 6.3e-05 6.4e-05 0.025 0.025 0.009 0.19 0.18 0.036 3.4e-11 3.4e-11 1.2e-10 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
303 30090000 0.71 0.003 0.0075 0.71 -2.1 -1 0.89 -9.2 -4.4 -3.7e+02 -1.2e-05 -5.7e-05 3.5e-06 -0.00015 -0.00024 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 8e-05 7.8e-05 6.3e-05 0.026 0.026 0.0091 0.2 0.2 0.036 3.4e-11 3.4e-11 1.2e-10 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
304 30190000 0.71 0.0031 0.0074 0.71 -2 -1 0.88 -9.4 -4.5 -3.7e+02 -1.2e-05 -5.7e-05 3.5e-06 -0.00017 -0.00025 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 8e-05 7.8e-05 6.3e-05 0.025 0.025 0.009 0.2 0.19 0.037 3.4e-11 3.3e-11 1.2e-10 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
305 30290000 0.71 0.003 0.0072 0.71 -2 -1 0.86 -9.6 -4.6 -3.7e+02 -1.2e-05 -5.7e-05 3.4e-06 -0.00017 -0.00024 -0.0011 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 8e-05 7.8e-05 6.3e-05 0.026 0.027 0.0091 0.21 0.21 0.037 3.4e-11 3.3e-11 1.2e-10 2.8e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
306 30390000 0.71 0.003 0.0071 0.71 -2 -1 0.85 -9.9 -4.7 -3.7e+02 -1.3e-05 -5.7e-05 3.4e-06 -0.00018 -0.00023 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 8e-05 7.8e-05 6.3e-05 0.025 0.025 0.009 0.21 0.2 0.036 3.3e-11 3.3e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
307 30490000 0.71 0.0029 0.0068 0.71 -2 -1 0.83 -10 -4.8 -3.7e+02 -1.3e-05 -5.7e-05 3.4e-06 -0.00019 -0.00022 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 8e-05 7.8e-05 6.3e-05 0.026 0.027 0.0091 0.22 0.22 0.037 3.3e-11 3.3e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
308 30590000 0.71 0.0028 0.0065 0.71 -1.9 -1 0.79 -10 -4.9 -3.7e+02 -1.3e-05 -5.7e-05 3.4e-06 -0.00019 -0.00022 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.4e-05 8e-05 7.7e-05 6.2e-05 6.3e-05 0.025 0.025 0.009 0.21 0.21 0.037 3.3e-11 3.2e-11 1.1e-10 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
309 30690000 0.71 0.0027 0.0062 0.71 -1.9 -0.99 0.79 -11 -5 -3.7e+02 -1.3e-05 -5.7e-05 3.3e-06 -0.0002 -0.00021 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8e-05 7.7e-05 6.2e-05 0.026 0.027 0.009 0.23 0.23 0.037 3.3e-11 3.2e-11 1.1e-10 1.2e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
310 30790000 0.71 0.0026 0.0027 0.0059 0.71 -1.9 -0.98 0.78 -11 -5.1 -3.7e+02 -1.3e-05 -5.7e-05 3.2e-06 -0.00021 -0.0002 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8e-05 7.7e-05 6.2e-05 0.025 0.025 0.009 0.22 0.22 0.037 3.2e-11 3.2e-11 1.1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
311 30890000 0.71 0.0025 0.0055 0.71 -1.9 -0.97 0.76 -11 -5.2 -3.7e+02 -1.3e-05 -5.7e-05 3.2e-06 -0.00021 -0.00019 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8.1e-05 7.7e-05 6.2e-05 0.026 0.027 0.009 0.24 0.24 0.037 3.2e-11 3.2e-11 1.1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
312 30990000 0.71 0.0024 0.0025 0.005 0.71 -1.8 -0.96 0.76 -11 -5.3 -3.7e+02 -1.3e-05 -5.7e-05 3.1e-06 -0.00022 -0.00018 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8e-05 8.1e-05 7.7e-05 6.2e-05 0.025 0.025 0.0089 0.23 0.23 0.037 3.2e-11 3.1e-11 1.1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
313 31090000 0.71 0.0022 0.0045 0.71 -1.8 -0.96 0.74 -11 -5.4 -3.7e+02 -1.3e-05 -5.7e-05 3e-06 -0.00023 -0.00017 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 6.4e-05 8.1e-05 7.7e-05 6.2e-05 0.026 0.027 0.009 0.25 0.24 0.037 3.2e-11 3.1e-11 1.1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
314 31190000 0.71 0.0022 0.0043 0.71 -1.8 -0.95 0.73 -12 -5.5 -3.7e+02 -1.4e-05 -5.7e-05 3e-06 -0.00024 -0.00014 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 8.1e-05 7.7e-05 6.1e-05 6.2e-05 0.025 0.025 0.0089 0.24 0.24 0.037 3.1e-11 3.1e-11 1.1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
315 31290000 0.71 0.002 0.0038 0.71 -1.8 -0.94 0.73 -12 -5.6 -3.7e+02 -1.4e-05 -5.7e-05 3e-06 -0.00024 -0.00025 -0.00013 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 8.1e-05 7.7e-05 6.1e-05 6.2e-05 0.026 0.027 0.0089 0.26 0.25 0.037 3.1e-11 3.1e-11 1.1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
316 31390000 0.71 0.0018 0.0033 0.71 -1.8 -0.93 0.73 -12 -5.7 -3.7e+02 -1.4e-05 -5.7e-05 2.9e-06 -0.00025 -0.00011 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 8.1e-05 7.6e-05 6.1e-05 0.025 0.025 0.0088 0.25 0.25 0.036 3.1e-11 3.1e-11 1.1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
317 31490000 0.71 0.0016 0.0027 0.71 -1.7 -0.92 0.72 -12 -5.8 -3.7e+02 -1.4e-05 -5.7e-05 2.8e-06 -0.00026 -0.0001 -9.9e-05 -0.001 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 8.1e-05 7.6e-05 6.1e-05 0.026 0.027 0.0088 0.26 0.26 0.037 3.1e-11 3.1e-11 1e-10 1.1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
318 31590000 0.71 0.0016 0.0023 0.0024 0.71 -1.7 -0.91 0.72 -12 -5.9 -3.7e+02 -1.4e-05 -5.7e-05 2.8e-06 -0.00027 -8.3e-05 -8.2e-05 -0.00099 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 8.1e-05 7.6e-05 6.1e-05 0.025 0.025 0.0087 0.26 0.26 0.037 3.1e-11 3e-11 1e-10 1.1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
319 31690000 0.71 0.0013 0.0017 0.71 -1.7 -0.9 0.72 -12 -5.9 -3.7e+02 -1.4e-05 -5.7e-05 2.8e-06 -0.00027 -7.1e-05 -7e-05 -0.00099 0.21 0.0021 0.44 0 0 0 0 0 6.3e-05 8.1e-05 7.6e-05 6.1e-05 0.026 0.026 0.0088 0.27 0.27 0.037 3.1e-11 3e-11 1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
320 31790000 0.71 0.0011 0.0011 0.71 -1.7 -0.89 0.72 -13 -6 -3.7e+02 -1.4e-05 -5.7e-05 2.8e-06 -0.00028 -5.3e-05 -5.2e-05 -0.00098 0.21 0.0021 0.44 0 0 0 0 0 6.2e-05 6.3e-05 8.1e-05 7.6e-05 6.1e-05 0.025 0.025 0.0087 0.27 0.27 0.037 3e-11 3e-11 1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
321 31890000 0.71 0.00087 0.00088 0.00038 0.71 -1.6 -0.88 0.72 -13 -6.1 -3.7e+02 -1.4e-05 -5.7e-05 2.8e-06 -0.00029 -4e-05 -3.9e-05 -0.00098 0.21 0.0021 0.44 0 0 0 0 0 6.2e-05 6.3e-05 8.1e-05 7.6e-05 6e-05 6.1e-05 0.026 0.026 0.0087 0.28 0.28 0.037 3e-11 3e-11 1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
322 31990000 0.71 0.00074 -8.2e-05 -7.4e-05 0.71 -1.6 -0.87 0.71 -13 -6.2 -3.7e+02 -1.4e-05 -5.7e-05 2.7e-06 -0.0003 -2.1e-05 -2e-05 -0.00097 0.21 0.0021 0.44 0 0 0 0 0 6.2e-05 6.3e-05 8.1e-05 7.6e-05 6e-05 0.025 0.025 0.0086 0.28 0.28 0.036 3e-11 3e-11 9.9e-11 1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
323 32090000 0.71 0.00045 0.00046 -0.0008 -0.00079 0.71 -1.6 -0.86 0.72 -13 -6.3 -3.7e+02 -1.4e-05 -5.7e-05 2.6e-06 -0.0003 -6.3e-06 -4.9e-06 -0.00096 0.21 0.0021 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.6e-05 6e-05 0.026 0.026 0.0087 0.29 0.29 0.037 3e-11 3e-11 9.9e-11 1e-10 2.7e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
324 32190000 0.71 0.00024 0.00025 -0.0016 0.71 -1.5 -0.85 0.72 -13 -6.4 -3.7e+02 -1.4e-05 -5.7e-05 2.5e-06 -0.00031 1.4e-05 1.6e-05 -0.00096 0.21 0.0021 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 6e-05 0.025 0.025 0.0086 0.29 0.29 0.036 2.9e-11 2.9e-11 9.8e-11 9.9e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
325 32290000 0.71 9.8e-06 1.3e-05 -0.0023 0.71 -1.5 -0.84 0.71 -13 -6.4 -3.7e+02 -1.4e-05 -5.7e-05 2.4e-06 -0.00032 3e-05 3.2e-05 -0.00095 0.21 0.0021 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 6e-05 0.026 0.026 0.0086 0.3 0.3 0.037 3e-11 2.9e-11 9.7e-11 9.8e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
326 32390000 0.71 -0.00017 -0.0029 0.71 -1.5 -0.83 0.71 -14 -6.5 -3.7e+02 -1.4e-05 -5.7e-05 2.5e-06 -0.00032 3.9e-05 4.1e-05 -0.00095 0.21 0.0021 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 6e-05 0.025 0.025 0.0085 0.3 0.3 0.037 2.9e-11 2.9e-11 9.6e-11 9.7e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
327 32490000 0.71 -0.00029 -0.0032 0.71 -1.4 -0.81 0.72 -14 -6.6 -3.7e+02 -1.4e-05 -5.7e-05 2.5e-06 -0.00033 5.1e-05 5.2e-05 -0.00094 0.21 0.0021 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 6e-05 0.026 0.026 0.0086 0.31 0.31 0.037 2.9e-11 2.9e-11 9.5e-11 9.7e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
328 32590000 0.71 -0.00029 -0.0034 0.71 -1.4 -0.8 0.71 -14 -6.7 -3.7e+02 -1.5e-05 -5.7e-05 2.4e-06 -0.00033 5.8e-05 5.9e-05 -0.00094 0.21 0.0021 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 6e-05 0.025 0.025 0.0084 0.31 0.31 0.036 2.9e-11 2.9e-11 9.4e-11 9.6e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
329 32690000 0.71 -0.00033 -0.0035 0.71 -1.4 -0.79 0.71 -14 -6.8 -3.7e+02 -1.5e-05 -5.7e-05 2.4e-06 -0.00033 6.4e-05 6.5e-05 -0.00094 0.21 0.0021 0.44 0 0 0 0 0 6.2e-05 8.1e-05 7.5e-05 5.9e-05 6e-05 0.026 0.026 0.0085 0.32 0.32 0.036 2.9e-11 2.9e-11 9.3e-11 9.5e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
330 32790000 0.71 -0.00029 -0.0034 0.71 -1.4 -0.78 0.71 -14 -6.8 -3.7e+02 -1.5e-05 -5.7e-05 2.3e-06 -0.00034 7.3e-05 7.4e-05 -0.00094 0.21 0.0021 0.44 0 0 0 0 0 6.1e-05 6.2e-05 8.1e-05 7.4e-05 5.9e-05 6e-05 0.025 0.025 0.0084 0.32 0.31 0.036 2.9e-11 2.9e-11 9.3e-11 9.4e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
331 32890000 0.71 -0.0002 -0.0034 0.71 -1.3 -0.77 0.71 -14 -6.9 -3.7e+02 -1.5e-05 -5.7e-05 2.2e-06 -0.00034 8.4e-05 8.5e-05 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 6.1e-05 6.2e-05 8.1e-05 7.4e-05 5.9e-05 0.026 0.026 0.0084 0.33 0.33 0.036 2.9e-11 2.9e-11 9.2e-11 9.3e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
332 32990000 0.71 -7.3e-05 -7e-05 -0.0033 0.71 -1.3 -0.77 -0.76 0.7 -15 -7 -3.7e+02 -1.5e-05 -5.7e-05 2.3e-06 -0.00035 9.7e-05 9.8e-05 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 6.1e-05 8.1e-05 7.4e-05 5.9e-05 0.025 0.025 0.0083 0.32 0.32 0.036 2.8e-11 2.8e-11 9.1e-11 9.2e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
333 33090000 0.71 -0.00011 -0.0001 -0.0033 0.71 -1.3 -0.76 0.69 -15 -7.1 -3.7e+02 -1.5e-05 -5.7e-05 2.4e-06 -0.00035 0.0001 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 6.1e-05 8.1e-05 7.4e-05 5.9e-05 0.026 0.026 0.0084 0.34 0.34 0.036 2.8e-11 2.8e-11 9e-11 9.1e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
334 33190000 0.7 0.0033 -0.0024 0.71 -1.3 -0.75 0.64 -15 -7.1 -3.7e+02 -1.5e-05 -5.7e-05 2.4e-06 -0.00035 0.00011 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 6.1e-05 8.1e-05 7.4e-05 5.9e-05 0.025 0.025 0.0083 0.33 0.33 0.036 2.8e-11 2.8e-11 8.9e-11 9.1e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
335 33290000 0.65 0.015 -0.0015 0.76 -1.3 -0.73 0.62 -15 -7.2 -3.7e+02 -1.5e-05 -5.7e-05 2.4e-06 -0.00036 0.00011 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.9e-05 8e-05 7.4e-05 6.1e-05 0.026 0.026 0.0083 0.35 0.35 0.036 2.8e-11 2.8e-11 8.9e-11 9e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
336 33390000 0.55 0.013 -0.0017 0.84 -1.3 -0.72 0.81 -15 -7.3 -3.7e+02 -1.5e-05 -5.7e-05 2.5e-06 -0.00036 0.00012 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 7.9e-05 7.5e-05 6.5e-05 0.024 0.024 0.0083 0.34 0.34 0.036 2.8e-11 2.8e-11 8.8e-11 8.9e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
337 33490000 0.41 0.0069 0.00072 0.00073 0.91 -1.2 -0.71 0.83 -15 -7.4 -3.7e+02 -1.5e-05 -5.7e-05 2.5e-06 -0.00036 0.00012 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5e-05 5.1e-05 7.8e-05 7.7e-05 7e-05 0.026 0.026 0.0081 0.36 0.35 0.036 2.8e-11 2.8e-11 8.7e-11 8.8e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
338 33590000 0.25 0.00099 -0.0018 0.97 -1.2 -0.71 0.79 -15 -7.4 -3.7e+02 -1.5e-05 -5.7e-05 2.5e-06 -0.00036 0.00012 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 4.7e-05 7.6e-05 7.8e-05 7.3e-05 0.025 0.025 0.0078 0.35 0.35 0.036 2.8e-11 2.8e-11 8.6e-11 8.7e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
339 33690000 0.087 -0.0023 -0.0049 1 -1.2 -0.71 0.8 -15 -7.5 -3.7e+02 -1.5e-05 -5.7e-05 2.5e-06 -0.00036 0.00012 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 4.5e-05 7.5e-05 8e-05 7.6e-05 7.5e-05 0.028 0.028 0.0076 0.36 0.36 0.036 2.8e-11 2.8e-11 8.6e-11 8.7e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
340 33790000 -0.082 -0.0038 -0.0067 1 -1.1 -0.69 0.78 -16 -7.6 -3.7e+02 -1.5e-05 -5.7e-05 2.5e-06 -0.00036 0.00012 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 4.4e-05 4.5e-05 7.2e-05 8e-05 7.6e-05 0.028 0.028 0.0074 0.36 0.36 0.036 2.7e-11 2.7e-11 8.5e-11 8.6e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
341 33890000 -0.25 -0.0049 -0.0074 0.97 -1 -0.67 0.77 -16 -7.6 -3.7e+02 -1.5e-05 -5.7e-05 2.5e-06 -0.00036 0.00012 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 4.6e-05 7.2e-05 8.1e-05 7.5e-05 0.031 0.032 0.0072 0.37 0.37 0.036 2.7e-11 2.8e-11 8.4e-11 8.5e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
342 33990000 -0.39 -0.0031 -0.011 0.92 -0.98 -0.63 0.74 -16 -7.7 -3.7e+02 -1.5e-05 -5.6e-05 2.5e-06 -0.00036 0.00012 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 4.8e-05 4.9e-05 6.9e-05 7.8e-05 7.2e-05 0.032 0.032 0.007 0.37 0.37 0.035 2.7e-11 2.7e-11 8.3e-11 8.5e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
343 34090000 -0.5 -0.0021 -0.002 -0.013 0.87 -0.93 -0.58 0.74 -16 -7.7 -3.7e+02 -1.5e-05 -5.6e-05 2.6e-06 -0.00036 0.00012 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.1e-05 5.2e-05 6.9e-05 7.8e-05 6.9e-05 0.036 0.037 0.0069 0.38 0.38 0.036 2.7e-11 2.7e-11 8.3e-11 8.4e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
344 34190000 -0.57 -0.0014 -0.011 0.82 -0.92 -0.54 0.74 -16 -7.8 -3.7e+02 -1.5e-05 -5.7e-05 2.6e-06 -0.00039 0.00014 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.4e-05 6.5e-05 7.3e-05 6.7e-05 0.036 0.037 0.0067 0.38 0.38 0.035 2.7e-11 2.7e-11 8.2e-11 8.3e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
345 34290000 -0.61 -0.0023 -0.0086 0.79 -0.87 -0.49 0.74 -16 -7.9 -3.7e+02 -1.5e-05 -5.7e-05 2.6e-06 -0.00039 0.00014 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 6.5e-05 7.3e-05 6.5e-05 0.042 0.043 0.0066 0.39 0.39 0.035 2.7e-11 2.7e-11 8.2e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
346 34390000 -0.64 -0.0025 -0.0061 0.77 -0.85 -0.46 0.73 -16 -7.9 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00044 0.00019 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 6e-05 6.7e-05 6.4e-05 0.042 0.043 0.0065 0.39 0.39 0.035 2.7e-11 2.7e-11 8.1e-11 8.2e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
347 34490000 -0.65 -0.0034 -0.0039 0.76 -0.8 -0.42 0.73 -16 -8 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00043 -0.00044 0.00019 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 6.1e-05 6.7e-05 6.3e-05 0.049 0.05 0.0064 0.4 0.4 0.035 2.7e-11 2.7e-11 8e-11 8.1e-11 2.7e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
348 34590000 -0.66 -0.0028 -0.0028 0.75 -0.8 -0.4 0.73 -17 -8.1 -3.7e+02 -1.6e-05 -5.7e-05 2.8e-06 -0.00053 0.00027 0.00028 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 5.5e-05 6.1e-05 6.2e-05 6.3e-05 0.047 0.048 0.0063 0.4 0.4 0.034 2.6e-11 2.7e-11 8e-11 2.6e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
349 34690000 -0.67 -0.0032 -0.002 0.74 -0.75 -0.37 0.73 -17 -8.1 -3.7e+02 -1.6e-05 -5.7e-05 2.8e-06 -0.00053 0.00027 0.00028 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 5.5e-05 6.1e-05 6.2e-05 0.054 0.056 0.0063 0.41 0.41 0.034 2.7e-11 2.7e-11 7.9e-11 8e-11 2.6e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
350 34790000 -0.67 -0.0021 -0.0018 0.74 -0.75 -0.36 0.72 -17 -8.2 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00064 0.00038 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 5.1e-05 5.5e-05 6.2e-05 0.051 0.053 0.0062 0.41 0.41 0.034 2.6e-11 2.7e-11 7.8e-11 7.9e-11 2.6e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
351 34890000 -0.68 -0.0021 -0.0017 0.74 -0.7 -0.71 -0.32 0.72 -17 -8.2 -3.7e+02 -1.6e-05 -5.7e-05 2.8e-06 -0.00064 0.00038 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 5.1e-05 5.5e-05 6.2e-05 0.059 0.061 0.0062 0.42 0.42 0.034 2.6e-11 2.7e-11 7.8e-11 7.9e-11 2.6e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
352 34990000 -0.68 -0.0085 -0.0045 0.73 0.31 0.29 -0.13 -17 -8.2 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00077 0.00052 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 4.6e-05 5e-05 6.1e-05 6.2e-05 0.058 0.058 0.0068 0.42 0.42 0.034 2.6e-11 2.7e-11 7.7e-11 7.8e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
353 35090000 -0.68 -0.0085 -0.0045 0.73 0.43 0.31 -0.19 -17 -8.2 -3.7e+02 -1.6e-05 -5.7e-05 2.8e-06 -0.00077 0.00052 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 4.6e-05 5e-05 6.1e-05 0.063 0.063 0.0068 0.43 0.43 0.034 2.7e-11 2.7e-11 7.7e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
354 35190000 -0.68 -0.0085 -0.0045 0.73 0.45 0.34 -0.18 -17 -8.2 -3.7e+02 -1.6e-05 -5.7e-05 2.8e-06 -0.00077 0.00052 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 4.6e-05 5e-05 6.1e-05 0.068 0.068 0.0067 0.44 0.44 0.034 2.7e-11 2.7e-11 7.6e-11 7.7e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
355 35290000 -0.68 -0.0086 -0.0046 0.73 0.48 0.37 -0.18 -17 -8.1 -3.7e+02 -1.6e-05 -5.7e-05 2.8e-06 -0.00077 0.00052 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 4.6e-05 5e-05 6.1e-05 0.073 0.074 0.0066 0.46 0.45 0.033 2.7e-11 2.7e-11 7.5e-11 7.6e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
356 35390000 -0.68 -0.0086 -0.0046 0.73 0.5 0.41 -0.18 -17 -8.1 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00077 0.00052 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 4.6e-05 5e-05 6.1e-05 0.079 0.08 0.0066 0.47 0.47 0.034 2.7e-11 2.7e-11 7.5e-11 7.6e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
357 35490000 -0.68 -0.0087 -0.0046 0.73 0.52 0.44 -0.18 -17 -8 -3.7e+02 -1.6e-05 -5.7e-05 2.7e-06 -0.00077 0.00052 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 4.6e-05 5e-05 6.1e-05 0.085 0.087 0.0065 0.49 0.49 0.034 2.7e-11 2.7e-11 7.4e-11 7.5e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
358 35590000 -0.68 -0.0056 -0.0045 0.73 0.41 0.36 -0.19 -17 -8.1 -3.7e+02 -1.7e-05 -5.7e-05 2.9e-06 -0.00077 0.00052 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 3.9e-05 4.2e-05 6.1e-05 0.068 0.069 0.0062 0.48 0.48 0.033 2.7e-11 2.7e-11 7.4e-11 7.5e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
359 35690000 -0.68 -0.0057 -0.0056 -0.0045 0.73 0.43 0.38 -0.19 -17 -8.1 -3.7e+02 -1.7e-05 -5.7e-05 2.9e-06 -0.00077 0.00052 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.7e-05 3.9e-05 4.2e-05 6e-05 6.1e-05 0.073 0.075 0.0061 0.49 0.49 0.033 2.7e-11 2.7e-11 7.3e-11 7.4e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
360 35790000 -0.68 -0.0034 -0.0044 0.73 0.35 0.32 -0.19 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3e-06 -0.00079 0.00053 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 3.4e-05 3.6e-05 6e-05 0.061 0.062 0.0059 0.49 0.48 0.033 2.7e-11 2.7e-11 7.3e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
361 35890000 -0.68 -0.0034 -0.0045 0.73 0.37 0.35 -0.19 -17 -8.1 -3.7e+02 -1.7e-05 -5.7e-05 3.1e-06 -0.00079 0.00053 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 3.4e-05 3.6e-05 6e-05 0.066 0.068 0.0059 0.5 0.5 0.033 2.7e-11 2.7e-11 7.2e-11 7.3e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
362 35990000 -0.68 -0.0016 -0.0015 -0.0044 0.73 0.3 0.29 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.3e-06 -0.00087 0.0006 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 3e-05 3.1e-05 6e-05 0.057 0.058 0.0057 0.49 0.49 0.033 2.7e-11 2.8e-11 7.2e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
363 36090000 -0.68 -0.0016 -0.0044 0.73 0.31 0.31 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.5e-06 -0.00087 0.0006 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 3e-05 3.1e-05 6e-05 0.062 0.064 0.0057 0.51 0.51 0.032 2.7e-11 2.8e-11 7.1e-11 7.2e-11 2.5e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
364 36190000 -0.68 -0.00014 -0.0043 -0.0042 0.73 0.26 0.27 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.5e-06 -0.00097 0.00068 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 2.6e-05 2.8e-05 6e-05 0.055 0.056 0.0055 0.5 0.5 0.032 2.7e-11 2.8e-11 7.1e-11 2.4e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
365 36290000 -0.68 -0.00021 -0.0002 -0.0042 0.73 0.27 0.28 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.7e-06 -0.00097 0.00068 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 2.6e-05 2.8e-05 6e-05 0.06 0.062 0.0056 0.52 0.52 0.032 2.7e-11 2.8e-11 7e-11 7.1e-11 2.4e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
366 36390000 -0.68 0.00084 0.00085 -0.0041 0.73 0.22 0.24 -0.21 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 3.9e-06 -0.0011 0.00077 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 2.4e-05 2.5e-05 6e-05 0.053 0.055 0.0055 0.51 0.51 0.032 2.8e-11 2.8e-11 7e-11 2.4e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
367 36490000 -0.68 0.00079 -0.0041 0.73 0.23 0.26 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.1e-06 -0.0011 0.00077 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 2.4e-05 2.5e-05 6e-05 0.059 0.061 0.0055 0.53 0.52 0.032 2.8e-11 2.8e-11 6.9e-11 7e-11 2.4e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
368 36590000 -0.68 0.0016 -0.004 0.73 0.19 0.22 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.3e-06 -0.0012 0.00086 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 2.2e-05 2.3e-05 6e-05 0.053 0.054 0.0055 0.52 0.52 0.031 2.8e-11 2.8e-11 6.9e-11 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
369 36690000 -0.68 0.0016 -0.004 0.74 0.19 0.23 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.4e-06 -0.0012 0.00086 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 2.2e-05 2.3e-05 5.9e-05 6e-05 0.058 0.06 0.0055 0.53 0.53 0.031 2.8e-11 2.8e-11 6.8e-11 6.9e-11 2.3e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
370 36790000 -0.68 0.0022 -0.0039 0.74 0.16 0.2 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.5e-06 -0.0013 0.00095 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 2.1e-05 2.2e-05 5.9e-05 6e-05 0.052 0.053 0.0055 0.53 0.53 0.031 2.8e-11 2.8e-11 6.8e-11 2.2e-06 2.1e-06 5e-08 0 0 0 0 0 0 0 0
371 36890000 -0.68 0.0022 -0.0039 0.74 0.16 0.21 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.6e-06 4.7e-06 -0.0013 0.00095 -0.00092 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 2.1e-05 2.2e-05 5.9e-05 0.057 0.059 0.0056 0.54 0.54 0.031 2.8e-11 2.8e-11 6.7e-11 6.8e-11 2.2e-06 2.1e-06 5e-08 0 0 0 0 0 0 0 0
372 36990000 -0.68 0.0026 -0.0037 0.74 0.13 0.18 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 4.8e-06 -0.0015 0.001 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 5.6e-05 1.9e-05 2e-05 5.9e-05 0.051 0.052 0.0056 0.54 0.54 0.031 2.8e-11 2.8e-11 6.7e-11 6.8e-11 2.2e-06 2e-06 5e-08 0 0 0 0 0 0 0 0
373 37090000 -0.68 0.0026 -0.0037 0.74 0.13 0.19 -0.2 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5e-06 -0.0015 0.001 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 5.6e-05 2e-05 2.1e-05 5.9e-05 0.056 0.058 0.0057 0.55 0.55 0.031 2.8e-11 2.9e-11 6.7e-11 2.2e-06 2e-06 5e-08 0 0 0 0 0 0 0 0
374 37190000 -0.68 0.0029 -0.0036 0.74 0.11 0.16 -0.19 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.2e-06 -0.0016 0.0011 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.9e-05 2e-05 5.9e-05 0.05 0.052 0.0057 0.55 0.55 0.031 2.8e-11 2.9e-11 6.6e-11 6.7e-11 2.1e-06 1.9e-06 5e-08 0 0 0 0 0 0 0 0
375 37290000 -0.68 0.0029 -0.0036 0.74 0.11 0.17 -0.19 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.4e-06 -0.0016 0.0011 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.9e-05 2e-05 5.9e-05 0.055 0.057 0.0059 0.56 0.56 0.031 2.8e-11 2.9e-11 6.6e-11 2.1e-06 1.9e-06 5e-08 0 0 0 0 0 0 0 0
376 37390000 -0.68 0.0032 -0.0034 0.74 0.088 0.14 -0.19 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.5e-06 -0.0017 0.0011 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.8e-05 1.9e-05 5.9e-05 0.05 0.051 0.0059 0.56 0.56 0.031 2.9e-11 2.9e-11 6.5e-11 6.6e-11 2e-06 1.8e-06 5e-08 0 0 0 0 0 0 0 0
377 37490000 -0.68 0.0032 0.0031 -0.0034 0.74 0.087 0.15 -0.19 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.6e-06 5.7e-06 -0.0017 0.0011 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.8e-05 1.9e-05 5.9e-05 0.054 0.055 0.006 0.57 0.57 0.031 2.9e-11 2.9e-11 6.5e-11 2e-06 1.8e-06 5e-08 0 0 0 0 0 0 0 0
378 37590000 -0.68 0.0033 -0.0033 0.74 0.069 0.12 -0.18 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.8e-06 -0.0017 0.0012 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.8e-05 1.9e-05 5.9e-05 0.049 0.05 0.0061 0.57 0.57 0.031 2.9e-11 2.9e-11 6.4e-11 6.5e-11 1.9e-06 1.8e-06 5e-08 0 0 0 0 0 0 0 0
379 37690000 -0.68 0.0033 -0.0034 -0.0033 0.74 0.066 0.13 -0.18 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 5.9e-06 6e-06 -0.0017 0.0012 -0.00093 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.8e-05 1.9e-05 5.9e-05 0.053 0.054 0.0062 0.58 0.58 0.031 2.9e-11 2.9e-11 6.4e-11 6.5e-11 1.9e-06 1.8e-06 5e-08 0 0 0 0 0 0 0 0
380 37790000 -0.68 0.0034 -0.0033 0.74 0.052 0.11 -0.17 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.1e-06 -0.0018 0.0012 -0.00094 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.8e-05 1.8e-05 5.9e-05 0.048 0.048 0.0063 0.58 0.58 0.03 2.9e-11 2.9e-11 6.4e-11 1.8e-06 1.7e-06 5e-08 0 0 0 0 0 0 0 0
381 37890000 -0.68 0.0034 -0.0033 0.74 0.05 0.11 -0.16 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.3e-06 -0.0018 0.0012 -0.00094 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.8e-05 1.9e-05 5.9e-05 0.052 0.053 0.0064 0.59 0.59 0.03 2.9e-11 2.9e-11 6.3e-11 6.4e-11 1.8e-06 1.7e-06 5e-08 0 0 0 0 0 0 0 0
382 37990000 -0.68 0.0034 -0.0033 0.74 0.037 0.097 -0.15 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.5e-06 -0.0019 0.0013 -0.00095 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.7e-05 1.8e-05 5.9e-05 0.047 0.047 0.0065 0.59 0.59 0.031 2.9e-11 2.9e-11 6.3e-11 1.7e-06 1.6e-06 5e-08 0 0 0 0 0 0 0 0
383 38090000 -0.68 0.0034 -0.0033 0.74 0.034 0.1 -0.14 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.6e-06 -0.0019 0.0013 -0.00095 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.8e-05 1.8e-05 5.9e-05 0.05 0.051 0.0066 0.6 0.6 0.031 2.9e-11 3e-11 6.2e-11 6.3e-11 1.7e-06 1.6e-06 5e-08 0 0 0 0 0 0 0 0
384 38190000 -0.68 0.0034 -0.0032 0.74 0.022 0.085 -0.13 -0.14 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.8e-06 -0.002 0.0013 -0.00096 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.7e-05 1.8e-05 5.9e-05 0.045 0.046 0.0067 0.6 0.6 0.031 2.9e-11 3e-11 6.2e-11 6.3e-11 1.6e-06 1.5e-06 5e-08 0 0 0 0 0 0 0 0
385 38290000 -0.68 0.0034 -0.0032 0.74 0.019 0.086 -0.13 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 6.9e-06 -0.002 0.0013 -0.00096 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.8e-05 1.8e-05 5.9e-05 0.049 0.05 0.0068 0.61 0.61 0.031 2.9e-11 3e-11 6.2e-11 1.6e-06 1.5e-06 5e-08 0 0 0 0 0 0 0 0
386 38390000 -0.68 0.0034 -0.0031 0.74 0.012 0.074 -0.12 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.1e-06 -0.002 0.0013 -0.00097 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.7e-05 1.8e-05 5.9e-05 0.044 0.045 0.0069 0.61 0.61 0.031 2.9e-11 3e-11 6.1e-11 6.2e-11 1.6e-06 1.5e-06 5e-08 0 0 0 0 0 0 0 0
387 38490000 -0.68 0.0034 -0.0031 0.74 0.0091 0.009 0.076 -0.11 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.2e-06 7.3e-06 -0.002 0.0013 -0.00097 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.8e-05 1.8e-05 5.8e-05 5.9e-05 0.048 0.048 0.007 0.62 0.62 0.031 3e-11 3e-11 6.1e-11 1.6e-06 1.5e-06 5e-08 0 0 0 0 0 0 0 0
388 38590000 -0.68 0.0034 -0.003 0.74 0.0051 0.065 -0.11 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.4e-06 -0.002 0.0013 -0.00098 0.21 0.0021 0.44 0 0 0 0 0 5.5e-05 1.8e-05 1.8e-05 5.8e-05 5.9e-05 0.043 0.044 0.0071 0.62 0.62 0.031 3e-11 3e-11 6.1e-11 1.5e-06 1.4e-06 5e-08 0 0 0 0 0 0 0 0
389 38690000 -0.68 0.0033 -0.003 0.74 0.0012 0.065 -0.097 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.5e-06 7.6e-06 -0.0021 0.0013 -0.00098 0.21 0.0021 0.44 0 0 0 0 0 5.4e-05 5.5e-05 1.8e-05 1.9e-05 5.8e-05 0.046 0.047 0.0072 0.63 0.63 0.031 3e-11 3e-11 6e-11 6.1e-11 1.5e-06 1.4e-06 5e-08 0 0 0 0 0 0 0 0
390 38790000 -0.68 0.0033 -0.003 0.74 -0.0034 -0.0035 0.054 -0.089 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.7e-06 -0.0021 0.0013 -0.00098 0.21 0.0021 0.44 0 0 0 0 0 5.4e-05 1.8e-05 1.9e-05 5.8e-05 0.042 0.042 0.0073 0.63 0.63 0.031 3e-11 3e-11 6e-11 1.4e-06 1.4e-06 5e-08 0 0 0 0 0 0 0 0
391 38890000 -0.67 0.0031 -0.003 0.74 -0.013 0.043 0.41 -17 -8.2 -3.7e+02 -1.7e-05 -5.7e-05 7.8e-06 -0.0021 0.0013 -0.00099 0.21 0.0021 0.44 0 0 0 0 0 5.4e-05 1.8e-05 1.9e-05 5.8e-05 0.045 0.045 0.0075 0.64 0.64 0.032 3e-11 3e-11 6e-11 1.4e-06 1.4e-06 5e-08 0 0 0 0 0 0 0 0
@@ -65,287 +65,287 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
6290000,0.98,-0.0068,-0.013,0.18,0.004,0.021,0.19,0.0035,0.0084,0.051,-1.9e-05,-5.5e-05,7.4e-07,0,0,-0.0019,0.2,-6.1e-09,0.43,0,0,0,0,0,5e-06,0.00044,0.00044,0.00015,0.31,0.31,0.039,0.17,0.17,0.07,1.8e-08,1.8e-08,4.8e-09,4e-06,4e-06,3.9e-07,0,0,0,0,0,0,0,0
6390000,0.98,-0.0068,-0.013,0.18,0.0046,0.018,0.19,0.0024,0.0066,0.064,-1.8e-05,-5.6e-05,7.2e-07,0,0,-0.0019,0.2,-6.1e-09,0.43,0,0,0,0,0,4.9e-06,0.00036,0.00036,0.00015,0.24,0.24,0.038,0.13,0.13,0.07,1.5e-08,1.5e-08,4.6e-09,4e-06,4e-06,3.6e-07,0,0,0,0,0,0,0,0
6490000,0.98,-0.0068,-0.013,0.18,0.0024,0.017,0.19,0.0027,0.0083,0.08,-1.8e-05,-5.6e-05,7.2e-07,0,0,-0.0019,0.2,-6.1e-09,0.43,0,0,0,0,0,4.8e-06,0.00038,0.00038,0.00015,0.28,0.28,0.036,0.16,0.16,0.069,1.5e-08,1.5e-08,4.4e-09,4e-06,4e-06,3.4e-07,0,0,0,0,0,0,0,0
6590000,0.98,-0.0067,-0.013,0.19,0.00045,0.015,0.19,0.0017,0.0063,0.088,-1.7e-05,-5.6e-05,7.1e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,5.5e-05,0.0003,0.0003,0.0015,0.2,0.2,0.035,0.12,0.12,0.068,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,3.2e-07,0,0,0,0,0,0,0,0
6690000,0.98,-0.0066,-0.013,0.19,-0.0022,0.017,0.19,0.0016,0.0079,0.097,-1.7e-05,-5.6e-05,6.9e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,3.5e-05,0.0003,0.0003,0.00097,0.21,0.21,0.033,0.15,0.15,0.067,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,3e-07,0,0,0,0,0,0,0,0
6790000,0.98,-0.0066,-0.013,0.19,-0.00042,0.019,0.19,0.0014,0.0096,0.11,-1.7e-05,-5.6e-05,6.8e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,2.7e-05,0.0003,0.0003,0.00074,0.21,0.21,0.032,0.18,0.18,0.067,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2.8e-07,0,0,0,0,0,0,0,0
6890000,0.98,-0.0064,-0.013,0.19,-0.00086,0.019,0.19,0.0013,0.011,0.12,-1.7e-05,-5.6e-05,6.8e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,2.1e-05,0.0003,0.0003,0.00058,0.22,0.22,0.031,0.22,0.22,0.066,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2.6e-07,0,0,0,0,0,0,0,0
6990000,0.98,-0.0064,-0.013,0.19,-0.00089,0.02,0.19,0.0011,0.013,0.12,-1.7e-05,-5.6e-05,6.9e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,1.7e-05,0.0003,0.0003,0.00048,0.23,0.23,0.03,0.26,0.26,0.065,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2.5e-07,0,0,0,0,0,0,0,0
7090000,0.98,-0.0063,-0.013,0.19,-0.0018,0.025,0.18,0.00095,0.016,0.13,-1.7e-05,-5.6e-05,7.1e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,1.5e-05,0.00031,0.00031,0.00041,0.25,0.25,0.029,0.31,0.31,0.065,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2.3e-07,0,0,0,0,0,0,0,0
7190000,0.98,-0.0062,-0.013,0.19,-0.0022,0.027,0.18,0.00066,0.018,0.13,-1.7e-05,-5.6e-05,6.7e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,1.3e-05,0.00031,0.00031,0.00036,0.27,0.27,0.028,0.36,0.36,0.064,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2.2e-07,0,0,0,0,0,0,0,0
7290000,0.98,-0.0062,-0.013,0.19,-0.0013,0.031,0.18,0.00039,0.021,0.14,-1.7e-05,-5.6e-05,7e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00031,0.00031,0.00032,0.29,0.29,0.027,0.42,0.42,0.063,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2.1e-07,0,0,0,0,0,0,0,0
7390000,0.98,-0.0061,-0.013,0.19,-0.003,0.034,0.17,0.00015,0.024,0.15,-1.7e-05,-5.6e-05,7.2e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,1.1e-05,0.00032,0.00032,0.00029,0.32,0.32,0.026,0.48,0.48,0.063,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2e-07,0,0,0,0,0,0,0,0
7490000,0.98,-0.0061,-0.013,0.19,-0.00063,0.036,0.17,-3.1e-05,0.028,0.15,-1.7e-05,-5.6e-05,8.3e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,9.6e-06,0.00033,0.00032,0.00026,0.35,0.35,0.026,0.56,0.56,0.062,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.8e-07,0,0,0,0,0,0,0,0
7590000,0.98,-0.0062,-0.013,0.19,0.00044,0.039,0.17,-7.4e-05,0.031,0.16,-1.7e-05,-5.6e-05,8.6e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00033,0.00033,0.00024,0.38,0.38,0.025,0.64,0.64,0.061,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.7e-07,0,0,0,0,0,0,0,0
7690000,0.98,-0.0062,-0.013,0.19,0.00019,0.043,0.17,-7.8e-05,0.035,0.17,-1.7e-05,-5.6e-05,8.5e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00034,0.00034,0.00022,0.41,0.41,0.024,0.73,0.73,0.061,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0
7790000,0.98,-0.0061,-0.013,0.19,0.0019,0.045,0.16,-4.8e-05,0.039,0.16,-1.7e-05,-5.6e-05,8e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,7.7e-06,0.00034,0.00034,0.00021,0.45,0.45,0.023,0.83,0.83,0.06,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0
7890000,0.98,-0.0061,-0.013,0.19,0.0006,0.049,0.15,-7.2e-05,0.044,0.16,-1.7e-05,-5.6e-05,7.7e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,0.00035,0.00035,0.0002,0.49,0.49,0.022,0.95,0.95,0.059,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.5e-07,0,0,0,0,0,0,0,0
7990000,0.98,-0.006,-0.013,0.19,0.00096,0.052,0.15,-3.8e-05,0.048,0.16,-1.7e-05,-5.7e-05,8e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,0.00036,0.00036,0.00018,0.53,0.53,0.022,1.1,1.1,0.058,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0
8090000,0.98,-0.0059,-0.013,0.19,0.0025,0.056,0.15,0.00011,0.053,0.16,-1.7e-05,-5.7e-05,6e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,0.00037,0.00037,0.00018,0.59,0.59,0.021,1.2,1.2,0.058,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0
8190000,0.98,-0.0059,-0.013,0.19,0.0032,0.061,0.15,0.00033,0.058,0.17,-1.7e-05,-5.7e-05,4.4e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,6.1e-06,0.00037,0.00037,0.00017,0.63,0.63,0.02,1.4,1.4,0.057,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0
8290000,0.98,-0.0059,-0.013,0.19,0.0055,0.065,0.14,0.0007,0.064,0.17,-1.7e-05,-5.7e-05,4e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,5.8e-06,0.00038,0.00038,0.00016,0.69,0.69,0.02,1.5,1.5,0.057,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0
8390000,0.98,-0.0059,-0.013,0.19,0.0034,0.067,0.14,0.0011,0.071,0.17,-1.7e-05,-5.7e-05,3.6e-07,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,5.6e-06,0.00039,0.00039,0.00015,0.75,0.75,0.019,1.7,1.7,0.057,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0
8490000,0.98,-0.0058,-0.013,0.19,0.0033,0.071,0.13,0.0014,0.076,0.16,-1.7e-05,-5.7e-05,5.1e-07,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,5.4e-06,0.0004,0.0004,0.00015,0.81,0.81,0.019,1.9,1.9,0.056,1.1e-08,1.1e-08,4.2e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0
8590000,0.98,-0.0057,-0.013,0.19,0.0044,0.074,0.13,0.0017,0.083,0.17,-1.7e-05,-5.7e-05,4.3e-07,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,5.2e-06,0.00041,0.00041,0.00014,0.87,0.88,0.018,2.2,2.2,0.055,1.1e-08,1.1e-08,4.2e-09,4e-06,4e-06,1e-07,0,0,0,0,0,0,0,0
8690000,0.98,-0.0058,-0.013,0.19,0.0045,0.075,0.12,0.002,0.088,0.16,-1.7e-05,-5.7e-05,4.8e-07,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,5.1e-06,0.00042,0.00042,0.00014,0.93,0.93,0.018,2.4,2.4,0.055,1.1e-08,1.1e-08,4.2e-09,4e-06,4e-06,9.9e-08,0,0,0,0,0,0,0,0
8790000,0.98,-0.0057,-0.013,0.19,0.006,0.078,0.12,0.0023,0.096,0.16,-1.7e-05,-5.7e-05,3e-07,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,4.9e-06,0.00043,0.00043,0.00013,1,1,0.017,2.7,2.7,0.054,1.1e-08,1.1e-08,4.1e-09,4e-06,4e-06,9.4e-08,0,0,0,0,0,0,0,0
8890000,0.98,-0.0058,-0.013,0.19,0.006,0.08,0.12,0.0029,0.1,0.17,-1.7e-05,-5.7e-05,4.9e-07,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,4.8e-06,0.00043,0.00043,0.00013,1.1,1.1,0.017,2.9,2.9,0.053,1.1e-08,1.1e-08,4.1e-09,4e-06,4e-06,9e-08,0,0,0,0,0,0,0,0
8990000,0.98,-0.0057,-0.013,0.19,0.0052,0.085,0.12,0.0033,0.11,0.16,-1.7e-05,-5.7e-05,7.5e-07,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,4.7e-06,0.00045,0.00045,0.00013,1.1,1.1,0.016,3.3,3.3,0.053,1.1e-08,1.1e-08,4.1e-09,4e-06,4e-06,8.6e-08,0,0,0,0,0,0,0,0
9090000,0.98,-0.0058,-0.013,0.19,0.0056,0.088,0.11,0.0038,0.11,0.16,-1.7e-05,-5.7e-05,1e-06,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,4.6e-06,0.00045,0.00045,0.00012,1.2,1.2,0.016,3.5,3.5,0.053,1.1e-08,1.1e-08,4.1e-09,4e-06,4e-06,8.2e-08,0,0,0,0,0,0,0,0
9190000,0.98,-0.0058,-0.013,0.19,0.0093,0.09,0.11,0.0045,0.12,0.16,-1.7e-05,-5.7e-05,1.3e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.5e-06,0.00046,0.00046,0.00012,1.3,1.3,0.016,3.9,3.9,0.052,1.1e-08,1.1e-08,4.1e-09,4e-06,4e-06,7.9e-08,0,0,0,0,0,0,0,0
9290000,0.98,-0.0057,-0.013,0.19,0.012,0.091,0.1,0.0053,0.12,0.16,-1.7e-05,-5.7e-05,1.4e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.4e-06,0.00046,0.00046,0.00012,1.3,1.3,0.015,4.2,4.2,0.051,1.1e-08,1.1e-08,4e-09,4e-06,4e-06,7.5e-08,0,0,0,0,0,0,0,0
9390000,0.98,-0.0056,-0.013,0.19,0.012,0.093,0.1,0.0064,0.13,0.16,-1.7e-05,-5.7e-05,1.1e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00047,0.00047,0.00012,1.4,1.4,0.015,4.7,4.7,0.051,1.1e-08,1.1e-08,4e-09,4e-06,4e-06,7.2e-08,0,0,0,0,0,0,0,0
9490000,0.98,-0.0056,-0.013,0.19,0.011,0.092,0.097,0.0071,0.14,0.16,-1.6e-05,-5.7e-05,1.3e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00047,0.00047,0.00011,1.5,1.5,0.014,5,5,0.051,1e-08,1e-08,4e-09,4e-06,4e-06,6.9e-08,0,0,0,0,0,0,0,0
9590000,0.98,-0.0057,-0.013,0.19,0.011,0.093,0.093,0.0079,0.14,0.15,-1.6e-05,-5.7e-05,7.3e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00048,0.00048,0.00011,1.6,1.6,0.014,5.5,5.5,0.05,1e-08,1e-08,3.9e-09,4e-06,4e-06,6.7e-08,0,0,0,0,0,0,0,0
9690000,0.98,-0.0057,-0.013,0.19,0.011,0.092,0.092,0.0085,0.14,0.15,-1.6e-05,-5.7e-05,5.9e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00047,0.00047,0.00011,1.6,1.6,0.014,5.7,5.7,0.05,1e-08,1e-08,3.9e-09,4e-06,4e-06,6.4e-08,0,0,0,0,0,0,0,0
9790000,0.98,-0.0057,-0.013,0.19,0.012,0.095,0.087,0.0093,0.15,0.15,-1.6e-05,-5.7e-05,3.6e-08,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00049,0.00049,0.00011,1.7,1.7,0.014,6.4,6.4,0.049,1e-08,1e-08,3.9e-09,4e-06,4e-06,6.2e-08,0,0,0,0,0,0,0,0
9890000,0.98,-0.0058,-0.012,0.19,0.014,0.091,0.084,0.0098,0.15,0.14,-1.6e-05,-5.7e-05,1.7e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00048,0.00048,0.00011,1.7,1.7,0.013,6.6,6.6,0.049,9.9e-09,9.9e-09,3.8e-09,4e-06,4e-06,5.9e-08,0,0,0,0,0,0,0,0
9990000,0.98,-0.0058,-0.013,0.19,0.016,0.093,0.082,0.011,0.16,0.14,-1.6e-05,-5.7e-05,-2.7e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00049,0.00049,0.00011,1.8,1.8,0.013,7.2,7.2,0.049,9.9e-09,9.9e-09,3.8e-09,4e-06,4e-06,5.7e-08,0,0,0,0,0,0,0,0
10090000,0.98,-0.0058,-0.013,0.19,0.014,0.087,0.079,0.011,0.16,0.14,-1.6e-05,-5.8e-05,-8.1e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00047,0.00047,0.00011,1.8,1.8,0.013,7.4,7.4,0.048,9.6e-09,9.6e-09,3.7e-09,4e-06,4e-06,5.5e-08,0,0,0,0,0,0,0,0
10190000,0.98,-0.0058,-0.013,0.19,0.012,0.089,0.077,0.012,0.16,0.13,-1.6e-05,-5.8e-05,-1.4e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00049,0.00049,0.00011,1.9,1.9,0.012,8.1,8.1,0.048,9.6e-09,9.6e-09,3.7e-09,4e-06,4e-06,5.3e-08,0,0,0,0,0,0,0,0
10290000,0.98,-0.0059,-0.012,0.19,0.012,0.084,0.073,0.012,0.16,0.13,-1.5e-05,-5.8e-05,-1.2e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00047,0.00047,0.00011,1.9,1.9,0.012,8.2,8.2,0.048,9.3e-09,9.3e-09,3.7e-09,4e-06,4e-06,5.1e-08,0,0,0,0,0,0,0,0
10390000,0.98,-0.0059,-0.012,0.19,0.007,0.0043,-0.0063,0.00075,0.00011,0.12,-1.5e-05,-5.8e-05,-9.6e-07,1.5e-09,-1.1e-09,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00048,0.00048,0.00011,0.25,0.25,0.56,0.25,0.25,0.048,9.3e-09,9.3e-09,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10490000,0.98,-0.0058,-0.012,0.19,0.0082,0.0058,-0.01,0.0015,0.00058,0.12,-1.5e-05,-5.8e-05,-1.4e-06,5.9e-09,-4.4e-09,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.0005,0.0005,0.00011,0.26,0.26,0.55,0.26,0.26,0.057,9.3e-09,9.3e-09,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10590000,0.98,-0.0058,-0.012,0.19,-0.0014,0.0037,-0.0056,-0.0012,-0.0055,0.11,-1.5e-05,-5.8e-05,-1e-06,3.1e-06,-1.8e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0005,0.0005,0.0001,0.13,0.13,0.27,0.13,0.13,0.055,9.2e-09,9.2e-09,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10690000,0.98,-0.0057,-0.012,0.19,-0.00039,0.004,-0.012,-0.0013,-0.0051,0.11,-1.5e-05,-5.8e-05,-1.2e-06,3.1e-06,-1.9e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00052,0.00052,0.0001,0.14,0.14,0.26,0.14,0.14,0.065,9.2e-09,9.2e-09,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10790000,0.98,-0.0058,-0.012,0.19,0.0014,0.00059,-0.014,-0.00079,-0.0047,0.1,-1.5e-05,-5.8e-05,-1.2e-06,4.7e-06,3.8e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00051,0.00051,0.0001,0.1,0.1,0.17,0.091,0.091,0.062,9e-09,9e-09,3.4e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10890000,0.98,-0.0058,-0.012,0.19,0.0014,0.0032,-0.025,-0.00064,-0.0046,0.088,-1.5e-05,-5.8e-05,-5.4e-07,4.7e-06,3.8e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00053,0.00053,0.0001,0.12,0.12,0.16,0.098,0.098,0.068,9e-09,9e-09,3.4e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10990000,0.98,-0.0058,-0.013,0.19,0.00095,0.0094,-0.017,-0.00047,-0.0032,0.089,-1.5e-05,-5.8e-05,-7e-07,5.4e-06,5.1e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0005,0.0005,0.0001,0.091,0.091,0.12,0.073,0.073,0.065,8.7e-09,8.7e-09,3.3e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
11090000,0.98,-0.0059,-0.012,0.19,0.0018,0.014,-0.018,-0.00037,-0.0021,0.084,-1.5e-05,-5.8e-05,-1.3e-06,5.4e-06,5.1e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00052,0.00052,0.0001,0.11,0.11,0.11,0.079,0.079,0.069,8.7e-09,8.7e-09,3.3e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
11190000,0.98,-0.0062,-0.013,0.19,0.0035,0.014,-0.0092,0.001,-0.002,0.087,-1.4e-05,-5.8e-05,-1.6e-06,4.2e-06,1.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00047,0.00047,0.0001,0.09,0.09,0.083,0.063,0.063,0.066,8.1e-09,8.1e-09,3.2e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
11290000,0.98,-0.0061,-0.013,0.19,0.0035,0.014,-0.012,0.0013,-0.00055,0.08,-1.4e-05,-5.8e-05,-1.8e-06,4.2e-06,1.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00048,0.00048,0.0001,0.11,0.11,0.077,0.07,0.07,0.069,8.1e-09,8.1e-09,3.2e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
11390000,0.98,-0.0062,-0.012,0.19,0.002,0.013,-0.019,0.00084,-0.0011,0.068,-1.4e-05,-5.8e-05,-1.7e-06,8.5e-06,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00043,0.00043,0.0001,0.091,0.091,0.062,0.057,0.057,0.066,7.5e-09,7.5e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11490000,0.98,-0.0062,-0.012,0.19,0.001,0.013,-0.016,0.00093,0.00026,0.068,-1.4e-05,-5.8e-05,-1.6e-06,8.4e-06,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00044,0.00044,0.0001,0.11,0.11,0.057,0.065,0.065,0.067,7.5e-09,7.5e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11590000,0.98,-0.0064,-0.012,0.19,0.0029,0.011,-0.016,0.0008,-0.0005,0.065,-1.3e-05,-5.9e-05,-1.6e-06,1.1e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00038,0.00038,0.0001,0.091,0.091,0.048,0.054,0.054,0.065,6.9e-09,6.9e-09,3e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11690000,0.98,-0.0064,-0.012,0.19,0.0033,0.014,-0.016,0.0011,0.00073,0.058,-1.3e-05,-5.9e-05,-1.4e-06,1.1e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00039,0.00039,0.0001,0.11,0.11,0.044,0.062,0.062,0.066,6.9e-09,6.9e-09,3e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11790000,0.98,-0.0067,-0.012,0.19,0.0021,0.0092,-0.013,0.00068,-0.0018,0.06,-1.3e-05,-5.9e-05,-7.7e-07,1.6e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00034,0.00034,0.0001,0.088,0.088,0.037,0.052,0.052,0.063,6.4e-09,6.4e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
11890000,0.98,-0.0068,-0.012,0.19,0.0047,0.01,-0.015,0.00096,-0.00089,0.056,-1.3e-05,-5.9e-05,-8.8e-07,1.6e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00035,0.00035,0.0001,0.11,0.11,0.034,0.06,0.06,0.063,6.4e-09,6.4e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
11990000,0.98,-0.0069,-0.012,0.19,0.0077,0.011,-0.015,0.0021,-0.0018,0.051,-1.2e-05,-5.9e-05,-6.7e-07,1.5e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0003,0.0003,0.0001,0.085,0.085,0.03,0.051,0.051,0.061,5.9e-09,5.9e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12090000,0.98,-0.0069,-0.012,0.19,0.0092,0.011,-0.011,0.0029,-0.00079,0.054,-1.2e-05,-5.9e-05,-6.8e-07,1.5e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00031,0.00031,0.0001,0.1,0.1,0.027,0.059,0.059,0.06,5.9e-09,5.9e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12190000,0.98,-0.0067,-0.012,0.19,0.0075,0.01,-0.01,0.0018,0.00035,0.055,-1.3e-05,-5.9e-05,-9.2e-07,1.7e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00027,0.00027,0.0001,0.08,0.08,0.024,0.05,0.05,0.058,5.5e-09,5.5e-09,2.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12290000,0.98,-0.0068,-0.012,0.19,0.0051,0.0095,-0.011,0.0024,0.0014,0.054,-1.3e-05,-5.9e-05,-1.1e-06,1.7e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00028,0.00028,0.0001,0.095,0.095,0.022,0.059,0.059,0.058,5.5e-09,5.5e-09,2.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12390000,0.98,-0.0069,-0.012,0.19,0.0038,0.0065,-0.011,0.0017,0.00048,0.047,-1.2e-05,-6e-05,-1.1e-06,1.9e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00025,0.00025,0.0001,0.076,0.076,0.02,0.05,0.05,0.056,5.2e-09,5.2e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12490000,0.98,-0.0069,-0.012,0.19,0.0037,0.0075,-0.0056,0.0021,0.0012,0.047,-1.2e-05,-6e-05,-1.2e-06,1.9e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00026,0.00026,0.0001,0.089,0.089,0.018,0.058,0.058,0.055,5.2e-09,5.2e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12590000,0.98,-0.0071,-0.012,0.19,0.0075,0.0011,-0.0026,0.0033,-0.0013,0.049,-1.2e-05,-6e-05,-1.2e-06,1.9e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00023,0.00023,0.0001,0.071,0.071,0.017,0.049,0.049,0.054,4.9e-09,4.9e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12690000,0.98,-0.007,-0.012,0.19,0.008,-0.001,-0.0019,0.004,-0.0013,0.049,-1.2e-05,-6e-05,-1.2e-06,1.9e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00024,0.00024,0.0001,0.082,0.082,0.016,0.058,0.058,0.053,4.9e-09,4.9e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12790000,0.98,-0.0073,-0.012,0.19,0.0096,-0.0042,0.0011,0.0041,-0.0044,0.051,-1.1e-05,-6e-05,-3.8e-07,1.9e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00022,0.00022,0.0001,0.067,0.067,0.014,0.049,0.049,0.052,4.6e-09,4.6e-09,2.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12890000,0.98,-0.0073,-0.012,0.19,0.0097,-0.0051,0.0031,0.0051,-0.0049,0.053,-1.1e-05,-6e-05,1.4e-07,1.9e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00023,0.00023,0.0001,0.077,0.077,0.013,0.057,0.057,0.051,4.6e-09,4.6e-09,2.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12990000,0.98,-0.0072,-0.012,0.19,0.0077,-0.003,0.0047,0.0036,-0.0036,0.054,-1.1e-05,-6e-05,6.2e-07,1.9e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.063,0.063,0.012,0.049,0.049,0.05,4.4e-09,4.4e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13090000,0.98,-0.0073,-0.012,0.19,0.0085,-0.0029,0.0034,0.0044,-0.0038,0.052,-1.1e-05,-6e-05,1.3e-06,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00022,0.00022,0.0001,0.072,0.072,0.012,0.057,0.057,0.049,4.4e-09,4.4e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13190000,0.98,-0.0073,-0.012,0.19,0.0036,-0.0045,0.0039,0.00097,-0.0045,0.053,-1.1e-05,-6e-05,1.7e-06,2.1e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.059,0.059,0.011,0.049,0.049,0.047,4.2e-09,4.2e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13290000,0.98,-0.0073,-0.012,0.19,0.0031,-0.0054,0.0023,0.0013,-0.005,0.051,-1.1e-05,-6e-05,1.7e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.067,0.067,0.01,0.057,0.057,0.047,4.2e-09,4.2e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13390000,0.98,-0.0072,-0.012,0.19,0.0023,-0.0034,0.0033,0.00085,-0.0037,0.052,-1.2e-05,-6e-05,1.5e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.056,0.056,0.0097,0.049,0.049,0.046,4e-09,4e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13490000,0.98,-0.0072,-0.012,0.19,0.0027,-0.0016,0.0037,0.0011,-0.0039,0.048,-1.2e-05,-6e-05,1.7e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.064,0.064,0.0093,0.056,0.056,0.045,4e-09,4e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13590000,0.98,-0.0072,-0.012,0.19,0.0072,-0.0018,0.0063,0.004,-0.0032,0.047,-1.1e-05,-6e-05,1.5e-06,2.3e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.053,0.053,0.0089,0.048,0.048,0.044,3.8e-09,3.8e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13690000,0.98,-0.0071,-0.012,0.19,0.0071,-0.0032,0.0074,0.0047,-0.0034,0.049,-1.1e-05,-6e-05,1.9e-06,2.2e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.06,0.06,0.0085,0.056,0.056,0.044,3.8e-09,3.8e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13790000,0.98,-0.0071,-0.012,0.19,0.014,0.00098,0.0084,0.0083,-0.00094,0.049,-1.2e-05,-5.9e-05,1.7e-06,2.5e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.051,0.051,0.0082,0.048,0.048,0.043,3.6e-09,3.6e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13890000,0.98,-0.007,-0.012,0.19,0.015,0.0018,0.01,0.0097,-0.00079,0.051,-1.2e-05,-5.9e-05,2.2e-06,2.5e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.057,0.057,0.008,0.056,0.056,0.042,3.6e-09,3.6e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0019,0.01,0.0073,-0.0023,0.051,-1.1e-05,-6e-05,2.6e-06,2.3e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.048,0.048,0.0077,0.048,0.048,0.041,3.4e-09,3.5e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14090000,0.98,-0.0071,-0.012,0.19,0.012,-0.0024,0.012,0.0088,-0.0023,0.047,-1.1e-05,-6e-05,1.6e-06,2.4e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.055,0.055,0.0076,0.055,0.055,0.041,3.4e-09,3.5e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14190000,0.98,-0.007,-0.011,0.19,0.0095,-0.0011,0.013,0.008,-0.0017,0.048,-1.2e-05,-6e-05,1.2e-06,2.5e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-09,3.3e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14290000,0.98,-0.007,-0.011,0.19,0.011,-0.0011,0.012,0.0089,-0.0019,0.052,-1.2e-05,-6e-05,1.2e-06,2.4e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.053,0.053,0.0073,0.055,0.055,0.04,3.3e-09,3.3e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14390000,0.98,-0.0071,-0.011,0.19,0.011,-0.0041,0.014,0.0084,-0.0031,0.057,-1.1e-05,-6e-05,1.5e-06,2.3e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,0.0001,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-09,3.1e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14490000,0.98,-0.0072,-0.011,0.19,0.0095,-0.0038,0.019,0.0094,-0.0035,0.06,-1.1e-05,-6e-05,1e-06,2.2e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-09,3.1e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14590000,0.98,-0.0072,-0.011,0.19,0.0074,-0.0039,0.017,0.0058,-0.0041,0.056,-1.2e-05,-6e-05,9.3e-07,2e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,0.0001,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-09,2.9e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14690000,0.98,-0.0072,-0.011,0.19,0.0065,-0.0038,0.018,0.0065,-0.0045,0.057,-1.2e-05,-6e-05,1.1e-06,2.1e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-09,2.9e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14790000,0.98,-0.0071,-0.011,0.19,0.0082,0.0031,0.019,0.0052,0.00085,0.06,-1.2e-05,-6e-05,1.7e-06,2.1e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-09,2.7e-09,1.6e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
14890000,0.98,-0.0071,-0.011,0.19,0.0068,0.00084,0.024,0.0059,0.0011,0.062,-1.2e-05,-6e-05,2.1e-06,2.1e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.048,0.048,0.007,0.054,0.054,0.037,2.7e-09,2.7e-09,1.5e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
14990000,0.98,-0.0072,-0.011,0.19,0.0056,-0.00083,0.027,0.0047,-0.00061,0.064,-1.2e-05,-6.1e-05,2.3e-06,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-09,2.6e-09,1.5e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15090000,0.98,-0.0072,-0.011,0.19,0.0056,0.00034,0.032,0.0052,-0.00067,0.068,-1.2e-05,-6.1e-05,2.3e-06,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00019,0.00019,9.8e-05,0.047,0.047,0.007,0.054,0.054,0.036,2.6e-09,2.6e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15190000,0.98,-0.0073,-0.011,0.19,0.0038,-0.00077,0.033,0.0041,-0.00066,0.07,-1.2e-05,-6.1e-05,2.1e-06,1.9e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.8e-05,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-09,2.4e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15290000,0.98,-0.0074,-0.011,0.19,0.0043,-0.0018,0.033,0.0046,-0.00076,0.067,-1.2e-05,-6.1e-05,2.5e-06,2.2e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00019,0.00019,9.7e-05,0.046,0.046,0.0071,0.054,0.054,0.035,2.4e-09,2.4e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15390000,0.98,-0.0075,-0.011,0.19,0.0046,0.00058,0.034,0.0037,-0.00052,0.068,-1.2e-05,-6.1e-05,2.5e-06,2.2e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.7e-05,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-09,2.2e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15490000,0.98,-0.0075,-0.011,0.19,0.0039,-0.0019,0.034,0.0041,-0.00056,0.07,-1.2e-05,-6.1e-05,2.5e-06,2.3e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00019,0.00019,9.7e-05,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-09,2.2e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15590000,0.98,-0.0077,-0.011,0.19,0.0075,-0.0058,0.034,0.0061,-0.0046,0.069,-1.1e-05,-6.1e-05,2.7e-06,2.7e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-09,2.1e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15690000,0.98,-0.0077,-0.011,0.19,0.0092,-0.0088,0.036,0.007,-0.0053,0.071,-1.1e-05,-6.1e-05,3.1e-06,2.7e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-09,2.1e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15790000,0.98,-0.0077,-0.011,0.19,0.0058,-0.0081,0.036,0.0054,-0.0041,0.073,-1.2e-05,-6.1e-05,3.6e-06,2.6e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00017,9.5e-05,0.039,0.039,0.0073,0.046,0.046,0.034,1.9e-09,1.9e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
15890000,0.98,-0.0077,-0.011,0.19,0.0046,-0.0065,0.037,0.0059,-0.0049,0.073,-1.2e-05,-6.1e-05,3.2e-06,2.9e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00018,9.5e-05,0.044,0.044,0.0074,0.053,0.053,0.034,1.9e-09,1.9e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
15990000,0.98,-0.0075,-0.011,0.19,0.0027,-0.0051,0.035,0.0047,-0.0038,0.073,-1.2e-05,-6.1e-05,3.2e-06,3.1e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.5e-05,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-09,1.7e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16090000,0.98,-0.0075,-0.011,0.19,0.002,-0.0063,0.033,0.0049,-0.0043,0.074,-1.2e-05,-6.1e-05,2.9e-06,3.3e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00018,9.4e-05,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-09,1.7e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16190000,0.98,-0.0074,-0.011,0.19,-0.0019,-0.004,0.032,0.0026,-0.0032,0.071,-1.2e-05,-6.1e-05,2.7e-06,3.4e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.4e-05,0.038,0.038,0.0076,0.046,0.046,0.034,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16290000,0.98,-0.0075,-0.011,0.19,-0.0016,-0.0054,0.033,0.0024,-0.0037,0.074,-1.2e-05,-6.1e-05,2.8e-06,3.5e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00017,0.00017,9.3e-05,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16390000,0.98,-0.0074,-0.011,0.19,0.00091,-0.0048,0.033,0.0035,-0.0028,0.074,-1.2e-05,-6.1e-05,3.1e-06,4.1e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.3e-05,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-09,1.5e-09,1.1e-09,3.2e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16490000,0.98,-0.0075,-0.011,0.19,0.0028,-0.0063,0.036,0.0037,-0.0034,0.079,-1.2e-05,-6.1e-05,3e-06,4e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00017,0.00017,9.3e-05,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-09,1.5e-09,1.1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16590000,0.98,-0.0075,-0.011,0.19,0.007,-0.0064,0.04,0.0032,-0.0027,0.08,-1.2e-05,-6.1e-05,3e-06,4.2e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.2e-05,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-09,1.3e-09,1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16690000,0.98,-0.0076,-0.011,0.19,0.0084,-0.011,0.041,0.004,-0.0035,0.081,-1.2e-05,-6.1e-05,3.1e-06,4.3e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.1e-05,0.042,0.042,0.008,0.052,0.052,0.034,1.3e-09,1.3e-09,1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16790000,0.98,-0.0074,-0.011,0.19,0.0093,-0.0099,0.04,0.0031,-0.0025,0.082,-1.3e-05,-6.1e-05,3.3e-06,4.5e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00015,9.1e-05,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-09,1.2e-09,9.9e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16890000,0.98,-0.0074,-0.011,0.19,0.0083,-0.01,0.041,0.004,-0.0035,0.081,-1.3e-05,-6.1e-05,3.7e-06,4.8e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00016,0.00016,9.1e-05,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-09,1.2e-09,9.7e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16990000,0.98,-0.0074,-0.011,0.19,0.0081,-0.0097,0.041,0.0039,-0.0026,0.08,-1.3e-05,-6.1e-05,3.8e-06,5.4e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,9e-05,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-09,1.1e-09,9.5e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17090000,0.98,-0.0075,-0.011,0.19,0.0096,-0.012,0.041,0.0048,-0.0038,0.08,-1.3e-05,-6.1e-05,3.7e-06,5.7e-05,1.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.04,0.04,0.0083,0.052,0.052,0.034,1.1e-09,1.1e-09,9.3e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17190000,0.98,-0.0076,-0.011,0.19,0.0085,-0.018,0.043,0.0032,-0.0073,0.084,-1.3e-05,-6.1e-05,3.2e-06,5.6e-05,1.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-10,9.9e-10,9.1e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17290000,0.98,-0.0076,-0.011,0.19,0.0094,-0.018,0.043,0.0042,-0.0091,0.084,-1.3e-05,-6.1e-05,2.9e-06,5.9e-05,1.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-10,9.9e-10,8.9e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17390000,0.98,-0.0075,-0.011,0.19,0.0062,-0.018,0.042,0.0056,-0.0057,0.084,-1.3e-05,-6e-05,3.2e-06,6.7e-05,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.8e-05,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-10,8.9e-10,8.7e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17490000,0.98,-0.0075,-0.011,0.19,0.0043,-0.018,0.042,0.0061,-0.0075,0.087,-1.3e-05,-6e-05,3.1e-06,6.9e-05,1.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00015,0.00014,8.8e-05,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-10,8.9e-10,8.5e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17590000,0.98,-0.0074,-0.011,0.19,0.00051,-0.014,0.042,0.0023,-0.0056,0.085,-1.4e-05,-6.1e-05,3.1e-06,6.9e-05,2.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-10,8.1e-10,8.3e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17690000,0.98,-0.0075,-0.011,0.19,-0.00045,-0.015,0.043,0.0024,-0.0071,0.088,-1.4e-05,-6.1e-05,3.1e-06,6.9e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-10,8.1e-10,8.2e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17790000,0.98,-0.0074,-0.011,0.19,0.0023,-0.013,0.044,0.0034,-0.006,0.094,-1.4e-05,-6e-05,3.1e-06,7.4e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00013,0.00013,8.7e-05,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-10,7.3e-10,8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17890000,0.98,-0.0074,-0.011,0.19,0.0044,-0.015,0.044,0.0038,-0.0074,0.099,-1.4e-05,-6e-05,3.2e-06,7.3e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.6e-05,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-10,7.3e-10,7.8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17990000,0.98,-0.0071,-0.011,0.19,0.0038,-0.0085,0.043,0.003,-0.0017,0.099,-1.4e-05,-6e-05,3.2e-06,7.8e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-10,6.6e-10,7.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18090000,0.98,-0.0072,-0.011,0.19,0.0033,-0.009,0.043,0.0035,-0.0027,0.098,-1.4e-05,-6e-05,3.1e-06,8.2e-05,3.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-10,6.6e-10,7.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18190000,0.98,-0.0073,-0.011,0.19,0.0034,-0.0081,0.043,0.0041,-0.0019,0.096,-1.5e-05,-6e-05,3.6e-06,8.8e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.032,0.032,0.0086,0.045,0.045,0.035,6e-10,6e-10,7.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18290000,0.98,-0.0073,-0.011,0.19,0.0043,-0.0085,0.042,0.0044,-0.0028,0.095,-1.4e-05,-6e-05,3.6e-06,9.1e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.4e-05,0.036,0.036,0.0087,0.051,0.051,0.035,6e-10,6e-10,7.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18390000,0.98,-0.0072,-0.011,0.19,0.0053,-0.0073,0.041,0.0061,-0.0021,0.095,-1.5e-05,-6e-05,3.4e-06,9.8e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00012,0.00012,8.4e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-10,5.4e-10,7.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18490000,0.98,-0.0073,-0.011,0.19,0.008,-0.0073,0.041,0.0069,-0.0029,0.097,-1.5e-05,-6e-05,3.6e-06,9.9e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00012,8.3e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-10,5.4e-10,6.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18590000,0.98,-0.0071,-0.011,0.19,0.0064,-0.0067,0.041,0.0055,-0.0022,0.099,-1.5e-05,-6e-05,3.3e-06,9.8e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.3e-05,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-10,4.9e-10,6.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18690000,0.98,-0.0071,-0.011,0.19,0.0065,-0.0056,0.039,0.0062,-0.0028,0.098,-1.5e-05,-6e-05,3.5e-06,0.0001,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-10,4.9e-10,6.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18790000,0.98,-0.007,-0.011,0.19,0.0055,-0.0054,0.038,0.0062,-0.0023,0.096,-1.5e-05,-6e-05,3.4e-06,0.00011,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-10,4.4e-10,6.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18890000,0.98,-0.007,-0.011,0.19,0.0042,-0.005,0.036,0.0067,-0.0029,0.093,-1.5e-05,-6e-05,3.3e-06,0.00011,1.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-10,4.4e-10,6.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18990000,0.98,-0.007,-0.011,0.19,0.0026,-0.0052,0.037,0.0055,-0.0023,0.096,-1.5e-05,-6e-05,3.2e-06,0.00011,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00011,8.1e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-10,4e-10,6.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19090000,0.98,-0.0071,-0.011,0.19,0.00058,-0.0056,0.037,0.0058,-0.0028,0.093,-1.5e-05,-6e-05,3.4e-06,0.00011,1.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.1e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-10,4e-10,6.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19190000,0.98,-0.007,-0.011,0.19,-0.00089,-0.0053,0.037,0.0048,-0.0023,0.092,-1.5e-05,-6e-05,3e-06,0.00012,1.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,8e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-10,3.7e-10,6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19290000,0.98,-0.0069,-0.011,0.19,-0.0017,-0.0051,0.037,0.0047,-0.0028,0.091,-1.5e-05,-6e-05,2.9e-06,0.00012,1.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,8e-05,0.031,0.031,0.0087,0.05,0.05,0.036,3.7e-10,3.7e-10,5.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19390000,0.98,-0.007,-0.011,0.19,-0.0022,-0.0017,0.038,0.0041,-0.00095,0.09,-1.5e-05,-6e-05,2.8e-06,0.00012,1.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,8e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-10,3.3e-10,5.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19490000,0.98,-0.0071,-0.011,0.19,-0.003,-0.0017,0.038,0.0038,-0.0011,0.09,-1.5e-05,-6e-05,2.5e-06,0.00012,1.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.9e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-10,3.3e-10,5.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19590000,0.98,-0.007,-0.011,0.19,-0.0041,-0.0046,0.039,0.0044,-0.0022,0.09,-1.5e-05,-6e-05,2.4e-06,0.00013,9.6e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.9e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-10,3e-10,5.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19690000,0.98,-0.007,-0.011,0.19,-0.0057,-0.0032,0.038,0.0039,-0.0026,0.09,-1.5e-05,-6e-05,2.6e-06,0.00013,7.7e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.8e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-10,3e-10,5.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19790000,0.98,-0.0071,-0.011,0.19,-0.0057,-0.0018,0.036,0.0064,-0.0021,0.085,-1.5e-05,-6e-05,2.4e-06,0.00014,4e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.00011,0.0001,7.8e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-10,2.8e-10,5.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19890000,0.98,-0.0072,-0.011,0.19,-0.0058,-0.0015,0.036,0.0058,-0.0022,0.084,-1.5e-05,-6e-05,2.2e-06,0.00014,2.2e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.00011,0.00011,7.7e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-10,2.8e-10,5.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19990000,0.98,-0.0072,-0.011,0.19,-0.0054,-0.0015,0.033,0.0061,-0.00071,0.081,-1.5e-05,-5.9e-05,2.3e-06,0.00014,2.9e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.7e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-10,2.5e-10,5.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20090000,0.98,-0.0072,-0.011,0.19,-0.0049,-0.0037,0.033,0.0056,-0.00098,0.084,-1.5e-05,-5.9e-05,2.2e-06,0.00014,4.2e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.7e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-10,2.5e-10,5.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20190000,0.98,-0.0072,-0.011,0.19,-0.0039,-0.0012,0.034,0.0066,-0.00071,0.084,-1.5e-05,-5.9e-05,2e-06,0.00015,-8.7e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-10,2.3e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20290000,0.98,-0.0072,-0.011,0.19,-0.0071,-0.0022,0.034,0.0061,-0.00082,0.085,-1.5e-05,-5.9e-05,1.9e-06,0.00015,-1.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-10,2.3e-10,4.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20390000,0.98,-0.0072,-0.011,0.19,-0.0077,-0.0011,0.034,0.0069,-0.00058,0.086,-1.5e-05,-5.9e-05,2.1e-06,0.00015,-3.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,9.9e-05,7.5e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-10,2.1e-10,4.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20490000,0.98,-0.0072,-0.011,0.19,-0.012,-0.002,0.033,0.0059,-0.00072,0.084,-1.5e-05,-5.9e-05,2e-06,0.00015,-5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,0.0001,7.5e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-10,2.1e-10,4.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20590000,0.98,-0.0071,-0.011,0.19,-0.011,-0.003,0.033,0.007,-0.0006,0.082,-1.5e-05,-5.9e-05,2.3e-06,0.00016,-7.6e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.9e-05,9.8e-05,7.4e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-10,2e-10,4.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20690000,0.98,-0.0071,-0.011,0.19,-0.013,-0.0017,0.033,0.0058,-0.00079,0.082,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-8.3e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,9.8e-05,7.4e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-10,2e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20790000,0.98,-0.0065,-0.011,0.19,-0.016,0.00077,0.018,0.0049,-0.00063,0.081,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.8e-05,9.6e-05,7.4e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-10,1.8e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20890000,0.98,0.0026,-0.0074,0.19,-0.021,0.013,-0.1,0.003,8.9e-05,0.074,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-1.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.8e-05,9.7e-05,7.3e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-10,1.8e-10,4.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20990000,0.98,0.006,-0.004,0.19,-0.032,0.031,-0.24,0.0023,0.00069,0.059,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-1.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.6e-05,9.5e-05,7.3e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-10,1.7e-10,4.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21090000,0.98,0.0044,-0.0043,0.19,-0.045,0.047,-0.36,-0.0016,0.0046,0.029,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-1.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.7e-05,9.5e-05,7.3e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-10,1.7e-10,4.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21190000,0.98,0.0015,-0.006,0.19,-0.049,0.051,-0.49,-0.0012,0.0036,-0.0072,-1.4e-05,-5.9e-05,2.1e-06,0.00016,-2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.4e-05,9.3e-05,7.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-10,1.6e-10,4.2e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21290000,0.98,-0.00066,-0.0073,0.19,-0.049,0.054,-0.62,-0.006,0.0089,-0.066,-1.4e-05,-5.9e-05,1.9e-06,0.00016,-2.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.5e-05,9.4e-05,7.2e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-10,1.6e-10,4.1e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21390000,0.98,-0.0021,-0.008,0.19,-0.044,0.05,-0.74,-0.0049,0.011,-0.13,-1.4e-05,-5.9e-05,1.9e-06,0.00017,-2.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.3e-05,9.1e-05,7.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-10,1.4e-10,4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21490000,0.98,-0.0029,-0.0084,0.19,-0.04,0.047,-0.88,-0.0091,0.016,-0.22,-1.4e-05,-5.9e-05,2e-06,0.00017,-2.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.3e-05,9.2e-05,7.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-10,1.4e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21590000,0.98,-0.0034,-0.0084,0.19,-0.031,0.043,-1,-0.0078,0.017,-0.31,-1.4e-05,-5.9e-05,2.1e-06,0.00017,-2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.1e-05,9e-05,7.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-10,1.3e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21690000,0.98,-0.0038,-0.0083,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.42,-1.4e-05,-5.9e-05,2.2e-06,0.00017,-2.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.1e-05,9e-05,7e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-10,1.3e-10,3.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21790000,0.98,-0.0041,-0.0085,0.19,-0.021,0.033,-1.3,-0.0036,0.018,-0.54,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.9e-05,8.8e-05,7e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-10,1.2e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21890000,0.98,-0.0044,-0.0087,0.19,-0.017,0.028,-1.4,-0.0055,0.021,-0.68,-1.4e-05,-5.8e-05,2.3e-06,0.00018,-3.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.9e-05,8.8e-05,7e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-10,1.2e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21990000,0.98,-0.0051,-0.0089,0.19,-0.014,0.023,-1.4,-0.00017,0.017,-0.82,-1.4e-05,-5.8e-05,2.4e-06,0.00017,-3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.7e-05,8.6e-05,6.9e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-10,1.1e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22090000,0.98,-0.0059,-0.0098,0.19,-0.011,0.019,-1.3,-0.0014,0.019,-0.96,-1.4e-05,-5.8e-05,2.6e-06,0.00018,-3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.7e-05,8.6e-05,6.9e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-10,1.1e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22190000,0.98,-0.0063,-0.01,0.19,-0.0031,0.013,-1.4,0.0062,0.013,-1.1,-1.4e-05,-5.8e-05,2.7e-06,0.00018,-3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.5e-05,8.4e-05,6.9e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-10,1.1e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22290000,0.98,-0.007,-0.01,0.19,0.002,0.0078,-1.4,0.0062,0.014,-1.2,-1.4e-05,-5.8e-05,2.6e-06,0.00018,-3.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.6e-05,8.4e-05,6.8e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-10,1.1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22390000,0.98,-0.0074,-0.01,0.19,0.007,-0.0018,-1.4,0.013,0.0042,-1.4,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-3.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.4e-05,8.3e-05,6.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1e-10,1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22490000,0.98,-0.0076,-0.011,0.19,0.011,-0.0077,-1.4,0.014,0.0037,-1.5,-1.4e-05,-5.8e-05,2.3e-06,0.00018,-3.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.4e-05,8.3e-05,6.8e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-10,1e-10,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22590000,0.98,-0.0075,-0.012,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.2e-05,8.1e-05,6.7e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-11,9.4e-11,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22690000,0.98,-0.0074,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.8,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-4.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.3e-05,8.2e-05,6.7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-11,9.4e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22790000,0.98,-0.0074,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-1.4e-05,-5.8e-05,2.2e-06,0.00019,-4.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.1e-05,8e-05,6.7e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-11,8.9e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22890000,0.98,-0.0076,-0.013,0.19,0.032,-0.034,-1.4,0.041,-0.02,-2.1,-1.4e-05,-5.8e-05,2.4e-06,0.00019,-4.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8.1e-05,8e-05,6.6e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-11,8.9e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22990000,0.98,-0.0075,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-1.4e-05,-5.8e-05,2.6e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8e-05,7.9e-05,6.6e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-11,8.4e-11,3.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23090000,0.98,-0.0076,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.4,-1.4e-05,-5.8e-05,2.6e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8e-05,7.9e-05,6.6e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-11,8.4e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23190000,0.98,-0.0076,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.5,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.9e-05,7.8e-05,6.5e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-11,7.9e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23290000,0.98,-0.0081,-0.014,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.7,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.9e-05,7.8e-05,6.5e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8e-11,8e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23390000,0.98,-0.008,-0.014,0.18,0.057,-0.053,-1.4,0.082,-0.055,-2.8,-1.4e-05,-5.8e-05,2.3e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.5e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-11,7.6e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23490000,0.98,-0.0081,-0.014,0.18,0.061,-0.055,-1.4,0.088,-0.061,-3,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.9e-05,7.8e-05,6.4e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-11,7.6e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23590000,0.98,-0.0083,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.1,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.4e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-11,7.2e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23690000,0.98,-0.009,-0.015,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-1.4e-05,-5.8e-05,2.6e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.4e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-11,7.2e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.95,0.11,-0.081,-3.4,-1.4e-05,-5.8e-05,2.8e-06,0.0002,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-11,6.9e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23890000,0.98,-0.014,-0.021,0.18,0.052,-0.058,-0.52,0.12,-0.087,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.0002,-4.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-11,6.9e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23990000,0.98,-0.016,-0.024,0.18,0.054,-0.057,-0.14,0.13,-0.089,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.00021,-5.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-11,6.6e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24090000,0.98,-0.016,-0.023,0.18,0.06,-0.066,0.097,0.13,-0.095,-3.5,-1.4e-05,-5.8e-05,2.7e-06,0.00021,-5.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-11,6.6e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24190000,0.98,-0.013,-0.019,0.18,0.071,-0.071,0.083,0.14,-0.1,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.00021,-6.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.2e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-11,6.3e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24290000,0.98,-0.011,-0.016,0.18,0.075,-0.074,0.061,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.00021,-6.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.2e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-11,6.3e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24390000,0.98,-0.0097,-0.015,0.18,0.068,-0.069,0.077,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,3e-06,0.00022,-6.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.2e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-11,6.1e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24490000,0.98,-0.01,-0.015,0.18,0.064,-0.066,0.075,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00022,-7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.016,0.016,0.0081,0.044,0.044,0.035,6.1e-11,6.1e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24590000,0.98,-0.011,-0.015,0.18,0.061,-0.061,0.07,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00021,-7.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-11,5.9e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24690000,0.98,-0.011,-0.015,0.18,0.058,-0.061,0.069,0.17,-0.12,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00021,-7.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-11,5.9e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24790000,0.98,-0.011,-0.014,0.18,0.055,-0.058,0.061,0.17,-0.11,-3.5,-1.5e-05,-5.8e-05,3.2e-06,0.00021,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-11,5.7e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24890000,0.98,-0.011,-0.014,0.18,0.054,-0.062,0.05,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00022,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-11,5.7e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24990000,0.98,-0.011,-0.013,0.18,0.045,-0.057,0.042,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00021,-8.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-11,5.5e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25090000,0.98,-0.011,-0.013,0.18,0.041,-0.057,0.04,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.2e-06,0.00021,-9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.6e-05,6e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-11,5.5e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.039,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.1e-06,0.00021,-9.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.6e-05,5.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-11,5.3e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25290000,0.98,-0.011,-0.013,0.18,0.032,-0.051,0.034,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3e-06,0.00021,-9.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-11,5.3e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.032,0.18,-0.1,-3.5,-1.5e-05,-5.8e-05,2.9e-06,0.00021,-0.0001,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-11,5.1e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25490000,0.98,-0.012,-0.012,0.18,0.019,-0.044,0.031,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,2.9e-06,0.00021,-0.0001,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.1e-11,5.1e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25590000,0.98,-0.012,-0.012,0.18,0.014,-0.04,0.032,0.18,-0.098,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-11,5e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25690000,0.98,-0.011,-0.012,0.18,0.013,-0.039,0.021,0.18,-0.1,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-11,5e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25790000,0.98,-0.011,-0.011,0.18,0.0018,-0.03,0.021,0.17,-0.092,-3.5,-1.6e-05,-5.8e-05,2.7e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-11,4.8e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25890000,0.98,-0.011,-0.011,0.18,-0.004,-0.028,0.023,0.17,-0.095,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-11,4.8e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25990000,0.98,-0.011,-0.011,0.18,-0.013,-0.021,0.016,0.16,-0.086,-3.5,-1.6e-05,-5.8e-05,2.4e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26090000,0.98,-0.011,-0.011,0.18,-0.018,-0.021,0.015,0.16,-0.088,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26190000,0.98,-0.011,-0.012,0.18,-0.024,-0.015,0.0095,0.15,-0.081,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26290000,0.98,-0.011,-0.012,0.18,-0.026,-0.013,0.0037,0.15,-0.082,-3.5,-1.6e-05,-5.8e-05,2.4e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26390000,0.98,-0.01,-0.012,0.18,-0.032,-0.0061,0.0075,0.13,-0.074,-3.5,-1.6e-05,-5.8e-05,2.3e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.7e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-11,4.4e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26490000,0.98,-0.0098,-0.012,0.18,-0.035,-0.0029,0.017,0.13,-0.075,-3.5,-1.6e-05,-5.8e-05,2.2e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-11,4.5e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26590000,0.98,-0.0092,-0.012,0.18,-0.036,0.005,0.017,0.12,-0.068,-3.5,-1.6e-05,-5.8e-05,2.1e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26690000,0.98,-0.0091,-0.012,0.18,-0.038,0.01,0.015,0.12,-0.067,-3.5,-1.6e-05,-5.8e-05,1.9e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26790000,0.98,-0.0089,-0.011,0.18,-0.045,0.014,0.014,0.1,-0.062,-3.5,-1.6e-05,-5.8e-05,1.8e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26890000,0.98,-0.0082,-0.011,0.18,-0.051,0.017,0.0095,0.1,-0.06,-3.5,-1.6e-05,-5.8e-05,1.8e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26990000,0.98,-0.0077,-0.012,0.18,-0.058,0.023,0.0086,0.087,-0.054,-3.5,-1.6e-05,-5.8e-05,1.7e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27090000,0.98,-0.0075,-0.012,0.18,-0.06,0.03,0.011,0.082,-0.051,-3.5,-1.6e-05,-5.8e-05,1.7e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-11,4.1e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27190000,0.98,-0.0076,-0.012,0.18,-0.066,0.036,0.013,0.071,-0.045,-3.5,-1.6e-05,-5.8e-05,1.6e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27290000,0.98,-0.0077,-0.013,0.18,-0.073,0.042,0.13,0.064,-0.041,-3.5,-1.6e-05,-5.8e-05,1.6e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,7.9e-05,7.8e-05,5.4e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27390000,0.98,-0.0091,-0.015,0.18,-0.078,0.048,0.45,0.055,-0.034,-3.5,-1.6e-05,-5.8e-05,1.5e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,7.9e-05,7.8e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27490000,0.98,-0.01,-0.017,0.18,-0.082,0.053,0.76,0.046,-0.029,-3.4,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.8e-05,5.4e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27590000,0.98,-0.01,-0.016,0.18,-0.076,0.056,0.86,0.038,-0.025,-3.4,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00014,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.8e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27690000,0.98,-0.0091,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00014,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27790000,0.98,-0.0078,-0.012,0.18,-0.071,0.05,0.75,0.025,-0.017,-3.2,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-11,3.8e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27890000,0.98,-0.0074,-0.012,0.18,-0.078,0.057,0.79,0.017,-0.012,-3.1,-1.6e-05,-5.8e-05,1.2e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-11,3.8e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27990000,0.98,-0.0079,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.01,-3.1,-1.6e-05,-5.8e-05,1.2e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-11,3.7e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28090000,0.98,-0.0082,-0.012,0.18,-0.082,0.059,0.78,0.0041,-0.0044,-3,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28190000,0.98,-0.0076,-0.012,0.18,-0.082,0.056,0.79,-0.0024,-0.004,-2.9,-1.6e-05,-5.8e-05,1.2e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28290000,0.98,-0.0071,-0.013,0.18,-0.088,0.059,0.79,-0.011,0.0017,-2.8,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28390000,0.98,-0.0071,-0.013,0.18,-0.088,0.062,0.79,-0.015,0.0047,-2.8,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28490000,0.98,-0.0074,-0.014,0.18,-0.09,0.066,0.79,-0.024,0.011,-2.7,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28590000,0.98,-0.0075,-0.014,0.18,-0.083,0.061,0.79,-0.028,0.0087,-2.6,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28690000,0.98,-0.0072,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28790000,0.98,-0.0066,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.017,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28890000,0.98,-0.0064,-0.013,0.18,-0.084,0.064,0.79,-0.046,0.023,-2.4,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28990000,0.98,-0.0062,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.3,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29090000,0.98,-0.006,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29190000,0.98,-0.006,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29290000,0.98,-0.0062,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.034,-2.1,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29390000,0.98,-0.0067,-0.013,0.18,-0.075,0.066,0.78,-0.058,0.034,-2,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29490000,0.98,-0.0067,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-1.5e-05,-5.8e-05,1.5e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29590000,0.98,-0.0066,-0.012,0.18,-0.074,0.064,0.79,-0.062,0.04,-1.9,-1.5e-05,-5.8e-05,1.6e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29690000,0.98,-0.0067,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.047,-1.8,-1.5e-05,-5.8e-05,1.7e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29790000,0.98,-0.0065,-0.013,0.18,-0.073,0.056,0.78,-0.065,0.044,-1.7,-1.4e-05,-5.8e-05,1.8e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29890000,0.98,-0.006,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-1.4e-05,-5.8e-05,1.9e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29990000,0.98,-0.0061,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.045,-1.6,-1.4e-05,-5.8e-05,1.9e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30090000,0.98,-0.0063,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.5,-1.4e-05,-5.8e-05,1.7e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
6590000,0.98,-0.0067,-0.013,0.19,0.00045,0.015,0.19,0.0017,0.0063,0.088,-1.7e-05,-5.6e-05,4.7e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,5.5e-05,0.0003,0.0003,0.0015,0.2,0.2,0.035,0.12,0.12,0.068,1.2e-08,1.2e-08,1e-06,4e-06,4e-06,3.2e-07,0,0,0,0,0,0,0,0
6690000,0.98,-0.0066,-0.013,0.19,-0.0022,0.017,0.19,0.0016,0.0079,0.097,-1.7e-05,-5.6e-05,-3.6e-06,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,3.6e-05,0.0003,0.0003,0.00099,0.21,0.21,0.033,0.15,0.15,0.067,1.2e-08,1.2e-08,9.9e-07,4e-06,4e-06,3e-07,0,0,0,0,0,0,0,0
6790000,0.98,-0.0066,-0.013,0.19,-0.00042,0.019,0.19,0.0014,0.0096,0.11,-1.7e-05,-5.6e-05,-5.2e-06,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,2.9e-05,0.0003,0.0003,0.0008,0.21,0.21,0.032,0.18,0.18,0.067,1.2e-08,1.2e-08,9.8e-07,4e-06,4e-06,2.8e-07,0,0,0,0,0,0,0,0
6890000,0.98,-0.0064,-0.013,0.19,-0.00087,0.019,0.19,0.0013,0.011,0.12,-1.7e-05,-5.6e-05,-4.8e-06,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,2.5e-05,0.0003,0.0003,0.00069,0.22,0.22,0.031,0.22,0.22,0.066,1.2e-08,1.2e-08,9.4e-07,4e-06,4e-06,2.6e-07,0,0,0,0,0,0,0,0
6990000,0.98,-0.0064,-0.013,0.19,-0.00089,0.02,0.19,0.0011,0.013,0.12,-1.7e-05,-5.6e-05,-2.7e-06,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,2.3e-05,0.0003,0.0003,0.00064,0.23,0.23,0.03,0.26,0.26,0.065,1.2e-08,1.2e-08,8.9e-07,4e-06,4e-06,2.5e-07,0,0,0,0,0,0,0,0
7090000,0.98,-0.0063,-0.013,0.19,-0.0018,0.025,0.18,0.00095,0.016,0.13,-1.7e-05,-5.6e-05,1.1e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,2.3e-05,0.00031,0.00031,0.00063,0.25,0.25,0.029,0.31,0.31,0.065,1.2e-08,1.2e-08,8.4e-07,4e-06,4e-06,2.3e-07,0,0,0,0,0,0,0,0
7190000,0.98,-0.0062,-0.013,0.19,-0.0022,0.027,0.18,0.00066,0.018,0.13,-1.7e-05,-5.6e-05,-5.5e-06,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,2.3e-05,0.00031,0.00031,0.00062,0.27,0.27,0.028,0.36,0.36,0.064,1.2e-08,1.2e-08,7.7e-07,4e-06,4e-06,2.2e-07,0,0,0,0,0,0,0,0
7290000,0.98,-0.0062,-0.013,0.19,-0.0013,0.031,0.18,0.00039,0.021,0.14,-1.7e-05,-5.6e-05,-1.3e-06,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,2.3e-05,0.00032,0.00031,0.00062,0.29,0.29,0.027,0.42,0.42,0.063,1.2e-08,1.2e-08,6.9e-07,4e-06,4e-06,2.1e-07,0,0,0,0,0,0,0,0
7390000,0.98,-0.0061,-0.013,0.19,-0.003,0.034,0.17,0.00015,0.024,0.15,-1.7e-05,-5.6e-05,3e-06,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,2.3e-05,0.00032,0.00032,0.00064,0.32,0.32,0.026,0.48,0.48,0.063,1.2e-08,1.2e-08,6.2e-07,4e-06,4e-06,2e-07,0,0,0,0,0,0,0,0
7490000,0.98,-0.0061,-0.013,0.19,-0.00058,0.037,0.17,-1.8e-05,0.028,0.15,-1.7e-05,-5.6e-05,1.6e-05,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,2.3e-05,0.00033,0.00033,0.00063,0.35,0.35,0.026,0.56,0.56,0.062,1.2e-08,1.2e-08,5.4e-07,4e-06,4e-06,1.8e-07,0,0,0,0,0,0,0,0
7590000,0.98,-0.0061,-0.013,0.19,0.00051,0.039,0.17,-5.7e-05,0.031,0.16,-1.7e-05,-5.6e-05,1.7e-05,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,2.3e-05,0.00033,0.00033,0.00062,0.38,0.38,0.025,0.64,0.64,0.061,1.2e-08,1.2e-08,4.7e-07,4e-06,4e-06,1.7e-07,0,0,0,0,0,0,0,0
7690000,0.98,-0.0062,-0.013,0.19,0.00025,0.043,0.17,-6e-05,0.035,0.17,-1.7e-05,-5.6e-05,1.3e-05,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,2.3e-05,0.00034,0.00034,0.00062,0.41,0.41,0.024,0.73,0.73,0.061,1.2e-08,1.2e-08,4.1e-07,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0
7790000,0.98,-0.006,-0.013,0.19,0.0019,0.045,0.16,-3.7e-05,0.039,0.16,-1.7e-05,-5.6e-05,7.8e-06,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,2.2e-05,0.00034,0.00034,0.00061,0.45,0.45,0.023,0.83,0.83,0.06,1.2e-08,1.2e-08,3.6e-07,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0
7890000,0.98,-0.0061,-0.013,0.19,0.00063,0.049,0.15,-6.4e-05,0.044,0.16,-1.7e-05,-5.6e-05,5.1e-06,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,2.2e-05,0.00035,0.00035,0.00059,0.49,0.49,0.022,0.95,0.95,0.059,1.2e-08,1.2e-08,3.1e-07,4e-06,4e-06,1.5e-07,0,0,0,0,0,0,0,0
7990000,0.98,-0.006,-0.013,0.19,0.001,0.052,0.15,-2.6e-05,0.048,0.16,-1.7e-05,-5.7e-05,6e-06,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,2.1e-05,0.00036,0.00036,0.00057,0.53,0.54,0.022,1.1,1.1,0.058,1.2e-08,1.2e-08,2.6e-07,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0
8090000,0.98,-0.0059,-0.013,0.19,0.0025,0.056,0.15,9e-05,0.053,0.16,-1.7e-05,-5.7e-05,-5.6e-06,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,2.1e-05,0.00037,0.00037,0.00056,0.59,0.59,0.021,1.2,1.2,0.058,1.2e-08,1.2e-08,2.3e-07,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0
8190000,0.98,-0.006,-0.013,0.19,0.0031,0.06,0.15,0.00029,0.058,0.17,-1.7e-05,-5.7e-05,-1.2e-05,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,2e-05,0.00037,0.00037,0.00054,0.63,0.63,0.02,1.4,1.4,0.057,1.2e-08,1.2e-08,2e-07,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0
8290000,0.98,-0.0059,-0.013,0.19,0.0053,0.065,0.14,0.00065,0.064,0.17,-1.7e-05,-5.7e-05,-1.2e-05,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,1.9e-05,0.00038,0.00038,0.00052,0.69,0.69,0.02,1.5,1.5,0.057,1.2e-08,1.2e-08,1.8e-07,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0
8390000,0.98,-0.0059,-0.013,0.19,0.0032,0.067,0.14,0.001,0.07,0.17,-1.7e-05,-5.7e-05,-1.2e-05,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,1.9e-05,0.00039,0.00039,0.00051,0.75,0.75,0.019,1.7,1.7,0.057,1.2e-08,1.2e-08,1.6e-07,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0
8490000,0.98,-0.0058,-0.013,0.19,0.0032,0.07,0.13,0.0013,0.076,0.16,-1.7e-05,-5.7e-05,-5.1e-06,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,1.8e-05,0.0004,0.0004,0.00049,0.81,0.81,0.019,1.9,1.9,0.056,1.1e-08,1.1e-08,1.4e-07,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0
8590000,0.98,-0.0057,-0.013,0.19,0.0043,0.073,0.13,0.0016,0.083,0.17,-1.7e-05,-5.7e-05,-6.8e-06,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,1.7e-05,0.00041,0.00041,0.00047,0.87,0.88,0.018,2.2,2.2,0.055,1.1e-08,1.1e-08,1.2e-07,4e-06,4e-06,1e-07,0,0,0,0,0,0,0,0
8690000,0.98,-0.0058,-0.013,0.19,0.0044,0.075,0.12,0.0019,0.088,0.16,-1.7e-05,-5.7e-05,-4.7e-06,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,1.7e-05,0.00042,0.00042,0.00046,0.93,0.93,0.018,2.4,2.4,0.055,1.1e-08,1.1e-08,1.1e-07,4e-06,4e-06,9.9e-08,0,0,0,0,0,0,0,0
8790000,0.98,-0.0058,-0.013,0.19,0.0058,0.078,0.12,0.0023,0.095,0.16,-1.7e-05,-5.7e-05,-8e-06,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,1.6e-05,0.00043,0.00043,0.00044,1,1,0.017,2.7,2.7,0.054,1.1e-08,1.1e-08,9.5e-08,4e-06,4e-06,9.4e-08,0,0,0,0,0,0,0,0
8890000,0.98,-0.0058,-0.013,0.19,0.006,0.08,0.12,0.0028,0.1,0.17,-1.7e-05,-5.7e-05,-3.2e-06,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,1.6e-05,0.00043,0.00043,0.00042,1.1,1.1,0.017,2.9,2.9,0.053,1.1e-08,1.1e-08,8.5e-08,4e-06,4e-06,9e-08,0,0,0,0,0,0,0,0
8990000,0.98,-0.0057,-0.013,0.19,0.0053,0.085,0.12,0.0033,0.11,0.16,-1.7e-05,-5.7e-05,2e-06,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,1.5e-05,0.00045,0.00045,0.00042,1.1,1.1,0.016,3.3,3.3,0.053,1.1e-08,1.1e-08,7.7e-08,4e-06,4e-06,8.6e-08,0,0,0,0,0,0,0,0
9090000,0.98,-0.0057,-0.013,0.19,0.0057,0.088,0.11,0.0038,0.11,0.16,-1.7e-05,-5.7e-05,6.9e-06,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,1.5e-05,0.00045,0.00045,0.0004,1.2,1.2,0.016,3.5,3.5,0.053,1.1e-08,1.1e-08,6.9e-08,4e-06,4e-06,8.2e-08,0,0,0,0,0,0,0,0
9190000,0.98,-0.0057,-0.013,0.19,0.0095,0.091,0.11,0.0046,0.12,0.16,-1.7e-05,-5.7e-05,1e-05,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.4e-05,0.00046,0.00046,0.00039,1.3,1.3,0.016,3.9,3.9,0.052,1.1e-08,1.1e-08,6.2e-08,4e-06,4e-06,7.9e-08,0,0,0,0,0,0,0,0
9290000,0.98,-0.0056,-0.013,0.19,0.012,0.091,0.1,0.0055,0.13,0.16,-1.7e-05,-5.7e-05,1.1e-05,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.4e-05,0.00046,0.00046,0.00037,1.3,1.3,0.015,4.2,4.2,0.051,1.1e-08,1.1e-08,5.5e-08,4e-06,4e-06,7.5e-08,0,0,0,0,0,0,0,0
9390000,0.98,-0.0055,-0.013,0.19,0.012,0.094,0.1,0.0065,0.13,0.16,-1.7e-05,-5.7e-05,6.5e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.4e-05,0.00047,0.00047,0.00037,1.4,1.4,0.015,4.7,4.7,0.051,1.1e-08,1.1e-08,5.1e-08,4e-06,4e-06,7.2e-08,0,0,0,0,0,0,0,0
9490000,0.98,-0.0056,-0.013,0.19,0.012,0.093,0.097,0.0072,0.14,0.16,-1.6e-05,-5.7e-05,7.5e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.3e-05,0.00047,0.00047,0.00035,1.5,1.5,0.014,5,5,0.051,1e-08,1e-08,4.6e-08,4e-06,4e-06,6.9e-08,0,0,0,0,0,0,0,0
9590000,0.98,-0.0057,-0.013,0.19,0.011,0.093,0.093,0.0079,0.14,0.15,-1.6e-05,-5.7e-05,1e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.3e-05,0.00048,0.00048,0.00034,1.6,1.6,0.014,5.5,5.5,0.05,1e-08,1e-08,4.2e-08,4e-06,4e-06,6.7e-08,0,0,0,0,0,0,0,0
9690000,0.98,-0.0057,-0.013,0.19,0.011,0.092,0.092,0.0084,0.14,0.15,-1.6e-05,-5.7e-05,-3.6e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00047,0.00047,0.00034,1.6,1.6,0.014,5.7,5.7,0.05,1e-08,1e-08,3.9e-08,4e-06,4e-06,6.4e-08,0,0,0,0,0,0,0,0
9790000,0.98,-0.0057,-0.013,0.19,0.012,0.094,0.087,0.0092,0.15,0.15,-1.6e-05,-5.7e-05,-5.3e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00049,0.00049,0.00032,1.7,1.7,0.014,6.4,6.4,0.049,1e-08,1e-08,3.5e-08,4e-06,4e-06,6.2e-08,0,0,0,0,0,0,0,0
9890000,0.98,-0.0058,-0.012,0.19,0.014,0.091,0.084,0.0098,0.15,0.14,-1.6e-05,-5.7e-05,-3.6e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00048,0.00048,0.00031,1.7,1.7,0.013,6.6,6.6,0.049,9.9e-09,9.9e-09,3.2e-08,4e-06,4e-06,5.9e-08,0,0,0,0,0,0,0,0
9990000,0.98,-0.0058,-0.013,0.19,0.016,0.092,0.082,0.011,0.16,0.14,-1.6e-05,-5.7e-05,-6.8e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00049,0.00049,0.00031,1.8,1.8,0.013,7.2,7.2,0.049,9.9e-09,9.9e-09,3e-08,4e-06,4e-06,5.7e-08,0,0,0,0,0,0,0,0
10090000,0.98,-0.0058,-0.013,0.19,0.013,0.085,0.079,0.011,0.15,0.14,-1.6e-05,-5.8e-05,-1e-05,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.1e-05,0.00047,0.00047,0.0003,1.8,1.8,0.013,7.4,7.4,0.048,9.6e-09,9.6e-09,2.8e-08,4e-06,4e-06,5.5e-08,0,0,0,0,0,0,0,0
10190000,0.98,-0.0058,-0.013,0.19,0.011,0.087,0.077,0.012,0.16,0.13,-1.6e-05,-5.8e-05,-1.4e-05,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.1e-05,0.00049,0.00049,0.00029,1.9,1.9,0.012,8.1,8.1,0.048,9.6e-09,9.6e-09,2.5e-08,4e-06,4e-06,5.3e-08,0,0,0,0,0,0,0,0
10290000,0.98,-0.006,-0.012,0.19,0.011,0.083,0.073,0.012,0.16,0.13,-1.5e-05,-5.8e-05,-1.1e-05,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1.1e-05,0.00047,0.00047,0.00029,1.9,1.9,0.012,8.2,8.2,0.048,9.3e-09,9.3e-09,2.4e-08,4e-06,4e-06,5.1e-08,0,0,0,0,0,0,0,0
10390000,0.98,-0.0059,-0.012,0.19,0.0069,0.0042,-0.0063,0.00075,0.00011,0.12,-1.5e-05,-5.8e-05,-8.9e-06,1.5e-09,-1.1e-09,-0.0015,0.2,0.002,0.43,0,0,0,0,0,1e-05,0.00048,0.00048,0.00028,0.25,0.25,0.56,0.25,0.25,0.048,9.3e-09,9.3e-09,2.2e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10490000,0.98,-0.0059,-0.012,0.19,0.0082,0.0056,-0.01,0.0015,0.00056,0.12,-1.5e-05,-5.8e-05,-1.1e-05,5.9e-09,-4.4e-09,-0.0014,0.2,0.002,0.43,0,0,0,0,0,1e-05,0.0005,0.0005,0.00027,0.26,0.26,0.55,0.26,0.26,0.057,9.3e-09,9.3e-09,2e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10590000,0.98,-0.0058,-0.012,0.19,-0.0014,0.0035,-0.0056,-0.0012,-0.0055,0.11,-1.5e-05,-5.8e-05,-8.1e-06,3.1e-06,-2e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.9e-06,0.0005,0.0005,0.00026,0.13,0.13,0.27,0.13,0.13,0.055,9.2e-09,9.2e-09,1.9e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10690000,0.98,-0.0057,-0.012,0.19,-0.00045,0.0037,-0.012,-0.0013,-0.0051,0.11,-1.5e-05,-5.8e-05,-8.3e-06,3.1e-06,-2.2e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.8e-06,0.00052,0.00052,0.00026,0.14,0.14,0.26,0.14,0.14,0.065,9.2e-09,9.2e-09,1.8e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10790000,0.98,-0.0058,-0.012,0.19,0.0014,0.00037,-0.014,-0.00079,-0.0048,0.1,-1.5e-05,-5.8e-05,-7.8e-06,4.6e-06,3.7e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.5e-06,0.00051,0.00051,0.00025,0.1,0.1,0.17,0.091,0.091,0.062,9e-09,9e-09,1.6e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10890000,0.98,-0.0058,-0.012,0.19,0.0014,0.003,-0.025,-0.00064,-0.0046,0.088,-1.5e-05,-5.8e-05,-4.4e-06,4.7e-06,3.7e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.3e-06,0.00053,0.00053,0.00025,0.12,0.12,0.16,0.098,0.098,0.068,9e-09,9e-09,1.5e-08,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
10990000,0.98,-0.0058,-0.013,0.19,0.0009,0.0092,-0.017,-0.00047,-0.0032,0.089,-1.5e-05,-5.8e-05,-4.9e-06,5.3e-06,5e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9.2e-06,0.0005,0.0005,0.00024,0.091,0.091,0.12,0.073,0.073,0.065,8.7e-09,8.7e-09,1.5e-08,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
11090000,0.98,-0.006,-0.012,0.19,0.0017,0.013,-0.018,-0.00038,-0.0022,0.084,-1.5e-05,-5.8e-05,-7.1e-06,5.3e-06,4.9e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,9e-06,0.00052,0.00052,0.00024,0.11,0.11,0.11,0.079,0.079,0.069,8.7e-09,8.7e-09,1.4e-08,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
11190000,0.98,-0.0062,-0.013,0.19,0.0034,0.014,-0.0092,0.001,-0.002,0.087,-1.4e-05,-5.8e-05,-7.9e-06,4e-06,1.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00047,0.00047,0.00023,0.09,0.09,0.083,0.063,0.063,0.066,8.1e-09,8.1e-09,1.3e-08,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
11290000,0.98,-0.0062,-0.013,0.19,0.0034,0.014,-0.012,0.0013,-0.00062,0.08,-1.4e-05,-5.8e-05,-8.2e-06,4e-06,1.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.7e-06,0.00048,0.00048,0.00023,0.11,0.11,0.077,0.07,0.07,0.069,8.1e-09,8.1e-09,1.2e-08,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
11390000,0.98,-0.0062,-0.012,0.19,0.002,0.012,-0.019,0.00084,-0.0011,0.068,-1.4e-05,-5.8e-05,-7.5e-06,8.2e-06,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.4e-06,0.00043,0.00043,0.00022,0.091,0.091,0.062,0.057,0.057,0.066,7.5e-09,7.5e-09,1.1e-08,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11490000,0.98,-0.0062,-0.012,0.19,0.00094,0.013,-0.016,0.00092,0.0002,0.068,-1.4e-05,-5.8e-05,-6.7e-06,8.2e-06,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.3e-06,0.00044,0.00044,0.00022,0.11,0.11,0.057,0.065,0.065,0.067,7.5e-09,7.5e-09,1.1e-08,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11590000,0.98,-0.0064,-0.012,0.19,0.0029,0.011,-0.016,0.0008,-0.00053,0.065,-1.3e-05,-5.9e-05,-6.4e-06,1.1e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00038,0.00038,0.00022,0.091,0.091,0.048,0.054,0.054,0.065,6.9e-09,6.9e-09,1e-08,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11690000,0.98,-0.0064,-0.012,0.19,0.0032,0.014,-0.016,0.0011,0.00069,0.058,-1.3e-05,-5.9e-05,-5.5e-06,1.1e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,8e-06,0.00039,0.00039,0.00021,0.11,0.11,0.044,0.062,0.062,0.066,6.9e-09,6.9e-09,9.5e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
11790000,0.98,-0.0067,-0.012,0.19,0.0021,0.0091,-0.013,0.00068,-0.0018,0.06,-1.3e-05,-5.9e-05,-3.3e-06,1.6e-05,3.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,7.8e-06,0.00034,0.00034,0.00021,0.088,0.088,0.037,0.052,0.052,0.063,6.4e-09,6.4e-09,9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
11890000,0.98,-0.0068,-0.012,0.19,0.0047,0.01,-0.015,0.00096,-0.0009,0.056,-1.3e-05,-5.9e-05,-3.5e-06,1.6e-05,3.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,7.7e-06,0.00035,0.00035,0.0002,0.11,0.11,0.034,0.06,0.06,0.063,6.4e-09,6.4e-09,8.5e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
11990000,0.98,-0.0069,-0.012,0.19,0.0077,0.011,-0.015,0.0021,-0.0018,0.051,-1.2e-05,-5.9e-05,-2.8e-06,1.5e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,7.6e-06,0.0003,0.0003,0.0002,0.085,0.085,0.03,0.051,0.051,0.061,5.9e-09,5.9e-09,8.1e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12090000,0.98,-0.0069,-0.012,0.19,0.0092,0.011,-0.011,0.0029,-0.0008,0.054,-1.2e-05,-5.9e-05,-2.7e-06,1.5e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,7.4e-06,0.00031,0.00031,0.0002,0.1,0.1,0.027,0.059,0.059,0.06,5.9e-09,5.9e-09,7.6e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
12190000,0.98,-0.0067,-0.012,0.19,0.0074,0.01,-0.01,0.0018,0.00035,0.055,-1.3e-05,-5.9e-05,-3.2e-06,1.7e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,7.3e-06,0.00027,0.00027,0.00019,0.08,0.08,0.024,0.05,0.05,0.058,5.5e-09,5.5e-09,7.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12290000,0.98,-0.0068,-0.012,0.19,0.0051,0.0094,-0.011,0.0024,0.0013,0.054,-1.3e-05,-5.9e-05,-3.6e-06,1.7e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,0.00028,0.00028,0.00019,0.095,0.095,0.022,0.059,0.059,0.058,5.5e-09,5.5e-09,6.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12390000,0.98,-0.0069,-0.012,0.19,0.0038,0.0064,-0.011,0.0017,0.00047,0.047,-1.2e-05,-6e-05,-3.6e-06,1.9e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,7e-06,0.00025,0.00025,0.00019,0.076,0.076,0.02,0.05,0.05,0.056,5.2e-09,5.2e-09,6.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12490000,0.98,-0.0069,-0.012,0.19,0.0037,0.0074,-0.0056,0.0021,0.0012,0.047,-1.2e-05,-6e-05,-3.6e-06,1.9e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,6.9e-06,0.00026,0.00026,0.00018,0.089,0.089,0.018,0.058,0.058,0.055,5.2e-09,5.2e-09,6.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12590000,0.98,-0.0071,-0.012,0.19,0.0075,0.001,-0.0026,0.0033,-0.0013,0.049,-1.2e-05,-6e-05,-3.6e-06,1.9e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,0.00023,0.00023,0.00018,0.071,0.071,0.017,0.049,0.049,0.054,4.9e-09,4.9e-09,6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12690000,0.98,-0.007,-0.012,0.19,0.008,-0.0011,-0.0019,0.004,-0.0013,0.049,-1.2e-05,-6e-05,-3.4e-06,1.9e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,6.7e-06,0.00024,0.00024,0.00018,0.082,0.082,0.016,0.058,0.058,0.053,4.9e-09,4.9e-09,5.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12790000,0.98,-0.0073,-0.012,0.19,0.0096,-0.0043,0.0011,0.0041,-0.0044,0.051,-1.1e-05,-6e-05,-1.5e-06,1.9e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,6.6e-06,0.00022,0.00022,0.00018,0.067,0.067,0.014,0.049,0.049,0.052,4.6e-09,4.6e-09,5.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12890000,0.98,-0.0073,-0.012,0.19,0.0097,-0.0051,0.0031,0.0051,-0.0048,0.053,-1.1e-05,-6e-05,-2.6e-07,1.9e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,6.5e-06,0.00023,0.00023,0.00017,0.077,0.077,0.013,0.057,0.057,0.051,4.6e-09,4.6e-09,5.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
12990000,0.98,-0.0072,-0.012,0.19,0.0077,-0.003,0.0047,0.0036,-0.0035,0.054,-1.1e-05,-6e-05,7.8e-07,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,0.00021,0.00021,0.00017,0.063,0.063,0.012,0.049,0.049,0.05,4.4e-09,4.4e-09,4.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13090000,0.98,-0.0073,-0.012,0.19,0.0085,-0.0029,0.0034,0.0044,-0.0038,0.052,-1.1e-05,-6e-05,2.1e-06,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,6.3e-06,0.00022,0.00022,0.00017,0.072,0.072,0.012,0.057,0.057,0.049,4.4e-09,4.4e-09,4.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13190000,0.98,-0.0073,-0.012,0.19,0.0035,-0.0045,0.0039,0.00097,-0.0045,0.053,-1.1e-05,-6e-05,2.8e-06,2.1e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,6.2e-06,0.00021,0.00021,0.00017,0.059,0.059,0.011,0.049,0.049,0.047,4.2e-09,4.2e-09,4.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13290000,0.98,-0.0073,-0.012,0.19,0.0031,-0.0053,0.0023,0.0013,-0.005,0.052,-1.1e-05,-6e-05,2.9e-06,2.1e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,6.1e-06,0.00021,0.00021,0.00016,0.067,0.067,0.01,0.057,0.057,0.047,4.2e-09,4.2e-09,4.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13390000,0.98,-0.0072,-0.012,0.19,0.0023,-0.0033,0.0033,0.00086,-0.0037,0.052,-1.2e-05,-6e-05,2.4e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,6e-06,0.0002,0.0002,0.00016,0.056,0.056,0.0097,0.049,0.049,0.046,4e-09,4e-09,4.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13490000,0.98,-0.0072,-0.012,0.19,0.0027,-0.0016,0.0037,0.0011,-0.0039,0.048,-1.2e-05,-6e-05,2.7e-06,2.2e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.9e-06,0.00021,0.00021,0.00016,0.064,0.064,0.0093,0.056,0.056,0.045,4e-09,4e-09,4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13590000,0.98,-0.0072,-0.012,0.19,0.0072,-0.0018,0.0063,0.004,-0.0032,0.047,-1.1e-05,-6e-05,2.4e-06,2.3e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.9e-06,0.0002,0.0002,0.00016,0.053,0.053,0.0089,0.048,0.048,0.044,3.8e-09,3.8e-09,3.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13690000,0.98,-0.0071,-0.012,0.19,0.0071,-0.0032,0.0074,0.0047,-0.0034,0.049,-1.1e-05,-6e-05,3e-06,2.3e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.8e-06,0.0002,0.0002,0.00015,0.06,0.06,0.0085,0.056,0.056,0.044,3.8e-09,3.8e-09,3.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13790000,0.98,-0.0071,-0.012,0.19,0.014,0.001,0.0084,0.0083,-0.00092,0.049,-1.2e-05,-5.9e-05,2.7e-06,2.5e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.7e-06,0.0002,0.0002,0.00015,0.051,0.051,0.0082,0.048,0.048,0.043,3.6e-09,3.6e-09,3.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13890000,0.98,-0.007,-0.012,0.19,0.015,0.0018,0.01,0.0097,-0.00077,0.051,-1.2e-05,-5.9e-05,3.4e-06,2.5e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.6e-06,0.0002,0.0002,0.00015,0.057,0.057,0.008,0.056,0.056,0.042,3.6e-09,3.6e-09,3.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0019,0.01,0.0073,-0.0023,0.051,-1.1e-05,-6e-05,4.1e-06,2.4e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.5e-06,0.00019,0.00019,0.00015,0.048,0.048,0.0077,0.048,0.048,0.041,3.4e-09,3.5e-09,3.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14090000,0.98,-0.0071,-0.012,0.19,0.012,-0.0024,0.012,0.0088,-0.0023,0.047,-1.1e-05,-6e-05,2.4e-06,2.4e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.5e-06,0.0002,0.0002,0.00015,0.055,0.055,0.0076,0.055,0.055,0.041,3.4e-09,3.5e-09,3.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14190000,0.98,-0.007,-0.011,0.19,0.0095,-0.0011,0.013,0.008,-0.0017,0.048,-1.2e-05,-6e-05,1.6e-06,2.5e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.4e-06,0.00019,0.00019,0.00015,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-09,3.3e-09,3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14290000,0.98,-0.007,-0.011,0.19,0.011,-0.0011,0.012,0.0089,-0.0019,0.052,-1.2e-05,-6e-05,1.6e-06,2.4e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.3e-06,0.0002,0.0002,0.00014,0.053,0.053,0.0073,0.055,0.055,0.04,3.3e-09,3.3e-09,2.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14390000,0.98,-0.0071,-0.011,0.19,0.011,-0.0041,0.014,0.0084,-0.003,0.057,-1.1e-05,-6e-05,2.1e-06,2.3e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.3e-06,0.00019,0.00019,0.00014,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-09,3.1e-09,2.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14490000,0.98,-0.0072,-0.011,0.19,0.0095,-0.0038,0.019,0.0094,-0.0035,0.06,-1.1e-05,-6e-05,1.3e-06,2.3e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.2e-06,0.0002,0.0002,0.00014,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-09,3.1e-09,2.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14590000,0.98,-0.0072,-0.011,0.19,0.0074,-0.0039,0.017,0.0058,-0.0041,0.056,-1.2e-05,-6e-05,1.1e-06,2e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.1e-06,0.00019,0.00019,0.00014,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-09,2.9e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14690000,0.98,-0.0072,-0.011,0.19,0.0065,-0.0038,0.018,0.0065,-0.0045,0.057,-1.2e-05,-6e-05,1.4e-06,2.1e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5.1e-06,0.0002,0.0002,0.00014,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-09,2.9e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
14790000,0.98,-0.0071,-0.011,0.19,0.0082,0.0032,0.019,0.0052,0.00085,0.06,-1.2e-05,-6e-05,2.2e-06,2.1e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5e-06,0.00019,0.00019,0.00013,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-09,2.7e-09,2.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
14890000,0.98,-0.0071,-0.011,0.19,0.0068,0.00087,0.024,0.0059,0.0011,0.062,-1.2e-05,-6e-05,2.8e-06,2.1e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,5e-06,0.00019,0.00019,0.00013,0.048,0.048,0.007,0.054,0.054,0.037,2.7e-09,2.7e-09,2.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
14990000,0.98,-0.0072,-0.011,0.19,0.0056,-0.0008,0.027,0.0047,-0.0006,0.064,-1.2e-05,-6.1e-05,3.2e-06,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.9e-06,0.00019,0.00019,0.00013,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-09,2.6e-09,2.2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15090000,0.98,-0.0072,-0.011,0.19,0.0056,0.00037,0.032,0.0052,-0.00066,0.068,-1.2e-05,-6.1e-05,3.1e-06,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.8e-06,0.00019,0.00019,0.00013,0.047,0.047,0.007,0.054,0.054,0.036,2.6e-09,2.6e-09,2.2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15190000,0.98,-0.0073,-0.011,0.19,0.0038,-0.00075,0.033,0.0041,-0.00065,0.07,-1.2e-05,-6.1e-05,2.8e-06,1.9e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.8e-06,0.00018,0.00018,0.00013,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-09,2.4e-09,2.1e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15290000,0.98,-0.0074,-0.011,0.19,0.0043,-0.0017,0.033,0.0046,-0.00075,0.067,-1.2e-05,-6.1e-05,3.4e-06,2.2e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.7e-06,0.00019,0.00019,0.00013,0.046,0.046,0.0071,0.054,0.054,0.035,2.4e-09,2.4e-09,2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15390000,0.98,-0.0075,-0.011,0.19,0.0046,0.00061,0.034,0.0037,-0.00051,0.068,-1.2e-05,-6.1e-05,3.3e-06,2.3e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.7e-06,0.00018,0.00018,0.00013,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-09,2.2e-09,2e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15490000,0.98,-0.0075,-0.011,0.19,0.0039,-0.0018,0.034,0.0041,-0.00055,0.07,-1.2e-05,-6.1e-05,3.2e-06,2.4e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.6e-06,0.00019,0.00019,0.00012,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-09,2.2e-09,1.9e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15590000,0.98,-0.0077,-0.011,0.19,0.0075,-0.0057,0.034,0.0061,-0.0045,0.069,-1.1e-05,-6.1e-05,3.6e-06,2.7e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.6e-06,0.00018,0.00018,0.00012,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-09,2.1e-09,1.8e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15690000,0.98,-0.0077,-0.011,0.19,0.0092,-0.0087,0.036,0.007,-0.0053,0.071,-1.1e-05,-6.1e-05,4e-06,2.7e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.5e-06,0.00018,0.00018,0.00012,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-09,2.1e-09,1.8e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
15790000,0.98,-0.0077,-0.011,0.19,0.0058,-0.0081,0.036,0.0054,-0.0041,0.073,-1.2e-05,-6.1e-05,4.7e-06,2.7e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.5e-06,0.00018,0.00017,0.00012,0.039,0.039,0.0073,0.046,0.046,0.034,1.9e-09,1.9e-09,1.7e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
15890000,0.98,-0.0077,-0.011,0.19,0.0046,-0.0064,0.037,0.0059,-0.0048,0.073,-1.2e-05,-6.1e-05,4.1e-06,2.9e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.4e-06,0.00018,0.00018,0.00012,0.044,0.044,0.0074,0.053,0.053,0.034,1.9e-09,1.9e-09,1.7e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
15990000,0.98,-0.0075,-0.011,0.19,0.0027,-0.005,0.035,0.0047,-0.0037,0.073,-1.2e-05,-6.1e-05,4.1e-06,3.1e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.4e-06,0.00017,0.00017,0.00012,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-09,1.7e-09,1.6e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16090000,0.98,-0.0075,-0.011,0.19,0.002,-0.0062,0.033,0.0049,-0.0043,0.074,-1.2e-05,-6.1e-05,3.7e-06,3.3e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00018,0.00018,0.00012,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-09,1.7e-09,1.6e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16190000,0.98,-0.0074,-0.011,0.19,-0.0019,-0.0039,0.032,0.0026,-0.0032,0.071,-1.2e-05,-6.1e-05,3.3e-06,3.4e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00017,0.00017,0.00012,0.038,0.038,0.0076,0.046,0.046,0.034,1.6e-09,1.6e-09,1.5e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16290000,0.98,-0.0075,-0.011,0.19,-0.0016,-0.0054,0.033,0.0024,-0.0037,0.074,-1.2e-05,-6.1e-05,3.5e-06,3.5e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00017,0.00017,0.00011,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-09,1.6e-09,1.5e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16390000,0.98,-0.0074,-0.011,0.19,0.00092,-0.0048,0.033,0.0035,-0.0028,0.074,-1.2e-05,-6.1e-05,3.8e-06,4.1e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00016,0.00016,0.00011,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-09,1.5e-09,1.4e-09,3.2e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
16490000,0.98,-0.0075,-0.011,0.19,0.0028,-0.0063,0.036,0.0037,-0.0034,0.079,-1.2e-05,-6.1e-05,3.7e-06,4e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00017,0.00017,0.00011,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-09,1.5e-09,1.4e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16590000,0.98,-0.0075,-0.011,0.19,0.007,-0.0064,0.04,0.0032,-0.0027,0.08,-1.2e-05,-6.1e-05,3.6e-06,4.2e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00016,0.00016,0.00011,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-09,1.3e-09,1.4e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16690000,0.98,-0.0076,-0.011,0.19,0.0084,-0.011,0.041,0.004,-0.0035,0.081,-1.2e-05,-6.1e-05,3.9e-06,4.4e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00016,0.00016,0.00011,0.042,0.042,0.008,0.052,0.052,0.034,1.3e-09,1.3e-09,1.3e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16790000,0.98,-0.0074,-0.011,0.19,0.0093,-0.0098,0.04,0.0032,-0.0025,0.082,-1.3e-05,-6.1e-05,4e-06,4.5e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00016,0.00015,0.00011,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-09,1.2e-09,1.3e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16890000,0.98,-0.0074,-0.011,0.19,0.0083,-0.01,0.041,0.0041,-0.0035,0.081,-1.3e-05,-6.1e-05,4.5e-06,4.8e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00016,0.00016,0.00011,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-09,1.2e-09,1.2e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
16990000,0.98,-0.0074,-0.011,0.19,0.0081,-0.0097,0.041,0.0039,-0.0026,0.08,-1.3e-05,-6.1e-05,4.6e-06,5.5e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00015,0.00015,0.00011,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-09,1.1e-09,1.2e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17090000,0.98,-0.0075,-0.011,0.19,0.0096,-0.012,0.041,0.0049,-0.0038,0.08,-1.3e-05,-6.1e-05,4.4e-06,5.7e-05,1.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00015,0.00015,0.00011,0.04,0.04,0.0083,0.052,0.052,0.034,1.1e-09,1.1e-09,1.2e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
17190000,0.98,-0.0076,-0.011,0.19,0.0085,-0.017,0.043,0.0032,-0.0073,0.084,-1.3e-05,-6.1e-05,3.9e-06,5.6e-05,1.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00015,0.00015,0.00011,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-10,9.9e-10,1.1e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17290000,0.98,-0.0076,-0.011,0.19,0.0094,-0.018,0.043,0.0042,-0.009,0.084,-1.3e-05,-6.1e-05,3.5e-06,5.9e-05,1.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00015,0.00015,0.0001,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-10,9.9e-10,1.1e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17390000,0.98,-0.0075,-0.011,0.19,0.0062,-0.018,0.042,0.0056,-0.0057,0.084,-1.3e-05,-6e-05,3.8e-06,6.8e-05,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00014,0.00014,0.0001,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-10,8.9e-10,1.1e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17490000,0.98,-0.0075,-0.011,0.19,0.0043,-0.018,0.042,0.0061,-0.0075,0.087,-1.3e-05,-6e-05,3.6e-06,6.9e-05,1.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00015,0.00014,0.0001,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-10,8.9e-10,1.1e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17590000,0.98,-0.0074,-0.011,0.19,0.00053,-0.014,0.042,0.0024,-0.0056,0.085,-1.3e-05,-6.1e-05,3.6e-06,6.9e-05,2.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00014,0.00014,0.0001,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-10,8.1e-10,1e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17690000,0.98,-0.0075,-0.011,0.19,-0.00042,-0.015,0.043,0.0024,-0.0071,0.088,-1.3e-05,-6.1e-05,3.6e-06,7e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00014,0.00014,0.0001,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-10,8.1e-10,1e-09,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17790000,0.98,-0.0074,-0.011,0.19,0.0023,-0.013,0.044,0.0034,-0.006,0.094,-1.4e-05,-6e-05,3.6e-06,7.4e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00013,0.00013,0.0001,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-10,7.3e-10,9.8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17890000,0.98,-0.0074,-0.011,0.19,0.0044,-0.015,0.044,0.0038,-0.0074,0.099,-1.4e-05,-6e-05,3.8e-06,7.4e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00014,0.00014,9.9e-05,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-10,7.3e-10,9.5e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
17990000,0.98,-0.0071,-0.011,0.19,0.0038,-0.0085,0.043,0.003,-0.0017,0.099,-1.4e-05,-6e-05,3.7e-06,7.9e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00013,0.00013,9.8e-05,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-10,6.6e-10,9.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18090000,0.98,-0.0072,-0.011,0.19,0.0033,-0.009,0.043,0.0035,-0.0027,0.098,-1.4e-05,-6e-05,3.6e-06,8.2e-05,3.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00013,0.00013,9.8e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-10,6.6e-10,9.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18190000,0.98,-0.0073,-0.011,0.19,0.0034,-0.0081,0.043,0.0041,-0.0019,0.096,-1.4e-05,-6e-05,4.1e-06,8.8e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00013,0.00013,9.7e-05,0.032,0.032,0.0086,0.045,0.045,0.035,6e-10,6e-10,8.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18290000,0.98,-0.0073,-0.011,0.19,0.0043,-0.0085,0.042,0.0045,-0.0028,0.095,-1.4e-05,-6e-05,4.1e-06,9.2e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00013,0.00013,9.6e-05,0.036,0.036,0.0087,0.051,0.051,0.035,6e-10,6e-10,8.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18390000,0.98,-0.0072,-0.011,0.19,0.0053,-0.0073,0.041,0.0061,-0.0021,0.095,-1.5e-05,-6e-05,3.9e-06,9.8e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00012,0.00012,9.5e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-10,5.4e-10,8.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18490000,0.98,-0.0073,-0.011,0.19,0.008,-0.0073,0.041,0.0069,-0.0028,0.097,-1.5e-05,-6e-05,4e-06,9.9e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00013,0.00012,9.4e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-10,5.4e-10,8.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18590000,0.98,-0.0071,-0.011,0.19,0.0064,-0.0067,0.041,0.0055,-0.0022,0.099,-1.5e-05,-6e-05,3.7e-06,9.9e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00012,0.00012,9.3e-05,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-10,4.9e-10,8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18690000,0.98,-0.0071,-0.011,0.19,0.0065,-0.0056,0.039,0.0062,-0.0028,0.098,-1.5e-05,-6e-05,3.9e-06,0.0001,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00012,0.00012,9.3e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-10,4.9e-10,7.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18790000,0.98,-0.007,-0.011,0.19,0.0055,-0.0054,0.038,0.0062,-0.0023,0.096,-1.5e-05,-6e-05,3.9e-06,0.00011,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00012,0.00012,9.2e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-10,4.4e-10,7.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18890000,0.98,-0.007,-0.011,0.19,0.0042,-0.005,0.036,0.0067,-0.0029,0.093,-1.5e-05,-6e-05,3.7e-06,0.00011,1.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00012,0.00012,9.1e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-10,4.4e-10,7.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
18990000,0.98,-0.007,-0.011,0.19,0.0026,-0.0051,0.037,0.0055,-0.0023,0.096,-1.5e-05,-6e-05,3.6e-06,0.00011,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00012,0.00011,9e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-10,4e-10,7.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19090000,0.98,-0.0071,-0.011,0.19,0.00059,-0.0056,0.037,0.0058,-0.0028,0.093,-1.5e-05,-6e-05,3.8e-06,0.00011,1.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00012,0.00012,9e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-10,4e-10,7.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
19190000,0.98,-0.007,-0.011,0.19,-0.00088,-0.0053,0.037,0.0048,-0.0023,0.092,-1.5e-05,-6e-05,3.3e-06,0.00012,1.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00011,0.00011,8.9e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-10,3.7e-10,7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19290000,0.98,-0.0069,-0.011,0.19,-0.0017,-0.0051,0.037,0.0047,-0.0028,0.091,-1.5e-05,-6e-05,3.2e-06,0.00012,1.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00011,0.00011,8.8e-05,0.031,0.031,0.0087,0.05,0.05,0.036,3.7e-10,3.7e-10,6.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19390000,0.98,-0.007,-0.011,0.19,-0.0022,-0.0017,0.038,0.0041,-0.00094,0.09,-1.5e-05,-6e-05,3.1e-06,0.00012,1.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00011,0.00011,8.8e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-10,3.3e-10,6.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19490000,0.98,-0.0071,-0.011,0.19,-0.003,-0.0017,0.038,0.0038,-0.0011,0.09,-1.5e-05,-6e-05,2.8e-06,0.00012,1.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00011,0.00011,8.7e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-10,3.3e-10,6.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19590000,0.98,-0.007,-0.011,0.19,-0.0041,-0.0046,0.039,0.0044,-0.0022,0.09,-1.5e-05,-6e-05,2.6e-06,0.00013,9.6e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00011,0.00011,8.6e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-10,3e-10,6.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19690000,0.98,-0.007,-0.011,0.19,-0.0057,-0.0031,0.038,0.0039,-0.0026,0.09,-1.5e-05,-6e-05,2.8e-06,0.00013,7.7e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00011,0.00011,8.6e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-10,3e-10,6.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19790000,0.98,-0.0071,-0.011,0.19,-0.0057,-0.0017,0.036,0.0064,-0.0021,0.085,-1.5e-05,-6e-05,2.5e-06,0.00014,4e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00011,0.0001,8.5e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-10,2.8e-10,6.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19890000,0.98,-0.0072,-0.011,0.19,-0.0057,-0.0015,0.036,0.0058,-0.0022,0.084,-1.5e-05,-6e-05,2.4e-06,0.00014,2.2e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00011,0.00011,8.5e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-10,2.8e-10,6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
19990000,0.98,-0.0072,-0.011,0.19,-0.0054,-0.0015,0.033,0.0061,-0.00071,0.081,-1.5e-05,-5.9e-05,2.4e-06,0.00014,2.8e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.0001,0.0001,8.4e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-10,2.5e-10,5.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20090000,0.98,-0.0072,-0.011,0.19,-0.0049,-0.0037,0.033,0.0056,-0.00097,0.084,-1.5e-05,-5.9e-05,2.4e-06,0.00014,4.2e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.0001,0.0001,8.4e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-10,2.5e-10,5.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20190000,0.98,-0.0072,-0.011,0.19,-0.0039,-0.0011,0.034,0.0066,-0.00071,0.084,-1.5e-05,-5.9e-05,2.1e-06,0.00015,-8.7e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.0001,0.0001,8.3e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-10,2.3e-10,5.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20290000,0.98,-0.0072,-0.011,0.19,-0.0071,-0.0022,0.034,0.0061,-0.00082,0.085,-1.5e-05,-5.9e-05,2.1e-06,0.00015,-1.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.0001,0.0001,8.2e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-10,2.3e-10,5.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20390000,0.98,-0.0072,-0.011,0.19,-0.0077,-0.0011,0.034,0.0069,-0.00058,0.086,-1.5e-05,-5.9e-05,2.2e-06,0.00015,-3.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.0001,9.9e-05,8.2e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-10,2.1e-10,5.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20490000,0.98,-0.0072,-0.011,0.19,-0.012,-0.002,0.033,0.0059,-0.00072,0.084,-1.5e-05,-5.9e-05,2.2e-06,0.00015,-5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.0001,0.0001,8.1e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-10,2.1e-10,5.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20590000,0.98,-0.0071,-0.011,0.19,-0.011,-0.003,0.033,0.007,-0.0006,0.082,-1.5e-05,-5.9e-05,2.4e-06,0.00016,-7.5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,9.9e-05,9.8e-05,8.1e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-10,2e-10,5.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20690000,0.98,-0.0071,-0.011,0.19,-0.013,-0.0017,0.033,0.0058,-0.00079,0.082,-1.5e-05,-5.9e-05,2.2e-06,0.00016,-8.3e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.0001,9.8e-05,8e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-10,2e-10,5.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20790000,0.98,-0.0065,-0.011,0.19,-0.016,0.00078,0.018,0.0049,-0.00063,0.081,-1.5e-05,-5.9e-05,2.3e-06,0.00016,-1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,9.8e-05,9.6e-05,8e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-10,1.8e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20890000,0.98,0.0026,-0.0074,0.19,-0.021,0.013,-0.1,0.003,9e-05,0.074,-1.5e-05,-5.9e-05,2.2e-06,0.00016,-1.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,9.8e-05,9.7e-05,7.9e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-10,1.8e-10,4.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
20990000,0.98,0.006,-0.004,0.19,-0.032,0.031,-0.24,0.0023,0.0007,0.059,-1.5e-05,-5.9e-05,2.2e-06,0.00016,-1.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,9.6e-05,9.5e-05,7.8e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-10,1.7e-10,4.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21090000,0.98,0.0044,-0.0043,0.19,-0.045,0.047,-0.36,-0.0016,0.0046,0.029,-1.5e-05,-5.9e-05,2.2e-06,0.00016,-1.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,9.7e-05,9.5e-05,7.8e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-10,1.7e-10,4.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21190000,0.98,0.0015,-0.006,0.19,-0.049,0.051,-0.49,-0.0012,0.0036,-0.0072,-1.4e-05,-5.9e-05,2.2e-06,0.00016,-2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,9.4e-05,9.3e-05,7.7e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-10,1.6e-10,4.6e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21290000,0.98,-0.00066,-0.0073,0.19,-0.049,0.054,-0.62,-0.006,0.0089,-0.066,-1.4e-05,-5.9e-05,1.9e-06,0.00016,-2.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,9.5e-05,9.4e-05,7.7e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-10,1.6e-10,4.5e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
21390000,0.98,-0.0021,-0.008,0.19,-0.044,0.05,-0.74,-0.0049,0.011,-0.13,-1.4e-05,-5.9e-05,1.9e-06,0.00017,-2.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,9.3e-05,9.1e-05,7.6e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-10,1.4e-10,4.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21490000,0.98,-0.0029,-0.0084,0.19,-0.04,0.047,-0.88,-0.0091,0.016,-0.22,-1.4e-05,-5.9e-05,2.1e-06,0.00017,-2.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,9.3e-05,9.2e-05,7.6e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-10,1.4e-10,4.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21590000,0.98,-0.0034,-0.0084,0.19,-0.031,0.043,-1,-0.0078,0.017,-0.31,-1.4e-05,-5.9e-05,2.2e-06,0.00017,-2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,9.1e-05,9e-05,7.5e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-10,1.3e-10,4.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21690000,0.98,-0.0038,-0.0083,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.42,-1.4e-05,-5.9e-05,2.3e-06,0.00017,-2.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,9.1e-05,9e-05,7.5e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-10,1.3e-10,4.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21790000,0.98,-0.0041,-0.0085,0.19,-0.021,0.033,-1.3,-0.0036,0.018,-0.54,-1.4e-05,-5.8e-05,2.5e-06,0.00018,-3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,8.9e-05,8.8e-05,7.4e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-10,1.2e-10,4.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21890000,0.98,-0.0044,-0.0087,0.19,-0.017,0.028,-1.4,-0.0055,0.021,-0.68,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-3.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,8.9e-05,8.8e-05,7.4e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-10,1.2e-10,4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
21990000,0.98,-0.0051,-0.0089,0.19,-0.014,0.023,-1.4,-0.00017,0.017,-0.82,-1.4e-05,-5.8e-05,2.5e-06,0.00017,-3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,8.7e-05,8.6e-05,7.4e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-10,1.1e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22090000,0.98,-0.0059,-0.0098,0.19,-0.011,0.019,-1.3,-0.0014,0.019,-0.96,-1.4e-05,-5.8e-05,2.7e-06,0.00018,-3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,8.7e-05,8.6e-05,7.3e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-10,1.1e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22190000,0.98,-0.0063,-0.01,0.19,-0.0031,0.013,-1.4,0.0062,0.013,-1.1,-1.4e-05,-5.8e-05,2.8e-06,0.00018,-3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,8.5e-05,8.4e-05,7.3e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-10,1.1e-10,3.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22290000,0.98,-0.007,-0.01,0.19,0.002,0.0078,-1.4,0.0062,0.014,-1.2,-1.4e-05,-5.8e-05,2.7e-06,0.00018,-3.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.6e-05,8.4e-05,7.2e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-10,1.1e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22390000,0.98,-0.0074,-0.01,0.19,0.007,-0.0018,-1.4,0.013,0.0042,-1.4,-1.4e-05,-5.8e-05,2.5e-06,0.00018,-3.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.4e-05,8.3e-05,7.2e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1e-10,1e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22490000,0.98,-0.0076,-0.011,0.19,0.011,-0.0077,-1.4,0.014,0.0037,-1.5,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-3.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.4e-05,8.3e-05,7.1e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-10,1e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22590000,0.98,-0.0075,-0.012,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-1.4e-05,-5.8e-05,2.5e-06,0.00018,-4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.2e-05,8.1e-05,7.1e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-11,9.4e-11,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22690000,0.98,-0.0074,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.8,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-4.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.3e-05,8.2e-05,7.1e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-11,9.4e-11,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22790000,0.98,-0.0074,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-1.4e-05,-5.8e-05,2.3e-06,0.00019,-4.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.1e-05,8e-05,7e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-11,8.9e-11,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22890000,0.98,-0.0076,-0.013,0.19,0.032,-0.034,-1.4,0.041,-0.02,-2.1,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.1e-05,8e-05,7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-11,8.9e-11,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
22990000,0.98,-0.0075,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-1.4e-05,-5.8e-05,2.7e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8e-05,7.9e-05,6.9e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-11,8.4e-11,3.3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23090000,0.98,-0.0076,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.4,-1.4e-05,-5.8e-05,2.7e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8e-05,7.9e-05,6.9e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-11,8.4e-11,3.2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23190000,0.98,-0.0076,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.5,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,7.9e-05,7.8e-05,6.8e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-11,7.9e-11,3.2e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23290000,0.98,-0.0081,-0.014,0.18,0.052,-0.051,-1.4,0.071,-0.05,-2.7,-1.4e-05,-5.8e-05,2.6e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,7.9e-05,7.8e-05,6.8e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8e-11,8e-11,3.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23390000,0.98,-0.008,-0.014,0.18,0.057,-0.053,-1.4,0.082,-0.055,-2.8,-1.4e-05,-5.8e-05,2.4e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,7.8e-05,7.7e-05,6.8e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-11,7.6e-11,3.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23490000,0.98,-0.0081,-0.014,0.18,0.061,-0.055,-1.4,0.088,-0.061,-3,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.9e-05,7.8e-05,6.7e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-11,7.6e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23590000,0.98,-0.0083,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.1,-1.4e-05,-5.8e-05,2.6e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.8e-05,7.7e-05,6.7e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-11,7.2e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23690000,0.98,-0.009,-0.015,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-1.4e-05,-5.8e-05,2.7e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.8e-05,7.7e-05,6.7e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-11,7.2e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.95,0.11,-0.081,-3.4,-1.4e-05,-5.8e-05,2.9e-06,0.0002,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.7e-05,7.6e-05,6.6e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-11,6.9e-11,2.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23890000,0.98,-0.014,-0.021,0.18,0.052,-0.058,-0.52,0.12,-0.087,-3.5,-1.4e-05,-5.8e-05,2.9e-06,0.0002,-4.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.7e-05,7.6e-05,6.6e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-11,6.9e-11,2.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
23990000,0.98,-0.016,-0.024,0.18,0.054,-0.057,-0.14,0.13,-0.089,-3.5,-1.4e-05,-5.8e-05,2.9e-06,0.00021,-5.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.7e-05,7.6e-05,6.6e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-11,6.6e-11,2.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24090000,0.98,-0.016,-0.023,0.18,0.06,-0.066,0.097,0.13,-0.095,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.00021,-5.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.7e-05,7.6e-05,6.5e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-11,6.6e-11,2.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24190000,0.98,-0.013,-0.019,0.18,0.071,-0.071,0.083,0.14,-0.1,-3.5,-1.4e-05,-5.8e-05,2.9e-06,0.00021,-6.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.5e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-11,6.3e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24290000,0.98,-0.011,-0.016,0.18,0.075,-0.074,0.061,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,2.9e-06,0.00021,-6.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.5e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-11,6.3e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24390000,0.98,-0.0097,-0.015,0.18,0.068,-0.069,0.077,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,3e-06,0.00022,-6.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.4e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-11,6.1e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24490000,0.98,-0.01,-0.015,0.18,0.064,-0.066,0.075,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.3e-06,0.00022,-6.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.4e-05,0.016,0.016,0.0081,0.044,0.044,0.035,6.1e-11,6.1e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24590000,0.98,-0.011,-0.015,0.18,0.061,-0.061,0.07,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.3e-06,0.00021,-7.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.4e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-11,5.9e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24690000,0.98,-0.011,-0.015,0.18,0.058,-0.061,0.069,0.17,-0.12,-3.5,-1.4e-05,-5.8e-05,3.3e-06,0.00021,-7.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-11,5.9e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24790000,0.98,-0.011,-0.014,0.18,0.055,-0.058,0.061,0.17,-0.11,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00021,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-11,5.7e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24890000,0.98,-0.011,-0.014,0.18,0.054,-0.062,0.05,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.4e-06,0.00022,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.2e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-11,5.7e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
24990000,0.98,-0.011,-0.013,0.18,0.045,-0.057,0.042,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.4e-06,0.00021,-8.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.2e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-11,5.5e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25090000,0.98,-0.011,-0.013,0.18,0.041,-0.057,0.04,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00021,-9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.6e-05,6.2e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-11,5.5e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.039,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.2e-06,0.00021,-9.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.6e-05,6.2e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-11,5.3e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25290000,0.98,-0.011,-0.013,0.18,0.032,-0.051,0.034,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3e-06,0.00021,-9.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6.1e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-11,5.3e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.032,0.18,-0.1,-3.5,-1.5e-05,-5.8e-05,3e-06,0.00021,-0.0001,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6.1e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-11,5.1e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25490000,0.98,-0.012,-0.012,0.18,0.019,-0.044,0.031,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,2.9e-06,0.00021,-0.0001,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6.1e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.1e-11,5.1e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25590000,0.98,-0.012,-0.012,0.18,0.014,-0.04,0.032,0.18,-0.098,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-11,5e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25690000,0.98,-0.011,-0.012,0.18,0.013,-0.039,0.021,0.18,-0.1,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-11,5e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25790000,0.98,-0.011,-0.011,0.18,0.0018,-0.03,0.021,0.17,-0.092,-3.5,-1.6e-05,-5.8e-05,2.8e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.7e-05,6e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-11,4.8e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25890000,0.98,-0.011,-0.011,0.18,-0.004,-0.028,0.023,0.17,-0.095,-3.5,-1.6e-05,-5.8e-05,2.6e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,6e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-11,4.8e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
25990000,0.98,-0.011,-0.011,0.18,-0.013,-0.021,0.016,0.16,-0.086,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.9e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-11,4.7e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26090000,0.98,-0.011,-0.011,0.18,-0.018,-0.021,0.015,0.16,-0.088,-3.5,-1.6e-05,-5.8e-05,2.6e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.9e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26190000,0.98,-0.011,-0.012,0.18,-0.024,-0.015,0.0095,0.15,-0.081,-3.5,-1.6e-05,-5.8e-05,2.6e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.9e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-11,4.6e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26290000,0.98,-0.011,-0.012,0.18,-0.026,-0.013,0.0037,0.15,-0.082,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.8e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-11,4.6e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26390000,0.98,-0.01,-0.012,0.18,-0.032,-0.0061,0.0075,0.13,-0.074,-3.5,-1.6e-05,-5.8e-05,2.3e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-11,4.4e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26490000,0.98,-0.0098,-0.012,0.18,-0.035,-0.0029,0.017,0.13,-0.075,-3.5,-1.6e-05,-5.8e-05,2.3e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.8e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-11,4.5e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26590000,0.98,-0.0092,-0.012,0.18,-0.036,0.005,0.017,0.12,-0.068,-3.5,-1.6e-05,-5.8e-05,2.1e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.8e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-11,4.3e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26690000,0.98,-0.0091,-0.012,0.18,-0.038,0.01,0.015,0.12,-0.067,-3.5,-1.6e-05,-5.8e-05,1.9e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.8e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-11,4.3e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26790000,0.98,-0.0089,-0.011,0.18,-0.045,0.014,0.014,0.1,-0.062,-3.5,-1.6e-05,-5.8e-05,1.8e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.7e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-11,4.2e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26890000,0.98,-0.0082,-0.011,0.18,-0.051,0.017,0.0095,0.1,-0.06,-3.5,-1.6e-05,-5.8e-05,1.9e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
26990000,0.98,-0.0077,-0.012,0.18,-0.058,0.023,0.0086,0.087,-0.054,-3.5,-1.6e-05,-5.8e-05,1.8e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.7e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27090000,0.98,-0.0075,-0.012,0.18,-0.06,0.03,0.011,0.082,-0.051,-3.5,-1.6e-05,-5.8e-05,1.7e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27190000,0.98,-0.0076,-0.012,0.18,-0.066,0.036,0.013,0.071,-0.045,-3.5,-1.6e-05,-5.8e-05,1.6e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-11,4e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27290000,0.98,-0.0077,-0.013,0.18,-0.073,0.042,0.13,0.064,-0.041,-3.5,-1.6e-05,-5.8e-05,1.6e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27390000,0.98,-0.0091,-0.015,0.18,-0.078,0.048,0.45,0.055,-0.034,-3.5,-1.6e-05,-5.8e-05,1.5e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27490000,0.98,-0.01,-0.017,0.18,-0.082,0.053,0.76,0.046,-0.029,-3.4,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.8e-05,5.5e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27590000,0.98,-0.01,-0.016,0.18,-0.076,0.056,0.86,0.038,-0.025,-3.4,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00014,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.8e-05,5.5e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27690000,0.98,-0.0091,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00014,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,8e-05,7.9e-05,5.5e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27790000,0.98,-0.0078,-0.012,0.18,-0.071,0.05,0.75,0.025,-0.017,-3.2,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-11,3.8e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27890000,0.98,-0.0074,-0.012,0.18,-0.078,0.057,0.79,0.017,-0.012,-3.1,-1.6e-05,-5.8e-05,1.2e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.4e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-11,3.8e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
27990000,0.98,-0.0079,-0.012,0.18,-0.079,0.058,0.78,0.012,-0.01,-3.1,-1.6e-05,-5.8e-05,1.2e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-11,3.7e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28090000,0.98,-0.0082,-0.012,0.18,-0.082,0.059,0.78,0.0041,-0.0044,-3,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.4e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28190000,0.98,-0.0076,-0.012,0.18,-0.082,0.056,0.79,-0.0024,-0.004,-2.9,-1.6e-05,-5.8e-05,1.2e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28290000,0.98,-0.0071,-0.013,0.18,-0.088,0.059,0.79,-0.011,0.0017,-2.8,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28390000,0.98,-0.0071,-0.013,0.18,-0.088,0.062,0.79,-0.015,0.0047,-2.8,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28490000,0.98,-0.0074,-0.014,0.18,-0.09,0.066,0.79,-0.024,0.011,-2.7,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28590000,0.98,-0.0075,-0.014,0.18,-0.083,0.061,0.79,-0.028,0.0087,-2.6,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-11,3.5e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28690000,0.98,-0.0072,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.2e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-11,3.5e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28790000,0.98,-0.0066,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.017,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-11,3.5e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28890000,0.98,-0.0064,-0.013,0.18,-0.084,0.064,0.79,-0.046,0.023,-2.4,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
28990000,0.98,-0.0062,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.3,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,8e-05,5.2e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29090000,0.98,-0.006,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.2e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29190000,0.98,-0.006,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29290000,0.98,-0.0062,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.034,-2.1,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29390000,0.98,-0.0067,-0.013,0.18,-0.075,0.066,0.78,-0.058,0.034,-2,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29490000,0.98,-0.0067,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-1.5e-05,-5.8e-05,1.5e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29590000,0.98,-0.0066,-0.012,0.18,-0.074,0.064,0.79,-0.062,0.04,-1.9,-1.5e-05,-5.8e-05,1.6e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29690000,0.98,-0.0067,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.047,-1.8,-1.5e-05,-5.8e-05,1.7e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29790000,0.98,-0.0065,-0.013,0.18,-0.073,0.056,0.78,-0.065,0.044,-1.7,-1.4e-05,-5.8e-05,1.8e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29890000,0.98,-0.006,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-1.4e-05,-5.8e-05,1.9e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
29990000,0.98,-0.0061,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.045,-1.6,-1.4e-05,-5.8e-05,1.9e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30090000,0.98,-0.0063,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.5,-1.4e-05,-5.8e-05,1.8e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30190000,0.98,-0.0062,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.4,-1.4e-05,-5.7e-05,1.6e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30290000,0.98,-0.0063,-0.013,0.18,-0.062,0.05,0.77,-0.074,0.053,-1.4,-1.4e-05,-5.7e-05,1.6e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30390000,0.98,-0.0063,-0.013,0.18,-0.055,0.044,0.76,-0.066,0.05,-1.3,-1.4e-05,-5.7e-05,1.8e-06,0.00024,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30490000,0.98,-0.0063,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.2,-1.4e-05,-5.7e-05,1.8e-06,0.00024,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30590000,0.98,-0.0066,-0.014,0.18,-0.053,0.041,0.77,-0.065,0.05,-1.2,-1.4e-05,-5.7e-05,1.9e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30690000,0.98,-0.007,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-1.4e-05,-5.7e-05,1.9e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30790000,0.98,-0.0067,-0.014,0.18,-0.044,0.035,0.76,-0.063,0.052,-1,-1.4e-05,-5.7e-05,2e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30890000,0.98,-0.006,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-0.95,-1.4e-05,-5.7e-05,1.9e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30990000,0.98,-0.0062,-0.013,0.18,-0.036,0.026,0.76,-0.057,0.049,-0.88,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31090000,0.98,-0.0064,-0.014,0.18,-0.035,0.025,0.76,-0.061,0.051,-0.81,-1.4e-05,-5.7e-05,1.8e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31190000,0.98,-0.0066,-0.014,0.18,-0.031,0.02,0.76,-0.052,0.046,-0.74,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30290000,0.98,-0.0063,-0.013,0.18,-0.062,0.05,0.77,-0.074,0.053,-1.4,-1.4e-05,-5.7e-05,1.6e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30390000,0.98,-0.0063,-0.013,0.18,-0.055,0.044,0.76,-0.066,0.05,-1.3,-1.4e-05,-5.7e-05,1.8e-06,0.00024,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30490000,0.98,-0.0063,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.2,-1.4e-05,-5.7e-05,1.9e-06,0.00024,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30590000,0.98,-0.0066,-0.014,0.18,-0.053,0.041,0.77,-0.065,0.05,-1.2,-1.4e-05,-5.7e-05,2e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30690000,0.98,-0.007,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-1.4e-05,-5.7e-05,2e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30790000,0.98,-0.0067,-0.014,0.18,-0.044,0.035,0.76,-0.063,0.052,-1,-1.4e-05,-5.7e-05,2e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30890000,0.98,-0.006,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-0.95,-1.4e-05,-5.7e-05,1.9e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
30990000,0.98,-0.0062,-0.013,0.18,-0.036,0.026,0.76,-0.057,0.049,-0.88,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31090000,0.98,-0.0064,-0.014,0.18,-0.035,0.025,0.76,-0.061,0.051,-0.81,-1.4e-05,-5.7e-05,1.8e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31190000,0.98,-0.0065,-0.014,0.18,-0.031,0.02,0.76,-0.052,0.046,-0.74,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31290000,0.98,-0.0068,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.67,-1.4e-05,-5.7e-05,2e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31390000,0.98,-0.0066,-0.014,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.6,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,7.9e-05,4.7e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31490000,0.98,-0.0063,-0.014,0.18,-0.022,0.0089,0.76,-0.048,0.043,-0.52,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31590000,0.98,-0.0062,-0.014,0.18,-0.018,0.0066,0.76,-0.037,0.039,-0.45,-1.4e-05,-5.7e-05,2e-06,0.00027,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,7.9e-05,4.6e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31690000,0.98,-0.0062,-0.015,0.18,-0.02,0.0055,0.76,-0.039,0.039,-0.38,-1.4e-05,-5.7e-05,2.1e-06,0.00027,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31790000,0.98,-0.0064,-0.015,0.18,-0.011,0.003,0.76,-0.028,0.037,-0.31,-1.4e-05,-5.7e-05,2.2e-06,0.00027,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31490000,0.98,-0.0063,-0.014,0.18,-0.022,0.0089,0.76,-0.048,0.043,-0.52,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31590000,0.98,-0.0062,-0.014,0.18,-0.018,0.0066,0.76,-0.037,0.039,-0.45,-1.4e-05,-5.7e-05,2e-06,0.00027,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,7.9e-05,4.7e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31690000,0.98,-0.0062,-0.015,0.18,-0.02,0.0055,0.76,-0.039,0.039,-0.38,-1.4e-05,-5.7e-05,2.1e-06,0.00027,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,7.9e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31790000,0.98,-0.0064,-0.015,0.18,-0.011,0.003,0.76,-0.028,0.037,-0.31,-1.4e-05,-5.7e-05,2.2e-06,0.00027,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.7e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-11,2.8e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31890000,0.98,-0.0061,-0.015,0.18,-0.0078,0.00068,0.76,-0.029,0.038,-0.24,-1.4e-05,-5.7e-05,2.2e-06,0.00027,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
31990000,0.98,-0.0064,-0.015,0.18,0.00012,1.8e-05,0.75,-0.017,0.034,-0.18,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32090000,0.98,-0.0067,-0.014,0.18,-0.0004,-0.0034,0.76,-0.017,0.034,-0.1,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32190000,0.98,-0.0069,-0.015,0.18,0.0049,-0.0066,0.76,-0.0059,0.033,-0.037,-1.3e-05,-5.7e-05,2.1e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.5e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32290000,0.98,-0.0068,-0.015,0.18,0.0065,-0.0093,0.75,-0.0054,0.032,0.031,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,9.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32390000,0.98,-0.0069,-0.015,0.18,0.013,-0.011,0.75,0.0059,0.03,0.11,-1.3e-05,-5.7e-05,2.2e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.8e-05,4.5e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-11,2.7e-11,9.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32490000,0.98,-0.0098,-0.013,0.18,0.04,-0.074,-0.12,0.0091,0.023,0.11,-1.3e-05,-5.7e-05,2.1e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.5e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-11,2.8e-11,9.7e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32590000,0.98,-0.0097,-0.013,0.18,0.04,-0.075,-0.12,0.021,0.02,0.09,-1.4e-05,-5.7e-05,2.2e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.9e-05,7.7e-05,4.5e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-11,2.7e-11,9.6e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32690000,0.98,-0.0097,-0.013,0.18,0.036,-0.081,-0.12,0.025,0.012,0.075,-1.4e-05,-5.7e-05,2.2e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.9e-05,7.8e-05,4.5e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-11,2.7e-11,9.6e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32790000,0.98,-0.0094,-0.013,0.18,0.034,-0.078,-0.12,0.035,0.01,0.059,-1.4e-05,-5.7e-05,2.2e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.6e-05,7.5e-05,4.5e-05,0.019,0.019,0.0071,0.037,0.037,0.035,2.7e-11,2.7e-11,9.5e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32890000,0.98,-0.0094,-0.013,0.18,0.034,-0.084,-0.13,0.038,0.0019,0.044,-1.4e-05,-5.7e-05,2.3e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.6e-05,7.5e-05,4.4e-05,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-11,2.7e-11,9.4e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32990000,0.98,-0.0091,-0.013,0.18,0.031,-0.08,-0.12,0.046,-0.0012,0.031,-1.4e-05,-5.6e-05,2.4e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.2e-05,7.1e-05,4.4e-05,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-11,2.7e-11,9.3e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33090000,0.98,-0.009,-0.013,0.18,0.027,-0.084,-0.12,0.049,-0.0094,0.024,-1.4e-05,-5.6e-05,2.3e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.2e-05,7.1e-05,4.4e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-11,2.7e-11,9.2e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33190000,0.98,-0.0087,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,0.017,-1.4e-05,-5.6e-05,2.3e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6.7e-05,6.6e-05,4.4e-05,0.029,0.029,0.0064,0.038,0.038,0.035,2.6e-11,2.6e-11,9.2e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33290000,0.98,-0.0088,-0.013,0.18,0.019,-0.081,-0.12,0.056,-0.019,0.0099,-1.4e-05,-5.6e-05,2.4e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6.7e-05,6.6e-05,4.4e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-11,2.6e-11,9.1e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33390000,0.98,-0.0083,-0.013,0.18,0.014,-0.067,-0.12,0.059,-0.014,-0.0011,-1.4e-05,-5.6e-05,2.4e-06,0.00028,-0.00021,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6e-05,5.9e-05,4.4e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-11,2.6e-11,9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33490000,0.98,-0.0083,-0.013,0.18,0.0097,-0.067,-0.12,0.061,-0.021,-0.015,-1.4e-05,-5.6e-05,2.4e-06,0.00028,-0.00021,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6e-05,5.9e-05,4.4e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-11,2.6e-11,8.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33590000,0.98,-0.0079,-0.013,0.18,0.0057,-0.058,-0.12,0.063,-0.017,-0.026,-1.4e-05,-5.6e-05,2.4e-06,0.00028,-0.00023,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,5.3e-05,5.2e-05,4.3e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-11,2.6e-11,8.8e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33690000,0.98,-0.0079,-0.013,0.18,0.001,-0.058,-0.12,0.063,-0.023,-0.038,-1.4e-05,-5.6e-05,2.4e-06,0.00028,-0.00023,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,5.3e-05,5.2e-05,4.3e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-11,2.6e-11,8.8e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33790000,0.98,-0.0077,-0.013,0.18,-0.0022,-0.048,-0.11,0.067,-0.018,-0.048,-1.4e-05,-5.6e-05,2.4e-06,0.00026,-0.00026,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,4.7e-05,4.6e-05,4.3e-05,0.044,0.045,0.0059,0.041,0.041,0.034,2.6e-11,2.6e-11,8.7e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33890000,0.98,-0.0077,-0.013,0.18,-0.0064,-0.045,-0.11,0.067,-0.023,-0.06,-1.4e-05,-5.6e-05,2.4e-06,0.00026,-0.00026,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,4.7e-05,4.6e-05,4.3e-05,0.052,0.052,0.0058,0.047,0.047,0.033,2.6e-11,2.6e-11,8.6e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33990000,0.98,-0.0074,-0.013,0.18,-0.0061,-0.031,-0.11,0.07,-0.015,-0.069,-1.4e-05,-5.6e-05,2.4e-06,0.00024,-0.00029,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,4.1e-05,4.1e-05,4.3e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-11,2.6e-11,8.6e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34090000,0.98,-0.0074,-0.013,0.18,-0.01,-0.031,-0.11,0.069,-0.018,-0.081,-1.4e-05,-5.6e-05,2.3e-06,0.00024,-0.00029,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,4.1e-05,4.1e-05,4.3e-05,0.054,0.054,0.0058,0.049,0.049,0.033,2.6e-11,2.6e-11,8.5e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34190000,0.98,-0.0073,-0.013,0.18,-0.011,-0.02,-0.11,0.072,-0.013,-0.091,-1.4e-05,-5.6e-05,2.4e-06,0.00022,-0.00031,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.7e-05,3.6e-05,4.3e-05,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-11,2.6e-11,8.4e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34290000,0.98,-0.0071,-0.013,0.18,-0.012,-0.02,-0.11,0.071,-0.015,-0.1,-1.4e-05,-5.6e-05,2.4e-06,0.00022,-0.00031,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.7e-05,3.6e-05,4.2e-05,0.054,0.055,0.0058,0.05,0.05,0.033,2.6e-11,2.6e-11,8.3e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34390000,0.98,-0.007,-0.013,0.18,-0.013,-0.01,-0.11,0.073,-0.01,-0.11,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.3e-05,3.3e-05,4.2e-05,0.047,0.047,0.0059,0.044,0.044,0.033,2.6e-11,2.6e-11,8.3e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34490000,0.98,-0.0071,-0.013,0.18,-0.016,-0.009,-0.11,0.071,-0.011,-0.12,-1.4e-05,-5.6e-05,2.4e-06,0.00021,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.3e-05,3.3e-05,4.2e-05,0.053,0.053,0.0059,0.051,0.051,0.032,2.6e-11,2.6e-11,8.2e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34590000,0.98,-0.007,-0.013,0.18,-0.015,-0.0045,0.69,0.073,-0.0088,-0.098,-1.4e-05,-5.6e-05,2.3e-06,0.0002,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.1e-05,3.1e-05,4.2e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-11,2.6e-11,8.2e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
34690000,0.98,-0.007,-0.013,0.18,-0.018,-0.0021,1.7,0.071,-0.0091,0.02,-1.4e-05,-5.6e-05,2.3e-06,0.0002,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.1e-05,3.1e-05,4.2e-05,0.047,0.047,0.006,0.052,0.052,0.032,2.6e-11,2.6e-11,8.1e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
34790000,0.98,-0.007,-0.012,0.18,-0.02,0.0026,2.6,0.072,-0.0068,0.2,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00034,-0.001,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,2.9e-05,2.9e-05,4.2e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-11,2.6e-11,8e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
34890000,0.98,-0.007,-0.012,0.18,-0.024,0.0053,3.6,0.07,-0.0062,0.49,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00034,-0.001,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3e-05,2.9e-05,4.2e-05,0.043,0.043,0.0061,0.052,0.052,0.032,2.6e-11,2.6e-11,8e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
31990000,0.98,-0.0064,-0.015,0.18,0.00013,1.9e-05,0.75,-0.017,0.034,-0.18,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32090000,0.98,-0.0067,-0.014,0.18,-0.0004,-0.0034,0.76,-0.017,0.034,-0.1,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32190000,0.98,-0.0069,-0.015,0.18,0.0049,-0.0066,0.76,-0.0059,0.033,-0.037,-1.3e-05,-5.7e-05,2.1e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32290000,0.98,-0.0068,-0.015,0.18,0.0065,-0.0093,0.75,-0.0054,0.032,0.031,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32390000,0.98,-0.0069,-0.015,0.18,0.013,-0.011,0.75,0.0059,0.03,0.11,-1.3e-05,-5.7e-05,2.2e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.8e-05,4.6e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-11,2.7e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32490000,0.98,-0.0098,-0.013,0.18,0.04,-0.074,-0.12,0.0091,0.023,0.11,-1.3e-05,-5.7e-05,2.1e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.6e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-11,2.8e-11,9.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32590000,0.98,-0.0097,-0.013,0.18,0.04,-0.075,-0.12,0.021,0.02,0.09,-1.4e-05,-5.7e-05,2.2e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.9e-05,7.7e-05,4.5e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-11,2.7e-11,9.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32690000,0.98,-0.0097,-0.013,0.18,0.036,-0.081,-0.12,0.025,0.012,0.075,-1.4e-05,-5.7e-05,2.2e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.9e-05,7.8e-05,4.5e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-11,2.7e-11,9.7e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32790000,0.98,-0.0094,-0.013,0.18,0.034,-0.078,-0.12,0.035,0.01,0.059,-1.4e-05,-5.7e-05,2.3e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.6e-05,7.5e-05,4.5e-05,0.019,0.019,0.0071,0.037,0.037,0.035,2.7e-11,2.7e-11,9.6e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32890000,0.98,-0.0094,-0.013,0.18,0.034,-0.084,-0.13,0.038,0.0019,0.044,-1.4e-05,-5.7e-05,2.3e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.6e-05,7.5e-05,4.5e-05,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-11,2.7e-11,9.5e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
32990000,0.98,-0.0091,-0.013,0.18,0.031,-0.08,-0.12,0.046,-0.0012,0.031,-1.4e-05,-5.6e-05,2.4e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.2e-05,7.1e-05,4.5e-05,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-11,2.7e-11,9.5e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33090000,0.98,-0.009,-0.013,0.18,0.027,-0.084,-0.12,0.049,-0.0094,0.024,-1.4e-05,-5.6e-05,2.3e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.2e-05,7.1e-05,4.5e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-11,2.7e-11,9.4e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33190000,0.98,-0.0087,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,0.017,-1.4e-05,-5.6e-05,2.3e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6.7e-05,6.6e-05,4.4e-05,0.029,0.029,0.0064,0.038,0.038,0.035,2.6e-11,2.6e-11,9.3e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33290000,0.98,-0.0088,-0.013,0.18,0.019,-0.081,-0.12,0.056,-0.019,0.0099,-1.4e-05,-5.6e-05,2.4e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6.7e-05,6.6e-05,4.4e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-11,2.6e-11,9.2e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33390000,0.98,-0.0083,-0.013,0.18,0.014,-0.067,-0.12,0.059,-0.014,-0.0011,-1.4e-05,-5.6e-05,2.4e-06,0.00028,-0.00021,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6e-05,5.9e-05,4.4e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-11,2.6e-11,9.1e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33490000,0.98,-0.0083,-0.013,0.18,0.0097,-0.067,-0.12,0.061,-0.021,-0.015,-1.4e-05,-5.6e-05,2.4e-06,0.00028,-0.00021,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6e-05,5.9e-05,4.4e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-11,2.6e-11,9.1e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
33590000,0.98,-0.0079,-0.013,0.18,0.0057,-0.058,-0.12,0.063,-0.017,-0.026,-1.4e-05,-5.6e-05,2.5e-06,0.00028,-0.00023,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,5.3e-05,5.2e-05,4.4e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-11,2.6e-11,9e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33690000,0.98,-0.0079,-0.013,0.18,0.0011,-0.058,-0.12,0.063,-0.023,-0.038,-1.4e-05,-5.6e-05,2.5e-06,0.00028,-0.00023,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,5.3e-05,5.2e-05,4.4e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-11,2.6e-11,8.9e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33790000,0.98,-0.0077,-0.013,0.18,-0.0022,-0.048,-0.11,0.067,-0.018,-0.048,-1.4e-05,-5.6e-05,2.4e-06,0.00026,-0.00026,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,4.7e-05,4.6e-05,4.4e-05,0.044,0.045,0.0059,0.041,0.041,0.034,2.6e-11,2.6e-11,8.8e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33890000,0.98,-0.0077,-0.013,0.18,-0.0064,-0.045,-0.11,0.067,-0.023,-0.06,-1.4e-05,-5.6e-05,2.5e-06,0.00026,-0.00026,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,4.7e-05,4.6e-05,4.3e-05,0.052,0.052,0.0058,0.047,0.047,0.033,2.6e-11,2.6e-11,8.7e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
33990000,0.98,-0.0074,-0.013,0.18,-0.0061,-0.031,-0.11,0.07,-0.015,-0.069,-1.4e-05,-5.6e-05,2.4e-06,0.00024,-0.00029,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,4.1e-05,4.1e-05,4.3e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-11,2.6e-11,8.7e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34090000,0.98,-0.0074,-0.013,0.18,-0.01,-0.031,-0.11,0.069,-0.018,-0.081,-1.4e-05,-5.6e-05,2.4e-06,0.00024,-0.00029,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,4.1e-05,4.1e-05,4.3e-05,0.054,0.054,0.0058,0.049,0.049,0.033,2.6e-11,2.6e-11,8.6e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
34190000,0.98,-0.0073,-0.013,0.18,-0.011,-0.02,-0.11,0.072,-0.013,-0.091,-1.4e-05,-5.6e-05,2.4e-06,0.00022,-0.00031,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.7e-05,3.6e-05,4.3e-05,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-11,2.6e-11,8.5e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34290000,0.98,-0.0071,-0.013,0.18,-0.012,-0.02,-0.11,0.071,-0.015,-0.1,-1.4e-05,-5.6e-05,2.4e-06,0.00022,-0.00031,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.7e-05,3.6e-05,4.3e-05,0.054,0.055,0.0058,0.05,0.05,0.033,2.6e-11,2.6e-11,8.5e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
34390000,0.98,-0.007,-0.013,0.18,-0.013,-0.01,-0.11,0.073,-0.01,-0.11,-1.4e-05,-5.6e-05,2.4e-06,0.00021,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.3e-05,3.3e-05,4.3e-05,0.047,0.047,0.0059,0.044,0.044,0.033,2.6e-11,2.6e-11,8.4e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34490000,0.98,-0.0071,-0.013,0.18,-0.016,-0.009,-0.11,0.071,-0.011,-0.12,-1.4e-05,-5.6e-05,2.4e-06,0.00021,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.3e-05,3.3e-05,4.3e-05,0.053,0.053,0.0059,0.051,0.051,0.032,2.6e-11,2.6e-11,8.3e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
34590000,0.98,-0.007,-0.013,0.18,-0.015,-0.0045,0.69,0.073,-0.0088,-0.098,-1.4e-05,-5.6e-05,2.3e-06,0.0002,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.1e-05,3.1e-05,4.3e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-11,2.6e-11,8.3e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
34690000,0.98,-0.007,-0.013,0.18,-0.018,-0.0021,1.7,0.071,-0.0091,0.02,-1.4e-05,-5.6e-05,2.3e-06,0.0002,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.1e-05,3.1e-05,4.2e-05,0.047,0.047,0.006,0.052,0.052,0.032,2.6e-11,2.6e-11,8.2e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
34790000,0.98,-0.007,-0.012,0.18,-0.02,0.0026,2.6,0.072,-0.0068,0.2,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00034,-0.001,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,2.9e-05,2.9e-05,4.2e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-11,2.6e-11,8.1e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
34890000,0.98,-0.007,-0.012,0.18,-0.024,0.0053,3.6,0.07,-0.0062,0.49,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00034,-0.001,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3e-05,2.9e-05,4.2e-05,0.043,0.043,0.0061,0.052,0.052,0.032,2.6e-11,2.6e-11,8.1e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
1 Timestamp state[0] state[1] state[2] state[3] state[4] state[5] state[6] state[7] state[8] state[9] state[10] state[11] state[12] state[13] state[14] state[15] state[16] state[17] state[18] state[19] state[20] state[21] state[22] state[23] variance[0] variance[1] variance[2] variance[3] variance[4] variance[5] variance[6] variance[7] variance[8] variance[9] variance[10] variance[11] variance[12] variance[13] variance[14] variance[15] variance[16] variance[17] variance[18] variance[19] variance[20] variance[21] variance[22] variance[23]
65 6290000 0.98 -0.0068 -0.013 0.18 0.004 0.021 0.19 0.0035 0.0084 0.051 -1.9e-05 -5.5e-05 7.4e-07 0 0 -0.0019 0.2 -6.1e-09 0.43 0 0 0 0 0 5e-06 0.00044 0.00044 0.00015 0.31 0.31 0.039 0.17 0.17 0.07 1.8e-08 1.8e-08 4.8e-09 4e-06 4e-06 3.9e-07 0 0 0 0 0 0 0 0
66 6390000 0.98 -0.0068 -0.013 0.18 0.0046 0.018 0.19 0.0024 0.0066 0.064 -1.8e-05 -5.6e-05 7.2e-07 0 0 -0.0019 0.2 -6.1e-09 0.43 0 0 0 0 0 4.9e-06 0.00036 0.00036 0.00015 0.24 0.24 0.038 0.13 0.13 0.07 1.5e-08 1.5e-08 4.6e-09 4e-06 4e-06 3.6e-07 0 0 0 0 0 0 0 0
67 6490000 0.98 -0.0068 -0.013 0.18 0.0024 0.017 0.19 0.0027 0.0083 0.08 -1.8e-05 -5.6e-05 7.2e-07 0 0 -0.0019 0.2 -6.1e-09 0.43 0 0 0 0 0 4.8e-06 0.00038 0.00038 0.00015 0.28 0.28 0.036 0.16 0.16 0.069 1.5e-08 1.5e-08 4.4e-09 4e-06 4e-06 3.4e-07 0 0 0 0 0 0 0 0
68 6590000 0.98 -0.0067 -0.013 0.19 0.00045 0.015 0.19 0.0017 0.0063 0.088 -1.7e-05 -5.6e-05 7.1e-07 4.7e-07 0 0 -0.0019 0.2 0.002 0.43 0 0 0 0 0 5.5e-05 0.0003 0.0003 0.0015 0.2 0.2 0.035 0.12 0.12 0.068 1.2e-08 1.2e-08 4.3e-09 1e-06 4e-06 4e-06 3.2e-07 0 0 0 0 0 0 0 0
69 6690000 0.98 -0.0066 -0.013 0.19 -0.0022 0.017 0.19 0.0016 0.0079 0.097 -1.7e-05 -5.6e-05 6.9e-07 -3.6e-06 0 0 -0.0019 0.2 0.002 0.43 0 0 0 0 0 3.5e-05 3.6e-05 0.0003 0.0003 0.00097 0.00099 0.21 0.21 0.033 0.15 0.15 0.067 1.2e-08 1.2e-08 4.3e-09 9.9e-07 4e-06 4e-06 3e-07 0 0 0 0 0 0 0 0
70 6790000 0.98 -0.0066 -0.013 0.19 -0.00042 0.019 0.19 0.0014 0.0096 0.11 -1.7e-05 -5.6e-05 6.8e-07 -5.2e-06 0 0 -0.0019 0.2 0.002 0.43 0 0 0 0 0 2.7e-05 2.9e-05 0.0003 0.0003 0.00074 0.0008 0.21 0.21 0.032 0.18 0.18 0.067 1.2e-08 1.2e-08 4.3e-09 9.8e-07 4e-06 4e-06 2.8e-07 0 0 0 0 0 0 0 0
71 6890000 0.98 -0.0064 -0.013 0.19 -0.00086 -0.00087 0.019 0.19 0.0013 0.011 0.12 -1.7e-05 -5.6e-05 6.8e-07 -4.8e-06 0 0 -0.0019 0.2 0.002 0.43 0 0 0 0 0 2.1e-05 2.5e-05 0.0003 0.0003 0.00058 0.00069 0.22 0.22 0.031 0.22 0.22 0.066 1.2e-08 1.2e-08 4.3e-09 9.4e-07 4e-06 4e-06 2.6e-07 0 0 0 0 0 0 0 0
72 6990000 0.98 -0.0064 -0.013 0.19 -0.00089 0.02 0.19 0.0011 0.013 0.12 -1.7e-05 -5.6e-05 6.9e-07 -2.7e-06 0 0 -0.0019 0.2 0.002 0.43 0 0 0 0 0 1.7e-05 2.3e-05 0.0003 0.0003 0.00048 0.00064 0.23 0.23 0.03 0.26 0.26 0.065 1.2e-08 1.2e-08 4.3e-09 8.9e-07 4e-06 4e-06 2.5e-07 0 0 0 0 0 0 0 0
73 7090000 0.98 -0.0063 -0.013 0.19 -0.0018 0.025 0.18 0.00095 0.016 0.13 -1.7e-05 -5.6e-05 7.1e-07 1.1e-07 0 0 -0.0018 0.2 0.002 0.43 0 0 0 0 0 1.5e-05 2.3e-05 0.00031 0.00031 0.00041 0.00063 0.25 0.25 0.029 0.31 0.31 0.065 1.2e-08 1.2e-08 4.3e-09 8.4e-07 4e-06 4e-06 2.3e-07 0 0 0 0 0 0 0 0
74 7190000 0.98 -0.0062 -0.013 0.19 -0.0022 0.027 0.18 0.00066 0.018 0.13 -1.7e-05 -5.6e-05 6.7e-07 -5.5e-06 0 0 -0.0018 0.2 0.002 0.43 0 0 0 0 0 1.3e-05 2.3e-05 0.00031 0.00031 0.00036 0.00062 0.27 0.27 0.028 0.36 0.36 0.064 1.2e-08 1.2e-08 4.3e-09 7.7e-07 4e-06 4e-06 2.2e-07 0 0 0 0 0 0 0 0
75 7290000 0.98 -0.0062 -0.013 0.19 -0.0013 0.031 0.18 0.00039 0.021 0.14 -1.7e-05 -5.6e-05 7e-07 -1.3e-06 0 0 -0.0018 0.2 0.002 0.43 0 0 0 0 0 1.2e-05 2.3e-05 0.00031 0.00032 0.00031 0.00032 0.00062 0.29 0.29 0.027 0.42 0.42 0.063 1.2e-08 1.2e-08 4.3e-09 6.9e-07 4e-06 4e-06 2.1e-07 0 0 0 0 0 0 0 0
76 7390000 0.98 -0.0061 -0.013 0.19 -0.003 0.034 0.17 0.00015 0.024 0.15 -1.7e-05 -5.6e-05 7.2e-07 3e-06 0 0 -0.0018 0.2 0.002 0.43 0 0 0 0 0 1.1e-05 2.3e-05 0.00032 0.00032 0.00029 0.00064 0.32 0.32 0.026 0.48 0.48 0.063 1.2e-08 1.2e-08 4.3e-09 6.2e-07 4e-06 4e-06 2e-07 0 0 0 0 0 0 0 0
77 7490000 0.98 -0.0061 -0.013 0.19 -0.00063 -0.00058 0.036 0.037 0.17 -3.1e-05 -1.8e-05 0.028 0.15 -1.7e-05 -5.6e-05 8.3e-07 1.6e-05 0 0 -0.0018 0.2 0.002 0.43 0 0 0 0 0 9.6e-06 2.3e-05 0.00033 0.00032 0.00033 0.00026 0.00063 0.35 0.35 0.026 0.56 0.56 0.062 1.2e-08 1.2e-08 4.3e-09 5.4e-07 4e-06 4e-06 1.8e-07 0 0 0 0 0 0 0 0
78 7590000 0.98 -0.0062 -0.0061 -0.013 0.19 0.00044 0.00051 0.039 0.17 -7.4e-05 -5.7e-05 0.031 0.16 -1.7e-05 -5.6e-05 8.6e-07 1.7e-05 0 0 -0.0018 0.2 0.002 0.43 0 0 0 0 0 8.8e-06 2.3e-05 0.00033 0.00033 0.00024 0.00062 0.38 0.38 0.025 0.64 0.64 0.061 1.2e-08 1.2e-08 4.3e-09 4.7e-07 4e-06 4e-06 1.7e-07 0 0 0 0 0 0 0 0
79 7690000 0.98 -0.0062 -0.013 0.19 0.00019 0.00025 0.043 0.17 -7.8e-05 -6e-05 0.035 0.17 -1.7e-05 -5.6e-05 8.5e-07 1.3e-05 0 0 -0.0018 0.2 0.002 0.43 0 0 0 0 0 8.2e-06 2.3e-05 0.00034 0.00034 0.00022 0.00062 0.41 0.41 0.024 0.73 0.73 0.061 1.2e-08 1.2e-08 4.3e-09 4.1e-07 4e-06 4e-06 1.6e-07 0 0 0 0 0 0 0 0
80 7790000 0.98 -0.0061 -0.006 -0.013 0.19 0.0019 0.045 0.16 -4.8e-05 -3.7e-05 0.039 0.16 -1.7e-05 -5.6e-05 8e-07 7.8e-06 0 0 -0.0017 0.2 0.002 0.43 0 0 0 0 0 7.7e-06 2.2e-05 0.00034 0.00034 0.00021 0.00061 0.45 0.45 0.023 0.83 0.83 0.06 1.2e-08 1.2e-08 4.3e-09 3.6e-07 4e-06 4e-06 1.6e-07 0 0 0 0 0 0 0 0
81 7890000 0.98 -0.0061 -0.013 0.19 0.0006 0.00063 0.049 0.15 -7.2e-05 -6.4e-05 0.044 0.16 -1.7e-05 -5.6e-05 7.7e-07 5.1e-06 0 0 -0.0017 0.2 0.002 0.43 0 0 0 0 0 7.2e-06 2.2e-05 0.00035 0.00035 0.0002 0.00059 0.49 0.49 0.022 0.95 0.95 0.059 1.2e-08 1.2e-08 4.3e-09 3.1e-07 4e-06 4e-06 1.5e-07 0 0 0 0 0 0 0 0
82 7990000 0.98 -0.006 -0.013 0.19 0.00096 0.001 0.052 0.15 -3.8e-05 -2.6e-05 0.048 0.16 -1.7e-05 -5.7e-05 8e-07 6e-06 0 0 -0.0017 0.2 0.002 0.43 0 0 0 0 0 6.8e-06 2.1e-05 0.00036 0.00036 0.00018 0.00057 0.53 0.53 0.54 0.022 1.1 1.1 0.058 1.2e-08 1.2e-08 4.3e-09 2.6e-07 4e-06 4e-06 1.4e-07 0 0 0 0 0 0 0 0
83 8090000 0.98 -0.0059 -0.013 0.19 0.0025 0.056 0.15 0.00011 9e-05 0.053 0.16 -1.7e-05 -5.7e-05 6e-07 -5.6e-06 0 0 -0.0017 0.2 0.002 0.43 0 0 0 0 0 6.4e-06 2.1e-05 0.00037 0.00037 0.00018 0.00056 0.59 0.59 0.021 1.2 1.2 0.058 1.2e-08 1.2e-08 4.3e-09 2.3e-07 4e-06 4e-06 1.3e-07 0 0 0 0 0 0 0 0
84 8190000 0.98 -0.0059 -0.006 -0.013 0.19 0.0032 0.0031 0.061 0.06 0.15 0.00033 0.00029 0.058 0.17 -1.7e-05 -5.7e-05 4.4e-07 -1.2e-05 0 0 -0.0017 0.2 0.002 0.43 0 0 0 0 0 6.1e-06 2e-05 0.00037 0.00037 0.00017 0.00054 0.63 0.63 0.02 1.4 1.4 0.057 1.2e-08 1.2e-08 4.2e-09 2e-07 4e-06 4e-06 1.3e-07 0 0 0 0 0 0 0 0
85 8290000 0.98 -0.0059 -0.013 0.19 0.0055 0.0053 0.065 0.14 0.0007 0.00065 0.064 0.17 -1.7e-05 -5.7e-05 4e-07 -1.2e-05 0 0 -0.0017 0.2 0.002 0.43 0 0 0 0 0 5.8e-06 1.9e-05 0.00038 0.00038 0.00016 0.00052 0.69 0.69 0.02 1.5 1.5 0.057 1.2e-08 1.2e-08 4.2e-09 1.8e-07 4e-06 4e-06 1.2e-07 0 0 0 0 0 0 0 0
86 8390000 0.98 -0.0059 -0.013 0.19 0.0034 0.0032 0.067 0.14 0.0011 0.001 0.071 0.07 0.17 -1.7e-05 -5.7e-05 3.6e-07 -1.2e-05 0 0 -0.0016 0.2 0.002 0.43 0 0 0 0 0 5.6e-06 1.9e-05 0.00039 0.00039 0.00015 0.00051 0.75 0.75 0.019 1.7 1.7 0.057 1.2e-08 1.2e-08 4.2e-09 1.6e-07 4e-06 4e-06 1.1e-07 0 0 0 0 0 0 0 0
87 8490000 0.98 -0.0058 -0.013 0.19 0.0033 0.0032 0.071 0.07 0.13 0.0014 0.0013 0.076 0.16 -1.7e-05 -5.7e-05 5.1e-07 -5.1e-06 0 0 -0.0016 0.2 0.002 0.43 0 0 0 0 0 5.4e-06 1.8e-05 0.0004 0.0004 0.00015 0.00049 0.81 0.81 0.019 1.9 1.9 0.056 1.1e-08 1.1e-08 4.2e-09 1.4e-07 4e-06 4e-06 1.1e-07 0 0 0 0 0 0 0 0
88 8590000 0.98 -0.0057 -0.013 0.19 0.0044 0.0043 0.074 0.073 0.13 0.0017 0.0016 0.083 0.17 -1.7e-05 -5.7e-05 4.3e-07 -6.8e-06 0 0 -0.0016 0.2 0.002 0.43 0 0 0 0 0 5.2e-06 1.7e-05 0.00041 0.00041 0.00014 0.00047 0.87 0.88 0.018 2.2 2.2 0.055 1.1e-08 1.1e-08 4.2e-09 1.2e-07 4e-06 4e-06 1e-07 0 0 0 0 0 0 0 0
89 8690000 0.98 -0.0058 -0.013 0.19 0.0045 0.0044 0.075 0.12 0.002 0.0019 0.088 0.16 -1.7e-05 -5.7e-05 4.8e-07 -4.7e-06 0 0 -0.0016 0.2 0.002 0.43 0 0 0 0 0 5.1e-06 1.7e-05 0.00042 0.00042 0.00014 0.00046 0.93 0.93 0.018 2.4 2.4 0.055 1.1e-08 1.1e-08 4.2e-09 1.1e-07 4e-06 4e-06 9.9e-08 0 0 0 0 0 0 0 0
90 8790000 0.98 -0.0057 -0.0058 -0.013 0.19 0.006 0.0058 0.078 0.12 0.0023 0.096 0.095 0.16 -1.7e-05 -5.7e-05 3e-07 -8e-06 0 0 -0.0016 0.2 0.002 0.43 0 0 0 0 0 4.9e-06 1.6e-05 0.00043 0.00043 0.00013 0.00044 1 1 0.017 2.7 2.7 0.054 1.1e-08 1.1e-08 4.1e-09 9.5e-08 4e-06 4e-06 9.4e-08 0 0 0 0 0 0 0 0
91 8890000 0.98 -0.0058 -0.013 0.19 0.006 0.08 0.12 0.0029 0.0028 0.1 0.17 -1.7e-05 -5.7e-05 4.9e-07 -3.2e-06 0 0 -0.0016 0.2 0.002 0.43 0 0 0 0 0 4.8e-06 1.6e-05 0.00043 0.00043 0.00013 0.00042 1.1 1.1 0.017 2.9 2.9 0.053 1.1e-08 1.1e-08 4.1e-09 8.5e-08 4e-06 4e-06 9e-08 0 0 0 0 0 0 0 0
92 8990000 0.98 -0.0057 -0.013 0.19 0.0052 0.0053 0.085 0.12 0.0033 0.11 0.16 -1.7e-05 -5.7e-05 7.5e-07 2e-06 0 0 -0.0016 0.2 0.002 0.43 0 0 0 0 0 4.7e-06 1.5e-05 0.00045 0.00045 0.00013 0.00042 1.1 1.1 0.016 3.3 3.3 0.053 1.1e-08 1.1e-08 4.1e-09 7.7e-08 4e-06 4e-06 8.6e-08 0 0 0 0 0 0 0 0
93 9090000 0.98 -0.0058 -0.0057 -0.013 0.19 0.0056 0.0057 0.088 0.11 0.0038 0.11 0.16 -1.7e-05 -5.7e-05 1e-06 6.9e-06 0 0 -0.0016 0.2 0.002 0.43 0 0 0 0 0 4.6e-06 1.5e-05 0.00045 0.00045 0.00012 0.0004 1.2 1.2 0.016 3.5 3.5 0.053 1.1e-08 1.1e-08 4.1e-09 6.9e-08 4e-06 4e-06 8.2e-08 0 0 0 0 0 0 0 0
94 9190000 0.98 -0.0058 -0.0057 -0.013 0.19 0.0093 0.0095 0.09 0.091 0.11 0.0045 0.0046 0.12 0.16 -1.7e-05 -5.7e-05 1.3e-06 1e-05 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4.5e-06 1.4e-05 0.00046 0.00046 0.00012 0.00039 1.3 1.3 0.016 3.9 3.9 0.052 1.1e-08 1.1e-08 4.1e-09 6.2e-08 4e-06 4e-06 7.9e-08 0 0 0 0 0 0 0 0
95 9290000 0.98 -0.0057 -0.0056 -0.013 0.19 0.012 0.091 0.1 0.0053 0.0055 0.12 0.13 0.16 -1.7e-05 -5.7e-05 1.4e-06 1.1e-05 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4.4e-06 1.4e-05 0.00046 0.00046 0.00012 0.00037 1.3 1.3 0.015 4.2 4.2 0.051 1.1e-08 1.1e-08 4e-09 5.5e-08 4e-06 4e-06 7.5e-08 0 0 0 0 0 0 0 0
96 9390000 0.98 -0.0056 -0.0055 -0.013 0.19 0.012 0.093 0.094 0.1 0.0064 0.0065 0.13 0.16 -1.7e-05 -5.7e-05 1.1e-06 6.5e-06 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4.3e-06 1.4e-05 0.00047 0.00047 0.00012 0.00037 1.4 1.4 0.015 4.7 4.7 0.051 1.1e-08 1.1e-08 4e-09 5.1e-08 4e-06 4e-06 7.2e-08 0 0 0 0 0 0 0 0
97 9490000 0.98 -0.0056 -0.013 0.19 0.011 0.012 0.092 0.093 0.097 0.0071 0.0072 0.14 0.16 -1.6e-05 -5.7e-05 1.3e-06 7.5e-06 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4.3e-06 1.3e-05 0.00047 0.00047 0.00011 0.00035 1.5 1.5 0.014 5 5 0.051 1e-08 1e-08 4e-09 4.6e-08 4e-06 4e-06 6.9e-08 0 0 0 0 0 0 0 0
98 9590000 0.98 -0.0057 -0.013 0.19 0.011 0.093 0.093 0.0079 0.14 0.15 -1.6e-05 -5.7e-05 7.3e-07 1e-06 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4.2e-06 1.3e-05 0.00048 0.00048 0.00011 0.00034 1.6 1.6 0.014 5.5 5.5 0.05 1e-08 1e-08 3.9e-09 4.2e-08 4e-06 4e-06 6.7e-08 0 0 0 0 0 0 0 0
99 9690000 0.98 -0.0057 -0.013 0.19 0.011 0.092 0.092 0.0085 0.0084 0.14 0.15 -1.6e-05 -5.7e-05 5.9e-07 -3.6e-07 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4.2e-06 1.2e-05 0.00047 0.00047 0.00011 0.00034 1.6 1.6 0.014 5.7 5.7 0.05 1e-08 1e-08 3.9e-09 3.9e-08 4e-06 4e-06 6.4e-08 0 0 0 0 0 0 0 0
100 9790000 0.98 -0.0057 -0.013 0.19 0.012 0.095 0.094 0.087 0.0093 0.0092 0.15 0.15 -1.6e-05 -5.7e-05 3.6e-08 -5.3e-06 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4.1e-06 1.2e-05 0.00049 0.00049 0.00011 0.00032 1.7 1.7 0.014 6.4 6.4 0.049 1e-08 1e-08 3.9e-09 3.5e-08 4e-06 4e-06 6.2e-08 0 0 0 0 0 0 0 0
101 9890000 0.98 -0.0058 -0.012 0.19 0.014 0.091 0.084 0.0098 0.15 0.14 -1.6e-05 -5.7e-05 1.7e-07 -3.6e-06 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4.1e-06 1.2e-05 0.00048 0.00048 0.00011 0.00031 1.7 1.7 0.013 6.6 6.6 0.049 9.9e-09 9.9e-09 3.8e-09 3.2e-08 4e-06 4e-06 5.9e-08 0 0 0 0 0 0 0 0
102 9990000 0.98 -0.0058 -0.013 0.19 0.016 0.093 0.092 0.082 0.011 0.16 0.14 -1.6e-05 -5.7e-05 -2.7e-07 -6.8e-06 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4.1e-06 1.2e-05 0.00049 0.00049 0.00011 0.00031 1.8 1.8 0.013 7.2 7.2 0.049 9.9e-09 9.9e-09 3.8e-09 3e-08 4e-06 4e-06 5.7e-08 0 0 0 0 0 0 0 0
103 10090000 0.98 -0.0058 -0.013 0.19 0.014 0.013 0.087 0.085 0.079 0.011 0.16 0.15 0.14 -1.6e-05 -5.8e-05 -8.1e-07 -1e-05 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4e-06 1.1e-05 0.00047 0.00047 0.00011 0.0003 1.8 1.8 0.013 7.4 7.4 0.048 9.6e-09 9.6e-09 3.7e-09 2.8e-08 4e-06 4e-06 5.5e-08 0 0 0 0 0 0 0 0
104 10190000 0.98 -0.0058 -0.013 0.19 0.012 0.011 0.089 0.087 0.077 0.012 0.16 0.13 -1.6e-05 -5.8e-05 -1.4e-06 -1.4e-05 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4e-06 1.1e-05 0.00049 0.00049 0.00011 0.00029 1.9 1.9 0.012 8.1 8.1 0.048 9.6e-09 9.6e-09 3.7e-09 2.5e-08 4e-06 4e-06 5.3e-08 0 0 0 0 0 0 0 0
105 10290000 0.98 -0.0059 -0.006 -0.012 0.19 0.012 0.011 0.084 0.083 0.073 0.012 0.16 0.13 -1.5e-05 -5.8e-05 -1.2e-06 -1.1e-05 0 0 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4e-06 1.1e-05 0.00047 0.00047 0.00011 0.00029 1.9 1.9 0.012 8.2 8.2 0.048 9.3e-09 9.3e-09 3.7e-09 2.4e-08 4e-06 4e-06 5.1e-08 0 0 0 0 0 0 0 0
106 10390000 0.98 -0.0059 -0.012 0.19 0.007 0.0069 0.0043 0.0042 -0.0063 0.00075 0.00011 0.12 -1.5e-05 -5.8e-05 -9.6e-07 -8.9e-06 1.5e-09 -1.1e-09 -0.0015 0.2 0.002 0.43 0 0 0 0 0 4e-06 1e-05 0.00048 0.00048 0.00011 0.00028 0.25 0.25 0.56 0.25 0.25 0.048 9.3e-09 9.3e-09 3.6e-09 2.2e-08 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
107 10490000 0.98 -0.0058 -0.0059 -0.012 0.19 0.0082 0.0058 0.0056 -0.01 0.0015 0.00058 0.00056 0.12 -1.5e-05 -5.8e-05 -1.4e-06 -1.1e-05 5.9e-09 -4.4e-09 -0.0014 0.2 0.002 0.43 0 0 0 0 0 4e-06 1e-05 0.0005 0.0005 0.00011 0.00027 0.26 0.26 0.55 0.26 0.26 0.057 9.3e-09 9.3e-09 3.6e-09 2e-08 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
108 10590000 0.98 -0.0058 -0.012 0.19 -0.0014 0.0037 0.0035 -0.0056 -0.0012 -0.0055 0.11 -1.5e-05 -5.8e-05 -1e-06 -8.1e-06 3.1e-06 -1.8e-07 -2e-07 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 9.9e-06 0.0005 0.0005 0.0001 0.00026 0.13 0.13 0.27 0.13 0.13 0.055 9.2e-09 9.2e-09 3.5e-09 1.9e-08 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
109 10690000 0.98 -0.0057 -0.012 0.19 -0.00039 -0.00045 0.004 0.0037 -0.012 -0.0013 -0.0051 0.11 -1.5e-05 -5.8e-05 -1.2e-06 -8.3e-06 3.1e-06 -1.9e-07 -2.2e-07 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 9.8e-06 0.00052 0.00052 0.0001 0.00026 0.14 0.14 0.26 0.14 0.14 0.065 9.2e-09 9.2e-09 3.5e-09 1.8e-08 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
110 10790000 0.98 -0.0058 -0.012 0.19 0.0014 0.00059 0.00037 -0.014 -0.00079 -0.0047 -0.0048 0.1 -1.5e-05 -5.8e-05 -1.2e-06 -7.8e-06 4.7e-06 4.6e-06 3.8e-06 3.7e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 9.5e-06 0.00051 0.00051 0.0001 0.00025 0.1 0.1 0.17 0.091 0.091 0.062 9e-09 9e-09 3.4e-09 1.6e-08 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
111 10890000 0.98 -0.0058 -0.012 0.19 0.0014 0.0032 0.003 -0.025 -0.00064 -0.0046 0.088 -1.5e-05 -5.8e-05 -5.4e-07 -4.4e-06 4.7e-06 3.8e-06 3.7e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 9.3e-06 0.00053 0.00053 0.0001 0.00025 0.12 0.12 0.16 0.098 0.098 0.068 9e-09 9e-09 3.4e-09 1.5e-08 4e-06 4e-06 5e-08 0 0 0 0 0 0 0 0
112 10990000 0.98 -0.0058 -0.013 0.19 0.00095 0.0009 0.0094 0.0092 -0.017 -0.00047 -0.0032 0.089 -1.5e-05 -5.8e-05 -7e-07 -4.9e-06 5.4e-06 5.3e-06 5.1e-06 5e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 9.2e-06 0.0005 0.0005 0.0001 0.00024 0.091 0.091 0.12 0.073 0.073 0.065 8.7e-09 8.7e-09 3.3e-09 1.5e-08 3.9e-06 3.9e-06 5e-08 0 0 0 0 0 0 0 0
113 11090000 0.98 -0.0059 -0.006 -0.012 0.19 0.0018 0.0017 0.014 0.013 -0.018 -0.00037 -0.00038 -0.0021 -0.0022 0.084 -1.5e-05 -5.8e-05 -1.3e-06 -7.1e-06 5.4e-06 5.3e-06 5.1e-06 4.9e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 9e-06 0.00052 0.00052 0.0001 0.00024 0.11 0.11 0.11 0.079 0.079 0.069 8.7e-09 8.7e-09 3.3e-09 1.4e-08 3.9e-06 3.9e-06 5e-08 0 0 0 0 0 0 0 0
114 11190000 0.98 -0.0062 -0.013 0.19 0.0035 0.0034 0.014 -0.0092 0.001 -0.002 0.087 -1.4e-05 -5.8e-05 -1.6e-06 -7.9e-06 4.2e-06 4e-06 1.3e-05 1.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.7e-06 0.00047 0.00047 0.0001 0.00023 0.09 0.09 0.083 0.063 0.063 0.066 8.1e-09 8.1e-09 3.2e-09 1.3e-08 3.8e-06 3.8e-06 5e-08 0 0 0 0 0 0 0 0
115 11290000 0.98 -0.0061 -0.0062 -0.013 0.19 0.0035 0.0034 0.014 -0.012 0.0013 -0.00055 -0.00062 0.08 -1.4e-05 -5.8e-05 -1.8e-06 -8.2e-06 4.2e-06 4e-06 1.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.7e-06 0.00048 0.00048 0.0001 0.00023 0.11 0.11 0.077 0.07 0.07 0.069 8.1e-09 8.1e-09 3.2e-09 1.2e-08 3.8e-06 3.8e-06 5e-08 0 0 0 0 0 0 0 0
116 11390000 0.98 -0.0062 -0.012 0.19 0.002 0.013 0.012 -0.019 0.00084 -0.0011 0.068 -1.4e-05 -5.8e-05 -1.7e-06 -7.5e-06 8.5e-06 8.2e-06 1.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.4e-06 0.00043 0.00043 0.0001 0.00022 0.091 0.091 0.062 0.057 0.057 0.066 7.5e-09 7.5e-09 3.1e-09 1.1e-08 3.7e-06 3.7e-06 5e-08 0 0 0 0 0 0 0 0
117 11490000 0.98 -0.0062 -0.012 0.19 0.001 0.00094 0.013 -0.016 0.00093 0.00092 0.00026 0.0002 0.068 -1.4e-05 -5.8e-05 -1.6e-06 -6.7e-06 8.4e-06 8.2e-06 1.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.3e-06 0.00044 0.00044 0.0001 0.00022 0.11 0.11 0.057 0.065 0.065 0.067 7.5e-09 7.5e-09 3.1e-09 1.1e-08 3.7e-06 3.7e-06 5e-08 0 0 0 0 0 0 0 0
118 11590000 0.98 -0.0064 -0.012 0.19 0.0029 0.011 -0.016 0.0008 -0.0005 -0.00053 0.065 -1.3e-05 -5.9e-05 -1.6e-06 -6.4e-06 1.1e-05 2.4e-05 2.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8.2e-06 0.00038 0.00038 0.0001 0.00022 0.091 0.091 0.048 0.054 0.054 0.065 6.9e-09 6.9e-09 3e-09 1e-08 3.7e-06 3.7e-06 5e-08 0 0 0 0 0 0 0 0
119 11690000 0.98 -0.0064 -0.012 0.19 0.0033 0.0032 0.014 -0.016 0.0011 0.00073 0.00069 0.058 -1.3e-05 -5.9e-05 -1.4e-06 -5.5e-06 1.1e-05 2.4e-05 2.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 8e-06 0.00039 0.00039 0.0001 0.00021 0.11 0.11 0.044 0.062 0.062 0.066 6.9e-09 6.9e-09 3e-09 9.5e-09 3.7e-06 3.7e-06 5e-08 0 0 0 0 0 0 0 0
120 11790000 0.98 -0.0067 -0.012 0.19 0.0021 0.0092 0.0091 -0.013 0.00068 -0.0018 0.06 -1.3e-05 -5.9e-05 -7.7e-07 -3.3e-06 1.6e-05 3.3e-05 3.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 7.8e-06 0.00034 0.00034 0.0001 0.00021 0.088 0.088 0.037 0.052 0.052 0.063 6.4e-09 6.4e-09 2.9e-09 9e-09 3.6e-06 3.6e-06 5e-08 0 0 0 0 0 0 0 0
121 11890000 0.98 -0.0068 -0.012 0.19 0.0047 0.01 -0.015 0.00096 -0.00089 -0.0009 0.056 -1.3e-05 -5.9e-05 -8.8e-07 -3.5e-06 1.6e-05 3.3e-05 3.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 7.7e-06 0.00035 0.00035 0.0001 0.0002 0.11 0.11 0.034 0.06 0.06 0.063 6.4e-09 6.4e-09 2.9e-09 8.5e-09 3.6e-06 3.6e-06 5e-08 0 0 0 0 0 0 0 0
122 11990000 0.98 -0.0069 -0.012 0.19 0.0077 0.011 -0.015 0.0021 -0.0018 0.051 -1.2e-05 -5.9e-05 -6.7e-07 -2.8e-06 1.5e-05 3.4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 7.6e-06 0.0003 0.0003 0.0001 0.0002 0.085 0.085 0.03 0.051 0.051 0.061 5.9e-09 5.9e-09 2.8e-09 8.1e-09 3.6e-06 3.6e-06 5e-08 0 0 0 0 0 0 0 0
123 12090000 0.98 -0.0069 -0.012 0.19 0.0092 0.011 -0.011 0.0029 -0.00079 -0.0008 0.054 -1.2e-05 -5.9e-05 -6.8e-07 -2.7e-06 1.5e-05 3.5e-05 3.4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 7.4e-06 0.00031 0.00031 0.0001 0.0002 0.1 0.1 0.027 0.059 0.059 0.06 5.9e-09 5.9e-09 2.8e-09 7.6e-09 3.6e-06 3.6e-06 5e-08 0 0 0 0 0 0 0 0
124 12190000 0.98 -0.0067 -0.012 0.19 0.0075 0.0074 0.01 -0.01 0.0018 0.00035 0.055 -1.3e-05 -5.9e-05 -9.2e-07 -3.2e-06 1.7e-05 3.4e-05 3.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 7.3e-06 0.00027 0.00027 0.0001 0.00019 0.08 0.08 0.024 0.05 0.05 0.058 5.5e-09 5.5e-09 2.7e-09 7.2e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
125 12290000 0.98 -0.0068 -0.012 0.19 0.0051 0.0095 0.0094 -0.011 0.0024 0.0014 0.0013 0.054 -1.3e-05 -5.9e-05 -1.1e-06 -3.6e-06 1.7e-05 3.4e-05 3.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 7.2e-06 0.00028 0.00028 0.0001 0.00019 0.095 0.095 0.022 0.059 0.059 0.058 5.5e-09 5.5e-09 2.7e-09 6.9e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
126 12390000 0.98 -0.0069 -0.012 0.19 0.0038 0.0065 0.0064 -0.011 0.0017 0.00048 0.00047 0.047 -1.2e-05 -6e-05 -1.1e-06 -3.6e-06 1.9e-05 3.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 7e-06 0.00025 0.00025 0.0001 0.00019 0.076 0.076 0.02 0.05 0.05 0.056 5.2e-09 5.2e-09 2.6e-09 6.6e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
127 12490000 0.98 -0.0069 -0.012 0.19 0.0037 0.0075 0.0074 -0.0056 0.0021 0.0012 0.047 -1.2e-05 -6e-05 -1.2e-06 -3.6e-06 1.9e-05 3.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 6.9e-06 0.00026 0.00026 0.0001 0.00018 0.089 0.089 0.018 0.058 0.058 0.055 5.2e-09 5.2e-09 2.6e-09 6.2e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
128 12590000 0.98 -0.0071 -0.012 0.19 0.0075 0.0011 0.001 -0.0026 0.0033 -0.0013 0.049 -1.2e-05 -6e-05 -1.2e-06 -3.6e-06 1.9e-05 3.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 6.8e-06 0.00023 0.00023 0.0001 0.00018 0.071 0.071 0.017 0.049 0.049 0.054 4.9e-09 4.9e-09 2.5e-09 6e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
129 12690000 0.98 -0.007 -0.012 0.19 0.008 -0.001 -0.0011 -0.0019 0.004 -0.0013 0.049 -1.2e-05 -6e-05 -1.2e-06 -3.4e-06 1.9e-05 3.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 6.7e-06 0.00024 0.00024 0.0001 0.00018 0.082 0.082 0.016 0.058 0.058 0.053 4.9e-09 4.9e-09 2.5e-09 5.7e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
130 12790000 0.98 -0.0073 -0.012 0.19 0.0096 -0.0042 -0.0043 0.0011 0.0041 -0.0044 0.051 -1.1e-05 -6e-05 -3.8e-07 -1.5e-06 1.9e-05 4.1e-05 4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 6.6e-06 0.00022 0.00022 0.0001 0.00018 0.067 0.067 0.014 0.049 0.049 0.052 4.6e-09 4.6e-09 2.4e-09 5.4e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
131 12890000 0.98 -0.0073 -0.012 0.19 0.0097 -0.0051 0.0031 0.0051 -0.0049 -0.0048 0.053 -1.1e-05 -6e-05 1.4e-07 -2.6e-07 1.9e-05 4.1e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.9e-06 6.5e-06 0.00023 0.00023 0.0001 0.00017 0.077 0.077 0.013 0.057 0.057 0.051 4.6e-09 4.6e-09 2.4e-09 5.2e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
132 12990000 0.98 -0.0072 -0.012 0.19 0.0077 -0.003 0.0047 0.0036 -0.0036 -0.0035 0.054 -1.1e-05 -6e-05 6.2e-07 7.8e-07 1.9e-05 2e-05 4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 6.4e-06 0.00021 0.00021 0.0001 0.00017 0.063 0.063 0.012 0.049 0.049 0.05 4.4e-09 4.4e-09 2.3e-09 4.9e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
133 13090000 0.98 -0.0073 -0.012 0.19 0.0085 -0.0029 0.0034 0.0044 -0.0038 0.052 -1.1e-05 -6e-05 1.3e-06 2.1e-06 2e-05 4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 6.3e-06 0.00022 0.00022 0.0001 0.00017 0.072 0.072 0.012 0.057 0.057 0.049 4.4e-09 4.4e-09 2.3e-09 4.7e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
134 13190000 0.98 -0.0073 -0.012 0.19 0.0036 0.0035 -0.0045 0.0039 0.00097 -0.0045 0.053 -1.1e-05 -6e-05 1.7e-06 2.8e-06 2.1e-05 4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 6.2e-06 0.00021 0.00021 0.0001 0.00017 0.059 0.059 0.011 0.049 0.049 0.047 4.2e-09 4.2e-09 2.2e-09 4.5e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
135 13290000 0.98 -0.0073 -0.012 0.19 0.0031 -0.0054 -0.0053 0.0023 0.0013 -0.005 0.051 0.052 -1.1e-05 -6e-05 1.7e-06 2.9e-06 2.1e-05 3.9e-05 4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 6.1e-06 0.00021 0.00021 0.0001 0.00016 0.067 0.067 0.01 0.057 0.057 0.047 4.2e-09 4.2e-09 2.2e-09 4.3e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
136 13390000 0.98 -0.0072 -0.012 0.19 0.0023 -0.0034 -0.0033 0.0033 0.00085 0.00086 -0.0037 0.052 -1.2e-05 -6e-05 1.5e-06 2.4e-06 2.1e-05 3.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 6e-06 0.0002 0.0002 0.0001 0.00016 0.056 0.056 0.0097 0.049 0.049 0.046 4e-09 4e-09 2.1e-09 4.1e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
137 13490000 0.98 -0.0072 -0.012 0.19 0.0027 -0.0016 0.0037 0.0011 -0.0039 0.048 -1.2e-05 -6e-05 1.7e-06 2.7e-06 2.1e-05 2.2e-05 3.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 5.9e-06 0.00021 0.00021 0.0001 0.00016 0.064 0.064 0.0093 0.056 0.056 0.045 4e-09 4e-09 2.1e-09 4e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
138 13590000 0.98 -0.0072 -0.012 0.19 0.0072 -0.0018 0.0063 0.004 -0.0032 0.047 -1.1e-05 -6e-05 1.5e-06 2.4e-06 2.3e-05 3.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 5.9e-06 0.0002 0.0002 0.0001 0.00016 0.053 0.053 0.0089 0.048 0.048 0.044 3.8e-09 3.8e-09 2e-09 3.8e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
139 13690000 0.98 -0.0071 -0.012 0.19 0.0071 -0.0032 0.0074 0.0047 -0.0034 0.049 -1.1e-05 -6e-05 1.9e-06 3e-06 2.2e-05 2.3e-05 3.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 5.8e-06 0.0002 0.0002 0.0001 0.00015 0.06 0.06 0.0085 0.056 0.056 0.044 3.8e-09 3.8e-09 2e-09 3.7e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
140 13790000 0.98 -0.0071 -0.012 0.19 0.014 0.00098 0.001 0.0084 0.0083 -0.00094 -0.00092 0.049 -1.2e-05 -5.9e-05 1.7e-06 2.7e-06 2.5e-05 3.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 5.7e-06 0.0002 0.0002 0.0001 0.00015 0.051 0.051 0.0082 0.048 0.048 0.043 3.6e-09 3.6e-09 1.9e-09 3.5e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
141 13890000 0.98 -0.007 -0.012 0.19 0.015 0.0018 0.01 0.0097 -0.00079 -0.00077 0.051 -1.2e-05 -5.9e-05 2.2e-06 3.4e-06 2.5e-05 3.8e-05 3.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 5.6e-06 0.0002 0.0002 0.0001 0.00015 0.057 0.057 0.008 0.056 0.056 0.042 3.6e-09 3.6e-09 1.9e-09 3.4e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
142 13990000 0.98 -0.0071 -0.012 0.19 0.015 0.0019 0.01 0.0073 -0.0023 0.051 -1.1e-05 -6e-05 2.6e-06 4.1e-06 2.3e-05 2.4e-05 3.7e-05 3.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 5.5e-06 0.00019 0.00019 0.0001 0.00015 0.048 0.048 0.0077 0.048 0.048 0.041 3.4e-09 3.5e-09 1.9e-09 3.2e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
143 14090000 0.98 -0.0071 -0.012 0.19 0.012 -0.0024 0.012 0.0088 -0.0023 0.047 -1.1e-05 -6e-05 1.6e-06 2.4e-06 2.4e-05 3.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 5.5e-06 0.0002 0.0002 0.0001 0.00015 0.055 0.055 0.0076 0.055 0.055 0.041 3.4e-09 3.5e-09 1.8e-09 3.1e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
144 14190000 0.98 -0.007 -0.011 0.19 0.0095 -0.0011 0.013 0.008 -0.0017 0.048 -1.2e-05 -6e-05 1.2e-06 1.6e-06 2.5e-05 3.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.8e-06 5.4e-06 0.00019 0.00019 0.0001 0.00015 0.047 0.047 0.0074 0.048 0.048 0.04 3.3e-09 3.3e-09 1.8e-09 3e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
145 14290000 0.98 -0.007 -0.011 0.19 0.011 -0.0011 0.012 0.0089 -0.0019 0.052 -1.2e-05 -6e-05 1.2e-06 1.6e-06 2.4e-05 3.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 5.3e-06 0.0002 0.0002 0.0001 0.00014 0.053 0.053 0.0073 0.055 0.055 0.04 3.3e-09 3.3e-09 1.7e-09 2.9e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
146 14390000 0.98 -0.0071 -0.011 0.19 0.011 -0.0041 0.014 0.0084 -0.0031 -0.003 0.057 -1.1e-05 -6e-05 1.5e-06 2.1e-06 2.3e-05 3.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 5.3e-06 0.00019 0.00019 0.0001 0.00014 0.045 0.045 0.0071 0.048 0.048 0.039 3.1e-09 3.1e-09 1.7e-09 2.8e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
147 14490000 0.98 -0.0072 -0.011 0.19 0.0095 -0.0038 0.019 0.0094 -0.0035 0.06 -1.1e-05 -6e-05 1e-06 1.3e-06 2.2e-05 2.3e-05 3.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 5.2e-06 0.0002 0.0002 0.0001 0.00014 0.051 0.051 0.0071 0.055 0.055 0.038 3.1e-09 3.1e-09 1.7e-09 2.7e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
148 14590000 0.98 -0.0072 -0.011 0.19 0.0074 -0.0039 0.017 0.0058 -0.0041 0.056 -1.2e-05 -6e-05 9.3e-07 1.1e-06 2e-05 3.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 5.1e-06 0.00019 0.00019 0.0001 0.00014 0.044 0.044 0.007 0.047 0.047 0.038 2.9e-09 2.9e-09 1.6e-09 2.6e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
149 14690000 0.98 -0.0072 -0.011 0.19 0.0065 -0.0038 0.018 0.0065 -0.0045 0.057 -1.2e-05 -6e-05 1.1e-06 1.4e-06 2.1e-05 3.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 5.1e-06 0.0002 0.0002 0.0001 0.00014 0.05 0.05 0.007 0.054 0.054 0.037 2.9e-09 2.9e-09 1.6e-09 2.5e-09 3.5e-06 3.5e-06 5e-08 0 0 0 0 0 0 0 0
150 14790000 0.98 -0.0071 -0.011 0.19 0.0082 0.0031 0.0032 0.019 0.0052 0.00085 0.06 -1.2e-05 -6e-05 1.7e-06 2.2e-06 2.1e-05 4.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 5e-06 0.00019 0.00019 9.9e-05 0.00013 0.043 0.043 0.0069 0.047 0.047 0.037 2.7e-09 2.7e-09 1.6e-09 2.4e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
151 14890000 0.98 -0.0071 -0.011 0.19 0.0068 0.00084 0.00087 0.024 0.0059 0.0011 0.062 -1.2e-05 -6e-05 2.1e-06 2.8e-06 2.1e-05 4.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 5e-06 0.00019 0.00019 9.9e-05 0.00013 0.048 0.048 0.007 0.054 0.054 0.037 2.7e-09 2.7e-09 1.5e-09 2.3e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
152 14990000 0.98 -0.0072 -0.011 0.19 0.0056 -0.00083 -0.0008 0.027 0.0047 -0.00061 -0.0006 0.064 -1.2e-05 -6.1e-05 2.3e-06 3.2e-06 2e-05 4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.7e-06 4.9e-06 0.00019 0.00019 9.9e-05 0.00013 0.042 0.042 0.0069 0.047 0.047 0.036 2.6e-09 2.6e-09 1.5e-09 2.2e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
153 15090000 0.98 -0.0072 -0.011 0.19 0.0056 0.00034 0.00037 0.032 0.0052 -0.00067 -0.00066 0.068 -1.2e-05 -6.1e-05 2.3e-06 3.1e-06 2e-05 4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 4.8e-06 0.00019 0.00019 9.8e-05 0.00013 0.047 0.047 0.007 0.054 0.054 0.036 2.6e-09 2.6e-09 1.4e-09 2.2e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
154 15190000 0.98 -0.0073 -0.011 0.19 0.0038 -0.00077 -0.00075 0.033 0.0041 -0.00066 -0.00065 0.07 -1.2e-05 -6.1e-05 2.1e-06 2.8e-06 1.9e-05 4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 4.8e-06 0.00018 0.00018 9.8e-05 0.00013 0.041 0.041 0.007 0.047 0.047 0.036 2.4e-09 2.4e-09 1.4e-09 2.1e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
155 15290000 0.98 -0.0074 -0.011 0.19 0.0043 -0.0018 -0.0017 0.033 0.0046 -0.00076 -0.00075 0.067 -1.2e-05 -6.1e-05 2.5e-06 3.4e-06 2.2e-05 3.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 4.7e-06 0.00019 0.00019 9.7e-05 0.00013 0.046 0.046 0.0071 0.054 0.054 0.035 2.4e-09 2.4e-09 1.4e-09 2e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
156 15390000 0.98 -0.0075 -0.011 0.19 0.0046 0.00058 0.00061 0.034 0.0037 -0.00052 -0.00051 0.068 -1.2e-05 -6.1e-05 2.5e-06 3.3e-06 2.2e-05 2.3e-05 3.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 4.7e-06 0.00018 0.00018 9.7e-05 0.00013 0.041 0.041 0.0071 0.047 0.047 0.035 2.2e-09 2.2e-09 1.4e-09 2e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
157 15490000 0.98 -0.0075 -0.011 0.19 0.0039 -0.0019 -0.0018 0.034 0.0041 -0.00056 -0.00055 0.07 -1.2e-05 -6.1e-05 2.5e-06 3.2e-06 2.3e-05 2.4e-05 3.6e-05 3.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 4.6e-06 0.00019 0.00019 9.7e-05 0.00012 0.046 0.046 0.0072 0.053 0.053 0.035 2.2e-09 2.2e-09 1.3e-09 1.9e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
158 15590000 0.98 -0.0077 -0.011 0.19 0.0075 -0.0058 -0.0057 0.034 0.0061 -0.0046 -0.0045 0.069 -1.1e-05 -6.1e-05 2.7e-06 3.6e-06 2.7e-05 2.5e-05 2.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 4.6e-06 0.00018 0.00018 9.6e-05 0.00012 0.04 0.04 0.0072 0.047 0.047 0.035 2.1e-09 2.1e-09 1.3e-09 1.8e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
159 15690000 0.98 -0.0077 -0.011 0.19 0.0092 -0.0088 -0.0087 0.036 0.007 -0.0053 0.071 -1.1e-05 -6.1e-05 3.1e-06 4e-06 2.7e-05 2.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.6e-06 4.5e-06 0.00018 0.00018 9.6e-05 0.00012 0.045 0.045 0.0073 0.053 0.053 0.034 2.1e-09 2.1e-09 1.3e-09 1.8e-09 3.4e-06 3.4e-06 5e-08 0 0 0 0 0 0 0 0
160 15790000 0.98 -0.0077 -0.011 0.19 0.0058 -0.0081 0.036 0.0054 -0.0041 0.073 -1.2e-05 -6.1e-05 3.6e-06 4.7e-06 2.6e-05 2.7e-05 2.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.5e-06 4.5e-06 0.00018 0.00017 9.5e-05 0.00012 0.039 0.039 0.0073 0.046 0.046 0.034 1.9e-09 1.9e-09 1.2e-09 1.7e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
161 15890000 0.98 -0.0077 -0.011 0.19 0.0046 -0.0065 -0.0064 0.037 0.0059 -0.0049 -0.0048 0.073 -1.2e-05 -6.1e-05 3.2e-06 4.1e-06 2.9e-05 2.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.5e-06 4.4e-06 0.00018 0.00018 9.5e-05 0.00012 0.044 0.044 0.0074 0.053 0.053 0.034 1.9e-09 1.9e-09 1.2e-09 1.7e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
162 15990000 0.98 -0.0075 -0.011 0.19 0.0027 -0.0051 -0.005 0.035 0.0047 -0.0038 -0.0037 0.073 -1.2e-05 -6.1e-05 3.2e-06 4.1e-06 3.1e-05 2.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.5e-06 4.4e-06 0.00017 0.00017 9.5e-05 0.00012 0.039 0.039 0.0074 0.046 0.046 0.034 1.7e-09 1.7e-09 1.2e-09 1.6e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
163 16090000 0.98 -0.0075 -0.011 0.19 0.002 -0.0063 -0.0062 0.033 0.0049 -0.0043 0.074 -1.2e-05 -6.1e-05 2.9e-06 3.7e-06 3.3e-05 2.4e-05 2.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.5e-06 4.3e-06 0.00018 0.00018 9.4e-05 0.00012 0.044 0.044 0.0076 0.053 0.053 0.034 1.7e-09 1.7e-09 1.2e-09 1.6e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
164 16190000 0.98 -0.0074 -0.011 0.19 -0.0019 -0.004 -0.0039 0.032 0.0026 -0.0032 0.071 -1.2e-05 -6.1e-05 2.7e-06 3.3e-06 3.4e-05 2.4e-05 2.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.5e-06 4.3e-06 0.00017 0.00017 9.4e-05 0.00012 0.038 0.038 0.0076 0.046 0.046 0.034 1.6e-09 1.6e-09 1.1e-09 1.5e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
165 16290000 0.98 -0.0075 -0.011 0.19 -0.0016 -0.0054 0.033 0.0024 -0.0037 0.074 -1.2e-05 -6.1e-05 2.8e-06 3.5e-06 3.5e-05 2.4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 4.2e-06 0.00017 0.00017 9.3e-05 0.00011 0.043 0.043 0.0077 0.053 0.053 0.034 1.6e-09 1.6e-09 1.1e-09 1.5e-09 3.3e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
166 16390000 0.98 -0.0074 -0.011 0.19 0.00091 0.00092 -0.0048 0.033 0.0035 -0.0028 0.074 -1.2e-05 -6.1e-05 3.1e-06 3.8e-06 4.1e-05 2.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 4.2e-06 0.00016 0.00016 9.3e-05 0.00011 0.038 0.038 0.0077 0.046 0.046 0.034 1.5e-09 1.5e-09 1.1e-09 1.4e-09 3.2e-06 3.3e-06 5e-08 0 0 0 0 0 0 0 0
167 16490000 0.98 -0.0075 -0.011 0.19 0.0028 -0.0063 0.036 0.0037 -0.0034 0.079 -1.2e-05 -6.1e-05 3e-06 3.7e-06 4e-05 2.3e-05 2.4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 4.2e-06 0.00017 0.00017 9.3e-05 0.00011 0.043 0.043 0.0079 0.053 0.053 0.034 1.5e-09 1.5e-09 1.1e-09 1.4e-09 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
168 16590000 0.98 -0.0075 -0.011 0.19 0.007 -0.0064 0.04 0.0032 -0.0027 0.08 -1.2e-05 -6.1e-05 3e-06 3.6e-06 4.2e-05 2.4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 4.1e-06 0.00016 0.00016 9.2e-05 0.00011 0.037 0.037 0.0079 0.046 0.046 0.034 1.3e-09 1.3e-09 1e-09 1.4e-09 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
169 16690000 0.98 -0.0076 -0.011 0.19 0.0084 -0.011 0.041 0.004 -0.0035 0.081 -1.2e-05 -6.1e-05 3.1e-06 3.9e-06 4.3e-05 4.4e-05 2.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 4.1e-06 0.00016 0.00016 9.1e-05 0.00011 0.042 0.042 0.008 0.052 0.052 0.034 1.3e-09 1.3e-09 1e-09 1.3e-09 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
170 16790000 0.98 -0.0074 -0.011 0.19 0.0093 -0.0099 -0.0098 0.04 0.0031 0.0032 -0.0025 0.082 -1.3e-05 -6.1e-05 3.3e-06 4e-06 4.5e-05 2.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.4e-06 4e-06 0.00016 0.00015 9.1e-05 0.00011 0.037 0.037 0.008 0.046 0.046 0.034 1.2e-09 1.2e-09 9.9e-10 1.3e-09 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
171 16890000 0.98 -0.0074 -0.011 0.19 0.0083 -0.01 0.041 0.004 0.0041 -0.0035 0.081 -1.3e-05 -6.1e-05 3.7e-06 4.5e-06 4.8e-05 2.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.3e-06 4e-06 0.00016 0.00016 9.1e-05 0.00011 0.041 0.041 0.0082 0.052 0.052 0.034 1.2e-09 1.2e-09 9.7e-10 1.2e-09 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
172 16990000 0.98 -0.0074 -0.011 0.19 0.0081 -0.0097 0.041 0.0039 -0.0026 0.08 -1.3e-05 -6.1e-05 3.8e-06 4.6e-06 5.4e-05 5.5e-05 2.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.3e-06 3.9e-06 0.00015 0.00015 9e-05 0.00011 0.036 0.036 0.0082 0.046 0.046 0.034 1.1e-09 1.1e-09 9.5e-10 1.2e-09 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
173 17090000 0.98 -0.0075 -0.011 0.19 0.0096 -0.012 0.041 0.0048 0.0049 -0.0038 0.08 -1.3e-05 -6.1e-05 3.7e-06 4.4e-06 5.7e-05 1.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.3e-06 3.9e-06 0.00015 0.00015 8.9e-05 0.00011 0.04 0.04 0.0083 0.052 0.052 0.034 1.1e-09 1.1e-09 9.3e-10 1.2e-09 3.2e-06 3.2e-06 5e-08 0 0 0 0 0 0 0 0
174 17190000 0.98 -0.0076 -0.011 0.19 0.0085 -0.018 -0.017 0.043 0.0032 -0.0073 0.084 -1.3e-05 -6.1e-05 3.2e-06 3.9e-06 5.6e-05 1.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.3e-06 3.9e-06 0.00015 0.00015 8.9e-05 0.00011 0.036 0.036 0.0083 0.046 0.046 0.034 9.9e-10 9.9e-10 9.1e-10 1.1e-09 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
175 17290000 0.98 -0.0076 -0.011 0.19 0.0094 -0.018 0.043 0.0042 -0.0091 -0.009 0.084 -1.3e-05 -6.1e-05 2.9e-06 3.5e-06 5.9e-05 1.4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.3e-06 3.8e-06 0.00015 0.00015 8.9e-05 0.0001 0.04 0.04 0.0084 0.052 0.052 0.034 9.9e-10 9.9e-10 8.9e-10 1.1e-09 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
176 17390000 0.98 -0.0075 -0.011 0.19 0.0062 -0.018 0.042 0.0056 -0.0057 0.084 -1.3e-05 -6e-05 3.2e-06 3.8e-06 6.7e-05 6.8e-05 1.8e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 3.8e-06 0.00014 0.00014 8.8e-05 0.0001 0.035 0.035 0.0084 0.046 0.046 0.034 8.9e-10 8.9e-10 8.7e-10 1.1e-09 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
177 17490000 0.98 -0.0075 -0.011 0.19 0.0043 -0.018 0.042 0.0061 -0.0075 0.087 -1.3e-05 -6e-05 3.1e-06 3.6e-06 6.9e-05 1.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 3.8e-06 0.00015 0.00014 8.8e-05 0.0001 0.039 0.039 0.0085 0.052 0.052 0.034 8.9e-10 8.9e-10 8.5e-10 1.1e-09 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
178 17590000 0.98 -0.0074 -0.011 0.19 0.00051 0.00053 -0.014 0.042 0.0023 0.0024 -0.0056 0.085 -1.4e-05 -1.3e-05 -6.1e-05 3.1e-06 3.6e-06 6.9e-05 2.1e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 3.7e-06 0.00014 0.00014 8.7e-05 0.0001 0.034 0.034 0.0085 0.046 0.046 0.034 8.1e-10 8.1e-10 8.3e-10 1e-09 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
179 17690000 0.98 -0.0075 -0.011 0.19 -0.00045 -0.00042 -0.015 0.043 0.0024 -0.0071 0.088 -1.4e-05 -1.3e-05 -6.1e-05 3.1e-06 3.6e-06 6.9e-05 7e-05 2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 3.7e-06 0.00014 0.00014 8.7e-05 0.0001 0.038 0.038 0.0086 0.052 0.052 0.034 8.1e-10 8.1e-10 8.2e-10 1e-09 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
180 17790000 0.98 -0.0074 -0.011 0.19 0.0023 -0.013 0.044 0.0034 -0.006 0.094 -1.4e-05 -6e-05 3.1e-06 3.6e-06 7.4e-05 2.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 3.7e-06 0.00013 0.00013 8.7e-05 0.0001 0.034 0.034 0.0086 0.046 0.046 0.034 7.3e-10 7.3e-10 8e-10 9.8e-10 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
181 17890000 0.98 -0.0074 -0.011 0.19 0.0044 -0.015 0.044 0.0038 -0.0074 0.099 -1.4e-05 -6e-05 3.2e-06 3.8e-06 7.3e-05 7.4e-05 2.6e-05 2.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.2e-06 3.6e-06 0.00014 0.00014 8.6e-05 9.9e-05 0.037 0.037 0.0086 0.052 0.052 0.035 7.3e-10 7.3e-10 7.8e-10 9.5e-10 3.1e-06 3.1e-06 5e-08 0 0 0 0 0 0 0 0
182 17990000 0.98 -0.0071 -0.011 0.19 0.0038 -0.0085 0.043 0.003 -0.0017 0.099 -1.4e-05 -6e-05 3.2e-06 3.7e-06 7.8e-05 7.9e-05 3.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 3.6e-06 0.00013 0.00013 8.5e-05 9.8e-05 0.033 0.033 0.0086 0.045 0.045 0.034 6.6e-10 6.6e-10 7.7e-10 9.3e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
183 18090000 0.98 -0.0072 -0.011 0.19 0.0033 -0.009 0.043 0.0035 -0.0027 0.098 -1.4e-05 -6e-05 3.1e-06 3.6e-06 8.2e-05 3.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 3.6e-06 0.00013 0.00013 8.5e-05 9.8e-05 0.036 0.036 0.0087 0.052 0.052 0.035 6.6e-10 6.6e-10 7.5e-10 9.1e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
184 18190000 0.98 -0.0073 -0.011 0.19 0.0034 -0.0081 0.043 0.0041 -0.0019 0.096 -1.5e-05 -1.4e-05 -6e-05 3.6e-06 4.1e-06 8.8e-05 3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 3.5e-06 0.00013 0.00013 8.5e-05 9.7e-05 0.032 0.032 0.0086 0.045 0.045 0.035 6e-10 6e-10 7.4e-10 8.8e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
185 18290000 0.98 -0.0073 -0.011 0.19 0.0043 -0.0085 0.042 0.0044 0.0045 -0.0028 0.095 -1.4e-05 -6e-05 3.6e-06 4.1e-06 9.1e-05 9.2e-05 2.8e-05 2.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 3.5e-06 0.00013 0.00013 8.4e-05 9.6e-05 0.036 0.036 0.0087 0.051 0.051 0.035 6e-10 6e-10 7.2e-10 8.6e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
186 18390000 0.98 -0.0072 -0.011 0.19 0.0053 -0.0073 0.041 0.0061 -0.0021 0.095 -1.5e-05 -6e-05 3.4e-06 3.9e-06 9.8e-05 2.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 3.5e-06 0.00012 0.00012 8.4e-05 9.5e-05 0.031 0.031 0.0086 0.045 0.045 0.035 5.4e-10 5.4e-10 7.1e-10 8.4e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
187 18490000 0.98 -0.0073 -0.011 0.19 0.008 -0.0073 0.041 0.0069 -0.0029 -0.0028 0.097 -1.5e-05 -6e-05 3.6e-06 4e-06 9.9e-05 2.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3.1e-06 3.4e-06 0.00013 0.00012 8.3e-05 9.4e-05 0.035 0.035 0.0087 0.051 0.051 0.035 5.4e-10 5.4e-10 6.9e-10 8.2e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
188 18590000 0.98 -0.0071 -0.011 0.19 0.0064 -0.0067 0.041 0.0055 -0.0022 0.099 -1.5e-05 -6e-05 3.3e-06 3.7e-06 9.8e-05 9.9e-05 2.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3e-06 3.4e-06 0.00012 0.00012 8.3e-05 9.3e-05 0.031 0.031 0.0087 0.045 0.045 0.035 4.9e-10 4.9e-10 6.8e-10 8e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
189 18690000 0.98 -0.0071 -0.011 0.19 0.0065 -0.0056 0.039 0.0062 -0.0028 0.098 -1.5e-05 -6e-05 3.5e-06 3.9e-06 0.0001 2.4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3e-06 3.4e-06 0.00012 0.00012 8.2e-05 9.3e-05 0.034 0.034 0.0087 0.051 0.051 0.035 4.9e-10 4.9e-10 6.6e-10 7.8e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
190 18790000 0.98 -0.007 -0.011 0.19 0.0055 -0.0054 0.038 0.0062 -0.0023 0.096 -1.5e-05 -6e-05 3.4e-06 3.9e-06 0.00011 2.2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3e-06 3.4e-06 0.00012 0.00012 8.2e-05 9.2e-05 0.03 0.03 0.0087 0.045 0.045 0.035 4.4e-10 4.4e-10 6.5e-10 7.7e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
191 18890000 0.98 -0.007 -0.011 0.19 0.0042 -0.005 0.036 0.0067 -0.0029 0.093 -1.5e-05 -6e-05 3.3e-06 3.7e-06 0.00011 1.9e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3e-06 3.3e-06 0.00012 0.00012 8.2e-05 9.1e-05 0.033 0.033 0.0087 0.051 0.051 0.035 4.4e-10 4.4e-10 6.4e-10 7.5e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
192 18990000 0.98 -0.007 -0.011 0.19 0.0026 -0.0052 -0.0051 0.037 0.0055 -0.0023 0.096 -1.5e-05 -6e-05 3.2e-06 3.6e-06 0.00011 2e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3e-06 3.3e-06 0.00012 0.00011 8.1e-05 9e-05 0.029 0.029 0.0086 0.045 0.045 0.035 4e-10 4e-10 6.3e-10 7.3e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
193 19090000 0.98 -0.0071 -0.011 0.19 0.00058 0.00059 -0.0056 0.037 0.0058 -0.0028 0.093 -1.5e-05 -6e-05 3.4e-06 3.8e-06 0.00011 1.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 3e-06 3.3e-06 0.00012 0.00012 8.1e-05 9e-05 0.032 0.032 0.0087 0.051 0.051 0.036 4e-10 4e-10 6.1e-10 7.1e-10 3e-06 3e-06 5e-08 0 0 0 0 0 0 0 0
194 19190000 0.98 -0.007 -0.011 0.19 -0.00089 -0.00088 -0.0053 0.037 0.0048 -0.0023 0.092 -1.5e-05 -6e-05 3e-06 3.3e-06 0.00012 1.6e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 3.3e-06 0.00011 0.00011 8e-05 8.9e-05 0.028 0.028 0.0086 0.045 0.045 0.036 3.7e-10 3.7e-10 6e-10 7e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
195 19290000 0.98 -0.0069 -0.011 0.19 -0.0017 -0.0051 0.037 0.0047 -0.0028 0.091 -1.5e-05 -6e-05 2.9e-06 3.2e-06 0.00012 1.4e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 3.2e-06 0.00011 0.00011 8e-05 8.8e-05 0.031 0.031 0.0087 0.05 0.05 0.036 3.7e-10 3.7e-10 5.9e-10 6.8e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
196 19390000 0.98 -0.007 -0.011 0.19 -0.0022 -0.0017 0.038 0.0041 -0.00095 -0.00094 0.09 -1.5e-05 -6e-05 2.8e-06 3.1e-06 0.00012 1.5e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 3.2e-06 0.00011 0.00011 8e-05 8.8e-05 0.028 0.028 0.0086 0.045 0.045 0.036 3.3e-10 3.3e-10 5.8e-10 6.7e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
197 19490000 0.98 -0.0071 -0.011 0.19 -0.003 -0.0017 0.038 0.0038 -0.0011 0.09 -1.5e-05 -6e-05 2.5e-06 2.8e-06 0.00012 1.3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 3.2e-06 0.00011 0.00011 7.9e-05 8.7e-05 0.03 0.03 0.0087 0.05 0.05 0.036 3.3e-10 3.3e-10 5.7e-10 6.5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
198 19590000 0.98 -0.007 -0.011 0.19 -0.0041 -0.0046 0.039 0.0044 -0.0022 0.09 -1.5e-05 -6e-05 2.4e-06 2.6e-06 0.00013 9.6e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 3.2e-06 0.00011 0.00011 7.9e-05 8.6e-05 0.027 0.027 0.0086 0.044 0.044 0.036 3e-10 3e-10 5.6e-10 6.4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
199 19690000 0.98 -0.007 -0.011 0.19 -0.0057 -0.0032 -0.0031 0.038 0.0039 -0.0026 0.09 -1.5e-05 -6e-05 2.6e-06 2.8e-06 0.00013 7.7e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.9e-06 3.1e-06 0.00011 0.00011 7.8e-05 8.6e-05 0.03 0.03 0.0086 0.05 0.05 0.036 3e-10 3e-10 5.5e-10 6.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
200 19790000 0.98 -0.0071 -0.011 0.19 -0.0057 -0.0018 -0.0017 0.036 0.0064 -0.0021 0.085 -1.5e-05 -6e-05 2.4e-06 2.5e-06 0.00014 4e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 3.1e-06 0.00011 0.0001 7.8e-05 8.5e-05 0.026 0.026 0.0086 0.044 0.044 0.036 2.8e-10 2.8e-10 5.4e-10 6.1e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
201 19890000 0.98 -0.0072 -0.011 0.19 -0.0058 -0.0057 -0.0015 0.036 0.0058 -0.0022 0.084 -1.5e-05 -6e-05 2.2e-06 2.4e-06 0.00014 2.2e-06 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 3.1e-06 0.00011 0.00011 7.7e-05 8.5e-05 0.029 0.029 0.0086 0.05 0.05 0.036 2.8e-10 2.8e-10 5.3e-10 6e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
202 19990000 0.98 -0.0072 -0.011 0.19 -0.0054 -0.0015 0.033 0.0061 -0.00071 0.081 -1.5e-05 -5.9e-05 2.3e-06 2.4e-06 0.00014 2.9e-07 2.8e-07 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 3.1e-06 0.0001 0.0001 7.7e-05 8.4e-05 0.026 0.026 0.0085 0.044 0.044 0.036 2.5e-10 2.5e-10 5.2e-10 5.8e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
203 20090000 0.98 -0.0072 -0.011 0.19 -0.0049 -0.0037 0.033 0.0056 -0.00098 -0.00097 0.084 -1.5e-05 -5.9e-05 2.2e-06 2.4e-06 0.00014 4.2e-07 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 3e-06 0.0001 0.0001 7.7e-05 8.4e-05 0.028 0.028 0.0086 0.05 0.05 0.036 2.5e-10 2.5e-10 5.1e-10 5.7e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
204 20190000 0.98 -0.0072 -0.011 0.19 -0.0039 -0.0012 -0.0011 0.034 0.0066 -0.00071 0.084 -1.5e-05 -5.9e-05 2e-06 2.1e-06 0.00015 -8.7e-07 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 3e-06 0.0001 0.0001 7.6e-05 8.3e-05 0.025 0.025 0.0085 0.044 0.044 0.036 2.3e-10 2.3e-10 5e-10 5.6e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
205 20290000 0.98 -0.0072 -0.011 0.19 -0.0071 -0.0022 0.034 0.0061 -0.00082 0.085 -1.5e-05 -5.9e-05 1.9e-06 2.1e-06 0.00015 -1.8e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 3e-06 0.0001 0.0001 7.6e-05 8.2e-05 0.027 0.027 0.0085 0.049 0.049 0.036 2.3e-10 2.3e-10 4.9e-10 5.5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
206 20390000 0.98 -0.0072 -0.011 0.19 -0.0077 -0.0011 0.034 0.0069 -0.00058 0.086 -1.5e-05 -5.9e-05 2.1e-06 2.2e-06 0.00015 -3.1e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.8e-06 3e-06 0.0001 9.9e-05 7.5e-05 8.2e-05 0.024 0.024 0.0084 0.044 0.044 0.036 2.1e-10 2.1e-10 4.8e-10 5.4e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
207 20490000 0.98 -0.0072 -0.011 0.19 -0.012 -0.002 0.033 0.0059 -0.00072 0.084 -1.5e-05 -5.9e-05 2e-06 2.2e-06 0.00015 -5e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 3e-06 0.0001 0.0001 7.5e-05 8.1e-05 0.027 0.027 0.0085 0.049 0.049 0.036 2.1e-10 2.1e-10 4.7e-10 5.3e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
208 20590000 0.98 -0.0071 -0.011 0.19 -0.011 -0.003 0.033 0.007 -0.0006 0.082 -1.5e-05 -5.9e-05 2.3e-06 2.4e-06 0.00016 -7.6e-06 -7.5e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 2.9e-06 9.9e-05 9.8e-05 7.4e-05 8.1e-05 0.024 0.024 0.0084 0.044 0.044 0.036 2e-10 2e-10 4.6e-10 5.2e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
209 20690000 0.98 -0.0071 -0.011 0.19 -0.013 -0.0017 0.033 0.0058 -0.00079 0.082 -1.5e-05 -5.9e-05 2.1e-06 2.2e-06 0.00016 -8.3e-06 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 2.9e-06 0.0001 9.8e-05 7.4e-05 8e-05 0.026 0.026 0.0084 0.049 0.049 0.036 2e-10 2e-10 4.5e-10 5.1e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
210 20790000 0.98 -0.0065 -0.011 0.19 -0.016 0.00077 0.00078 0.018 0.0049 -0.00063 0.081 -1.5e-05 -5.9e-05 2.1e-06 2.3e-06 0.00016 -1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 2.9e-06 9.8e-05 9.6e-05 7.4e-05 8e-05 0.023 0.023 0.0084 0.043 0.043 0.036 1.8e-10 1.8e-10 4.5e-10 5e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
211 20890000 0.98 0.0026 -0.0074 0.19 -0.021 0.013 -0.1 0.003 8.9e-05 9e-05 0.074 -1.5e-05 -5.9e-05 2.1e-06 2.2e-06 0.00016 -1.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.7e-06 2.9e-06 9.8e-05 9.7e-05 7.3e-05 7.9e-05 0.026 0.026 0.0084 0.049 0.049 0.036 1.8e-10 1.8e-10 4.4e-10 4.9e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
212 20990000 0.98 0.006 -0.004 0.19 -0.032 0.031 -0.24 0.0023 0.00069 0.0007 0.059 -1.5e-05 -5.9e-05 2.1e-06 2.2e-06 0.00016 -1.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.8e-06 9.6e-05 9.5e-05 7.3e-05 7.8e-05 0.023 0.023 0.0083 0.043 0.043 0.036 1.7e-10 1.7e-10 4.3e-10 4.8e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
213 21090000 0.98 0.0044 -0.0043 0.19 -0.045 0.047 -0.36 -0.0016 0.0046 0.029 -1.5e-05 -5.9e-05 2.1e-06 2.2e-06 0.00016 -1.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.8e-06 9.7e-05 9.5e-05 7.3e-05 7.8e-05 0.026 0.026 0.0084 0.048 0.048 0.036 1.7e-10 1.7e-10 4.2e-10 4.7e-10 2.9e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
214 21190000 0.98 0.0015 -0.006 0.19 -0.049 0.051 -0.49 -0.0012 0.0036 -0.0072 -1.4e-05 -5.9e-05 2.1e-06 2.2e-06 0.00016 -2e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.8e-06 9.4e-05 9.3e-05 7.2e-05 7.7e-05 0.023 0.023 0.0083 0.043 0.043 0.036 1.6e-10 1.6e-10 4.2e-10 4.6e-10 2.8e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
215 21290000 0.98 -0.00066 -0.0073 0.19 -0.049 0.054 -0.62 -0.006 0.0089 -0.066 -1.4e-05 -5.9e-05 1.9e-06 0.00016 -2.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.8e-06 9.5e-05 9.4e-05 7.2e-05 7.7e-05 0.026 0.026 0.0083 0.048 0.048 0.036 1.6e-10 1.6e-10 4.1e-10 4.5e-10 2.8e-06 2.9e-06 5e-08 0 0 0 0 0 0 0 0
216 21390000 0.98 -0.0021 -0.008 0.19 -0.044 0.05 -0.74 -0.0049 0.011 -0.13 -1.4e-05 -5.9e-05 1.9e-06 0.00017 -2.5e-05 -2.4e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.8e-06 9.3e-05 9.1e-05 7.1e-05 7.6e-05 0.023 0.023 0.0082 0.043 0.043 0.036 1.4e-10 1.4e-10 4e-10 4.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
217 21490000 0.98 -0.0029 -0.0084 0.19 -0.04 0.047 -0.88 -0.0091 0.016 -0.22 -1.4e-05 -5.9e-05 2e-06 2.1e-06 0.00017 -2.6e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.8e-06 9.3e-05 9.2e-05 7.1e-05 7.6e-05 0.026 0.026 0.0083 0.048 0.048 0.036 1.4e-10 1.4e-10 3.9e-10 4.3e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
218 21590000 0.98 -0.0034 -0.0084 0.19 -0.031 0.043 -1 -0.0078 0.017 -0.31 -1.4e-05 -5.9e-05 2.1e-06 2.2e-06 0.00017 -2.7e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.8e-06 9.1e-05 9e-05 7.1e-05 7.5e-05 0.023 0.023 0.0082 0.043 0.043 0.036 1.3e-10 1.3e-10 3.9e-10 4.2e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
219 21690000 0.98 -0.0038 -0.0083 0.19 -0.029 0.039 -1.1 -0.011 0.021 -0.42 -1.4e-05 -5.9e-05 2.2e-06 2.3e-06 0.00017 -2.9e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.8e-06 9.1e-05 9e-05 7e-05 7.5e-05 0.025 0.025 0.0083 0.048 0.048 0.036 1.3e-10 1.3e-10 3.8e-10 4.2e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
220 21790000 0.98 -0.0041 -0.0085 0.19 -0.021 0.033 -1.3 -0.0036 0.018 -0.54 -1.4e-05 -5.8e-05 2.4e-06 2.5e-06 0.00018 -3.1e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.7e-06 8.9e-05 8.8e-05 7e-05 7.4e-05 0.023 0.023 0.0082 0.043 0.043 0.036 1.2e-10 1.2e-10 3.7e-10 4.1e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
221 21890000 0.98 -0.0044 -0.0087 0.19 -0.017 0.028 -1.4 -0.0055 0.021 -0.68 -1.4e-05 -5.8e-05 2.3e-06 2.4e-06 0.00018 -3.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.7e-06 8.9e-05 8.8e-05 7e-05 7.4e-05 0.025 0.025 0.0082 0.048 0.048 0.036 1.2e-10 1.2e-10 3.7e-10 4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
222 21990000 0.98 -0.0051 -0.0089 0.19 -0.014 0.023 -1.4 -0.00017 0.017 -0.82 -1.4e-05 -5.8e-05 2.4e-06 2.5e-06 0.00017 -3.1e-05 -3e-05 -0.0014 0.2 0.002 0.43 0 0 0 0 0 2.6e-06 2.7e-06 8.7e-05 8.6e-05 6.9e-05 7.4e-05 0.022 0.022 0.0082 0.043 0.043 0.036 1.1e-10 1.1e-10 3.6e-10 3.9e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
223 22090000 0.98 -0.0059 -0.0098 0.19 -0.011 0.019 -1.3 -0.0014 0.019 -0.96 -1.4e-05 -5.8e-05 2.6e-06 2.7e-06 0.00018 -3.2e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 2.7e-06 8.7e-05 8.6e-05 6.9e-05 7.3e-05 0.024 0.024 0.0082 0.048 0.048 0.036 1.1e-10 1.1e-10 3.6e-10 3.9e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
224 22190000 0.98 -0.0063 -0.01 0.19 -0.0031 0.013 -1.4 0.0062 0.013 -1.1 -1.4e-05 -5.8e-05 2.7e-06 2.8e-06 0.00018 -3.2e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 2.7e-06 8.5e-05 8.4e-05 6.9e-05 7.3e-05 0.021 0.021 0.0081 0.043 0.043 0.036 1.1e-10 1.1e-10 3.5e-10 3.8e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
225 22290000 0.98 -0.007 -0.01 0.19 0.002 0.0078 -1.4 0.0062 0.014 -1.2 -1.4e-05 -5.8e-05 2.6e-06 2.7e-06 0.00018 -3.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 2.6e-06 8.6e-05 8.4e-05 6.8e-05 7.2e-05 0.023 0.023 0.0081 0.048 0.048 0.036 1.1e-10 1.1e-10 3.4e-10 3.7e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
226 22390000 0.98 -0.0074 -0.01 0.19 0.007 -0.0018 -1.4 0.013 0.0042 -1.4 -1.4e-05 -5.8e-05 2.4e-06 2.5e-06 0.00018 -3.7e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 2.6e-06 8.4e-05 8.3e-05 6.8e-05 7.2e-05 0.021 0.021 0.0081 0.043 0.043 0.036 1e-10 1e-10 3.4e-10 3.7e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
227 22490000 0.98 -0.0076 -0.011 0.19 0.011 -0.0077 -1.4 0.014 0.0037 -1.5 -1.4e-05 -5.8e-05 2.3e-06 2.4e-06 0.00018 -3.8e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 2.6e-06 8.4e-05 8.3e-05 6.8e-05 7.1e-05 0.022 0.022 0.0081 0.047 0.047 0.036 1e-10 1e-10 3.3e-10 3.6e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
228 22590000 0.98 -0.0075 -0.012 0.19 0.02 -0.017 -1.4 0.026 -0.0053 -1.7 -1.4e-05 -5.8e-05 2.4e-06 2.5e-06 0.00018 -4e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 2.6e-06 8.2e-05 8.1e-05 6.7e-05 7.1e-05 0.02 0.02 0.0081 0.042 0.042 0.036 9.4e-11 9.4e-11 3.3e-10 3.5e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
229 22690000 0.98 -0.0074 -0.012 0.19 0.022 -0.021 -1.4 0.028 -0.0072 -1.8 -1.4e-05 -5.8e-05 2.4e-06 0.00018 -4.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 2.6e-06 8.3e-05 8.2e-05 6.7e-05 7.1e-05 0.021 0.021 0.0081 0.047 0.047 0.036 9.4e-11 9.4e-11 3.2e-10 3.5e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
230 22790000 0.98 -0.0074 -0.012 0.19 0.028 -0.029 -1.4 0.038 -0.017 -2 -1.4e-05 -5.8e-05 2.2e-06 2.3e-06 0.00019 -4.2e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.5e-06 2.6e-06 8.1e-05 8e-05 6.7e-05 7e-05 0.019 0.019 0.0081 0.042 0.042 0.036 8.9e-11 8.9e-11 3.2e-10 3.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
231 22890000 0.98 -0.0076 -0.013 0.19 0.032 -0.034 -1.4 0.041 -0.02 -2.1 -1.4e-05 -5.8e-05 2.4e-06 2.5e-06 0.00019 -4.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.4e-06 2.6e-06 8.1e-05 8e-05 6.6e-05 7e-05 0.021 0.021 0.0081 0.047 0.047 0.036 8.9e-11 8.9e-11 3.1e-10 3.4e-10 2.8e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
232 22990000 0.98 -0.0075 -0.013 0.19 0.036 -0.04 -1.4 0.051 -0.031 -2.3 -1.4e-05 -5.8e-05 2.6e-06 2.7e-06 0.00019 -4.5e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.4e-06 2.5e-06 8e-05 7.9e-05 6.6e-05 6.9e-05 0.019 0.019 0.0081 0.042 0.042 0.036 8.4e-11 8.4e-11 3.1e-10 3.3e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
233 23090000 0.98 -0.0076 -0.013 0.19 0.041 -0.044 -1.4 0.055 -0.035 -2.4 -1.4e-05 -5.8e-05 2.6e-06 2.7e-06 0.00019 -4.5e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.4e-06 2.5e-06 8e-05 7.9e-05 6.6e-05 6.9e-05 0.02 0.02 0.0081 0.046 0.046 0.036 8.4e-11 8.4e-11 3e-10 3.2e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
234 23190000 0.98 -0.0076 -0.013 0.19 0.047 -0.046 -1.4 0.066 -0.045 -2.5 -1.4e-05 -5.8e-05 2.5e-06 0.00019 -4.7e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.4e-06 2.5e-06 7.9e-05 7.8e-05 6.5e-05 6.8e-05 0.018 0.018 0.008 0.042 0.042 0.035 7.9e-11 7.9e-11 3e-10 3.2e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
235 23290000 0.98 -0.0081 -0.014 0.19 0.18 0.052 -0.051 -1.4 0.071 -0.05 -2.7 -1.4e-05 -5.8e-05 2.5e-06 2.6e-06 0.00019 -4.8e-05 -4.7e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.4e-06 2.5e-06 7.9e-05 7.8e-05 6.5e-05 6.8e-05 0.02 0.02 0.0081 0.046 0.046 0.036 8e-11 8e-11 2.9e-10 3.1e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
236 23390000 0.98 -0.008 -0.014 0.18 0.057 -0.053 -1.4 0.082 -0.055 -2.8 -1.4e-05 -5.8e-05 2.3e-06 2.4e-06 0.00019 -4.5e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 2.5e-06 7.8e-05 7.7e-05 6.5e-05 6.8e-05 0.018 0.018 0.008 0.041 0.041 0.036 7.5e-11 7.6e-11 2.9e-10 3.1e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
237 23490000 0.98 -0.0081 -0.014 0.18 0.061 -0.055 -1.4 0.088 -0.061 -3 -1.4e-05 -5.8e-05 2.5e-06 0.00019 -4.6e-05 -4.5e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 2.4e-06 7.9e-05 7.8e-05 6.4e-05 6.7e-05 0.019 0.019 0.0081 0.046 0.046 0.036 7.6e-11 7.6e-11 2.8e-10 3e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
238 23590000 0.98 -0.0083 -0.014 0.18 0.064 -0.058 -1.4 0.095 -0.07 -3.1 -1.4e-05 -5.8e-05 2.5e-06 2.6e-06 0.00019 -4.7e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 2.4e-06 7.8e-05 7.7e-05 6.4e-05 6.7e-05 0.017 0.017 0.008 0.041 0.041 0.035 7.2e-11 7.2e-11 2.8e-10 3e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
239 23690000 0.98 -0.009 -0.015 0.18 0.062 -0.061 -1.3 0.1 -0.076 -3.3 -1.4e-05 -5.8e-05 2.6e-06 2.7e-06 0.00019 -4.7e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 2.4e-06 7.8e-05 7.7e-05 6.4e-05 6.7e-05 0.018 0.018 0.0081 0.046 0.046 0.036 7.2e-11 7.2e-11 2.8e-10 2.9e-10 2.7e-06 2.8e-06 5e-08 0 0 0 0 0 0 0 0
240 23790000 0.98 -0.011 -0.017 0.18 0.057 -0.058 -0.95 0.11 -0.081 -3.4 -1.4e-05 -5.8e-05 2.8e-06 2.9e-06 0.0002 -4.7e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 2.4e-06 7.7e-05 7.6e-05 6.3e-05 6.6e-05 0.016 0.016 0.008 0.041 0.041 0.035 6.9e-11 6.9e-11 2.7e-10 2.9e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
241 23890000 0.98 -0.014 -0.021 0.18 0.052 -0.058 -0.52 0.12 -0.087 -3.5 -1.4e-05 -5.8e-05 2.8e-06 2.9e-06 0.0002 -4.8e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 2.4e-06 7.7e-05 7.6e-05 6.3e-05 6.6e-05 0.017 0.017 0.008 0.045 0.045 0.035 6.9e-11 6.9e-11 2.7e-10 2.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
242 23990000 0.98 -0.016 -0.024 0.18 0.054 -0.057 -0.14 0.13 -0.089 -3.5 -1.4e-05 -5.8e-05 2.8e-06 2.9e-06 0.00021 -5.3e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 2.4e-06 7.7e-05 7.6e-05 6.3e-05 6.6e-05 0.015 0.015 0.008 0.041 0.041 0.036 6.6e-11 6.6e-11 2.6e-10 2.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
243 24090000 0.98 -0.016 -0.023 0.18 0.06 -0.066 0.097 0.13 -0.095 -3.5 -1.4e-05 -5.8e-05 2.7e-06 2.8e-06 0.00021 -5.4e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 2.4e-06 7.7e-05 7.6e-05 6.3e-05 6.5e-05 0.016 0.016 0.0081 0.045 0.045 0.036 6.6e-11 6.6e-11 2.6e-10 2.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
244 24190000 0.98 -0.013 -0.019 0.18 0.071 -0.071 0.083 0.14 -0.1 -3.5 -1.4e-05 -5.8e-05 2.8e-06 2.9e-06 0.00021 -6.1e-05 -0.0013 0.2 0.002 0.43 0 0 0 0 0 2.3e-06 7.7e-05 7.6e-05 6.2e-05 6.5e-05 0.015 0.015 0.008 0.04 0.04 0.035 6.3e-11 6.3e-11 2.6e-10 2.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
245 24290000 0.98 -0.011 -0.016 0.18 0.075 -0.074 0.061 0.15 -0.11 -3.5 -1.4e-05 -5.8e-05 2.8e-06 2.9e-06 0.00021 -6.2e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 2.3e-06 7.7e-05 7.6e-05 6.2e-05 6.5e-05 0.016 0.016 0.0081 0.044 0.044 0.036 6.3e-11 6.3e-11 2.5e-10 2.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
246 24390000 0.98 -0.0097 -0.015 0.18 0.068 -0.069 0.077 0.15 -0.11 -3.5 -1.4e-05 -5.8e-05 3e-06 0.00022 -6.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 2.3e-06 7.7e-05 7.6e-05 6.2e-05 6.4e-05 0.015 0.015 0.008 0.04 0.04 0.035 6.1e-11 6.1e-11 2.5e-10 2.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
247 24490000 0.98 -0.01 -0.015 0.18 0.064 -0.066 0.075 0.16 -0.11 -3.5 -1.4e-05 -5.8e-05 3.2e-06 3.3e-06 0.00022 -7e-05 -6.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 2.3e-06 7.7e-05 7.6e-05 6.1e-05 6.4e-05 0.016 0.016 0.0081 0.044 0.044 0.035 6.1e-11 6.1e-11 2.5e-10 2.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
248 24590000 0.98 -0.011 -0.015 0.18 0.061 -0.061 0.07 0.16 -0.11 -3.5 -1.4e-05 -5.8e-05 3.2e-06 3.3e-06 0.00021 -7.7e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 2.3e-06 7.7e-05 7.6e-05 6.1e-05 6.4e-05 0.015 0.015 0.008 0.04 0.04 0.036 5.9e-11 5.9e-11 2.4e-10 2.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
249 24690000 0.98 -0.011 -0.015 0.18 0.058 -0.061 0.069 0.17 -0.12 -3.5 -1.4e-05 -5.8e-05 3.2e-06 3.3e-06 0.00021 -7.7e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 2.3e-06 7.7e-05 7.6e-05 6.1e-05 6.3e-05 0.016 0.016 0.0081 0.044 0.044 0.036 5.9e-11 5.9e-11 2.4e-10 2.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
250 24790000 0.98 -0.011 -0.014 0.18 0.055 -0.058 0.061 0.17 -0.11 -3.5 -1.5e-05 -5.8e-05 3.2e-06 3.3e-06 0.00021 -8.3e-05 -8.2e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 2.3e-06 7.7e-05 7.6e-05 6.1e-05 6.3e-05 0.015 0.015 0.008 0.039 0.039 0.035 5.7e-11 5.7e-11 2.3e-10 2.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
251 24890000 0.98 -0.011 -0.014 0.18 0.054 -0.062 0.05 0.18 -0.12 -3.5 -1.5e-05 -5.8e-05 3.3e-06 3.4e-06 0.00022 -8.3e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 2.3e-06 7.7e-05 7.6e-05 6e-05 6.2e-05 0.016 0.016 0.008 0.043 0.043 0.035 5.7e-11 5.7e-11 2.3e-10 2.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
252 24990000 0.98 -0.011 -0.013 0.18 0.045 -0.057 0.042 0.18 -0.11 -3.5 -1.5e-05 -5.8e-05 3.3e-06 3.4e-06 0.00021 -8.9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 7.7e-05 7.6e-05 6e-05 6.2e-05 0.015 0.015 0.008 0.039 0.039 0.035 5.5e-11 5.5e-11 2.3e-10 2.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
253 25090000 0.98 -0.011 -0.013 0.18 0.041 -0.057 0.04 0.18 -0.12 -3.5 -1.5e-05 -5.8e-05 3.2e-06 3.3e-06 0.00021 -9e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 7.8e-05 7.6e-05 6e-05 6.2e-05 0.016 0.016 0.0081 0.043 0.043 0.035 5.5e-11 5.5e-11 2.3e-10 2.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
254 25190000 0.98 -0.011 -0.013 0.18 0.037 -0.05 0.039 0.18 -0.11 -3.5 -1.5e-05 -5.8e-05 3.1e-06 3.2e-06 0.00021 -9.5e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.2e-06 7.8e-05 7.6e-05 5.9e-05 6.2e-05 0.015 0.015 0.008 0.039 0.039 0.035 5.3e-11 5.3e-11 2.2e-10 2.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
255 25290000 0.98 -0.011 -0.013 0.18 0.032 -0.051 0.034 0.18 -0.11 -3.5 -1.5e-05 -5.8e-05 3e-06 0.00021 -9.5e-05 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 2.2e-06 7.8e-05 7.7e-05 5.9e-05 6.1e-05 0.016 0.016 0.0081 0.043 0.043 0.036 5.3e-11 5.3e-11 2.2e-10 2.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
256 25390000 0.98 -0.011 -0.012 0.18 0.024 -0.044 0.032 0.18 -0.1 -3.5 -1.5e-05 -5.8e-05 2.9e-06 3e-06 0.00021 -0.0001 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 2.2e-06 7.8e-05 7.7e-05 5.9e-05 6.1e-05 0.015 0.015 0.008 0.039 0.039 0.035 5.1e-11 5.1e-11 2.2e-10 2.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
257 25490000 0.98 -0.012 -0.012 0.18 0.019 -0.044 0.031 0.18 -0.11 -3.5 -1.5e-05 -5.8e-05 2.9e-06 0.00021 -0.0001 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 2.2e-06 7.8e-05 7.7e-05 5.9e-05 6.1e-05 0.016 0.016 0.0081 0.043 0.043 0.035 5.1e-11 5.1e-11 2.1e-10 2.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
258 25590000 0.98 -0.012 -0.012 0.18 0.014 -0.04 0.032 0.18 -0.098 -3.5 -1.5e-05 -5.8e-05 2.8e-06 0.00021 -0.00011 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 2.2e-06 7.8e-05 7.7e-05 5.8e-05 6e-05 0.014 0.014 0.008 0.039 0.039 0.035 5e-11 5e-11 2.1e-10 2.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
259 25690000 0.98 -0.011 -0.012 0.18 0.013 -0.039 0.021 0.18 -0.1 -3.5 -1.5e-05 -5.8e-05 2.8e-06 0.00021 -0.00011 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 2.2e-06 7.8e-05 7.7e-05 5.8e-05 6e-05 0.015 0.015 0.0081 0.043 0.043 0.035 5e-11 5e-11 2.1e-10 2.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
260 25790000 0.98 -0.011 -0.011 0.18 0.0018 -0.03 0.021 0.17 -0.092 -3.5 -1.6e-05 -5.8e-05 2.7e-06 2.8e-06 0.00021 -0.00011 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 2.2e-06 7.8e-05 7.7e-05 5.8e-05 6e-05 0.014 0.014 0.008 0.039 0.039 0.035 4.8e-11 4.8e-11 2e-10 2.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
261 25890000 0.98 -0.011 -0.011 0.18 -0.004 -0.028 0.023 0.17 -0.095 -3.5 -1.6e-05 -5.8e-05 2.5e-06 2.6e-06 0.00021 -0.00011 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 7.8e-05 7.7e-05 5.8e-05 6e-05 0.015 0.015 0.0081 0.043 0.043 0.036 4.8e-11 4.8e-11 2e-10 2.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
262 25990000 0.98 -0.011 -0.011 0.18 -0.013 -0.021 0.016 0.16 -0.086 -3.5 -1.6e-05 -5.8e-05 2.4e-06 2.5e-06 0.00022 -0.00012 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 7.8e-05 7.7e-05 5.7e-05 5.9e-05 0.014 0.014 0.008 0.039 0.039 0.035 4.7e-11 4.7e-11 2e-10 2.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
263 26090000 0.98 -0.011 -0.011 0.18 -0.018 -0.021 0.015 0.16 -0.088 -3.5 -1.6e-05 -5.8e-05 2.5e-06 2.6e-06 0.00022 -0.00012 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 7.9e-05 7.7e-05 5.7e-05 5.9e-05 0.015 0.015 0.0081 0.042 0.042 0.035 4.7e-11 4.7e-11 2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
264 26190000 0.98 -0.011 -0.012 0.18 -0.024 -0.015 0.0095 0.15 -0.081 -3.5 -1.6e-05 -5.8e-05 2.5e-06 2.6e-06 0.00022 -0.00012 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2.1e-06 7.9e-05 7.7e-05 5.7e-05 5.9e-05 0.014 0.014 0.008 0.039 0.039 0.035 4.6e-11 4.6e-11 1.9e-10 2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
265 26290000 0.98 -0.011 -0.012 0.18 -0.026 -0.013 0.0037 0.15 -0.082 -3.5 -1.6e-05 -5.8e-05 2.4e-06 2.5e-06 0.00022 -0.00012 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 2.1e-06 7.9e-05 7.8e-05 5.7e-05 5.8e-05 0.015 0.015 0.0081 0.042 0.042 0.036 4.6e-11 4.6e-11 1.9e-10 2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
266 26390000 0.98 -0.01 -0.012 0.18 -0.032 -0.0061 0.0075 0.13 -0.074 -3.5 -1.6e-05 -5.8e-05 2.3e-06 0.00022 -0.00012 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 2.1e-06 7.9e-05 7.7e-05 5.6e-05 5.8e-05 0.014 0.014 0.008 0.038 0.038 0.035 4.4e-11 4.4e-11 1.9e-10 2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
267 26490000 0.98 -0.0098 -0.012 0.18 -0.035 -0.0029 0.017 0.13 -0.075 -3.5 -1.6e-05 -5.8e-05 2.2e-06 2.3e-06 0.00022 -0.00012 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 2.1e-06 7.9e-05 7.8e-05 5.6e-05 5.8e-05 0.015 0.015 0.0081 0.042 0.042 0.035 4.5e-11 4.5e-11 1.9e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
268 26590000 0.98 -0.0092 -0.012 0.18 -0.036 0.005 0.017 0.12 -0.068 -3.5 -1.6e-05 -5.8e-05 2.1e-06 0.00022 -0.00012 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 2.1e-06 7.9e-05 7.8e-05 5.6e-05 5.8e-05 0.014 0.014 0.008 0.038 0.038 0.035 4.3e-11 4.3e-11 1.8e-10 1.9e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
269 26690000 0.98 -0.0091 -0.012 0.18 -0.038 0.01 0.015 0.12 -0.067 -3.5 -1.6e-05 -5.8e-05 1.9e-06 0.00022 -0.00012 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 2.1e-06 7.9e-05 7.8e-05 5.6e-05 5.7e-05 0.015 0.015 0.0081 0.042 0.042 0.035 4.3e-11 4.3e-11 1.8e-10 1.9e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
270 26790000 0.98 -0.0089 -0.011 0.18 -0.045 0.014 0.014 0.1 -0.062 -3.5 -1.6e-05 -5.8e-05 1.8e-06 0.00022 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 7.9e-05 7.8e-05 5.5e-05 5.7e-05 0.014 0.014 0.008 0.038 0.038 0.035 4.2e-11 4.2e-11 1.8e-10 1.9e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
271 26890000 0.98 -0.0082 -0.011 0.18 -0.051 0.017 0.0095 0.1 -0.06 -3.5 -1.6e-05 -5.8e-05 1.8e-06 1.9e-06 0.00022 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 7.9e-05 7.8e-05 5.5e-05 5.7e-05 0.015 0.015 0.0081 0.042 0.042 0.036 4.2e-11 4.2e-11 1.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
272 26990000 0.98 -0.0077 -0.012 0.18 -0.058 0.023 0.0086 0.087 -0.054 -3.5 -1.6e-05 -5.8e-05 1.7e-06 1.8e-06 0.00022 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 7.9e-05 7.8e-05 5.5e-05 5.7e-05 0.014 0.014 0.008 0.038 0.038 0.035 4.1e-11 4.1e-11 1.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
273 27090000 0.98 -0.0075 -0.012 0.18 -0.06 0.03 0.011 0.082 -0.051 -3.5 -1.6e-05 -5.8e-05 1.7e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 7.9e-05 7.8e-05 5.5e-05 5.6e-05 0.015 0.015 0.0081 0.042 0.042 0.035 4.1e-11 4.1e-11 1.7e-10 1.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
274 27190000 0.98 -0.0076 -0.012 0.18 -0.066 0.036 0.013 0.071 -0.045 -3.5 -1.6e-05 -5.8e-05 1.6e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 2e-06 7.9e-05 7.8e-05 5.5e-05 5.6e-05 0.014 0.014 0.008 0.038 0.038 0.035 4e-11 4e-11 1.7e-10 1.8e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
275 27290000 0.98 -0.0077 -0.013 0.18 -0.073 0.042 0.13 0.064 -0.041 -3.5 -1.6e-05 -5.8e-05 1.6e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 2e-06 7.9e-05 7.8e-05 5.4e-05 5.6e-05 0.015 0.015 0.0081 0.042 0.042 0.035 4e-11 4e-11 1.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
276 27390000 0.98 -0.0091 -0.015 0.18 -0.078 0.048 0.45 0.055 -0.034 -3.5 -1.6e-05 -5.8e-05 1.5e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 2e-06 7.9e-05 7.8e-05 5.4e-05 5.5e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.9e-11 3.9e-11 1.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
277 27490000 0.98 -0.01 -0.017 0.18 -0.082 0.053 0.76 0.046 -0.029 -3.4 -1.6e-05 -5.8e-05 1.3e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 2e-06 8e-05 7.8e-05 5.4e-05 5.5e-05 0.014 0.014 0.0081 0.042 0.042 0.035 3.9e-11 3.9e-11 1.6e-10 1.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
278 27590000 0.98 -0.01 -0.016 0.18 -0.076 0.056 0.86 0.038 -0.025 -3.4 -1.6e-05 -5.8e-05 1.3e-06 0.00023 -0.00014 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 2e-06 8e-05 7.8e-05 5.4e-05 5.5e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.9e-11 3.9e-11 1.6e-10 1.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
279 27690000 0.98 -0.0091 -0.013 0.18 -0.072 0.052 0.76 0.031 -0.02 -3.3 -1.6e-05 -5.8e-05 1.3e-06 0.00023 -0.00014 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 2e-06 8e-05 7.9e-05 5.3e-05 5.5e-05 0.014 0.014 0.0081 0.042 0.042 0.035 3.9e-11 3.9e-11 1.6e-10 1.7e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
280 27790000 0.98 -0.0078 -0.012 0.18 -0.071 0.05 0.75 0.025 -0.017 -3.2 -1.6e-05 -5.8e-05 1.3e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 8e-05 7.9e-05 5.3e-05 5.4e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.8e-11 3.8e-11 1.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
281 27890000 0.98 -0.0074 -0.012 0.18 -0.078 0.057 0.79 0.017 -0.012 -3.1 -1.6e-05 -5.8e-05 1.2e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 8e-05 7.9e-05 5.3e-05 5.4e-05 0.014 0.014 0.0081 0.041 0.041 0.036 3.8e-11 3.8e-11 1.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
282 27990000 0.98 -0.0079 -0.012 0.18 -0.078 -0.079 0.058 0.78 0.012 -0.01 -3.1 -1.6e-05 -5.8e-05 1.2e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 8e-05 7.9e-05 5.3e-05 5.4e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.7e-11 3.7e-11 1.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
283 28090000 0.98 -0.0082 -0.012 0.18 -0.082 0.059 0.78 0.0041 -0.0044 -3 -1.6e-05 -5.8e-05 1.3e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 8e-05 7.9e-05 5.3e-05 5.4e-05 0.014 0.014 0.0081 0.041 0.041 0.035 3.7e-11 3.7e-11 1.5e-10 1.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
284 28190000 0.98 -0.0076 -0.012 0.18 -0.082 0.056 0.79 -0.0024 -0.004 -2.9 -1.6e-05 -5.8e-05 1.2e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 8e-05 7.9e-05 5.2e-05 5.4e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.6e-11 3.6e-11 1.5e-10 1.6e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
285 28290000 0.98 -0.0071 -0.013 0.18 -0.088 0.059 0.79 -0.011 0.0017 -2.8 -1.6e-05 -5.8e-05 1.3e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 8e-05 7.9e-05 5.2e-05 5.3e-05 0.014 0.014 0.0081 0.041 0.041 0.035 3.7e-11 3.7e-11 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
286 28390000 0.98 -0.0071 -0.013 0.18 -0.088 0.062 0.79 -0.015 0.0047 -2.8 -1.5e-05 -5.8e-05 1.3e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 8.1e-05 7.9e-05 5.2e-05 5.3e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.6e-11 3.6e-11 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
287 28490000 0.98 -0.0074 -0.014 0.18 -0.09 0.066 0.79 -0.024 0.011 -2.7 -1.5e-05 -5.8e-05 1.3e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 8.1e-05 7.9e-05 5.2e-05 5.3e-05 0.014 0.014 0.0081 0.041 0.041 0.036 3.6e-11 3.6e-11 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
288 28590000 0.98 -0.0075 -0.014 0.18 -0.083 0.061 0.79 -0.028 0.0087 -2.6 -1.5e-05 -5.8e-05 1.3e-06 0.00023 -0.00012 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.9e-06 8.1e-05 7.9e-05 5.2e-05 5.3e-05 0.013 0.013 0.008 0.038 0.038 0.035 3.5e-11 3.5e-11 1.4e-10 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
289 28690000 0.98 -0.0072 -0.013 0.18 -0.083 0.062 0.79 -0.036 0.015 -2.5 -1.5e-05 -5.8e-05 1.3e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 1.9e-06 8.1e-05 8e-05 5.1e-05 5.2e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.5e-11 3.5e-11 1.4e-10 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
290 28790000 0.98 -0.0066 -0.013 0.18 -0.079 0.062 0.79 -0.038 0.017 -2.5 -1.5e-05 -5.8e-05 1.3e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 1.9e-06 8.1e-05 8e-05 5.1e-05 5.2e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.5e-11 3.5e-11 1.4e-10 1.5e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
291 28890000 0.98 -0.0064 -0.013 0.18 -0.084 0.064 0.79 -0.046 0.023 -2.4 -1.5e-05 -5.8e-05 1.4e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 1.9e-06 8.1e-05 8e-05 5.1e-05 5.2e-05 0.014 0.014 0.0081 0.041 0.041 0.036 3.5e-11 3.5e-11 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
292 28990000 0.98 -0.0062 -0.013 0.18 -0.079 0.06 0.78 -0.046 0.022 -2.3 -1.5e-05 -5.8e-05 1.4e-06 1.3e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 1.9e-06 8.1e-05 8e-05 5.1e-05 5.2e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.4e-11 3.4e-11 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
293 29090000 0.98 -0.006 -0.013 0.18 -0.082 0.063 0.78 -0.054 0.028 -2.3 -1.5e-05 -5.8e-05 1.3e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.1e-05 8e-05 5.1e-05 5.2e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.4e-11 3.4e-11 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
294 29190000 0.98 -0.006 -0.013 0.18 -0.078 0.061 0.78 -0.051 0.027 -2.2 -1.5e-05 -5.8e-05 1.4e-06 0.00023 -0.00013 -0.0012 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.1e-05 8e-05 5e-05 5.1e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.4e-11 3.4e-11 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
295 29290000 0.98 -0.0062 -0.013 0.18 -0.08 0.067 0.78 -0.059 0.034 -2.1 -1.5e-05 -5.8e-05 1.4e-06 0.00023 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.1e-05 8e-05 5e-05 5.1e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.4e-11 3.4e-11 1.3e-10 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
296 29390000 0.98 -0.0067 -0.013 0.18 -0.075 0.066 0.78 -0.058 0.034 -2 -1.5e-05 -5.8e-05 1.4e-06 0.00023 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.1e-05 8e-05 5e-05 5.1e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.3e-11 3.3e-11 1.3e-10 1.4e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
297 29490000 0.98 -0.0067 -0.012 0.18 -0.078 0.066 0.78 -0.065 0.041 -2 -1.5e-05 -5.8e-05 1.5e-06 0.00023 -0.00013 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.1e-05 8e-05 5e-05 5.1e-05 0.014 0.014 0.0081 0.041 0.041 0.036 3.3e-11 3.3e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
298 29590000 0.98 -0.0066 -0.012 0.18 -0.074 0.064 0.79 -0.062 0.04 -1.9 -1.5e-05 -5.8e-05 1.6e-06 0.00023 -0.00014 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.1e-05 8e-05 5e-05 5.1e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.3e-11 3.3e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
299 29690000 0.98 -0.0067 -0.012 0.18 -0.078 0.063 0.78 -0.07 0.047 -1.8 -1.5e-05 -5.8e-05 1.7e-06 0.00023 -0.00014 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.2e-05 8e-05 4.9e-05 5e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.3e-11 3.3e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
300 29790000 0.98 -0.0065 -0.013 0.18 -0.073 0.056 0.78 -0.065 0.044 -1.7 -1.4e-05 -5.8e-05 1.8e-06 0.00023 -0.00014 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.1e-05 8e-05 4.9e-05 5e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.2e-11 3.2e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
301 29890000 0.98 -0.006 -0.013 0.18 -0.074 0.057 0.77 -0.072 0.049 -1.7 -1.4e-05 -5.8e-05 1.9e-06 0.00023 -0.00014 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.2e-05 8e-05 4.9e-05 5e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.2e-11 3.2e-11 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
302 29990000 0.98 -0.0061 -0.013 0.18 -0.069 0.052 0.77 -0.068 0.045 -1.6 -1.4e-05 -5.8e-05 1.9e-06 0.00024 -0.00015 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.1e-05 8e-05 4.9e-05 5e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.2e-11 3.2e-11 1.2e-10 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
303 30090000 0.98 -0.0063 -0.013 0.18 -0.069 0.053 0.77 -0.075 0.05 -1.5 -1.4e-05 -5.8e-05 1.7e-06 1.8e-06 0.00024 -0.00015 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.2e-05 8e-05 4.9e-05 5e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.2e-11 3.2e-11 1.2e-10 1.3e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
304 30190000 0.98 -0.0062 -0.013 0.18 -0.063 0.05 0.77 -0.068 0.048 -1.4 -1.4e-05 -5.7e-05 1.6e-06 0.00024 -0.00015 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.8e-06 8.1e-05 8e-05 4.9e-05 0.013 0.013 0.008 0.037 0.037 0.035 3.1e-11 3.1e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
305 30290000 0.98 -0.0063 -0.013 0.18 -0.062 0.05 0.77 -0.074 0.053 -1.4 -1.4e-05 -5.7e-05 1.6e-06 0.00024 -0.00015 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 1.8e-06 8.2e-05 8e-05 4.8e-05 4.9e-05 0.014 0.014 0.008 0.041 0.041 0.035 3.1e-11 3.1e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
306 30390000 0.98 -0.0063 -0.013 0.18 -0.055 0.044 0.76 -0.066 0.05 -1.3 -1.4e-05 -5.7e-05 1.8e-06 0.00024 -0.00016 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 1.8e-06 8.1e-05 8e-05 4.8e-05 4.9e-05 0.013 0.013 0.0079 0.037 0.037 0.035 3.1e-11 3.1e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
307 30490000 0.98 -0.0063 -0.013 0.18 -0.057 0.044 0.77 -0.072 0.054 -1.2 -1.4e-05 -5.7e-05 1.8e-06 1.9e-06 0.00024 -0.00016 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 1.8e-06 8.1e-05 8e-05 4.8e-05 4.9e-05 0.014 0.014 0.008 0.041 0.041 0.036 3.1e-11 3.1e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
308 30590000 0.98 -0.0066 -0.014 0.18 -0.053 0.041 0.77 -0.065 0.05 -1.2 -1.4e-05 -5.7e-05 1.9e-06 2e-06 0.00025 -0.00016 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 1.8e-06 8.1e-05 8e-05 4.8e-05 4.9e-05 0.013 0.013 0.008 0.037 0.037 0.035 3e-11 3e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
309 30690000 0.98 -0.007 -0.014 0.18 -0.051 0.04 0.76 -0.07 0.054 -1.1 -1.4e-05 -5.7e-05 1.9e-06 2e-06 0.00025 -0.00016 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 8e-05 4.8e-05 0.013 0.013 0.008 0.041 0.041 0.035 3e-11 3e-11 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
310 30790000 0.98 -0.0067 -0.014 0.18 -0.044 0.035 0.76 -0.063 0.052 -1 -1.4e-05 -5.7e-05 2e-06 0.00025 -0.00016 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 8e-05 4.8e-05 0.013 0.013 0.008 0.037 0.037 0.035 3e-11 3e-11 1.1e-10 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
311 30890000 0.98 -0.006 -0.013 0.18 -0.044 0.032 0.76 -0.067 0.056 -0.95 -1.4e-05 -5.7e-05 1.9e-06 0.00025 -0.00016 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 8e-05 4.7e-05 4.8e-05 0.013 0.013 0.008 0.04 0.04 0.035 3e-11 3e-11 1.1e-10 1.2e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
312 30990000 0.98 -0.0062 -0.013 0.18 -0.036 0.026 0.76 -0.057 0.049 -0.88 -1.4e-05 -5.7e-05 1.9e-06 0.00026 -0.00017 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 8e-05 4.7e-05 4.8e-05 0.013 0.013 0.0079 0.037 0.037 0.035 3e-11 3e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
313 31090000 0.98 -0.0064 -0.014 0.18 -0.035 0.025 0.76 -0.061 0.051 -0.81 -1.4e-05 -5.7e-05 1.8e-06 0.00026 -0.00017 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 8e-05 4.7e-05 4.8e-05 0.013 0.013 0.008 0.04 0.04 0.036 3e-11 3e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
314 31190000 0.98 -0.0066 -0.0065 -0.014 0.18 -0.031 0.02 0.76 -0.052 0.046 -0.74 -1.4e-05 -5.7e-05 1.9e-06 0.00026 -0.00017 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 8e-05 4.7e-05 4.8e-05 0.013 0.013 0.008 0.037 0.037 0.035 2.9e-11 2.9e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
315 31290000 0.98 -0.0068 -0.014 0.18 -0.028 0.018 0.76 -0.055 0.048 -0.67 -1.4e-05 -5.7e-05 2e-06 0.00026 -0.00017 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 8e-05 4.7e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.9e-11 2.9e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
316 31390000 0.98 -0.0066 -0.014 0.18 -0.022 0.012 0.76 -0.046 0.042 -0.6 -1.4e-05 -5.7e-05 1.9e-06 0.00026 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 7.9e-05 4.7e-05 0.013 0.013 0.0079 0.037 0.037 0.035 2.9e-11 2.9e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
317 31490000 0.98 -0.0063 -0.014 0.18 -0.022 0.0089 0.76 -0.048 0.043 -0.52 -1.4e-05 -5.7e-05 1.9e-06 0.00026 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 8e-05 4.6e-05 4.7e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.9e-11 2.9e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
318 31590000 0.98 -0.0062 -0.014 0.18 -0.018 0.0066 0.76 -0.037 0.039 -0.45 -1.4e-05 -5.7e-05 2e-06 0.00027 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 7.9e-05 4.6e-05 4.7e-05 0.012 0.012 0.0079 0.037 0.037 0.035 2.9e-11 2.9e-11 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
319 31690000 0.98 -0.0062 -0.015 0.18 -0.02 0.0055 0.76 -0.039 0.039 -0.38 -1.4e-05 -5.7e-05 2.1e-06 0.00027 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8.1e-05 7.9e-05 4.6e-05 4.7e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.9e-11 2.9e-11 1e-10 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
320 31790000 0.98 -0.0064 -0.015 0.18 -0.011 0.003 0.76 -0.028 0.037 -0.31 -1.4e-05 -5.7e-05 2.2e-06 0.00027 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8e-05 7.9e-05 4.6e-05 4.7e-05 0.012 0.012 0.008 0.037 0.037 0.035 2.8e-11 2.8e-11 1e-10 1.1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
321 31890000 0.98 -0.0061 -0.015 0.18 -0.0078 0.00068 0.76 -0.029 0.038 -0.24 -1.4e-05 -5.7e-05 2.2e-06 0.00027 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8e-05 7.9e-05 4.6e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.8e-11 2.8e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
322 31990000 0.98 -0.0064 -0.015 0.18 0.00012 0.00013 1.8e-05 1.9e-05 0.75 -0.017 0.034 -0.18 -1.3e-05 -5.7e-05 2.2e-06 0.00028 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.7e-06 8e-05 7.9e-05 4.6e-05 0.012 0.012 0.0079 0.037 0.037 0.035 2.8e-11 2.8e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
323 32090000 0.98 -0.0067 -0.014 0.18 -0.0004 -0.0034 0.76 -0.017 0.034 -0.1 -1.3e-05 -5.7e-05 2.2e-06 0.00028 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 1.7e-06 8e-05 7.9e-05 4.6e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.8e-11 2.8e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
324 32190000 0.98 -0.0069 -0.015 0.18 0.0049 -0.0066 0.76 -0.0059 0.033 -0.037 -1.3e-05 -5.7e-05 2.1e-06 0.00028 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 1.7e-06 8e-05 7.9e-05 4.5e-05 4.6e-05 0.012 0.012 0.0079 0.037 0.037 0.035 2.8e-11 2.8e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
325 32290000 0.98 -0.0068 -0.015 0.18 0.0065 -0.0093 0.75 -0.0054 0.032 0.031 -1.3e-05 -5.7e-05 2.2e-06 0.00028 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 1.7e-06 8e-05 7.9e-05 4.5e-05 4.6e-05 0.013 0.013 0.008 0.04 0.04 0.035 2.8e-11 2.8e-11 9.9e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
326 32390000 0.98 -0.0069 -0.015 0.18 0.013 -0.011 0.75 0.0059 0.03 0.11 -1.3e-05 -5.7e-05 2.2e-06 0.00029 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 1.7e-06 8e-05 7.8e-05 4.5e-05 4.6e-05 0.012 0.012 0.008 0.037 0.037 0.035 2.7e-11 2.7e-11 9.8e-11 1e-10 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
327 32490000 0.98 -0.0098 -0.013 0.18 0.04 -0.074 -0.12 0.0091 0.023 0.11 -1.3e-05 -5.7e-05 2.1e-06 0.00029 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 8e-05 7.9e-05 4.5e-05 4.6e-05 0.015 0.015 0.0078 0.04 0.04 0.035 2.8e-11 2.8e-11 9.7e-11 9.9e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
328 32590000 0.98 -0.0097 -0.013 0.18 0.04 -0.075 -0.12 0.021 0.02 0.09 -1.4e-05 -5.7e-05 2.2e-06 0.00029 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 7.9e-05 7.7e-05 4.5e-05 0.016 0.016 0.0075 0.037 0.037 0.035 2.7e-11 2.7e-11 9.6e-11 9.8e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
329 32690000 0.98 -0.0097 -0.013 0.18 0.036 -0.081 -0.12 0.025 0.012 0.075 -1.4e-05 -5.7e-05 2.2e-06 0.00029 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 7.9e-05 7.8e-05 4.5e-05 0.019 0.019 0.0074 0.041 0.041 0.035 2.7e-11 2.7e-11 9.6e-11 9.7e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
330 32790000 0.98 -0.0094 -0.013 0.18 0.034 -0.078 -0.12 0.035 0.01 0.059 -1.4e-05 -5.7e-05 2.2e-06 2.3e-06 0.00029 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 7.6e-05 7.5e-05 4.5e-05 0.019 0.019 0.0071 0.037 0.037 0.035 2.7e-11 2.7e-11 9.5e-11 9.6e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
331 32890000 0.98 -0.0094 -0.013 0.18 0.034 -0.084 -0.13 0.038 0.0019 0.044 -1.4e-05 -5.7e-05 2.3e-06 0.00029 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 7.6e-05 7.5e-05 4.4e-05 4.5e-05 0.023 0.023 0.007 0.041 0.041 0.035 2.7e-11 2.7e-11 9.4e-11 9.5e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
332 32990000 0.98 -0.0091 -0.013 0.18 0.031 -0.08 -0.12 0.046 -0.0012 0.031 -1.4e-05 -5.6e-05 2.4e-06 0.00029 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 7.2e-05 7.1e-05 4.4e-05 4.5e-05 0.024 0.024 0.0067 0.038 0.038 0.035 2.7e-11 2.7e-11 9.3e-11 9.5e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
333 33090000 0.98 -0.009 -0.013 0.18 0.027 -0.084 -0.12 0.049 -0.0094 0.024 -1.4e-05 -5.6e-05 2.3e-06 0.00029 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 7.2e-05 7.1e-05 4.4e-05 4.5e-05 0.028 0.029 0.0066 0.042 0.042 0.035 2.7e-11 2.7e-11 9.2e-11 9.4e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
334 33190000 0.98 -0.0087 -0.013 0.18 0.022 -0.079 -0.12 0.054 -0.011 0.017 -1.4e-05 -5.6e-05 2.3e-06 0.00029 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.7e-05 6.6e-05 4.4e-05 0.029 0.029 0.0064 0.038 0.038 0.035 2.6e-11 2.6e-11 9.2e-11 9.3e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
335 33290000 0.98 -0.0088 -0.013 0.18 0.019 -0.081 -0.12 0.056 -0.019 0.0099 -1.4e-05 -5.6e-05 2.4e-06 0.00029 -0.00018 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6.7e-05 6.6e-05 4.4e-05 0.035 0.035 0.0063 0.043 0.043 0.034 2.6e-11 2.6e-11 9.1e-11 9.2e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
336 33390000 0.98 -0.0083 -0.013 0.18 0.014 -0.067 -0.12 0.059 -0.014 -0.0011 -1.4e-05 -5.6e-05 2.4e-06 0.00028 -0.00021 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6e-05 5.9e-05 4.4e-05 0.035 0.035 0.0062 0.039 0.039 0.034 2.6e-11 2.6e-11 9e-11 9.1e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
337 33490000 0.98 -0.0083 -0.013 0.18 0.0097 -0.067 -0.12 0.061 -0.021 -0.015 -1.4e-05 -5.6e-05 2.4e-06 0.00028 -0.00021 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 6e-05 5.9e-05 4.4e-05 0.042 0.042 0.0061 0.044 0.044 0.034 2.6e-11 2.6e-11 8.9e-11 9.1e-11 2.7e-06 2.7e-06 5e-08 0 0 0 0 0 0 0 0
338 33590000 0.98 -0.0079 -0.013 0.18 0.0057 -0.058 -0.12 0.063 -0.017 -0.026 -1.4e-05 -5.6e-05 2.4e-06 2.5e-06 0.00028 -0.00023 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 5.3e-05 5.2e-05 4.3e-05 4.4e-05 0.04 0.041 0.006 0.04 0.04 0.034 2.6e-11 2.6e-11 8.8e-11 9e-11 2.6e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
339 33690000 0.98 -0.0079 -0.013 0.18 0.001 0.0011 -0.058 -0.12 0.063 -0.023 -0.038 -1.4e-05 -5.6e-05 2.4e-06 2.5e-06 0.00028 -0.00023 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 5.3e-05 5.2e-05 4.3e-05 4.4e-05 0.048 0.048 0.0059 0.046 0.046 0.034 2.6e-11 2.6e-11 8.8e-11 8.9e-11 2.6e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
340 33790000 0.98 -0.0077 -0.013 0.18 -0.0022 -0.048 -0.11 0.067 -0.018 -0.048 -1.4e-05 -5.6e-05 2.4e-06 0.00026 -0.00026 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.6e-06 4.7e-05 4.6e-05 4.3e-05 4.4e-05 0.044 0.045 0.0059 0.041 0.041 0.034 2.6e-11 2.6e-11 8.7e-11 8.8e-11 2.5e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
341 33890000 0.98 -0.0077 -0.013 0.18 -0.0064 -0.045 -0.11 0.067 -0.023 -0.06 -1.4e-05 -5.6e-05 2.4e-06 2.5e-06 0.00026 -0.00026 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 1.6e-06 4.7e-05 4.6e-05 4.3e-05 0.052 0.052 0.0058 0.047 0.047 0.033 2.6e-11 2.6e-11 8.6e-11 8.7e-11 2.5e-06 2.6e-06 5e-08 0 0 0 0 0 0 0 0
342 33990000 0.98 -0.0074 -0.013 0.18 -0.0061 -0.031 -0.11 0.07 -0.015 -0.069 -1.4e-05 -5.6e-05 2.4e-06 0.00024 -0.00029 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 1.6e-06 4.1e-05 4.1e-05 4.3e-05 0.047 0.047 0.0058 0.042 0.042 0.033 2.6e-11 2.6e-11 8.6e-11 8.7e-11 2.5e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
343 34090000 0.98 -0.0074 -0.013 0.18 -0.01 -0.031 -0.11 0.069 -0.018 -0.081 -1.4e-05 -5.6e-05 2.3e-06 2.4e-06 0.00024 -0.00029 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 1.6e-06 4.1e-05 4.1e-05 4.3e-05 0.054 0.054 0.0058 0.049 0.049 0.033 2.6e-11 2.6e-11 8.5e-11 8.6e-11 2.5e-06 2.5e-06 5e-08 0 0 0 0 0 0 0 0
344 34190000 0.98 -0.0073 -0.013 0.18 -0.011 -0.02 -0.11 0.072 -0.013 -0.091 -1.4e-05 -5.6e-05 2.4e-06 0.00022 -0.00031 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 3.7e-05 3.6e-05 4.3e-05 0.048 0.048 0.0058 0.043 0.043 0.033 2.6e-11 2.6e-11 8.4e-11 8.5e-11 2.4e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
345 34290000 0.98 -0.0071 -0.013 0.18 -0.012 -0.02 -0.11 0.071 -0.015 -0.1 -1.4e-05 -5.6e-05 2.4e-06 0.00022 -0.00031 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 3.7e-05 3.6e-05 4.2e-05 4.3e-05 0.054 0.055 0.0058 0.05 0.05 0.033 2.6e-11 2.6e-11 8.3e-11 8.5e-11 2.4e-06 2.4e-06 5e-08 0 0 0 0 0 0 0 0
346 34390000 0.98 -0.007 -0.013 0.18 -0.013 -0.01 -0.11 0.073 -0.01 -0.11 -1.4e-05 -5.6e-05 2.3e-06 2.4e-06 0.00021 -0.00032 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 3.3e-05 3.3e-05 4.2e-05 4.3e-05 0.047 0.047 0.0059 0.044 0.044 0.033 2.6e-11 2.6e-11 8.3e-11 8.4e-11 2.3e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
347 34490000 0.98 -0.0071 -0.013 0.18 -0.016 -0.009 -0.11 0.071 -0.011 -0.12 -1.4e-05 -5.6e-05 2.4e-06 0.00021 -0.00032 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 3.3e-05 3.3e-05 4.2e-05 4.3e-05 0.053 0.053 0.0059 0.051 0.051 0.032 2.6e-11 2.6e-11 8.2e-11 8.3e-11 2.3e-06 2.3e-06 5e-08 0 0 0 0 0 0 0 0
348 34590000 0.98 -0.007 -0.013 0.18 -0.015 -0.0045 0.69 0.073 -0.0088 -0.098 -1.4e-05 -5.6e-05 2.3e-06 0.0002 -0.00032 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 3.1e-05 3.1e-05 4.2e-05 4.3e-05 0.044 0.044 0.0059 0.045 0.045 0.032 2.6e-11 2.6e-11 8.2e-11 8.3e-11 2.2e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
349 34690000 0.98 -0.007 -0.013 0.18 -0.018 -0.0021 1.7 0.071 -0.0091 0.02 -1.4e-05 -5.6e-05 2.3e-06 0.0002 -0.00032 -0.0011 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 3.1e-05 3.1e-05 4.2e-05 0.047 0.047 0.006 0.052 0.052 0.032 2.6e-11 2.6e-11 8.1e-11 8.2e-11 2.2e-06 2.2e-06 5e-08 0 0 0 0 0 0 0 0
350 34790000 0.98 -0.007 -0.012 0.18 -0.02 0.0026 2.6 0.072 -0.0068 0.2 -1.4e-05 -5.6e-05 2.3e-06 0.00021 -0.00034 -0.001 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 2.9e-05 2.9e-05 4.2e-05 0.04 0.04 0.0061 0.045 0.045 0.032 2.6e-11 2.6e-11 8e-11 8.1e-11 2e-06 2e-06 5e-08 0 0 0 0 0 0 0 0
351 34890000 0.98 -0.007 -0.012 0.18 -0.024 0.0053 3.6 0.07 -0.0062 0.49 -1.4e-05 -5.6e-05 2.3e-06 0.00021 -0.00034 -0.001 0.2 0.002 0.43 0 0 0 0 0 1.5e-06 3e-05 2.9e-05 4.2e-05 0.043 0.043 0.0061 0.052 0.052 0.032 2.6e-11 2.6e-11 8e-11 8.1e-11 2e-06 2e-06 5e-08 0 0 0 0 0 0 0 0
@@ -77,6 +77,7 @@ void EkfWrapper::setExternalVisionHeightRef()
void EkfWrapper::enableExternalVisionHeightFusion()
{
_ekf_params->ev_ctrl |= static_cast<int32_t>(EvCtrl::VPOS);
setExternalVisionHeightRef(); // TODO: replace by EV control parameter
}
@@ -137,12 +138,12 @@ void EkfWrapper::setFlowOffset(const Vector3f &offset)
void EkfWrapper::enableExternalVisionPositionFusion()
{
_ekf_params->fusion_mode |= SensorFusionMask::USE_EXT_VIS_POS;
_ekf_params->ev_ctrl |= static_cast<int32_t>(EvCtrl::HPOS);
}
void EkfWrapper::disableExternalVisionPositionFusion()
{
_ekf_params->fusion_mode &= ~SensorFusionMask::USE_EXT_VIS_POS;
_ekf_params->ev_ctrl &= ~static_cast<int32_t>(EvCtrl::HPOS);
}
bool EkfWrapper::isIntendingExternalVisionPositionFusion() const
@@ -167,12 +168,12 @@ bool EkfWrapper::isIntendingExternalVisionVelocityFusion() const
void EkfWrapper::enableExternalVisionHeadingFusion()
{
_ekf_params->fusion_mode |= SensorFusionMask::USE_EXT_VIS_YAW;
_ekf_params->ev_ctrl |= static_cast<int32_t>(EvCtrl::YAW);
}
void EkfWrapper::disableExternalVisionHeadingFusion()
{
_ekf_params->fusion_mode &= ~SensorFusionMask::USE_EXT_VIS_YAW;
_ekf_params->ev_ctrl &= ~static_cast<int32_t>(EvCtrl::YAW);
}
bool EkfWrapper::isIntendingExternalVisionHeadingFusion() const
@@ -180,16 +181,6 @@ bool EkfWrapper::isIntendingExternalVisionHeadingFusion() const
return _ekf->control_status_flags().ev_yaw;
}
void EkfWrapper::enableExternalVisionAlignment()
{
_ekf_params->fusion_mode |= SensorFusionMask::ROTATE_EXT_VIS;
}
void EkfWrapper::disableExternalVisionAlignment()
{
_ekf_params->fusion_mode &= ~SensorFusionMask::ROTATE_EXT_VIS;
}
bool EkfWrapper::isIntendingMagHeadingFusion() const
{
return _ekf->control_status_flags().mag_hdg;
@@ -98,9 +98,6 @@ public:
bool isIntendingMag3DFusion() const;
void setMagFuseTypeNone();
void enableExternalVisionAlignment();
void disableExternalVisionAlignment();
bool isWindVelocityEstimated() const;
void enableTerrainRngFusion();
+16 -4
View File
@@ -8,6 +8,7 @@ namespace sensor
Vio::Vio(std::shared_ptr<Ekf> ekf): Sensor(ekf)
{
_vio_data.vel_frame = VelocityFrame::LOCAL_FRAME_FRD;
_vio_data.pos_frame = PositionFrame::LOCAL_FRAME_FRD;
}
Vio::~Vio()
@@ -32,7 +33,7 @@ void Vio::setVelocityVariance(const Vector3f &velVar)
void Vio::setPositionVariance(const Vector3f &posVar)
{
_vio_data.posVar = posVar;
_vio_data.position_var = posVar;
}
void Vio::setAngularVariance(float angVar)
@@ -70,16 +71,27 @@ void Vio::setVelocityFrameToLocalNED()
_vio_data.vel_frame = VelocityFrame::LOCAL_FRAME_NED;
}
void Vio::setPositionFrameToLocalNED()
{
_vio_data.pos_frame = PositionFrame::LOCAL_FRAME_NED;
}
void Vio::setPositionFrameToLocalFRD()
{
_vio_data.pos_frame = PositionFrame::LOCAL_FRAME_FRD;
}
extVisionSample Vio::dataAtRest()
{
extVisionSample vio_data;
vio_data.pos = Vector3f{0.0f, 0.0f, 0.0f};;
vio_data.vel = Vector3f{0.0f, 0.0f, 0.0f};;
vio_data.pos = Vector3f{0.0f, 0.0f, 0.0f};
vio_data.vel = Vector3f{0.0f, 0.0f, 0.0f};
vio_data.quat = Quatf{1.0f, 0.0f, 0.0f, 0.0f};
vio_data.posVar = Vector3f{0.1f, 0.1f, 0.1f};
vio_data.position_var = Vector3f{0.1f, 0.1f, 0.1f};
vio_data.velocity_var = Vector3f{0.1f, 0.1f, 0.1f};
vio_data.orientation_var(2) = 0.05f;
vio_data.vel_frame = VelocityFrame::LOCAL_FRAME_FRD;
vio_data.pos_frame = PositionFrame::LOCAL_FRAME_FRD;
return vio_data;
}
@@ -63,6 +63,9 @@ public:
void setVelocityFrameToLocalFRD();
void setVelocityFrameToBody();
void setPositionFrameToLocalNED();
void setPositionFrameToLocalFRD();
extVisionSample dataAtRest();
private:
@@ -78,6 +78,7 @@ TEST_F(EkfExternalVisionTest, checkVisionFusionLogic)
{
_sensor_simulator.runSeconds(_tilt_align_time); // Let the tilt align
_ekf_wrapper.enableExternalVisionPositionFusion();
_sensor_simulator._vio.setPositionFrameToLocalNED();
_sensor_simulator.startExternalVision();
_sensor_simulator.runSeconds(2);
@@ -147,7 +148,6 @@ TEST_F(EkfExternalVisionTest, visionVelocityResetWithAlignment)
// WHEN: Vision frame is rotate +90°. The reported heading is -90°
Quatf vision_to_ekf(Eulerf(0.0f, 0.0f, math::radians(-90.0f)));
_sensor_simulator._vio.setOrientation(vision_to_ekf.inversed());
_ekf_wrapper.enableExternalVisionAlignment();
const Vector3f simulated_velocity_in_vision_frame(0.3f, -1.0f, 0.4f);
const Vector3f simulated_velocity_in_ekf_frame =
@@ -179,6 +179,7 @@ TEST_F(EkfExternalVisionTest, visionHorizontalPositionReset)
const Vector3f simulated_position(8.3f, -1.0f, 0.0f);
_sensor_simulator._vio.setPosition(simulated_position);
_sensor_simulator._vio.setPositionFrameToLocalNED();
_ekf_wrapper.enableExternalVisionPositionFusion();
_sensor_simulator.startExternalVision();
_sensor_simulator.runMicroseconds(2e5);
@@ -197,7 +198,6 @@ TEST_F(EkfExternalVisionTest, visionHorizontalPositionResetWithAlignment)
// WHEN: Vision frame is rotate +90°. The reported heading is -90°
Quatf vision_to_ekf(Eulerf(0.0f, 0.0f, math::radians(-90.0f)));
_sensor_simulator._vio.setOrientation(vision_to_ekf.inversed());
_ekf_wrapper.enableExternalVisionAlignment();
const Vector3f simulated_position_in_vision_frame(8.3f, -1.0f, 0.0f);
const Vector3f simulated_position_in_ekf_frame =
@@ -236,7 +236,6 @@ TEST_F(EkfExternalVisionTest, visionAlignment)
// WHEN: Vision frame is rotate +90°. The reported heading is -90°
Quatf externalVisionFrameOffset(Eulerf(0.0f, 0.0f, math::radians(90.0f)));
_sensor_simulator._vio.setOrientation(externalVisionFrameOffset.inversed());
_ekf_wrapper.enableExternalVisionAlignment();
// Simulate high uncertainty on vision x axis which is in this case
// the y EKF frame axis
@@ -254,9 +253,9 @@ TEST_F(EkfExternalVisionTest, visionAlignment)
EXPECT_TRUE(velVar_new(1) > velVar_new(0));
// THEN: the frame offset should be estimated correctly
Quatf estimatedExternalVisionFrameOffset = _ekf->getVisionAlignmentQuaternion();
EXPECT_TRUE(matrix::isEqual(externalVisionFrameOffset.canonical(),
estimatedExternalVisionFrameOffset.canonical()));
// Quatf estimatedExternalVisionFrameOffset = _ekf->getVisionAlignmentQuaternion();
// EXPECT_TRUE(matrix::isEqual(externalVisionFrameOffset.canonical(),
// estimatedExternalVisionFrameOffset.canonical()));
}
TEST_F(EkfExternalVisionTest, velocityFrameBody)
@@ -340,7 +339,6 @@ TEST_F(EkfExternalVisionTest, positionFrameLocal)
// WHEN: using EV yaw fusion and rotate EV is set
Quatf vision_to_ekf(Eulerf(0.0f, 0.0f, 0.f));
_sensor_simulator._vio.setOrientation(vision_to_ekf.inversed());
_ekf_wrapper.enableExternalVisionAlignment(); // ROTATE_EV
_ekf_wrapper.enableExternalVisionHeadingFusion(); // EV_YAW
// AND WHEN: using EV position aiding
@@ -106,10 +106,10 @@ TEST_F(EKFYawEstimatorTest, inAirYawAlignment)
EXPECT_NEAR(yaw_est, yaw, tolerance_rad);
EXPECT_LT(yaw_est_var, tolerance_rad);
// 2 resets: 1 after IMU+GNSS yaw alignment and 1 when starting GNSS aiding
// 1 reset when starting GNSS aiding
reset_logging_checker.capturePostResetState();
EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(2));
EXPECT_TRUE(reset_logging_checker.isHorizontalPositionResetCounterIncreasedBy(2));
EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(1));
EXPECT_TRUE(reset_logging_checker.isHorizontalPositionResetCounterIncreasedBy(1));
EXPECT_TRUE(_ekf->local_position_is_valid());
EXPECT_TRUE(_ekf->global_position_is_valid());
+37 -21
View File
@@ -144,27 +144,26 @@ void LoggedTopics::add_default_topics()
#endif
// always add the first instance
add_topic("estimator_baro_bias", 500);
add_topic("estimator_gnss_hgt_bias", 500);
add_topic("estimator_rng_hgt_bias", 500);
add_topic("estimator_ev_hgt_bias", 500);
add_topic("estimator_baro_bias", 0);
add_topic("estimator_gnss_hgt_bias", 0);
add_topic("estimator_rng_hgt_bias", 0);
add_topic("estimator_ev_pos_bias", 0);
add_topic("estimator_event_flags", 0);
add_topic("estimator_gps_status", 1000);
add_topic("estimator_innovation_test_ratios", 500);
add_topic("estimator_innovation_variances", 500);
add_topic("estimator_innovation_test_ratios", 50);
add_topic("estimator_innovation_variances", 50);
add_topic("estimator_innovations", 500);
add_topic("estimator_optical_flow_vel", 200);
add_topic("estimator_optical_flow_vel", 0);
add_topic("estimator_sensor_bias", 0);
add_topic("estimator_states", 1000);
add_topic("estimator_status", 200);
add_topic("estimator_states", 10);
add_topic("estimator_status", 10);
add_topic("estimator_status_flags", 0);
add_topic("estimator_visual_odometry_aligned", 200);
add_topic("yaw_estimator_status", 1000);
add_topic("yaw_estimator_status", 100);
add_optional_topic_multi("estimator_baro_bias", 500, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_gnss_hgt_bias", 500, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_rng_hgt_bias", 500, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_ev_hgt_bias", 500, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_ev_pos_bias", 500, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_event_flags", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_gps_status", 1000, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_innovation_test_ratios", 500, MAX_ESTIMATOR_INSTANCES);
@@ -175,7 +174,6 @@ void LoggedTopics::add_default_topics()
add_optional_topic_multi("estimator_states", 1000, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_status", 200, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_status_flags", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_visual_odometry_aligned", 200, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("yaw_estimator_status", 1000, MAX_ESTIMATOR_INSTANCES);
// add_optional_topic_multi("estimator_aid_src_airspeed", 100, MAX_ESTIMATOR_INSTANCES);
@@ -194,6 +192,26 @@ void LoggedTopics::add_default_topics()
// add_optional_topic_multi("estimator_aid_src_optical_flow", 100, MAX_ESTIMATOR_INSTANCES);
// add_optional_topic_multi("estimator_aid_src_ev_yaw", 100, MAX_ESTIMATOR_INSTANCES);
// TODO: temporary
add_topic_multi("estimator_aid_src_airspeed", 10, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_aux_vel", 10, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_baro_hgt", 0, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_ev_hgt", 0, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_ev_pos", 0, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_ev_vel", 0, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_ev_yaw", 0, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_fake_hgt", 10, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_fake_pos", 10, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_gnss_hgt", 10, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_gnss_pos", 10, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_gnss_vel", 10, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_gnss_yaw", 10, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_mag", 10, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_mag_heading", 10, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_optical_flow", 0, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_rng_hgt", 0, MAX_ESTIMATOR_INSTANCES);
add_topic_multi("estimator_aid_src_sideslip", 10, MAX_ESTIMATOR_INSTANCES);
// log all raw sensors at minimal rate (at least 1 Hz)
add_topic_multi("battery_status", 200, 2);
add_topic_multi("differential_pressure", 1000, 2);
@@ -204,13 +222,13 @@ void LoggedTopics::add_default_topics()
add_topic_multi("sensor_gnss_relative", 1000, 1);
add_optional_topic_multi("sensor_gyro", 1000, 4);
add_topic_multi("sensor_mag", 1000, 4);
add_topic_multi("sensor_optical_flow", 1000, 2);
add_topic_multi("sensor_optical_flow", 10, 2);
add_topic_multi("vehicle_imu", 500, 4);
add_topic_multi("vehicle_imu_status", 1000, 4);
add_optional_topic_multi("vehicle_magnetometer", 500, 4);
add_topic("vehicle_optical_flow", 500);
//add_optional_topic("vehicle_optical_flow_vel", 100);
add_topic("vehicle_optical_flow", 10);
add_optional_topic("vehicle_optical_flow_vel", 10);
add_optional_topic("pps_capture");
// additional control allocation logging
@@ -248,7 +266,7 @@ void LoggedTopics::add_default_topics()
add_topic("estimator_baro_bias");
add_topic("estimator_gnss_hgt_bias");
add_topic("estimator_rng_hgt_bias");
add_topic("estimator_ev_hgt_bias");
add_topic("estimator_ev_pos_bias");
add_topic("estimator_event_flags");
add_topic("estimator_gps_status");
add_topic("estimator_innovation_test_ratios");
@@ -259,7 +277,6 @@ void LoggedTopics::add_default_topics()
add_topic("estimator_states");
add_topic("estimator_status");
add_topic("estimator_status_flags");
add_topic("estimator_visual_odometry_aligned");
add_topic("vehicle_attitude");
add_topic("vehicle_global_position");
add_topic("vehicle_local_position");
@@ -281,7 +298,6 @@ void LoggedTopics::add_default_topics()
add_optional_topic_multi("estimator_aid_src_gnss_yaw", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_mag_heading", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_mag", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_ev_yaw", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_optical_flow", 0, MAX_ESTIMATOR_INSTANCES);
add_optional_topic_multi("estimator_aid_src_sideslip", 0, MAX_ESTIMATOR_INSTANCES);
@@ -324,13 +340,13 @@ void LoggedTopics::add_estimator_replay_topics()
// current EKF2 subscriptions
add_topic("airspeed");
add_topic("optical_flow");
add_topic("sensor_combined");
add_topic("sensor_selection");
add_topic("vehicle_air_data");
add_topic("vehicle_gps_position");
add_topic("vehicle_land_detected");
add_topic("vehicle_magnetometer");
add_topic("vehicle_optical_flow");
add_topic("vehicle_status");
add_topic("vehicle_visual_odometry");
add_topic_multi("distance_sensor");
@@ -358,7 +374,7 @@ void LoggedTopics::add_vision_and_avoidance_topics()
add_topic("vehicle_mocap_odometry", 30);
add_topic("vehicle_trajectory_waypoint", 200);
add_topic("vehicle_trajectory_waypoint_desired", 200);
add_topic("vehicle_visual_odometry", 30);
add_topic("vehicle_visual_odometry", 0);
}
void LoggedTopics::add_raw_imu_gyro_fifo()
-2
View File
@@ -502,7 +502,6 @@ public:
bool hash_check_enabled() const { return _param_mav_hash_chk_en.get(); }
bool forward_heartbeats_enabled() const { return _param_mav_hb_forw_en.get(); }
bool odometry_loopback_enabled() const { return _param_mav_odom_lp.get(); }
bool failure_injection_enabled() const { return _param_sys_failure_injection_enabled.get(); }
@@ -675,7 +674,6 @@ private:
(ParamBool<px4::params::MAV_FWDEXTSP>) _param_mav_fwdextsp,
(ParamBool<px4::params::MAV_HASH_CHK_EN>) _param_mav_hash_chk_en,
(ParamBool<px4::params::MAV_HB_FORW_EN>) _param_mav_hb_forw_en,
(ParamBool<px4::params::MAV_ODOM_LP>) _param_mav_odom_lp,
(ParamInt<px4::params::MAV_RADIO_TOUT>) _param_mav_radio_timeout,
(ParamInt<px4::params::SYS_HITL>) _param_sys_hitl,
(ParamBool<px4::params::SYS_FAILURE_EN>) _param_sys_failure_injection_enabled
-11
View File
@@ -142,17 +142,6 @@ PARAM_DEFINE_INT32(MAV_HASH_CHK_EN, 1);
*/
PARAM_DEFINE_INT32(MAV_HB_FORW_EN, 1);
/**
* Activate ODOMETRY loopback.
*
* If set, it gets the data from 'vehicle_visual_odometry' instead of 'vehicle_odometry'
* serving as a loopback of the received ODOMETRY messages on the Mavlink receiver.
*
* @boolean
* @group MAVLink
*/
PARAM_DEFINE_INT32(MAV_ODOM_LP, 0);
/**
* Timeout in seconds for the RADIO_STATUS reports coming in
*
+5 -27
View File
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2021 PX4 Development Team. All rights reserved.
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@@ -49,42 +49,20 @@ public:
unsigned get_size() override
{
if (_mavlink->odometry_loopback_enabled()) {
return _vodom_sub.advertised() ? MAVLINK_MSG_ID_ODOMETRY_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
} else {
return _odom_sub.advertised() ? MAVLINK_MSG_ID_ODOMETRY_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
}
return _vehicle_odometry_sub.advertised() ? MAVLINK_MSG_ID_ODOMETRY_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES : 0;
}
private:
explicit MavlinkStreamOdometry(Mavlink *mavlink) : MavlinkStream(mavlink) {}
uORB::Subscription _odom_sub{ORB_ID(vehicle_odometry)};
uORB::Subscription _vodom_sub{ORB_ID(vehicle_visual_odometry)};
uORB::Subscription _vehicle_odometry_sub{ORB_ID(vehicle_odometry)};
bool send() override
{
vehicle_odometry_s odom;
// check if it is to send visual odometry loopback or not
bool odom_updated = false;
mavlink_odometry_t msg{};
if (_mavlink->odometry_loopback_enabled()) {
odom_updated = _vodom_sub.update(&odom);
// source: external vision system
msg.estimator_type = MAV_ESTIMATOR_TYPE_VISION;
} else {
odom_updated = _odom_sub.update(&odom);
// source: PX4 estimator
msg.estimator_type = MAV_ESTIMATOR_TYPE_AUTOPILOT;
}
if (odom_updated) {
if (_vehicle_odometry_sub.update(&odom)) {
mavlink_odometry_t msg{};
msg.time_usec = odom.timestamp_sample;
// set the frame_id according to the local frame of the data