diff --git a/msg/ekf_gps_drift.msg b/msg/ekf_gps_drift.msg index 5016c97c0e..68163d7910 100644 --- a/msg/ekf_gps_drift.msg +++ b/msg/ekf_gps_drift.msg @@ -2,4 +2,5 @@ uint64 timestamp # time since system start (microseconds) float32 hpos_drift_rate # Horizontal position rate magnitude checked using EKF2_REQ_HDRIFT (m/s) float32 vpos_drift_rate # Vertical position rate magnitude checked using EKF2_REQ_VDRIFT (m/s) float32 hspd # Filtered horizontal velocity magnitude checked using EKF2_REQ_HDRIFT (m/s) -bool blocked # true when drift calculation is blocked due to IMU movement check controlled by EKF2_MOVE_TEST + +bool blocked # true when drift calculation is blocked due to IMU movement check diff --git a/msg/estimator_status.msg b/msg/estimator_status.msg index e96087a7a5..a34e5672a4 100644 --- a/msg/estimator_status.msg +++ b/msg/estimator_status.msg @@ -1,11 +1,6 @@ uint64 timestamp # time since system start (microseconds) uint64 timestamp_sample # the timestamp of the raw data (microseconds) -float32[3] vibe # IMU vibration metrics in the following array locations -# 0 : Gyro delta angle coning metric = filtered length of (delta_angle x prev_delta_angle) -# 1 : Gyro high frequency vibe = filtered length of (delta_angle - prev_delta_angle) -# 2 : Accel high frequency vibe = filtered length of (delta_velocity - prev_delta_velocity) - float32[3] output_tracking_error # return a vector containing the output predictor angular, velocity and position tracking error magnitudes (rad), (m/s), (m) uint16 gps_check_fail_flags # Bitmask to indicate status of GPS checks - see definition below diff --git a/msg/vehicle_land_detected.msg b/msg/vehicle_land_detected.msg index b11e3e794d..a35a8414c3 100644 --- a/msg/vehicle_land_detected.msg +++ b/msg/vehicle_land_detected.msg @@ -1,11 +1,18 @@ uint64 timestamp # time since system start (microseconds) + bool freefall # true if vehicle is currently in free-fall bool ground_contact # true if vehicle has ground contact but is not landed (1. stage) bool maybe_landed # true if the vehicle might have landed (2. stage) bool landed # true if vehicle is currently landed on the ground (3. stage) + bool in_ground_effect # indicates if from the perspective of the landing detector the vehicle might be in ground effect (baro). This flag will become true if the vehicle is not moving horizontally and is descending (crude assumption that user is landing). bool in_descend + bool has_low_throttle + bool vertical_movement bool horizontal_movement + bool close_to_ground_or_skipped_check + +bool at_rest diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 639eb1977a..9fd3aceff9 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -374,9 +374,6 @@ struct parameters { const float auxvel_noise{0.5f}; ///< minimum observation noise, uses reported noise if greater (m/s) const float auxvel_gate{5.0f}; ///< velocity fusion innovation consistency gate size (STD) - // control of on-ground movement check - float is_moving_scaler{1.0f}; ///< gain scaler used to adjust the threshold for the on-ground movement detection. Larger values make the test less sensitive. - // compute synthetic magnetomter Z value if possible int32_t synthesize_mag_z{0}; int32_t check_mag_strength{0}; diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 7984842ea4..d2a2ff4663 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -82,6 +82,8 @@ void Ekf::reset() _prev_dvel_bias_var.zero(); + _control_status.flags.vehicle_at_rest = true; + resetGpsDriftCheckFilters(); } diff --git a/src/modules/ekf2/EKF/estimator_interface.cpp b/src/modules/ekf2/EKF/estimator_interface.cpp index 2b75adc2d3..fb6ccb71db 100644 --- a/src/modules/ekf2/EKF/estimator_interface.cpp +++ b/src/modules/ekf2/EKF/estimator_interface.cpp @@ -75,9 +75,6 @@ void EstimatorInterface::setIMUData(const imuSample &imu_sample) _newest_high_rate_imu_sample = imu_sample; - // Do not change order of computeVibrationMetric and checkIfVehicleAtRest - _control_status.flags.vehicle_at_rest = checkIfVehicleAtRest(dt, imu_sample); - _imu_updated = _imu_down_sampler.update(imu_sample); // accumulate and down-sample imu data and push to the buffer when new downsampled data becomes available @@ -96,25 +93,6 @@ void EstimatorInterface::setIMUData(const imuSample &imu_sample) } } -bool EstimatorInterface::checkIfVehicleAtRest(float dt, const imuSample &imu) -{ - // detect if the vehicle is not moving when on ground - if (!_control_status.flags.in_air) { - if (((_vibe_metrics(1) * 4.0e4f > _params.is_moving_scaler) || (_vibe_metrics(2) * 2.1e2f > _params.is_moving_scaler)) - && ((imu.delta_ang.norm() / dt) > 0.05f * _params.is_moving_scaler)) { - - _time_last_move_detect_us = imu.time_us; - } - - return ((imu.time_us - _time_last_move_detect_us) > (uint64_t)1E6); - - } else { - _time_last_move_detect_us = imu.time_us; - return false; - } -} - - void EstimatorInterface::setMagData(const magSample &mag_sample) { if (!_initialised) { diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index a7b3ae0e3a..aa7faac64f 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -81,17 +81,6 @@ public: void setIMUData(const imuSample &imu_sample); - /* - Returns following IMU vibration metrics in the following array locations - 0 : Gyro delta angle coning metric = filtered length of (delta_angle x prev_delta_angle) - 1 : Gyro high frequency vibe = filtered length of (delta_angle - prev_delta_angle) - 2 : Accel high frequency vibe = filtered length of (delta_velocity - prev_delta_velocity) - */ - const Vector3f &getImuVibrationMetrics() const { return _vibe_metrics; } - void setDeltaAngleConingMetric(float delta_angle_coning_metric) { _vibe_metrics(0) = delta_angle_coning_metric; } - void setDeltaAngleHighFrequencyVibrationMetric(float delta_angle_vibration_metric) { _vibe_metrics(1) = delta_angle_vibration_metric; } - void setDeltaVelocityHighFrequencyVibrationMetric(float delta_velocity_vibration_metric) { _vibe_metrics(2) = delta_velocity_vibration_metric; } - void setMagData(const magSample &mag_sample); void setGpsData(const gps_message &gps); @@ -127,6 +116,8 @@ public: _control_status.flags.in_air = in_air; } + void set_vehicle_at_rest(bool at_rest) { _control_status.flags.vehicle_at_rest = at_rest; } + // return true if the attitude is usable bool attitude_valid() const { return PX4_ISFINITE(_output_new.quat_nominal(0)) && _control_status.flags.tilt_align; } @@ -248,8 +239,6 @@ public: const decltype(information_event_status_u::flags) &information_event_flags() const { return _information_events.flags; } void clear_information_events() { _information_events.value = 0; } - bool isVehicleAtRest() const { return _control_status.flags.vehicle_at_rest; } - // Getter for the average imu update period in s float get_dt_imu_avg() const { return _dt_imu_avg; } @@ -363,7 +352,7 @@ protected: // [0] Horizontal position drift rate (m/s) // [1] Vertical position drift rate (m/s) // [2] Filtered horizontal velocity (m/s) - uint64_t _time_last_move_detect_us{0}; // timestamp of last movement detection event in microseconds + uint64_t _time_last_on_ground_us{0}; ///< last time we were on the ground (uSec) uint64_t _time_last_in_air{0}; ///< last time we were in air (uSec) bool _gps_drift_updated{false}; // true when _gps_drift_metrics has been updated and is ready for retrieval @@ -422,26 +411,14 @@ private: inline void setDragData(const imuSample &imu); - inline void computeVibrationMetric(const imuSample &imu); - inline bool checkIfVehicleAtRest(float dt, const imuSample &imu); - void printBufferAllocationFailed(const char *buffer_name); ImuDownSampler _imu_down_sampler{_params.filter_update_interval_us}; unsigned _min_obs_interval_us{0}; // minimum time interval between observations that will guarantee data is not lost (usec) - // IMU vibration and movement monitoring - Vector3f _vibe_metrics{}; // IMU vibration metrics - // [0] Level of coning vibration in the IMU delta angles (rad^2) - // [1] high frequency vibration level in the IMU delta angle data (rad) - // [2] high frequency vibration level in the IMU delta velocity data (m/s) - // Used by the multi-rotor specific drag force fusion uint8_t _drag_sample_count{0}; // number of drag specific force samples assumulated at the filter prediction rate float _drag_sample_time_dt{0.0f}; // time integral across all samples used to form _drag_down_sampled (sec) - - // observation buffer final allocation failed - uint64_t _last_allocation_fail_print{0}; }; #endif // !EKF_ESTIMATOR_INTERFACE_H diff --git a/src/modules/ekf2/EKF/fake_pos_control.cpp b/src/modules/ekf2/EKF/fake_pos_control.cpp index 341877a9b4..cc8224f8ed 100644 --- a/src/modules/ekf2/EKF/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/fake_pos_control.cpp @@ -105,7 +105,7 @@ void Ekf::fuseFakePosition() if (_control_status.flags.in_air && _control_status.flags.tilt_align) { fake_pos_obs_var(0) = fake_pos_obs_var(1) = sq(fmaxf(_params.pos_noaid_noise, _params.gps_pos_noise)); - } else if (_control_status.flags.vehicle_at_rest) { + } else if (!_control_status.flags.in_air && _control_status.flags.vehicle_at_rest) { // Accelerate tilt fine alignment by fusing more // aggressively when the vehicle is at rest fake_pos_obs_var(0) = fake_pos_obs_var(1) = sq(0.1f); diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 4bd85f9a8b..1b294b0ba0 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -160,7 +160,6 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode): _param_ekf2_pcoef_yp(_params->static_pressure_coef_yp), _param_ekf2_pcoef_yn(_params->static_pressure_coef_yn), _param_ekf2_pcoef_z(_params->static_pressure_coef_z), - _param_ekf2_move_test(_params->is_moving_scaler), _param_ekf2_mag_check(_params->check_mag_strength), _param_ekf2_synthetic_mag_z(_params->synthesize_mag_z), _param_ekf2_gsf_tas_default(_params->EKFGSF_tas_default) @@ -385,8 +384,6 @@ void EKF2::Run() _gyro_calibration_count = imu.gyro_calibration_count; } else { - bool reset_actioned = false; - if ((imu.accel_calibration_count != _accel_calibration_count) || (imu.accel_device_id != _device_id_accel)) { @@ -398,8 +395,6 @@ void EKF2::Run() // reset bias learning _accel_cal = {}; - - reset_actioned = true; } if ((imu.gyro_calibration_count != _gyro_calibration_count) @@ -413,12 +408,6 @@ void EKF2::Run() // reset bias learning _gyro_cal = {}; - - reset_actioned = true; - } - - if (reset_actioned) { - SelectImuStatus(); } } } @@ -460,8 +449,6 @@ void EKF2::Run() // reset bias learning _accel_cal = {}; - - SelectImuStatus(); } if (_device_id_gyro != sensor_selection.gyro_device_id) { @@ -472,8 +459,6 @@ void EKF2::Run() // reset bias learning _gyro_cal = {}; - - SelectImuStatus(); } } } @@ -482,8 +467,6 @@ void EKF2::Run() if (imu_updated) { const hrt_abstime now = imu_sample_new.time_us; - UpdateImuStatus(); - // push imu data into estimator _ekf.setIMUData(imu_sample_new); PublishAttitude(now); // publish attitude immediately (uses quaternion from output predictor) @@ -534,6 +517,7 @@ void EKF2::Run() if (_vehicle_land_detected_sub.copy(&vehicle_land_detected)) { const bool was_in_air = _ekf.control_status_flags().in_air; _ekf.set_in_air_status(!vehicle_land_detected.landed); + _ekf.set_vehicle_at_rest(vehicle_land_detected.at_rest); if (_armed && (_param_ekf2_gnd_eff_dz.get() > 0.f)) { if (!_had_valid_terrain) { @@ -1194,7 +1178,6 @@ void EKF2::PublishStatus(const hrt_abstime ×tamp) _ekf.get_ekf_lpos_accuracy(&status.pos_horiz_accuracy, &status.pos_vert_accuracy); _ekf.get_ekf_soln_status(&status.solution_status_flags); - _ekf.getImuVibrationMetrics().copyTo(status.vibe); // reset counters status.reset_count_vel_ne = _ekf.state_reset_status().velNE_counter; @@ -1401,48 +1384,6 @@ float EKF2::filter_altitude_ellipsoid(float amsl_hgt) return amsl_hgt + _wgs84_hgt_offset; } -void EKF2::SelectImuStatus() -{ - for (uint8_t imu_instance = 0; imu_instance < MAX_NUM_IMUS; imu_instance++) { - uORB::Subscription imu_status_sub{ORB_ID(vehicle_imu_status), imu_instance}; - - vehicle_imu_status_s imu_status{}; - imu_status_sub.copy(&imu_status); - - if (imu_status.accel_device_id == _device_id_accel) { - _vehicle_imu_status_sub.ChangeInstance(imu_instance); - return; - } - } - - PX4_WARN("%d - IMU status not found for accel %" PRId32 ", gyro %" PRId32, _instance, _device_id_accel, - _device_id_gyro); -} - -void EKF2::UpdateImuStatus() -{ - vehicle_imu_status_s imu_status; - - if (_vehicle_imu_status_sub.update(&imu_status)) { - if (imu_status.accel_device_id != _device_id_accel) { - SelectImuStatus(); - return; - } - - const float dt = _ekf.get_dt_imu_avg(); - - // accel -> delta velocity - _ekf.setDeltaVelocityHighFrequencyVibrationMetric(imu_status.accel_vibration_metric * dt); - - // gyro -> delta angle - _ekf.setDeltaAngleHighFrequencyVibrationMetric(imu_status.gyro_vibration_metric * dt); - - // note: the coning metric uses the cross product of two consecutive angular velocities - // this is why the conversion to delta angle requires dt^2 - _ekf.setDeltaAngleConingMetric(imu_status.gyro_coning_vibration * dt * dt); - } -} - void EKF2::UpdateAirspeedSample(ekf2_timestamps_s &ekf2_timestamps) { // EKF airspeed sample diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index c1af51a4af..b062cd3392 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -86,7 +86,6 @@ #include #include #include -#include #include #include #include @@ -154,8 +153,6 @@ private: void PublishWindEstimate(const hrt_abstime ×tamp); void PublishYawEstimatorStatus(const hrt_abstime ×tamp); - void SelectImuStatus(); - void UpdateAirspeedSample(ekf2_timestamps_s &ekf2_timestamps); void UpdateAuxVelSample(ekf2_timestamps_s &ekf2_timestamps); void UpdateBaroSample(ekf2_timestamps_s &ekf2_timestamps); @@ -164,7 +161,6 @@ private: void UpdateGpsSample(ekf2_timestamps_s &ekf2_timestamps); void UpdateMagSample(ekf2_timestamps_s &ekf2_timestamps); void UpdateRangeSample(ekf2_timestamps_s &ekf2_timestamps); - void UpdateImuStatus(); void UpdateAccelCalibration(const hrt_abstime ×tamp); void UpdateGyroCalibration(const hrt_abstime ×tamp); @@ -257,7 +253,6 @@ private: uORB::Subscription _status_sub{ORB_ID(vehicle_status)}; uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)}; uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)}; - uORB::Subscription _vehicle_imu_status_sub{ORB_ID(vehicle_imu_status)}; uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; uORB::SubscriptionCallbackWorkItem _sensor_combined_sub{this, ORB_ID(sensor_combined)}; @@ -536,10 +531,6 @@ private: (ParamExtFloat) _param_ekf2_pcoef_z, ///< static pressure position error coefficient along the Z body axis - // Test used to determine if the vehicle is static or moving - (ParamExtFloat) - _param_ekf2_move_test, ///< scaling applied to IMU data thresholds used to determine if the vehicle is static or moving. - (ParamFloat) _param_ekf2_req_gps_h, ///< Required GPS health time (ParamExtInt) _param_ekf2_mag_check, ///< Mag field strength check (ParamExtInt) diff --git a/src/modules/ekf2/ekf2_params.c b/src/modules/ekf2/ekf2_params.c index ed017987c6..80f63d5327 100644 --- a/src/modules/ekf2/ekf2_params.c +++ b/src/modules/ekf2/ekf2_params.c @@ -159,9 +159,9 @@ PARAM_DEFINE_FLOAT(EKF2_AVEL_DELAY, 5); * 2 : Maximum allowed horizontal position error set by EKF2_REQ_EPH * 3 : Maximum allowed vertical position error set by EKF2_REQ_EPV * 4 : Maximum allowed speed error set by EKF2_REQ_SACC - * 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. - * 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. - * 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. Detecton of the stationary condition is controlled by the EKF2_MOVE_TEST parameter. + * 5 : Maximum allowed horizontal position rate set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. + * 6 : Maximum allowed vertical position rate set by EKF2_REQ_VDRIFT. This check will only run when the vehicle is on ground and stationary. + * 7 : Maximum allowed horizontal speed set by EKF2_REQ_HDRIFT. This check will only run when the vehicle is on ground and stationary. * 8 : Maximum allowed vertical velocity discrepancy set by EKF2_REQ_VDRIFT * * @group EKF2 @@ -480,7 +480,7 @@ PARAM_DEFINE_INT32(EKF2_DECL_TYPE, 7); * If set to 'Magnetic heading' magnetic heading fusion is used at all times * If set to '3-axis' 3-axis field fusion is used at all times. * If set to 'VTOL custom' the behaviour is the same as 'Automatic', but if fusing airspeed, magnetometer fusion is only allowed to modify the magnetic field states. This can be used by VTOL platforms with large magnetic field disturbances to prevent incorrect bias states being learned during forward flight operation which can adversely affect estimation accuracy after transition to hovering flight. - * If set to 'MC custom' the behaviour is the same as 'Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests controlled by the EKF2_MOVE_TEST parameter indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight. + * If set to 'MC custom' the behaviour is the same as 'Automatic, but if there are no earth frame position or velocity observations being used, the magnetometer will not be used. This enables vehicles to operate with no GPS in environments where the magnetic field cannot be used to provide a heading reference. Prior to flight, the yaw angle is assumed to be constant if movement tests indicate that the vehicle is static. This allows the vehicle to be placed on the ground to learn the yaw gyro bias prior to flight. * If set to 'None' the magnetometer will not be used under any circumstance. If no external source of yaw is available, it is possible to use post-takeoff horizontal movement combined with GPS velocity measurements to align the yaw angle with the timer required (depending on the amount of movement and GPS data quality). Other external sources of yaw may be used if selected via the EKF2_AID_MASK parameter. * @group EKF2 * @value 0 Automatic @@ -700,7 +700,7 @@ PARAM_DEFINE_FLOAT(EKF2_RNG_GATE, 5.0f); /** * Expected range finder reading when on ground. * - * If the vehicle is on ground, is not moving as determined by the motion test controlled by EKF2_MOVE_TEST and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is avilable at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. + * If the vehicle is on ground, is not moving as determined by the motion test and the range finder is returning invalid or no data, then an assumed range value of EKF2_MIN_RNG will be used by the terrain estimator so that a terrain height estimate is avilable at the start of flight in situations where the range finder may be inside its minimum measurements distance when on ground. * * @group EKF2 * @min 0.01 @@ -1320,18 +1320,6 @@ PARAM_DEFINE_FLOAT(EKF2_ABL_GYRLIM, 3.0f); */ PARAM_DEFINE_FLOAT(EKF2_ABL_TAU, 0.5f); -/** - * Vehicle movement test threshold - * - * Scales the threshold tests applied to IMU data used to determine if the vehicle is static or moving. See parameter descriptions for EKF2_GPS_CHECK and EKF2_MAG_TYPE for further information on the functionality affected by this parameter. - * - * @group EKF2 - * @min 0.1 - * @max 10.0 - * @decimal 1 - */ -PARAM_DEFINE_FLOAT(EKF2_MOVE_TEST, 1.0f); - /** * Required GPS health time on startup * diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index 1a287c567c..89ccf08b69 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -67,285 +67,285 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 6490000,0.979,-0.00643,-0.0125,0.204,-0.00462,0.0125,-0.0373,-0.000918,0.0053,-0.0482,-1.78e-05,-5.77e-05,2.64e-07,-2.38e-05,1.71e-05,-0.00126,0.203,0.0106,0.434,0,0,0,0,0,1.61e-05,0.00043,0.00043,0.000366,0.214,0.214,0.036,0.113,0.113,0.0692,1.21e-08,1.21e-08,1.09e-08,3.86e-06,3.86e-06,3.38e-07,0,0,0,0,0,0,0,0 6590000,0.979,-0.00638,-0.0125,0.204,-0.00581,0.0147,-0.0401,-0.0014,0.00661,-0.0511,-1.78e-05,-5.77e-05,2.64e-07,-2.38e-05,1.71e-05,-0.00127,0.203,0.0106,0.434,0,0,0,0,0,1.59e-05,0.00045,0.00045,0.000361,0.246,0.246,0.0345,0.142,0.142,0.0681,1.21e-08,1.21e-08,1.05e-08,3.86e-06,3.86e-06,3.16e-07,0,0,0,0,0,0,0,0 6690000,0.979,-0.0064,-0.0124,0.204,-0.00811,0.0134,-0.0423,-0.00142,0.00507,-0.052,-1.72e-05,-5.78e-05,2.5e-07,-2.4e-05,1.66e-05,-0.00127,0.203,0.0106,0.434,0,0,0,0,0,1.56e-05,0.000385,0.000385,0.000356,0.195,0.195,0.0332,0.108,0.108,0.067,9.86e-09,9.87e-09,1e-08,3.86e-06,3.86e-06,2.96e-07,0,0,0,0,0,0,0,0 -6790000,0.979,-0.00642,-0.0124,0.204,-0.00677,0.0147,-0.0407,-0.00221,0.00645,-0.0528,-1.72e-05,-5.78e-05,2.5e-07,-2.41e-05,1.67e-05,-0.00127,0.203,0.0106,0.434,0,0,0,0,0,1.54e-05,0.000401,0.000402,0.000351,0.223,0.223,0.0323,0.135,0.135,0.067,9.86e-09,9.87e-09,9.57e-09,3.86e-06,3.86e-06,2.8e-07,0,0,0,0,0,0,0,0 -6890000,0.979,-0.00634,-0.0123,0.204,-0.00645,0.0111,-0.0372,-0.00183,0.00487,-0.0503,-1.67e-05,-5.78e-05,2.37e-07,-2.43e-05,1.63e-05,-0.00128,0.203,0.0106,0.434,0,0,0,0,0,1.52e-05,0.000347,0.000347,0.000346,0.177,0.177,0.0311,0.103,0.103,0.0659,8.06e-09,8.07e-09,9.16e-09,3.86e-06,3.86e-06,2.62e-07,0,0,0,0,0,0,0,0 -6990000,0.979,-0.00629,-0.0123,0.204,-0.00687,0.0118,-0.0357,-0.00253,0.00601,-0.05,-1.67e-05,-5.78e-05,2.37e-07,-2.45e-05,1.63e-05,-0.00129,0.203,0.0106,0.434,0,0,0,0,0,1.49e-05,0.000361,0.000361,0.000341,0.203,0.203,0.0299,0.129,0.129,0.0648,8.06e-09,8.07e-09,8.78e-09,3.86e-06,3.86e-06,2.46e-07,0,0,0,0,0,0,0,0 -7090000,0.982,-0.00648,-0.0121,0.188,-0.00699,0.0135,-0.0363,-0.00209,0.00474,-0.0511,-1.63e-05,-5.78e-05,2.25e-07,-2.45e-05,1.59e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,9.13e-05,0.000313,0.000313,0.00244,0.16,0.16,0.0291,0.0991,0.0991,0.0649,6.62e-09,6.62e-09,8.49e-09,3.86e-06,3.86e-06,2.33e-07,0,0,0,0,0,0,0,0 -7190000,0.982,-0.00644,-0.0122,0.188,-0.00773,0.0148,-0.0354,-0.00286,0.00622,-0.0539,-1.63e-05,-5.78e-05,2.18e-07,-2.46e-05,1.59e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,4.81e-05,0.000313,0.000313,0.00128,0.161,0.161,0.028,0.122,0.122,0.0638,6.62e-09,6.62e-09,8.49e-09,3.86e-06,3.86e-06,2.19e-07,0,0,0,0,0,0,0,0 -7290000,0.982,-0.00642,-0.0122,0.188,-0.00723,0.0182,-0.0328,-0.00366,0.00785,-0.05,-1.63e-05,-5.78e-05,2.42e-07,-2.47e-05,1.6e-05,-0.0013,0.204,0.002,0.435,0,0,0,0,0,3.27e-05,0.000314,0.000314,0.000872,0.166,0.166,0.027,0.148,0.148,0.0628,6.61e-09,6.62e-09,8.49e-09,3.86e-06,3.86e-06,2.06e-07,0,0,0,0,0,0,0,0 -7390000,0.982,-0.0063,-0.0122,0.187,-0.00929,0.0204,-0.0309,-0.00447,0.00984,-0.0478,-1.63e-05,-5.78e-05,2.56e-07,-2.49e-05,1.61e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.56e-05,0.000315,0.000315,0.000681,0.176,0.176,0.0263,0.177,0.177,0.0628,6.61e-09,6.62e-09,8.48e-09,3.86e-06,3.86e-06,1.96e-07,0,0,0,0,0,0,0,0 -7490000,0.982,-0.00631,-0.0122,0.187,-0.00727,0.0226,-0.0254,-0.00525,0.012,-0.0417,-1.63e-05,-5.78e-05,3.47e-07,-2.51e-05,1.63e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.05e-05,0.000316,0.000316,0.000545,0.188,0.188,0.0253,0.21,0.21,0.0618,6.61e-09,6.61e-09,8.48e-09,3.86e-06,3.86e-06,1.85e-07,0,0,0,0,0,0,0,0 -7590000,0.982,-0.00639,-0.0121,0.187,-0.00659,0.0248,-0.0222,-0.00594,0.0143,-0.0368,-1.63e-05,-5.78e-05,3.56e-07,-2.53e-05,1.65e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,1.71e-05,0.000318,0.000318,0.000455,0.205,0.205,0.0244,0.247,0.247,0.0609,6.61e-09,6.61e-09,8.48e-09,3.86e-06,3.86e-06,1.74e-07,0,0,0,0,0,0,0,0 -7690000,0.982,-0.00641,-0.0122,0.187,-0.00726,0.0279,-0.0217,-0.00662,0.0171,-0.0324,-1.63e-05,-5.78e-05,3.34e-07,-2.54e-05,1.66e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,1.5e-05,0.000319,0.000319,0.000398,0.225,0.225,0.0239,0.289,0.289,0.0608,6.61e-09,6.61e-09,8.47e-09,3.86e-06,3.86e-06,1.66e-07,0,0,0,0,0,0,0,0 -7790000,0.982,-0.00629,-0.0122,0.187,-0.006,0.0295,-0.0241,-0.00727,0.0198,-0.0373,-1.63e-05,-5.78e-05,2.75e-07,-2.54e-05,1.65e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,1.32e-05,0.000322,0.000322,0.000348,0.249,0.249,0.023,0.335,0.335,0.0599,6.6e-09,6.6e-09,8.46e-09,3.86e-06,3.86e-06,1.57e-07,0,0,0,0,0,0,0,0 -7890000,0.982,-0.00631,-0.0123,0.187,-0.00769,0.0332,-0.0248,-0.00804,0.0229,-0.0408,-1.63e-05,-5.78e-05,2.43e-07,-2.53e-05,1.65e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,1.17e-05,0.000324,0.000324,0.00031,0.277,0.277,0.0222,0.388,0.388,0.059,6.6e-09,6.6e-09,8.45e-09,3.86e-06,3.86e-06,1.49e-07,0,0,0,0,0,0,0,0 -7990000,0.982,-0.00625,-0.0122,0.187,-0.00776,0.0353,-0.021,-0.00877,0.0262,-0.0377,-1.62e-05,-5.78e-05,2.65e-07,-2.54e-05,1.66e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,1.06e-05,0.000327,0.000327,0.00028,0.308,0.308,0.0215,0.447,0.447,0.0581,6.58e-09,6.59e-09,8.44e-09,3.86e-06,3.86e-06,1.41e-07,0,0,0,0,0,0,0,0 -8090000,0.982,-0.00611,-0.0122,0.187,-0.00664,0.0388,-0.0219,-0.00944,0.0298,-0.04,-1.63e-05,-5.78e-05,8e-09,-2.55e-05,1.66e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,9.83e-06,0.00033,0.00033,0.000259,0.343,0.343,0.021,0.515,0.515,0.0581,6.58e-09,6.59e-09,8.42e-09,3.86e-06,3.86e-06,1.34e-07,0,0,0,0,0,0,0,0 -8190000,0.982,-0.00618,-0.0121,0.188,-0.00636,0.0436,-0.0175,-0.01,0.0339,-0.0341,-1.62e-05,-5.78e-05,-1.9e-07,-2.56e-05,1.68e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,9.07e-06,0.000333,0.000333,0.000239,0.381,0.381,0.0203,0.589,0.589,0.0573,6.56e-09,6.57e-09,8.4e-09,3.86e-06,3.86e-06,1.28e-07,0,0,0,0,0,0,0,0 -8290000,0.982,-0.00616,-0.0121,0.188,-0.00454,0.0475,-0.0162,-0.0106,0.0384,-0.034,-1.62e-05,-5.78e-05,-2.35e-07,-2.56e-05,1.68e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,8.43e-06,0.000337,0.000337,0.000222,0.424,0.424,0.0197,0.677,0.677,0.0564,6.56e-09,6.57e-09,8.37e-09,3.86e-06,3.86e-06,1.21e-07,0,0,0,0,0,0,0,0 -8390000,0.982,-0.00611,-0.0121,0.188,-0.00705,0.0487,-0.0153,-0.0111,0.0429,-0.0324,-1.62e-05,-5.78e-05,-2.87e-07,-2.57e-05,1.69e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,7.97e-06,0.000341,0.000341,0.000209,0.469,0.469,0.0193,0.77,0.77,0.0564,6.53e-09,6.54e-09,8.35e-09,3.85e-06,3.85e-06,1.16e-07,0,0,0,0,0,0,0,0 -8490000,0.982,-0.006,-0.0121,0.188,-0.00766,0.0525,-0.0164,-0.0118,0.0479,-0.0371,-1.62e-05,-5.78e-05,-5.14e-08,-2.56e-05,1.69e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,7.52e-06,0.000345,0.000345,0.000197,0.52,0.52,0.0187,0.882,0.882,0.0556,6.53e-09,6.54e-09,8.32e-09,3.85e-06,3.85e-06,1.1e-07,0,0,0,0,0,0,0,0 -8590000,0.982,-0.00597,-0.0122,0.188,-0.00694,0.0547,-0.0117,-0.0124,0.0528,-0.0323,-1.62e-05,-5.78e-05,-1.68e-07,-2.57e-05,1.71e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,7.12e-06,0.000349,0.000349,0.000187,0.571,0.571,0.0181,0.999,0.999,0.0548,6.5e-09,6.51e-09,8.28e-09,3.85e-06,3.85e-06,1.05e-07,0,0,0,0,0,0,0,0 -8690000,0.982,-0.006,-0.0123,0.187,-0.00735,0.0567,-0.0136,-0.0132,0.0584,-0.0338,-1.62e-05,-5.78e-05,-8.76e-08,-2.57e-05,1.71e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,6.84e-06,0.000354,0.000354,0.000179,0.63,0.63,0.0177,1.14,1.14,0.0548,6.5e-09,6.51e-09,8.24e-09,3.85e-06,3.85e-06,1.01e-07,0,0,0,0,0,0,0,0 -8790000,0.982,-0.00598,-0.0123,0.188,-0.00623,0.0589,-0.0134,-0.0138,0.0634,-0.0311,-1.62e-05,-5.78e-05,-3.45e-07,-2.57e-05,1.74e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,6.55e-06,0.000357,0.000357,0.000172,0.686,0.686,0.0172,1.29,1.29,0.0541,6.46e-09,6.46e-09,8.2e-09,3.85e-06,3.85e-06,9.63e-08,0,0,0,0,0,0,0,0 -8890000,0.982,-0.00602,-0.0123,0.187,-0.00662,0.0621,-0.00913,-0.0144,0.0696,-0.0252,-1.62e-05,-5.78e-05,-5.55e-08,-2.58e-05,1.73e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,6.29e-06,0.000363,0.000363,0.000165,0.752,0.752,0.0167,1.46,1.46,0.0533,6.46e-09,6.46e-09,8.14e-09,3.85e-06,3.85e-06,9.2e-08,0,0,0,0,0,0,0,0 -8990000,0.982,-0.00596,-0.0122,0.187,-0.0078,0.0656,-0.00833,-0.0149,0.0748,-0.0282,-1.61e-05,-5.78e-05,3.41e-07,-2.57e-05,1.77e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,6.12e-06,0.000366,0.000366,0.00016,0.812,0.812,0.0164,1.64,1.64,0.0533,6.41e-09,6.41e-09,8.1e-09,3.85e-06,3.85e-06,8.84e-08,0,0,0,0,0,0,0,0 -9090000,0.982,-0.00595,-0.0123,0.187,-0.00789,0.0702,-0.00936,-0.0157,0.0815,-0.0284,-1.61e-05,-5.78e-05,8.01e-07,-2.57e-05,1.77e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,5.93e-06,0.000372,0.000372,0.000155,0.886,0.886,0.0159,1.86,1.86,0.0526,6.41e-09,6.41e-09,8.03e-09,3.85e-06,3.85e-06,8.46e-08,0,0,0,0,0,0,0,0 -9190000,0.982,-0.00595,-0.0123,0.187,-0.00455,0.0715,-0.00881,-0.016,0.087,-0.0287,-1.6e-05,-5.78e-05,1.2e-06,-2.56e-05,1.83e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,5.76e-06,0.000374,0.000374,0.000151,0.948,0.948,0.0155,2.07,2.07,0.0519,6.35e-09,6.35e-09,7.97e-09,3.84e-06,3.84e-06,8.1e-08,0,0,0,0,0,0,0,0 -9290000,0.982,-0.0058,-0.0121,0.187,-0.00268,0.0744,-0.00726,-0.0163,0.0943,-0.0263,-1.6e-05,-5.78e-05,1.33e-06,-2.56e-05,1.83e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,5.61e-06,0.00038,0.00038,0.000147,1.03,1.03,0.0151,2.34,2.34,0.0512,6.35e-09,6.35e-09,7.9e-09,3.84e-06,3.84e-06,7.77e-08,0,0,0,0,0,0,0,0 -9390000,0.982,-0.00572,-0.0122,0.187,-0.00279,0.0754,-0.00612,-0.0161,0.0993,-0.0267,-1.59e-05,-5.78e-05,8.81e-07,-2.55e-05,1.91e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,5.52e-06,0.000381,0.000381,0.000145,1.09,1.09,0.0148,2.57,2.57,0.0512,6.28e-09,6.28e-09,7.83e-09,3.84e-06,3.84e-06,7.49e-08,0,0,0,0,0,0,0,0 -9490000,0.982,-0.00574,-0.0122,0.187,-0.00331,0.0774,-0.00444,-0.0164,0.107,-0.0238,-1.59e-05,-5.78e-05,1.07e-06,-2.55e-05,1.91e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.41e-06,0.000388,0.000388,0.000142,1.18,1.18,0.0144,2.9,2.9,0.0506,6.28e-09,6.28e-09,7.75e-09,3.84e-06,3.84e-06,7.19e-08,0,0,0,0,0,0,0,0 -9590000,0.982,-0.00582,-0.0122,0.187,-0.00354,0.0769,-0.00436,-0.0163,0.111,-0.0251,-1.58e-05,-5.78e-05,1.41e-07,-2.53e-05,2.02e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.32e-06,0.000387,0.000387,0.000139,1.24,1.24,0.014,3.16,3.16,0.05,6.2e-09,6.2e-09,7.66e-09,3.83e-06,3.83e-06,6.91e-08,0,0,0,0,0,0,0,0 -9690000,0.982,-0.00581,-0.0122,0.187,-0.00403,0.0794,-0.00146,-0.0166,0.119,-0.0239,-1.59e-05,-5.78e-05,-1.09e-07,-2.53e-05,2.02e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.26e-06,0.000395,0.000395,0.000138,1.33,1.33,0.0138,3.55,3.55,0.05,6.2e-09,6.2e-09,7.58e-09,3.83e-06,3.83e-06,6.68e-08,0,0,0,0,0,0,0,0 -9790000,0.982,-0.00578,-0.0121,0.187,-0.00313,0.0826,-0.0028,-0.017,0.127,-0.0247,-1.59e-05,-5.78e-05,-1.05e-06,-2.53e-05,2.03e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.19e-06,0.000402,0.000402,0.000136,1.43,1.43,0.0135,3.98,3.98,0.0493,6.2e-09,6.2e-09,7.48e-09,3.83e-06,3.83e-06,6.42e-08,0,0,0,0,0,0,0,0 -9890000,0.982,-0.00578,-0.0121,0.187,-0.000924,0.0817,-0.0015,-0.0165,0.13,-0.0252,-1.58e-05,-5.79e-05,-8.59e-07,-2.5e-05,2.16e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.13e-06,0.000399,0.000399,0.000134,1.48,1.48,0.0131,4.29,4.29,0.0487,6.11e-09,6.11e-09,7.38e-09,3.81e-06,3.81e-06,6.19e-08,0,0,0,0,0,0,0,0 -9990000,0.982,-0.00577,-0.0121,0.187,0.000378,0.0833,-0.000786,-0.0166,0.138,-0.0272,-1.58e-05,-5.78e-05,-1.63e-06,-2.5e-05,2.17e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.11e-06,0.000407,0.000407,0.000134,1.58,1.58,0.0129,4.79,4.79,0.0488,6.11e-09,6.11e-09,7.29e-09,3.81e-06,3.81e-06,5.99e-08,0,0,0,0,0,0,0,0 -10090000,0.982,-0.00577,-0.0123,0.188,-0.0013,0.0796,0.000421,-0.0158,0.14,-0.0254,-1.57e-05,-5.79e-05,-2.53e-06,-2.46e-05,2.34e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.06e-06,0.000401,0.000402,0.000133,1.62,1.62,0.0126,5.09,5.09,0.0482,6.01e-09,6.01e-09,7.18e-09,3.8e-06,3.8e-06,5.78e-08,0,0,0,0,0,0,0,0 -10190000,0.982,-0.00573,-0.0122,0.188,-0.00331,0.0822,0.0013,-0.016,0.148,-0.0266,-1.57e-05,-5.78e-05,-3.61e-06,-2.46e-05,2.35e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.02e-06,0.00041,0.00041,0.000132,1.73,1.73,0.0123,5.66,5.67,0.0476,6.01e-09,6.01e-09,7.07e-09,3.8e-06,3.8e-06,5.58e-08,0,0,0,0,0,0,0,0 -10290000,0.982,-0.00583,-0.0121,0.188,-0.00277,0.0801,0.000229,-0.0154,0.147,-0.0258,-1.55e-05,-5.79e-05,-3.21e-06,-2.4e-05,2.54e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.01e-06,0.000401,0.000401,0.000132,1.75,1.75,0.0122,5.95,5.95,0.0476,5.9e-09,5.91e-09,6.97e-09,3.78e-06,3.78e-06,5.41e-08,0,0,0,0,0,0,0,0 -10390000,0.982,-0.00582,-0.012,0.188,0.00658,0.00423,-0.00275,0.000735,0.000107,-0.0249,-1.55e-05,-5.79e-05,-2.94e-06,-2.4e-05,2.54e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.98e-06,0.00041,0.00041,0.000131,0.0416,0.0416,0.0401,0.25,0.25,0.0441,5.9e-09,5.91e-09,6.85e-09,3.78e-06,3.78e-06,5.24e-08,0,0,0,0,0,0,0,0 -10490000,0.982,-0.00572,-0.012,0.188,0.00747,0.00566,-0.00119,0.00141,0.000565,-0.021,-1.55e-05,-5.79e-05,-3.75e-06,-2.41e-05,2.53e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.96e-06,0.000418,0.000419,0.00013,0.0467,0.0467,0.0402,0.251,0.251,0.0416,5.9e-09,5.91e-09,6.73e-09,3.78e-06,3.78e-06,5.09e-08,0,0,0,0,0,0,0,0 -10590000,0.982,-0.00567,-0.0118,0.188,0.00416,0.00601,0.000274,0.00066,-0.00483,-0.0209,-1.55e-05,-5.81e-05,-3.22e-06,-2.02e-05,2.52e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.94e-06,0.000419,0.000419,0.00013,0.0468,0.0468,0.0375,0.126,0.126,0.0399,5.87e-09,5.88e-09,6.6e-09,3.77e-06,3.77e-06,5e-08,0,0,0,0,0,0,0,0 -10690000,0.982,-0.00562,-0.0119,0.188,0.00472,0.00621,0.00114,0.00111,-0.00422,-0.0194,-1.55e-05,-5.81e-05,-3.48e-06,-2.03e-05,2.51e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.95e-06,0.000428,0.000428,0.00013,0.0581,0.0581,0.0373,0.128,0.128,0.0395,5.87e-09,5.88e-09,6.49e-09,3.77e-06,3.77e-06,5e-08,0,0,0,0,0,0,0,0 -10790000,0.982,-0.00574,-0.0119,0.188,0.00488,0.00458,0.00178,0.000908,-0.00313,-0.0177,-1.53e-05,-5.83e-05,-3.53e-06,-1.65e-05,2.97e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.93e-06,0.00041,0.00041,0.00013,0.0589,0.0589,0.0347,0.0865,0.0865,0.0389,5.77e-09,5.77e-09,6.36e-09,3.73e-06,3.73e-06,5e-08,0,0,0,0,0,0,0,0 -10890000,0.982,-0.00571,-0.012,0.188,0.00429,0.00697,0.00118,0.00137,-0.00261,-0.0199,-1.53e-05,-5.83e-05,-2.54e-06,-1.65e-05,2.97e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.92e-06,0.000419,0.000419,0.00013,0.0748,0.0748,0.0343,0.0899,0.0899,0.0391,5.77e-09,5.77e-09,6.23e-09,3.73e-06,3.73e-06,5e-08,0,0,0,0,0,0,0,0 -10990000,0.982,-0.00578,-0.012,0.188,0.00247,0.0121,0.00335,0.00104,-0.00159,-0.0164,-1.51e-05,-5.84e-05,-2.81e-06,-1.38e-05,3.19e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.92e-06,0.000381,0.000381,0.00013,0.0714,0.0714,0.0319,0.0684,0.0684,0.0395,5.58e-09,5.59e-09,6.11e-09,3.67e-06,3.67e-06,5e-08,0,0,0,0,0,0,0,0 -11090000,0.982,-0.0059,-0.012,0.188,0.00268,0.0161,0.00571,0.00126,-0.000234,-0.0141,-1.52e-05,-5.84e-05,-3.81e-06,-1.38e-05,3.19e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.92e-06,0.00039,0.00039,0.00013,0.0896,0.0896,0.0313,0.0732,0.0732,0.0402,5.58e-09,5.59e-09,5.98e-09,3.67e-06,3.67e-06,5e-08,0,0,0,0,0,0,0,0 -11190000,0.982,-0.00614,-0.012,0.188,0.00296,0.0158,0.00988,0.00205,-0.000295,-0.00976,-1.47e-05,-5.84e-05,-4.29e-06,-1.38e-05,3.95e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.89e-06,0.00034,0.00034,0.00013,0.0796,0.0796,0.0289,0.0592,0.0592,0.0403,5.35e-09,5.35e-09,5.85e-09,3.61e-06,3.61e-06,5e-08,0,0,0,0,0,0,0,0 -11290000,0.982,-0.00612,-0.012,0.188,0.00231,0.016,0.0109,0.00228,0.00134,-0.00964,-1.47e-05,-5.84e-05,-4.53e-06,-1.38e-05,3.95e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.91e-06,0.000349,0.000349,0.00013,0.0978,0.0978,0.0282,0.0653,0.0653,0.0417,5.35e-09,5.35e-09,5.73e-09,3.61e-06,3.61e-06,5e-08,0,0,0,0,0,0,0,0 -11390000,0.982,-0.00621,-0.012,0.188,0.000535,0.0138,0.00781,0.00166,0.000538,-0.0139,-1.43e-05,-5.86e-05,-4.38e-06,-1.02e-05,4.54e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.89e-06,0.0003,0.0003,0.00013,0.0824,0.0824,0.026,0.0543,0.0543,0.0418,5.12e-09,5.12e-09,5.59e-09,3.55e-06,3.55e-06,5e-08,0,0,0,0,0,0,0,0 -11490000,0.982,-0.00614,-0.0119,0.188,-0.00117,0.0142,0.0105,0.00156,0.00195,-0.00982,-1.43e-05,-5.86e-05,-4.19e-06,-1.02e-05,4.54e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.88e-06,0.000307,0.000307,0.00013,0.0994,0.0994,0.0251,0.0615,0.0615,0.0427,5.12e-09,5.12e-09,5.46e-09,3.55e-06,3.55e-06,5e-08,0,0,0,0,0,0,0,0 -11590000,0.982,-0.00638,-0.0119,0.188,0.000726,0.0111,0.0108,0.00141,0.000875,-0.00937,-1.4e-05,-5.87e-05,-4.15e-06,-8.51e-06,5.03e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.88e-06,0.000265,0.000265,0.00013,0.081,0.081,0.0232,0.0516,0.0516,0.0431,4.9e-09,4.9e-09,5.34e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -11690000,0.982,-0.00636,-0.0118,0.188,0.000463,0.0145,0.012,0.00149,0.00213,-0.0102,-1.4e-05,-5.87e-05,-3.84e-06,-8.51e-06,5.03e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.87e-06,0.000272,0.000272,0.00013,0.0961,0.0961,0.0223,0.0595,0.0595,0.0439,4.9e-09,4.9e-09,5.21e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 -11790000,0.982,-0.00663,-0.0118,0.188,-0.00042,0.00974,0.0131,0.00112,-0.00066,-0.0079,-1.34e-05,-5.9e-05,-2.86e-06,-5.54e-06,5.7e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.86e-06,0.000238,0.000238,0.00013,0.0773,0.0773,0.0205,0.0502,0.0502,0.0437,4.71e-09,4.71e-09,5.08e-09,3.47e-06,3.47e-06,5e-08,0,0,0,0,0,0,0,0 -11890000,0.982,-0.00672,-0.0117,0.188,0.00163,0.0109,0.0112,0.00113,0.000327,-0.00753,-1.34e-05,-5.9e-05,-3.06e-06,-5.55e-06,5.7e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.84e-06,0.000245,0.000245,0.000129,0.0906,0.0906,0.0196,0.0584,0.0584,0.0443,4.71e-09,4.71e-09,4.95e-09,3.47e-06,3.47e-06,5e-08,0,0,0,0,0,0,0,0 -11990000,0.982,-0.00685,-0.0118,0.188,0.00474,0.0108,0.01,0.00242,-0.000879,-0.0101,-1.33e-05,-5.89e-05,-2.76e-06,-6.6e-06,5.91e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.85e-06,0.000218,0.000219,0.00013,0.0726,0.0726,0.0182,0.0493,0.0493,0.0444,4.55e-09,4.55e-09,4.83e-09,3.45e-06,3.45e-06,5e-08,0,0,0,0,0,0,0,0 -12090000,0.982,-0.00676,-0.0118,0.188,0.00573,0.0106,0.0125,0.00293,0.000176,-0.00602,-1.33e-05,-5.89e-05,-2.8e-06,-6.59e-06,5.91e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.84e-06,0.000225,0.000225,0.000129,0.0841,0.0841,0.0174,0.0576,0.0576,0.0448,4.55e-09,4.55e-09,4.7e-09,3.45e-06,3.45e-06,5e-08,0,0,0,0,0,0,0,0 -12190000,0.982,-0.00666,-0.0118,0.188,0.00482,0.00993,0.0116,0.00202,0.00115,-0.00459,-1.33e-05,-5.9e-05,-3.18e-06,-5.37e-06,5.86e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.82e-06,0.000205,0.000205,0.000129,0.0676,0.0676,0.0161,0.0488,0.0488,0.0443,4.4e-09,4.4e-09,4.58e-09,3.44e-06,3.44e-06,5e-08,0,0,0,0,0,0,0,0 -12290000,0.982,-0.00673,-0.0118,0.188,0.00207,0.0091,0.0103,0.00239,0.00211,-0.00409,-1.33e-05,-5.9e-05,-3.49e-06,-5.38e-06,5.86e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.83e-06,0.000211,0.000211,0.000129,0.0778,0.0778,0.0154,0.0571,0.0571,0.045,4.4e-09,4.4e-09,4.47e-09,3.44e-06,3.44e-06,5e-08,0,0,0,0,0,0,0,0 -12390000,0.982,-0.00681,-0.0117,0.188,0.00135,0.00642,0.00962,0.00185,0.00115,-0.00871,-1.32e-05,-5.91e-05,-3.54e-06,-4.56e-06,5.97e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.81e-06,0.000196,0.000196,0.000129,0.0629,0.0629,0.0143,0.0485,0.0485,0.0444,4.26e-09,4.27e-09,4.34e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -12490000,0.982,-0.0068,-0.0117,0.188,0.000993,0.00735,0.0139,0.00201,0.00184,-0.00724,-1.32e-05,-5.91e-05,-3.64e-06,-4.56e-06,5.97e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.8e-06,0.000202,0.000202,0.000128,0.0718,0.0718,0.0136,0.0567,0.0567,0.0444,4.26e-09,4.27e-09,4.22e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -12590000,0.982,-0.00692,-0.0117,0.188,0.00484,0.00167,0.0153,0.00335,-0.000697,-0.00579,-1.28e-05,-5.91e-05,-3.72e-06,-4.56e-06,6.13e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.8e-06,0.00019,0.00019,0.000129,0.0586,0.0586,0.0128,0.0482,0.0482,0.0442,4.14e-09,4.14e-09,4.12e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -12690000,0.982,-0.00687,-0.0117,0.188,0.00497,-0.00042,0.015,0.0038,-0.000627,-0.00467,-1.28e-05,-5.91e-05,-3.69e-06,-4.56e-06,6.13e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.78e-06,0.000196,0.000196,0.000128,0.0667,0.0667,0.0122,0.0563,0.0563,0.0441,4.14e-09,4.14e-09,4e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -12790000,0.982,-0.00707,-0.0116,0.187,0.00645,-0.00292,0.0164,0.00401,-0.00372,-0.00297,-1.23e-05,-5.9e-05,-2.55e-06,-3.87e-06,6.18e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.76e-06,0.000186,0.000186,0.000128,0.0549,0.0549,0.0114,0.048,0.048,0.0433,4.01e-09,4.01e-09,3.89e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -12890000,0.982,-0.00706,-0.0116,0.187,0.00621,-0.00361,0.0174,0.00468,-0.00406,-0.000598,-1.23e-05,-5.9e-05,-1.83e-06,-3.83e-06,6.17e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.76e-06,0.000192,0.000192,0.000128,0.0622,0.0622,0.011,0.0559,0.0559,0.0436,4.01e-09,4.01e-09,3.79e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -12990000,0.982,-0.00704,-0.0116,0.187,0.00505,-0.00199,0.0177,0.00349,-0.00302,0.000451,-1.24e-05,-5.92e-05,-1.18e-06,-3.67e-06,6.14e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.73e-06,0.000184,0.000184,0.000127,0.0517,0.0517,0.0104,0.0478,0.0478,0.0428,3.88e-09,3.89e-09,3.68e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -13090000,0.982,-0.00706,-0.0115,0.187,0.00567,-0.00168,0.0156,0.00401,-0.00314,-0.000661,-1.24e-05,-5.92e-05,-3.26e-07,-3.67e-06,6.14e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.71e-06,0.00019,0.00019,0.000127,0.0584,0.0584,0.00995,0.0555,0.0555,0.0426,3.88e-09,3.89e-09,3.58e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -13190000,0.982,-0.00707,-0.0114,0.187,0.00148,-0.0032,0.0149,0.00089,-0.00402,-0.000171,-1.24e-05,-5.94e-05,1.93e-07,-3.4e-06,6.09e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.69e-06,0.000183,0.000183,0.000126,0.049,0.049,0.00943,0.0476,0.0476,0.0418,3.75e-09,3.75e-09,3.47e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -13290000,0.982,-0.0071,-0.0114,0.187,0.000915,-0.0039,0.0124,0.000961,-0.00435,-0.000947,-1.24e-05,-5.94e-05,2.26e-07,-3.42e-06,6.09e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.69e-06,0.000189,0.000189,0.000126,0.0554,0.0554,0.00916,0.0551,0.0551,0.0419,3.75e-09,3.75e-09,3.39e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -13390000,0.982,-0.00703,-0.0115,0.187,0.000503,-0.00224,0.0123,0.000758,-0.0033,-0.000412,-1.25e-05,-5.94e-05,-1.35e-07,-3.43e-06,6.1e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.66e-06,0.000183,0.000183,0.000125,0.0468,0.0468,0.00873,0.0474,0.0474,0.0411,3.61e-09,3.62e-09,3.29e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -13490000,0.982,-0.007,-0.0115,0.187,0.000789,-0.000358,0.012,0.000837,-0.00337,-0.00398,-1.25e-05,-5.94e-05,7.85e-08,-3.48e-06,6.1e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.64e-06,0.000189,0.000189,0.000125,0.0528,0.0528,0.00847,0.0547,0.0547,0.0408,3.61e-09,3.62e-09,3.19e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 -13590000,0.982,-0.007,-0.0116,0.187,0.00504,-0.000722,0.0137,0.00371,-0.0028,-0.00527,-1.23e-05,-5.9e-05,-1.66e-07,-1.76e-06,6.03e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.64e-06,0.000183,0.000183,0.000125,0.045,0.045,0.00817,0.0472,0.0472,0.0404,3.47e-09,3.47e-09,3.11e-09,3.42e-06,3.42e-06,5e-08,0,0,0,0,0,0,0,0 -13690000,0.982,-0.00695,-0.0115,0.187,0.00485,-0.00193,0.0138,0.00419,-0.00292,-0.00286,-1.23e-05,-5.9e-05,2.78e-07,-1.73e-06,6.03e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.6e-06,0.000189,0.000189,0.000124,0.0508,0.0508,0.00797,0.0544,0.0544,0.04,3.47e-09,3.47e-09,3.02e-09,3.42e-06,3.42e-06,5e-08,0,0,0,0,0,0,0,0 -13790000,0.982,-0.0069,-0.0117,0.187,0.0116,0.00176,0.0139,0.00776,-0.000716,-0.00333,-1.24e-05,-5.84e-05,1.47e-08,1.8e-06,6.05e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.57e-06,0.000183,0.000183,0.000123,0.0436,0.0436,0.00769,0.0469,0.0469,0.0393,3.32e-09,3.32e-09,2.93e-09,3.42e-06,3.42e-06,5e-08,0,0,0,0,0,0,0,0 -13890000,0.982,-0.00681,-0.0116,0.187,0.0125,0.00268,0.0149,0.00894,-0.000486,-0.00138,-1.24e-05,-5.84e-05,5.82e-07,1.82e-06,6.05e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.57e-06,0.000189,0.000189,0.000123,0.0492,0.0492,0.00759,0.054,0.054,0.0393,3.32e-09,3.32e-09,2.85e-09,3.42e-06,3.42e-06,5e-08,0,0,0,0,0,0,0,0 -13990000,0.982,-0.00687,-0.0114,0.186,0.0127,0.00309,0.0138,0.00695,-0.00197,-0.0025,-1.22e-05,-5.89e-05,1.16e-06,-7.1e-07,5.92e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.54e-06,0.000183,0.000183,0.000122,0.0425,0.0425,0.00737,0.0467,0.0467,0.0386,3.16e-09,3.16e-09,2.77e-09,3.41e-06,3.41e-06,5e-08,0,0,0,0,0,0,0,0 -14090000,0.982,-0.00687,-0.0113,0.187,0.0101,-0.00108,0.0152,0.00819,-0.00188,-0.00599,-1.23e-05,-5.89e-05,-2.15e-07,-8.25e-07,5.93e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.51e-06,0.000189,0.000189,0.000121,0.048,0.048,0.00727,0.0537,0.0537,0.0383,3.16e-09,3.16e-09,2.69e-09,3.41e-06,3.41e-06,5e-08,0,0,0,0,0,0,0,0 -14190000,0.982,-0.00684,-0.0113,0.187,0.00798,7.38e-05,0.0149,0.00764,-0.00143,-0.006,-1.23e-05,-5.89e-05,-8.52e-07,-8.31e-07,5.97e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.51e-06,0.000183,0.000183,0.000121,0.0416,0.0416,0.00714,0.0465,0.0465,0.038,2.99e-09,2.99e-09,2.62e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -14290000,0.982,-0.00678,-0.0113,0.187,0.00953,0.000269,0.0133,0.0084,-0.00146,-0.00226,-1.23e-05,-5.89e-05,-7.97e-07,-7.82e-07,5.96e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.48e-06,0.000188,0.000188,0.00012,0.0471,0.0471,0.00707,0.0534,0.0534,0.0376,2.99e-09,2.99e-09,2.54e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 -14390000,0.982,-0.00687,-0.0112,0.187,0.00996,-0.0027,0.0144,0.00803,-0.00269,0.00163,-1.21e-05,-5.9e-05,-4.13e-07,-1.44e-06,5.77e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.45e-06,0.000182,0.000182,0.00012,0.041,0.041,0.00694,0.0463,0.0463,0.037,2.82e-09,2.82e-09,2.47e-09,3.39e-06,3.39e-06,5e-08,0,0,0,0,0,0,0,0 -14490000,0.982,-0.00698,-0.0112,0.187,0.00834,-0.00219,0.0181,0.00889,-0.00295,0.00363,-1.21e-05,-5.9e-05,-1.11e-06,-1.44e-06,5.77e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.42e-06,0.000187,0.000187,0.000119,0.0464,0.0464,0.00691,0.0531,0.0531,0.0367,2.82e-09,2.82e-09,2.4e-09,3.39e-06,3.39e-06,5e-08,0,0,0,0,0,0,0,0 -14590000,0.982,-0.00705,-0.011,0.187,0.0067,-0.00235,0.0159,0.00564,-0.00374,-0.000473,-1.22e-05,-5.95e-05,-1.23e-06,-6.16e-06,5.78e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.41e-06,0.000181,0.000181,0.000118,0.0406,0.0406,0.00685,0.0462,0.0462,0.0365,2.64e-09,2.64e-09,2.34e-09,3.37e-06,3.37e-06,5e-08,0,0,0,0,0,0,0,0 -14690000,0.982,-0.00704,-0.011,0.187,0.00587,-0.00207,0.0157,0.00626,-0.00394,-0.000457,-1.22e-05,-5.95e-05,-9.92e-07,-6.21e-06,5.78e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.37e-06,0.000186,0.000186,0.000118,0.0459,0.0459,0.00685,0.0529,0.0529,0.0362,2.64e-09,2.64e-09,2.27e-09,3.37e-06,3.37e-06,5e-08,0,0,0,0,0,0,0,0 -14790000,0.982,-0.00697,-0.011,0.187,0.00787,0.00435,0.0161,0.00508,0.00104,0.00204,-1.29e-05,-5.94e-05,-2.57e-07,-4.7e-06,6.53e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.34e-06,0.000179,0.000179,0.000117,0.0402,0.0402,0.00678,0.046,0.046,0.0357,2.46e-09,2.46e-09,2.2e-09,3.36e-06,3.36e-06,5e-08,0,0,0,0,0,0,0,0 -14890000,0.982,-0.00688,-0.011,0.187,0.00652,0.00222,0.0202,0.00575,0.00138,0.00266,-1.29e-05,-5.94e-05,2.67e-07,-4.73e-06,6.54e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.33e-06,0.000184,0.000184,0.000116,0.0455,0.0455,0.00683,0.0527,0.0527,0.0357,2.46e-09,2.46e-09,2.15e-09,3.36e-06,3.36e-06,5e-08,0,0,0,0,0,0,0,0 -14990000,0.982,-0.00704,-0.0108,0.187,0.0055,0.000566,0.0228,0.00457,-0.000328,0.00451,-1.27e-05,-5.97e-05,5.67e-07,-7.63e-06,6.33e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.3e-06,0.000176,0.000176,0.000116,0.0399,0.0399,0.00679,0.0459,0.0459,0.0352,2.28e-09,2.28e-09,2.09e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0 -15090000,0.982,-0.00698,-0.0109,0.187,0.00554,0.00191,0.0265,0.00513,-0.000246,0.0068,-1.27e-05,-5.97e-05,5.44e-07,-7.63e-06,6.33e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.26e-06,0.000181,0.000181,0.000115,0.0451,0.0451,0.00683,0.0525,0.0525,0.035,2.28e-09,2.28e-09,2.03e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0 -15190000,0.982,-0.00712,-0.011,0.187,0.00385,0.000689,0.0271,0.00406,-0.000353,0.00823,-1.27e-05,-5.99e-05,3.08e-07,-9.35e-06,6.35e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.25e-06,0.000174,0.000174,0.000114,0.0396,0.0396,0.00683,0.0458,0.0458,0.0349,2.11e-09,2.11e-09,1.97e-09,3.32e-06,3.32e-06,5e-08,0,0,0,0,0,0,0,0 -15290000,0.982,-0.0072,-0.011,0.187,0.00437,-9.49e-05,0.0266,0.00449,-0.000296,0.00497,-1.27e-05,-5.99e-05,8.43e-07,-9.56e-06,6.37e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.22e-06,0.000178,0.000178,0.000114,0.0447,0.0447,0.00689,0.0524,0.0524,0.0347,2.11e-09,2.11e-09,1.92e-09,3.32e-06,3.32e-06,5e-08,0,0,0,0,0,0,0,0 -15390000,0.982,-0.00729,-0.011,0.187,0.00469,0.00213,0.0261,0.00361,-0.000199,0.00515,-1.28e-05,-6e-05,7.42e-07,-1.11e-05,6.43e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.19e-06,0.00017,0.00017,0.000113,0.0393,0.0393,0.00687,0.0457,0.0457,0.0343,1.93e-09,1.94e-09,1.86e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 -15490000,0.982,-0.0073,-0.011,0.187,0.00407,-0.000124,0.0261,0.00404,-6.75e-05,0.00583,-1.28e-05,-6e-05,7.35e-07,-1.11e-05,6.43e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.18e-06,0.000175,0.000175,0.000112,0.0443,0.0443,0.00698,0.0522,0.0522,0.0345,1.93e-09,1.94e-09,1.82e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 -15590000,0.982,-0.00751,-0.011,0.187,0.00762,-0.00403,0.0257,0.00603,-0.00412,0.00437,-1.2e-05,-6e-05,1.06e-06,-1.09e-05,5.59e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.15e-06,0.000167,0.000167,0.000111,0.039,0.039,0.00697,0.0456,0.0456,0.0341,1.77e-09,1.77e-09,1.77e-09,3.28e-06,3.28e-06,5e-08,0,0,0,0,0,0,0,0 -15690000,0.982,-0.00746,-0.0109,0.187,0.00939,-0.00684,0.0262,0.00687,-0.00464,0.0051,-1.2e-05,-6e-05,1.51e-06,-1.14e-05,5.64e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.11e-06,0.000171,0.000171,0.000111,0.0439,0.0439,0.00705,0.0522,0.0522,0.034,1.77e-09,1.77e-09,1.72e-09,3.28e-06,3.28e-06,5e-08,0,0,0,0,0,0,0,0 -15790000,0.982,-0.00746,-0.0108,0.186,0.00598,-0.00641,0.0261,0.00528,-0.00367,0.00649,-1.23e-05,-6.02e-05,2.14e-06,-1.4e-05,6.01e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.08e-06,0.000163,0.000163,0.00011,0.0386,0.0386,0.00706,0.0456,0.0456,0.0337,1.61e-09,1.61e-09,1.67e-09,3.26e-06,3.26e-06,5e-08,0,0,0,0,0,0,0,0 -15890000,0.982,-0.00751,-0.0109,0.186,0.00481,-0.00453,0.0268,0.0058,-0.00423,0.00594,-1.23e-05,-6.02e-05,1.64e-06,-1.37e-05,5.98e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.07e-06,0.000167,0.000167,0.000109,0.0434,0.0434,0.00718,0.0521,0.0521,0.0339,1.61e-09,1.61e-09,1.63e-09,3.26e-06,3.26e-06,5e-08,0,0,0,0,0,0,0,0 -15990000,0.982,-0.00731,-0.0108,0.186,0.00282,-0.00328,0.0238,0.00457,-0.0033,0.00523,-1.25e-05,-6.03e-05,1.59e-06,-1.53e-05,6.2e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.03e-06,0.000159,0.000159,0.000108,0.0382,0.0382,0.00718,0.0455,0.0455,0.0336,1.47e-09,1.47e-09,1.59e-09,3.24e-06,3.24e-06,5e-08,0,0,0,0,0,0,0,0 -16090000,0.982,-0.00728,-0.0108,0.186,0.00213,-0.00426,0.0216,0.00475,-0.00367,0.0051,-1.25e-05,-6.03e-05,1.31e-06,-1.54e-05,6.22e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,3.99e-06,0.000162,0.000162,0.000108,0.0429,0.0429,0.00728,0.052,0.052,0.0335,1.47e-09,1.47e-09,1.54e-09,3.24e-06,3.24e-06,5e-08,0,0,0,0,0,0,0,0 -16190000,0.982,-0.00718,-0.0107,0.187,-0.00177,-0.00215,0.0204,0.00245,-0.00272,0.00193,-1.27e-05,-6.05e-05,9.32e-07,-1.84e-05,6.52e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,3.98e-06,0.000155,0.000155,0.000107,0.0377,0.0377,0.00731,0.0455,0.0455,0.0336,1.33e-09,1.33e-09,1.51e-09,3.21e-06,3.22e-06,5e-08,0,0,0,0,0,0,0,0 -16290000,0.982,-0.0072,-0.0106,0.187,-0.00148,-0.0034,0.0203,0.00226,-0.00303,0.00331,-1.27e-05,-6.05e-05,1.07e-06,-1.85e-05,6.53e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,3.95e-06,0.000158,0.000158,0.000106,0.0423,0.0423,0.00741,0.0519,0.0519,0.0335,1.33e-09,1.33e-09,1.46e-09,3.21e-06,3.22e-06,5e-08,0,0,0,0,0,0,0,0 -16390000,0.982,-0.00717,-0.0106,0.186,0.00101,-0.00297,0.0208,0.00333,-0.00234,0.0034,-1.27e-05,-6.03e-05,1.45e-06,-1.57e-05,6.54e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.92e-06,0.000151,0.000151,0.000105,0.0371,0.0371,0.00742,0.0454,0.0454,0.0333,1.2e-09,1.2e-09,1.43e-09,3.19e-06,3.19e-06,5e-08,0,0,0,0,0,0,0,0 -16490000,0.982,-0.00729,-0.0106,0.186,0.00302,-0.00433,0.0232,0.00356,-0.00276,0.00758,-1.27e-05,-6.03e-05,1.3e-06,-1.55e-05,6.53e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,3.9e-06,0.000154,0.000154,0.000105,0.0416,0.0416,0.00755,0.0519,0.0519,0.0336,1.2e-09,1.2e-09,1.39e-09,3.19e-06,3.19e-06,5e-08,0,0,0,0,0,0,0,0 -16590000,0.982,-0.00726,-0.0106,0.186,0.00713,-0.00464,0.027,0.00312,-0.00216,0.00779,-1.28e-05,-6.03e-05,1.3e-06,-1.61e-05,6.7e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.87e-06,0.000146,0.000146,0.000104,0.0365,0.0365,0.00755,0.0454,0.0454,0.0334,1.08e-09,1.08e-09,1.35e-09,3.17e-06,3.18e-06,5e-08,0,0,0,0,0,0,0,0 -16690000,0.982,-0.00731,-0.0105,0.186,0.00855,-0.00896,0.0271,0.0039,-0.00282,0.00849,-1.28e-05,-6.03e-05,1.53e-06,-1.64e-05,6.73e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.84e-06,0.000149,0.000149,0.000103,0.0408,0.0408,0.00765,0.0518,0.0518,0.0334,1.08e-09,1.08e-09,1.32e-09,3.17e-06,3.18e-06,5e-08,0,0,0,0,0,0,0,0 -16790000,0.982,-0.00714,-0.0104,0.186,0.00945,-0.00807,0.0259,0.00301,-0.00201,0.00839,-1.31e-05,-6.04e-05,1.69e-06,-1.82e-05,7.09e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.82e-06,0.000142,0.000142,0.000103,0.0358,0.0358,0.00768,0.0453,0.0453,0.0335,9.78e-10,9.79e-10,1.29e-09,3.16e-06,3.16e-06,5e-08,0,0,0,0,0,0,0,0 -16890000,0.982,-0.00711,-0.0105,0.186,0.00838,-0.00826,0.027,0.00388,-0.0028,0.0071,-1.31e-05,-6.04e-05,2.18e-06,-1.85e-05,7.12e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.78e-06,0.000145,0.000145,0.000102,0.04,0.04,0.00778,0.0517,0.0517,0.0336,9.78e-10,9.79e-10,1.25e-09,3.16e-06,3.16e-06,5e-08,0,0,0,0,0,0,0,0 -16990000,0.982,-0.00713,-0.0105,0.186,0.00804,-0.00789,0.0268,0.00369,-0.00208,0.00574,-1.32e-05,-6.03e-05,2.28e-06,-1.65e-05,7.28e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.75e-06,0.000138,0.000138,0.000101,0.0351,0.0351,0.00778,0.0453,0.0453,0.0334,8.82e-10,8.82e-10,1.22e-09,3.14e-06,3.14e-06,5e-08,0,0,0,0,0,0,0,0 -17090000,0.982,-0.00722,-0.0105,0.186,0.00954,-0.0103,0.0264,0.0046,-0.00304,0.00514,-1.32e-05,-6.03e-05,2.15e-06,-1.66e-05,7.28e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.72e-06,0.000141,0.000141,0.0001,0.0392,0.0392,0.00787,0.0516,0.0516,0.0335,8.82e-10,8.82e-10,1.19e-09,3.14e-06,3.14e-06,5e-08,0,0,0,0,0,0,0,0 -17190000,0.982,-0.00734,-0.0104,0.186,0.00847,-0.0157,0.0282,0.003,-0.00676,0.00839,-1.31e-05,-6.04e-05,1.63e-06,-1.83e-05,7.04e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.71e-06,0.000135,0.000135,0.0001,0.0344,0.0344,0.00789,0.0452,0.0452,0.0336,7.95e-10,7.95e-10,1.16e-09,3.12e-06,3.12e-06,5e-08,0,0,0,0,0,0,0,0 -17290000,0.982,-0.0073,-0.0104,0.186,0.00933,-0.016,0.0278,0.00389,-0.00829,0.00826,-1.31e-05,-6.04e-05,1.26e-06,-1.83e-05,7.02e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.68e-06,0.000137,0.000137,9.93e-05,0.0383,0.0383,0.00798,0.0515,0.0515,0.0337,7.95e-10,7.95e-10,1.13e-09,3.12e-06,3.12e-06,5e-08,0,0,0,0,0,0,0,0 -17390000,0.982,-0.00717,-0.0104,0.186,0.00601,-0.0159,0.0273,0.0053,-0.00514,0.00806,-1.34e-05,-6.02e-05,1.6e-06,-1.47e-05,7.59e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.65e-06,0.000131,0.000131,9.85e-05,0.0336,0.0336,0.00796,0.0451,0.0451,0.0336,7.16e-10,7.17e-10,1.11e-09,3.11e-06,3.11e-06,5e-08,0,0,0,0,0,0,0,0 -17490000,0.982,-0.00719,-0.0105,0.186,0.00404,-0.0165,0.0271,0.00576,-0.00675,0.00986,-1.34e-05,-6.02e-05,1.42e-06,-1.46e-05,7.58e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.63e-06,0.000133,0.000133,9.81e-05,0.0374,0.0374,0.00809,0.0513,0.0513,0.034,7.17e-10,7.17e-10,1.08e-09,3.11e-06,3.11e-06,5e-08,0,0,0,0,0,0,0,0 -17590000,0.982,-0.0071,-0.0103,0.186,0.000346,-0.0128,0.0264,0.00206,-0.00503,0.00771,-1.38e-05,-6.04e-05,1.41e-06,-1.86e-05,8.17e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.6e-06,0.000128,0.000128,9.73e-05,0.0329,0.0329,0.00806,0.045,0.045,0.0338,6.46e-10,6.46e-10,1.05e-09,3.09e-06,3.09e-06,5e-08,0,0,0,0,0,0,0,0 -17690000,0.982,-0.00719,-0.0102,0.186,-0.000619,-0.0133,0.0275,0.00207,-0.00636,0.0102,-1.38e-05,-6.04e-05,1.47e-06,-1.86e-05,8.18e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.57e-06,0.000129,0.000129,9.65e-05,0.0364,0.0365,0.00814,0.0512,0.0512,0.034,6.46e-10,6.46e-10,1.03e-09,3.09e-06,3.09e-06,5e-08,0,0,0,0,0,0,0,0 -17790000,0.982,-0.00716,-0.0102,0.186,0.00211,-0.0118,0.028,0.00312,-0.00548,0.0155,-1.41e-05,-6.02e-05,1.52e-06,-1.5e-05,8.48e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.55e-06,0.000124,0.000124,9.62e-05,0.0321,0.0321,0.00814,0.0449,0.0449,0.0341,5.83e-10,5.83e-10,1.01e-09,3.08e-06,3.08e-06,5e-08,0,0,0,0,0,0,0,0 -17890000,0.982,-0.00708,-0.0103,0.186,0.00424,-0.0136,0.0278,0.0035,-0.00677,0.0199,-1.4e-05,-6.02e-05,1.65e-06,-1.49e-05,8.48e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.52e-06,0.000126,0.000126,9.54e-05,0.0355,0.0355,0.00822,0.051,0.051,0.0342,5.83e-10,5.83e-10,9.81e-10,3.08e-06,3.08e-06,5e-08,0,0,0,0,0,0,0,0 -17990000,0.982,-0.00689,-0.0103,0.186,0.00372,-0.00742,0.0276,0.00276,-0.00135,0.0206,-1.46e-05,-6e-05,1.61e-06,-1.29e-05,9.36e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.49e-06,0.000121,0.000121,9.46e-05,0.0313,0.0313,0.00817,0.0448,0.0448,0.0341,5.27e-10,5.27e-10,9.57e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0 -18090000,0.982,-0.00697,-0.0103,0.186,0.00314,-0.00781,0.0269,0.00314,-0.00213,0.0188,-1.46e-05,-6e-05,1.56e-06,-1.33e-05,9.38e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.48e-06,0.000123,0.000123,9.43e-05,0.0346,0.0346,0.00828,0.0509,0.0509,0.0345,5.27e-10,5.27e-10,9.37e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0 -18190000,0.983,-0.00698,-0.0103,0.186,0.00315,-0.00699,0.0273,0.00375,-0.00155,0.0169,-1.47e-05,-5.99e-05,2.05e-06,-1.18e-05,9.49e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.45e-06,0.000118,0.000118,9.35e-05,0.0305,0.0305,0.00823,0.0447,0.0447,0.0344,4.77e-10,4.77e-10,9.14e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0 -18290000,0.983,-0.00701,-0.0103,0.186,0.00396,-0.00734,0.0262,0.00404,-0.00224,0.0154,-1.47e-05,-5.99e-05,2.06e-06,-1.21e-05,9.51e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.42e-06,0.00012,0.00012,9.28e-05,0.0337,0.0337,0.0083,0.0507,0.0507,0.0345,4.77e-10,4.77e-10,8.92e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0 -18390000,0.983,-0.00693,-0.0103,0.186,0.00481,-0.00628,0.0261,0.00569,-0.00169,0.015,-1.47e-05,-5.98e-05,1.89e-06,-9.71e-06,9.58e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.4e-06,0.000116,0.000116,9.2e-05,0.0297,0.0297,0.00824,0.0446,0.0446,0.0343,4.32e-10,4.32e-10,8.71e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0 -18490000,0.983,-0.00697,-0.0104,0.186,0.00752,-0.0062,0.0253,0.00639,-0.00234,0.0167,-1.47e-05,-5.98e-05,2.07e-06,-9.67e-06,9.57e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.39e-06,0.000117,0.000117,9.17e-05,0.0328,0.0328,0.00834,0.0505,0.0505,0.0348,4.32e-10,4.32e-10,8.53e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0 -18590000,0.982,-0.0068,-0.0102,0.186,0.00606,-0.00576,0.0252,0.00515,-0.00179,0.0195,-1.48e-05,-5.98e-05,1.79e-06,-1.1e-05,9.77e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.36e-06,0.000113,0.000113,9.1e-05,0.029,0.029,0.00828,0.0445,0.0445,0.0346,3.92e-10,3.92e-10,8.33e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0 -18690000,0.983,-0.00676,-0.0102,0.186,0.00603,-0.00461,0.0237,0.00575,-0.0023,0.0183,-1.48e-05,-5.98e-05,2.01e-06,-1.11e-05,9.78e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.33e-06,0.000115,0.000115,9.03e-05,0.0319,0.0319,0.00834,0.0503,0.0503,0.0347,3.92e-10,3.92e-10,8.14e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0 -18790000,0.983,-0.00673,-0.0101,0.186,0.00504,-0.00447,0.0234,0.00576,-0.00187,0.0162,-1.49e-05,-5.98e-05,1.95e-06,-1.12e-05,9.89e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.32e-06,0.000111,0.000111,8.99e-05,0.0282,0.0282,0.00831,0.0443,0.0443,0.0349,3.56e-10,3.56e-10,7.97e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 -18890000,0.982,-0.00669,-0.0101,0.186,0.00361,-0.00397,0.0215,0.00615,-0.00236,0.0125,-1.49e-05,-5.98e-05,1.78e-06,-1.17e-05,9.93e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.29e-06,0.000112,0.000112,8.92e-05,0.031,0.031,0.00836,0.0501,0.0501,0.035,3.56e-10,3.56e-10,7.79e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 -18990000,0.982,-0.00667,-0.0101,0.186,0.00209,-0.00428,0.0223,0.00507,-0.00189,0.0162,-1.5e-05,-5.99e-05,1.74e-06,-1.23e-05,0.0001,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.27e-06,0.000109,0.000109,8.85e-05,0.0275,0.0275,0.00829,0.0442,0.0442,0.0348,3.24e-10,3.24e-10,7.61e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 -19090000,0.982,-0.00673,-0.0101,0.186,-8.79e-06,-0.00467,0.0228,0.00522,-0.00229,0.0123,-1.5e-05,-5.99e-05,1.91e-06,-1.27e-05,0.000101,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.26e-06,0.00011,0.00011,8.82e-05,0.0302,0.0302,0.00838,0.0499,0.0499,0.0352,3.24e-10,3.24e-10,7.46e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 -19190000,0.982,-0.00663,-0.0102,0.186,-0.00143,-0.00448,0.0224,0.00432,-0.00189,0.0116,-1.5e-05,-5.99e-05,1.47e-06,-1.32e-05,0.000102,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.24e-06,0.000107,0.000107,8.75e-05,0.0268,0.0268,0.0083,0.0441,0.0441,0.035,2.96e-10,2.96e-10,7.29e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 -19290000,0.982,-0.00659,-0.0102,0.186,-0.00235,-0.00425,0.0229,0.00417,-0.00232,0.0109,-1.5e-05,-5.99e-05,1.39e-06,-1.34e-05,0.000102,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.21e-06,0.000108,0.000108,8.68e-05,0.0293,0.0293,0.00835,0.0496,0.0496,0.0352,2.96e-10,2.96e-10,7.13e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 -19390000,0.982,-0.00667,-0.0101,0.186,-0.00274,-0.000986,0.0241,0.00357,-0.000596,0.00995,-1.52e-05,-5.98e-05,1.27e-06,-1.31e-05,0.000104,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.2e-06,0.000105,0.000105,8.65e-05,0.0261,0.0261,0.00831,0.0439,0.0439,0.0353,2.7e-10,2.7e-10,6.99e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 -19490000,0.982,-0.0067,-0.00999,0.186,-0.00364,-0.000894,0.0236,0.00324,-0.000678,0.00945,-1.52e-05,-5.98e-05,9.57e-07,-1.34e-05,0.000105,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.18e-06,0.000106,0.000106,8.58e-05,0.0285,0.0285,0.00835,0.0494,0.0494,0.0354,2.7e-10,2.71e-10,6.83e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 -19590000,0.982,-0.00665,-0.0101,0.186,-0.00472,-0.00389,0.0256,0.00384,-0.00179,0.00996,-1.51e-05,-5.97e-05,8.58e-07,-1.26e-05,0.000103,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.16e-06,0.000103,0.000103,8.52e-05,0.0254,0.0254,0.00827,0.0437,0.0437,0.0352,2.48e-10,2.48e-10,6.68e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -19690000,0.982,-0.00667,-0.0101,0.186,-0.00646,-0.00234,0.0241,0.00331,-0.00209,0.0096,-1.51e-05,-5.97e-05,1.01e-06,-1.27e-05,0.000103,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.13e-06,0.000104,0.000104,8.45e-05,0.0278,0.0278,0.00831,0.0492,0.0492,0.0353,2.48e-10,2.48e-10,6.54e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -19790000,0.982,-0.00675,-0.0102,0.187,-0.00656,-0.00103,0.0226,0.00573,-0.00172,0.00584,-1.5e-05,-5.96e-05,7.76e-07,-1.08e-05,0.000103,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.12e-06,0.000102,0.000102,8.42e-05,0.0248,0.0248,0.00827,0.0436,0.0436,0.0354,2.27e-10,2.27e-10,6.41e-10,2.99e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -19890000,0.982,-0.00677,-0.0102,0.187,-0.00666,-0.000697,0.0229,0.00503,-0.00176,0.00477,-1.5e-05,-5.96e-05,6.62e-07,-1.11e-05,0.000103,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.1e-06,0.000103,0.000103,8.36e-05,0.027,0.027,0.00831,0.0489,0.0489,0.0355,2.27e-10,2.28e-10,6.28e-10,2.99e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 -19990000,0.982,-0.00678,-0.0104,0.187,-0.00639,-0.000822,0.0203,0.00542,-0.000352,0.00186,-1.51e-05,-5.95e-05,7e-07,-9.56e-06,0.000104,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.08e-06,0.0001,0.0001,8.3e-05,0.0241,0.0241,0.00822,0.0434,0.0434,0.0352,2.09e-10,2.09e-10,6.14e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 -20090000,0.982,-0.00679,-0.0104,0.186,-0.00592,-0.00299,0.0207,0.00479,-0.000553,0.00547,-1.51e-05,-5.95e-05,6.74e-07,-9.45e-06,0.000104,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.06e-06,0.000101,0.000101,8.27e-05,0.0263,0.0263,0.0083,0.0487,0.0487,0.0356,2.09e-10,2.09e-10,6.03e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 -20190000,0.982,-0.00678,-0.0105,0.187,-0.00483,-0.00056,0.0217,0.00588,-0.000369,0.00553,-1.51e-05,-5.94e-05,4.29e-07,-8.59e-06,0.000104,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.04e-06,9.92e-05,9.91e-05,8.21e-05,0.0235,0.0235,0.00822,0.0432,0.0432,0.0354,1.93e-10,1.93e-10,5.9e-10,2.98e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 -20290000,0.982,-0.00677,-0.0105,0.186,-0.00809,-0.00158,0.0219,0.00526,-0.000415,0.00649,-1.51e-05,-5.94e-05,3.48e-07,-8.72e-06,0.000104,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.02e-06,9.98e-05,9.98e-05,8.15e-05,0.0256,0.0256,0.00825,0.0484,0.0484,0.0355,1.93e-10,1.93e-10,5.78e-10,2.98e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 -20390000,0.982,-0.00674,-0.0105,0.187,-0.00872,-0.00052,0.0222,0.00622,-0.000255,0.00795,-1.51e-05,-5.93e-05,4.93e-07,-7.53e-06,0.000104,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.01e-06,9.79e-05,9.79e-05,8.12e-05,0.023,0.023,0.00821,0.043,0.043,0.0356,1.78e-10,1.78e-10,5.67e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 -20490000,0.982,-0.00673,-0.0105,0.186,-0.0134,-0.00142,0.0221,0.0051,-0.000325,0.00648,-1.51e-05,-5.93e-05,4.72e-07,-7.8e-06,0.000104,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.98e-06,9.86e-05,9.85e-05,8.06e-05,0.025,0.025,0.00824,0.0482,0.0482,0.0356,1.78e-10,1.78e-10,5.55e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 -20590000,0.982,-0.00672,-0.0105,0.186,-0.0125,-0.00247,0.0217,0.00621,-0.000282,0.00509,-1.5e-05,-5.92e-05,7.31e-07,-6.21e-06,0.000104,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.96e-06,9.68e-05,9.67e-05,8e-05,0.0224,0.0224,0.00816,0.0429,0.0429,0.0354,1.65e-10,1.65e-10,5.44e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 -20690000,0.982,-0.00663,-0.0105,0.186,-0.0142,-0.0012,0.0227,0.00489,-0.000413,0.0059,-1.5e-05,-5.92e-05,5.11e-07,-6.4e-06,0.000104,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.95e-06,9.74e-05,9.73e-05,7.97e-05,0.0244,0.0244,0.00823,0.0479,0.0479,0.0358,1.65e-10,1.65e-10,5.34e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 -20790000,0.982,-0.00604,-0.0104,0.186,-0.0167,0.00127,0.00765,0.00409,-0.000311,0.00478,-1.5e-05,-5.92e-05,5.93e-07,-5.52e-06,0.000104,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.93e-06,9.57e-05,9.57e-05,7.91e-05,0.0219,0.0219,0.00815,0.0427,0.0427,0.0356,1.53e-10,1.53e-10,5.23e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 -20890000,0.982,0.00309,-0.00641,0.186,-0.023,0.0133,-0.111,0.00204,0.000461,-0.00116,-1.5e-05,-5.92e-05,5.98e-07,-5.51e-06,0.000104,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.9e-06,9.63e-05,9.62e-05,7.86e-05,0.0241,0.0241,0.00818,0.0477,0.0477,0.0356,1.53e-10,1.53e-10,5.13e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 -20990000,0.982,0.00642,-0.00298,0.186,-0.0338,0.0313,-0.25,0.00142,0.00105,-0.0158,-1.49e-05,-5.91e-05,5.57e-07,-3.52e-06,0.000101,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.88e-06,9.46e-05,9.46e-05,7.8e-05,0.0219,0.0219,0.0081,0.0425,0.0425,0.0354,1.42e-10,1.42e-10,5.03e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 -21090000,0.982,0.00483,-0.00336,0.187,-0.0475,0.0474,-0.368,-0.00264,0.00503,-0.0461,-1.49e-05,-5.91e-05,5.49e-07,-3.51e-06,0.000101,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.88e-06,9.52e-05,9.51e-05,7.77e-05,0.0241,0.0241,0.00817,0.0475,0.0475,0.0357,1.42e-10,1.42e-10,4.94e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 -21190000,0.982,0.00195,-0.00503,0.187,-0.0512,0.0516,-0.495,-0.00219,0.00417,-0.082,-1.46e-05,-5.89e-05,6.15e-07,8.45e-07,9.21e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.87e-06,9.34e-05,9.33e-05,7.72e-05,0.0219,0.0219,0.00809,0.0424,0.0424,0.0355,1.32e-10,1.32e-10,4.84e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 -21290000,0.982,-0.00021,-0.00636,0.187,-0.0516,0.0553,-0.625,-0.00732,0.00954,-0.14,-1.46e-05,-5.89e-05,3.24e-07,9.57e-07,9.23e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.85e-06,9.39e-05,9.38e-05,7.66e-05,0.0241,0.0241,0.00813,0.0474,0.0474,0.0355,1.32e-10,1.33e-10,4.74e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 -21390000,0.982,-0.0017,-0.00708,0.187,-0.0469,0.0511,-0.75,-0.00607,0.0118,-0.205,-1.44e-05,-5.88e-05,3.33e-07,6.14e-06,8.68e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.85e-06,9.2e-05,9.2e-05,7.64e-05,0.0219,0.0219,0.00809,0.0423,0.0423,0.0356,1.23e-10,1.23e-10,4.66e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 -21490000,0.982,-0.0025,-0.00749,0.187,-0.0427,0.0486,-0.886,-0.0106,0.0168,-0.29,-1.44e-05,-5.88e-05,4.61e-07,5.88e-06,8.69e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.83e-06,9.25e-05,9.24e-05,7.58e-05,0.024,0.024,0.00812,0.0473,0.0473,0.0356,1.23e-10,1.23e-10,4.57e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 -21590000,0.982,-0.003,-0.00751,0.187,-0.0341,0.044,-1.01,-0.00905,0.0172,-0.379,-1.43e-05,-5.87e-05,5.78e-07,8.68e-06,8.3e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.81e-06,9.05e-05,9.05e-05,7.53e-05,0.0218,0.0218,0.00805,0.0422,0.0422,0.0354,1.15e-10,1.15e-10,4.49e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 -21690000,0.982,-0.00333,-0.00737,0.187,-0.0324,0.0401,-1.14,-0.0124,0.0214,-0.493,-1.43e-05,-5.87e-05,7.53e-07,8.26e-06,8.33e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.81e-06,9.1e-05,9.09e-05,7.5e-05,0.0238,0.0238,0.00812,0.0472,0.0472,0.0358,1.15e-10,1.15e-10,4.41e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 -21790000,0.982,-0.00371,-0.00758,0.187,-0.024,0.0338,-1.27,-0.005,0.0186,-0.612,-1.41e-05,-5.85e-05,9.75e-07,1.49e-05,7.95e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.79e-06,8.89e-05,8.89e-05,7.45e-05,0.0216,0.0216,0.00804,0.0421,0.0421,0.0355,1.07e-10,1.07e-10,4.33e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0 -21890000,0.982,-0.004,-0.00772,0.187,-0.0209,0.0297,-1.39,-0.00725,0.0218,-0.751,-1.41e-05,-5.85e-05,8.55e-07,1.46e-05,7.99e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.77e-06,8.93e-05,8.93e-05,7.4e-05,0.0236,0.0236,0.00808,0.0471,0.0471,0.0355,1.07e-10,1.07e-10,4.24e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0 -21990000,0.982,-0.00471,-0.00802,0.187,-0.017,0.0237,-1.37,-0.00152,0.0173,-0.887,-1.4e-05,-5.85e-05,9.6e-07,1.38e-05,8.02e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.76e-06,8.73e-05,8.73e-05,7.37e-05,0.021,0.021,0.00805,0.042,0.042,0.0356,1e-10,1e-10,4.18e-10,2.92e-06,2.92e-06,5e-08,0,0,0,0,0,0,0,0 -22090000,0.982,-0.00543,-0.00882,0.187,-0.0147,0.0199,-1.36,-0.00315,0.0194,-1.03,-1.4e-05,-5.85e-05,1.16e-06,1.35e-05,8.05e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.75e-06,8.77e-05,8.76e-05,7.32e-05,0.0226,0.0226,0.00808,0.0469,0.0469,0.0357,1e-10,1.01e-10,4.1e-10,2.92e-06,2.92e-06,5e-08,0,0,0,0,0,0,0,0 -22190000,0.982,-0.00589,-0.00909,0.187,-0.00602,0.0141,-1.37,0.00485,0.0134,-1.17,-1.39e-05,-5.84e-05,1.32e-06,1.37e-05,8.15e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.73e-06,8.58e-05,8.58e-05,7.28e-05,0.0203,0.0203,0.00801,0.0419,0.0419,0.0354,9.42e-11,9.43e-11,4.02e-10,2.91e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 -22290000,0.982,-0.0066,-0.00934,0.187,-0.000933,0.00892,-1.37,0.00449,0.0146,-1.31,-1.39e-05,-5.84e-05,1.22e-06,1.34e-05,8.19e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.71e-06,8.62e-05,8.61e-05,7.23e-05,0.0218,0.0218,0.00804,0.0467,0.0467,0.0354,9.43e-11,9.44e-11,3.95e-10,2.91e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 -22390000,0.982,-0.00696,-0.00951,0.187,0.00446,-0.000694,-1.37,0.012,0.00471,-1.45,-1.38e-05,-5.85e-05,1.02e-06,9.51e-06,8.05e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.7e-06,8.45e-05,8.45e-05,7.2e-05,0.0196,0.0196,0.00801,0.0418,0.0418,0.0355,8.87e-11,8.88e-11,3.88e-10,2.91e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 -22490000,0.982,-0.0071,-0.00997,0.187,0.0083,-0.00663,-1.37,0.0126,0.0043,-1.59,-1.38e-05,-5.85e-05,8.8e-07,9.49e-06,8.05e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.69e-06,8.48e-05,8.48e-05,7.15e-05,0.021,0.021,0.00805,0.0465,0.0465,0.0355,8.88e-11,8.89e-11,3.81e-10,2.91e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 -22590000,0.982,-0.00703,-0.0106,0.187,0.0178,-0.0157,-1.37,0.0247,-0.00482,-1.74,-1.37e-05,-5.84e-05,1.05e-06,1.21e-05,7.97e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.67e-06,8.34e-05,8.33e-05,7.11e-05,0.0189,0.0189,0.00798,0.0416,0.0416,0.0353,8.38e-11,8.39e-11,3.75e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22690000,0.982,-0.00694,-0.0108,0.187,0.0199,-0.0201,-1.38,0.0266,-0.00665,-1.88,-1.37e-05,-5.84e-05,9.66e-07,1.16e-05,8.02e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.67e-06,8.37e-05,8.36e-05,7.08e-05,0.0204,0.0204,0.00806,0.0462,0.0462,0.0356,8.39e-11,8.4e-11,3.69e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 -22790000,0.982,-0.00694,-0.0112,0.187,0.0263,-0.0281,-1.38,0.037,-0.0168,-2.02,-1.37e-05,-5.84e-05,8.33e-07,9.7e-06,8.1e-05,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.64e-06,8.23e-05,8.23e-05,7.04e-05,0.0184,0.0184,0.00798,0.0414,0.0414,0.0354,7.94e-11,7.95e-11,3.62e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0 -22890000,0.982,-0.0071,-0.0115,0.187,0.0297,-0.0336,-1.38,0.0398,-0.0198,-2.17,-1.37e-05,-5.84e-05,1.02e-06,9.43e-06,8.15e-05,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.62e-06,8.26e-05,8.26e-05,6.99e-05,0.0197,0.0197,0.00802,0.0459,0.0459,0.0354,7.95e-11,7.96e-11,3.56e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0 -22990000,0.982,-0.00706,-0.0119,0.186,0.0343,-0.0389,-1.39,0.0499,-0.0305,-2.32,-1.37e-05,-5.84e-05,1.2e-06,7.29e-06,8.25e-05,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.6e-06,8.14e-05,8.14e-05,6.97e-05,0.0178,0.0178,0.00799,0.0412,0.0412,0.0355,7.54e-11,7.55e-11,3.5e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0 -23090000,0.982,-0.00708,-0.0122,0.186,0.0393,-0.0436,-1.38,0.0536,-0.0346,-2.46,-1.37e-05,-5.84e-05,1.21e-06,7.13e-06,8.27e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,2.58e-06,8.17e-05,8.16e-05,6.93e-05,0.0192,0.0192,0.00803,0.0456,0.0456,0.0355,7.55e-11,7.56e-11,3.44e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0 -23190000,0.982,-0.0071,-0.0125,0.186,0.0459,-0.0453,-1.39,0.0653,-0.0449,-2.6,-1.36e-05,-5.84e-05,1.1e-06,6.68e-06,8.23e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,2.56e-06,8.06e-05,8.06e-05,6.88e-05,0.0174,0.0174,0.00796,0.041,0.041,0.0353,7.18e-11,7.19e-11,3.38e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 -23290000,0.983,-0.00757,-0.0126,0.186,0.0508,-0.0502,-1.38,0.0701,-0.0497,-2.75,-1.36e-05,-5.84e-05,1.16e-06,6.33e-06,8.29e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,2.55e-06,8.09e-05,8.08e-05,6.86e-05,0.0186,0.0186,0.00804,0.0454,0.0454,0.0356,7.19e-11,7.2e-11,3.33e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 -23390000,0.983,-0.00749,-0.0127,0.186,0.0564,-0.0526,-1.38,0.0812,-0.055,-2.88,-1.37e-05,-5.84e-05,9.63e-07,7.64e-06,8.49e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,2.52e-06,7.99e-05,7.99e-05,6.82e-05,0.0169,0.0169,0.00797,0.0408,0.0408,0.0354,6.85e-11,6.86e-11,3.27e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 -23490000,0.983,-0.00757,-0.013,0.185,0.0606,-0.0549,-1.38,0.087,-0.0604,-3.03,-1.37e-05,-5.84e-05,1.11e-06,7.41e-06,8.53e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,2.51e-06,8.01e-05,8.01e-05,6.78e-05,0.0182,0.0182,0.00801,0.0451,0.0451,0.0354,6.86e-11,6.87e-11,3.22e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 -23590000,0.983,-0.00784,-0.0129,0.185,0.0637,-0.0579,-1.38,0.0948,-0.0703,-3.17,-1.38e-05,-5.85e-05,1.18e-06,5.71e-06,8.51e-05,-0.00128,0.204,0.002,0.435,0,0,0,0,0,2.49e-06,7.93e-05,7.93e-05,6.73e-05,0.0165,0.0165,0.00794,0.0405,0.0405,0.0352,6.56e-11,6.56e-11,3.16e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 -23690000,0.983,-0.00849,-0.0135,0.185,0.062,-0.0603,-1.28,0.101,-0.0763,-3.31,-1.38e-05,-5.85e-05,1.33e-06,5.71e-06,8.53e-05,-0.00128,0.204,0.002,0.435,0,0,0,0,0,2.49e-06,7.95e-05,7.95e-05,6.71e-05,0.0176,0.0176,0.00802,0.0448,0.0448,0.0355,6.57e-11,6.57e-11,3.12e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 -23790000,0.983,-0.0103,-0.0163,0.185,0.0575,-0.0578,-0.948,0.111,-0.081,-3.43,-1.39e-05,-5.84e-05,1.48e-06,6.93e-06,8.59e-05,-0.00128,0.204,0.002,0.435,0,0,0,0,0,2.48e-06,7.88e-05,7.88e-05,6.67e-05,0.0157,0.0157,0.00795,0.0403,0.0403,0.0353,6.29e-11,6.29e-11,3.06e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 -23890000,0.982,-0.0137,-0.0204,0.185,0.0538,-0.0585,-0.516,0.116,-0.0868,-3.5,-1.39e-05,-5.84e-05,1.5e-06,6.85e-06,8.61e-05,-0.00128,0.204,0.002,0.435,0,0,0,0,0,2.48e-06,7.9e-05,7.9e-05,6.63e-05,0.0165,0.0165,0.00799,0.0444,0.0444,0.0353,6.3e-11,6.3e-11,3.01e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 -23990000,0.982,-0.0158,-0.0228,0.185,0.0563,-0.058,-0.133,0.125,-0.0894,-3.56,-1.4e-05,-5.84e-05,1.49e-06,7.57e-06,8.56e-05,-0.00126,0.204,0.002,0.435,0,0,0,0,0,2.48e-06,7.87e-05,7.86e-05,6.61e-05,0.015,0.015,0.00796,0.04,0.04,0.0354,6.05e-11,6.05e-11,2.97e-10,2.87e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 -24090000,0.982,-0.0153,-0.0216,0.185,0.0632,-0.0664,0.0994,0.131,-0.0956,-3.56,-1.4e-05,-5.84e-05,1.4e-06,7.64e-06,8.53e-05,-0.00126,0.204,0.002,0.435,0,0,0,0,0,2.46e-06,7.89e-05,7.88e-05,6.57e-05,0.016,0.016,0.008,0.0439,0.0439,0.0354,6.06e-11,6.06e-11,2.92e-10,2.87e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 -24190000,0.983,-0.0125,-0.0179,0.185,0.0741,-0.0717,0.0865,0.138,-0.0998,-3.57,-1.4e-05,-5.84e-05,1.49e-06,1.1e-05,8.16e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.43e-06,7.87e-05,7.86e-05,6.53e-05,0.0148,0.0148,0.00794,0.0396,0.0396,0.0352,5.83e-11,5.84e-11,2.87e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0 -24290000,0.983,-0.0101,-0.0145,0.185,0.0779,-0.0751,0.0649,0.146,-0.107,-3.56,-1.4e-05,-5.84e-05,1.5e-06,1.09e-05,8.18e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.41e-06,7.89e-05,7.88e-05,6.51e-05,0.0159,0.0159,0.00802,0.0435,0.0435,0.0355,5.84e-11,5.85e-11,2.83e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0 -24390000,0.983,-0.00923,-0.0136,0.185,0.0714,-0.0697,0.0812,0.153,-0.108,-3.56,-1.42e-05,-5.84e-05,1.7e-06,1.14e-05,7.31e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.39e-06,7.87e-05,7.87e-05,6.47e-05,0.0146,0.0146,0.00795,0.0393,0.0393,0.0353,5.64e-11,5.64e-11,2.79e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0 -24490000,0.983,-0.00947,-0.0137,0.185,0.0669,-0.0666,0.0791,0.16,-0.115,-3.55,-1.42e-05,-5.84e-05,1.95e-06,1.16e-05,7.3e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.38e-06,7.89e-05,7.89e-05,6.43e-05,0.0157,0.0157,0.00799,0.0432,0.0432,0.0353,5.65e-11,5.65e-11,2.74e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0 -24590000,0.983,-0.0102,-0.0137,0.185,0.0635,-0.0626,0.0748,0.163,-0.112,-3.54,-1.44e-05,-5.84e-05,1.93e-06,9.39e-06,6.5e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.38e-06,7.89e-05,7.88e-05,6.41e-05,0.0145,0.0145,0.00797,0.0391,0.0391,0.0354,5.45e-11,5.45e-11,2.7e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0 -24690000,0.983,-0.0106,-0.0135,0.185,0.0613,-0.062,0.0743,0.169,-0.118,-3.53,-1.44e-05,-5.84e-05,1.93e-06,9.42e-06,6.49e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.36e-06,7.91e-05,7.9e-05,6.38e-05,0.0156,0.0156,0.00801,0.043,0.043,0.0354,5.46e-11,5.46e-11,2.66e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0 -24790000,0.983,-0.0107,-0.0129,0.185,0.058,-0.0596,0.0658,0.172,-0.114,-3.53,-1.46e-05,-5.84e-05,1.98e-06,9.21e-06,5.82e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.35e-06,7.9e-05,7.9e-05,6.34e-05,0.0144,0.0144,0.00794,0.0389,0.0389,0.0352,5.28e-11,5.28e-11,2.62e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0 -24890000,0.983,-0.0105,-0.0124,0.185,0.0564,-0.063,0.0552,0.177,-0.12,-3.53,-1.46e-05,-5.84e-05,2.05e-06,9.06e-06,5.85e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.33e-06,7.92e-05,7.92e-05,6.3e-05,0.0155,0.0155,0.00799,0.0427,0.0427,0.0352,5.29e-11,5.29e-11,2.58e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0 -24990000,0.983,-0.0103,-0.0121,0.185,0.0475,-0.0587,0.0479,0.177,-0.112,-3.52,-1.48e-05,-5.83e-05,2.06e-06,7.2e-06,5.01e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.33e-06,7.92e-05,7.92e-05,6.28e-05,0.0144,0.0144,0.00796,0.0388,0.0388,0.0353,5.12e-11,5.12e-11,2.54e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 -25090000,0.983,-0.0106,-0.0122,0.185,0.044,-0.0578,0.0452,0.182,-0.117,-3.52,-1.48e-05,-5.83e-05,2.02e-06,7.19e-06,5.04e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.32e-06,7.94e-05,7.94e-05,6.25e-05,0.0154,0.0154,0.00801,0.0426,0.0426,0.0353,5.13e-11,5.13e-11,2.5e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 -25190000,0.983,-0.0108,-0.012,0.185,0.039,-0.0512,0.045,0.182,-0.109,-3.52,-1.5e-05,-5.83e-05,1.92e-06,4.72e-06,4.44e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.31e-06,7.94e-05,7.94e-05,6.21e-05,0.0143,0.0143,0.00794,0.0386,0.0386,0.0351,4.96e-11,4.96e-11,2.47e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 -25290000,0.983,-0.0109,-0.0114,0.185,0.0342,-0.0525,0.0397,0.186,-0.114,-3.52,-1.5e-05,-5.83e-05,1.75e-06,4.92e-06,4.43e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.3e-06,7.96e-05,7.96e-05,6.19e-05,0.0153,0.0153,0.00802,0.0424,0.0424,0.0355,4.97e-11,4.97e-11,2.43e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 -25390000,0.983,-0.011,-0.0112,0.185,0.0259,-0.0454,0.038,0.181,-0.103,-3.52,-1.52e-05,-5.83e-05,1.75e-06,3.62e-06,3.59e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.29e-06,7.96e-05,7.96e-05,6.16e-05,0.0142,0.0142,0.00796,0.0385,0.0385,0.0352,4.82e-11,4.82e-11,2.4e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 -25490000,0.983,-0.011,-0.0109,0.185,0.0208,-0.0451,0.0372,0.184,-0.108,-3.52,-1.52e-05,-5.83e-05,1.67e-06,3.74e-06,3.59e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.27e-06,7.98e-05,7.98e-05,6.12e-05,0.0152,0.0152,0.008,0.0423,0.0423,0.0353,4.83e-11,4.83e-11,2.36e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 -25590000,0.983,-0.0112,-0.0107,0.185,0.0155,-0.041,0.0381,0.18,-0.0992,-3.52,-1.54e-05,-5.83e-05,1.57e-06,2.86e-06,3.18e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.27e-06,7.99e-05,7.98e-05,6.1e-05,0.0141,0.0141,0.00798,0.0384,0.0384,0.0353,4.69e-11,4.69e-11,2.33e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -25690000,0.983,-0.0106,-0.0103,0.185,0.0146,-0.0401,0.0272,0.181,-0.103,-3.52,-1.54e-05,-5.83e-05,1.57e-06,2.97e-06,3.18e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.25e-06,8.01e-05,8e-05,6.07e-05,0.0151,0.0151,0.00802,0.0422,0.0422,0.0354,4.7e-11,4.7e-11,2.3e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -25790000,0.983,-0.0104,-0.00964,0.185,0.00354,-0.0318,0.0264,0.174,-0.0936,-3.52,-1.56e-05,-5.83e-05,1.52e-06,2.48e-06,2.62e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.24e-06,8.01e-05,8e-05,6.04e-05,0.014,0.014,0.00796,0.0383,0.0383,0.0351,4.56e-11,4.56e-11,2.26e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -25890000,0.983,-0.0105,-0.00973,0.186,-0.00218,-0.0296,0.0287,0.174,-0.0966,-3.52,-1.56e-05,-5.83e-05,1.31e-06,2.74e-06,2.61e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.23e-06,8.03e-05,8.02e-05,6.02e-05,0.015,0.015,0.00804,0.0421,0.0421,0.0355,4.57e-11,4.57e-11,2.23e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -25990000,0.983,-0.0105,-0.00983,0.186,-0.0112,-0.0228,0.0219,0.163,-0.087,-3.51,-1.57e-05,-5.83e-05,1.24e-06,4.85e-06,2.08e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.22e-06,8.03e-05,8.03e-05,5.99e-05,0.0139,0.0139,0.00798,0.0382,0.0382,0.0353,4.44e-11,4.44e-11,2.2e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -26090000,0.983,-0.0102,-0.00982,0.185,-0.0164,-0.0226,0.0204,0.162,-0.0893,-3.51,-1.57e-05,-5.83e-05,1.33e-06,4.87e-06,2.08e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.21e-06,8.05e-05,8.05e-05,5.95e-05,0.0149,0.0149,0.00802,0.042,0.042,0.0353,4.45e-11,4.45e-11,2.17e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -26190000,0.983,-0.0101,-0.0103,0.185,-0.0229,-0.0159,0.0153,0.151,-0.0821,-3.52,-1.58e-05,-5.83e-05,1.38e-06,5.44e-06,1.82e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.2e-06,8.05e-05,8.05e-05,5.92e-05,0.0138,0.0138,0.00795,0.0382,0.0382,0.0351,4.33e-11,4.33e-11,2.14e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -26290000,0.983,-0.0101,-0.0106,0.185,-0.0244,-0.0146,0.00942,0.149,-0.0836,-3.52,-1.58e-05,-5.83e-05,1.25e-06,5.63e-06,1.8e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.19e-06,8.07e-05,8.07e-05,5.9e-05,0.0148,0.0148,0.00804,0.0419,0.0419,0.0354,4.34e-11,4.34e-11,2.11e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -26390000,0.983,-0.00953,-0.0105,0.185,-0.0305,-0.0074,0.0132,0.136,-0.0754,-3.52,-1.59e-05,-5.84e-05,1.13e-06,8.09e-06,1.47e-05,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.18e-06,8.07e-05,8.07e-05,5.87e-05,0.0138,0.0138,0.00797,0.0381,0.0381,0.0352,4.22e-11,4.22e-11,2.08e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -26490000,0.983,-0.00929,-0.0104,0.185,-0.0337,-0.0043,0.0226,0.132,-0.076,-3.52,-1.59e-05,-5.84e-05,1.06e-06,8.08e-06,1.47e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.16e-06,8.09e-05,8.09e-05,5.84e-05,0.0147,0.0147,0.00802,0.0418,0.0418,0.0352,4.23e-11,4.23e-11,2.05e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -26590000,0.983,-0.00873,-0.0107,0.185,-0.0353,0.00373,0.0223,0.122,-0.0688,-3.52,-1.59e-05,-5.84e-05,9.39e-07,9.01e-06,1.21e-05,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.16e-06,8.09e-05,8.09e-05,5.82e-05,0.0137,0.0137,0.00799,0.038,0.038,0.0353,4.12e-11,4.12e-11,2.03e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -26690000,0.983,-0.00859,-0.0104,0.185,-0.0372,0.00877,0.0206,0.118,-0.0682,-3.51,-1.59e-05,-5.84e-05,7.41e-07,9.23e-06,1.19e-05,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.14e-06,8.11e-05,8.1e-05,5.79e-05,0.0147,0.0147,0.00803,0.0417,0.0417,0.0354,4.13e-11,4.13e-11,2e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 -26790000,0.983,-0.00838,-0.00984,0.185,-0.0446,0.0124,0.0196,0.106,-0.0626,-3.52,-1.6e-05,-5.84e-05,6.44e-07,1.13e-05,9.99e-06,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.13e-06,8.11e-05,8.1e-05,5.76e-05,0.0136,0.0136,0.00797,0.0379,0.0379,0.0351,4.03e-11,4.03e-11,1.97e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -26890000,0.983,-0.00773,-0.00999,0.185,-0.0503,0.0156,0.0146,0.101,-0.0612,-3.52,-1.6e-05,-5.84e-05,6.87e-07,1.14e-05,9.89e-06,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.12e-06,8.13e-05,8.12e-05,5.75e-05,0.0146,0.0146,0.00805,0.0416,0.0416,0.0355,4.04e-11,4.04e-11,1.95e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -26990000,0.983,-0.0072,-0.0104,0.185,-0.0573,0.0223,0.0135,0.0885,-0.055,-3.52,-1.6e-05,-5.85e-05,6.04e-07,1.32e-05,7.44e-06,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.11e-06,8.12e-05,8.12e-05,5.72e-05,0.0135,0.0135,0.00799,0.0379,0.0379,0.0352,3.94e-11,3.94e-11,1.92e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27090000,0.983,-0.00705,-0.0107,0.185,-0.0595,0.0293,0.016,0.0826,-0.0524,-3.53,-1.6e-05,-5.85e-05,5.44e-07,1.36e-05,6.75e-06,-0.0012,0.204,0.002,0.435,0,0,0,0,0,2.1e-06,8.14e-05,8.14e-05,5.69e-05,0.0145,0.0145,0.00803,0.0415,0.0415,0.0353,3.95e-11,3.95e-11,1.89e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27190000,0.983,-0.00708,-0.0106,0.185,-0.0658,0.0348,0.0177,0.0717,-0.0462,-3.53,-1.59e-05,-5.85e-05,4.77e-07,1.45e-05,5.23e-06,-0.0012,0.204,0.002,0.435,0,0,0,0,0,2.1e-06,8.14e-05,8.13e-05,5.67e-05,0.0135,0.0135,0.008,0.0378,0.0378,0.0354,3.85e-11,3.85e-11,1.87e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27290000,0.983,-0.00726,-0.0116,0.185,-0.0722,0.0407,0.131,0.0648,-0.0424,-3.53,-1.59e-05,-5.85e-05,4.35e-07,1.47e-05,4.86e-06,-0.0012,0.204,0.002,0.435,0,0,0,0,0,2.09e-06,8.16e-05,8.15e-05,5.64e-05,0.0143,0.0143,0.00805,0.0414,0.0414,0.0354,3.86e-11,3.86e-11,1.85e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27390000,0.983,-0.00864,-0.0141,0.185,-0.077,0.0466,0.454,0.0553,-0.0352,-3.51,-1.59e-05,-5.84e-05,3.9e-07,1.47e-05,2.42e-06,-0.0012,0.204,0.002,0.435,0,0,0,0,0,2.08e-06,8.15e-05,8.15e-05,5.61e-05,0.0131,0.0131,0.00798,0.0377,0.0377,0.0352,3.77e-11,3.77e-11,1.82e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27490000,0.982,-0.00999,-0.016,0.185,-0.0798,0.052,0.765,0.0474,-0.0302,-3.45,-1.59e-05,-5.84e-05,2.16e-07,1.44e-05,2.29e-06,-0.00119,0.204,0.002,0.435,0,0,0,0,0,2.08e-06,8.17e-05,8.17e-05,5.59e-05,0.0139,0.0139,0.00802,0.0413,0.0413,0.0352,3.78e-11,3.78e-11,1.8e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27590000,0.983,-0.00986,-0.0148,0.185,-0.0737,0.0545,0.859,0.039,-0.026,-3.38,-1.59e-05,-5.84e-05,1.84e-07,1.35e-05,2.34e-06,-0.00118,0.204,0.002,0.435,0,0,0,0,0,2.07e-06,8.18e-05,8.17e-05,5.57e-05,0.0129,0.0129,0.008,0.0376,0.0376,0.0353,3.7e-11,3.7e-11,1.78e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27690000,0.983,-0.00864,-0.0119,0.185,-0.0706,0.0511,0.762,0.0319,-0.0207,-3.3,-1.59e-05,-5.84e-05,1.73e-07,1.4e-05,1.37e-06,-0.00118,0.204,0.002,0.435,0,0,0,0,0,2.05e-06,8.2e-05,8.19e-05,5.54e-05,0.0138,0.0138,0.00804,0.0412,0.0412,0.0354,3.71e-11,3.71e-11,1.75e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27790000,0.983,-0.00731,-0.0104,0.185,-0.0699,0.0489,0.755,0.0257,-0.0181,-3.23,-1.58e-05,-5.84e-05,1.73e-07,1.15e-05,7.75e-06,-0.00118,0.204,0.002,0.435,0,0,0,0,0,2.04e-06,8.2e-05,8.2e-05,5.52e-05,0.0129,0.0129,0.00797,0.0375,0.0375,0.0351,3.64e-11,3.64e-11,1.73e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27890000,0.983,-0.00694,-0.0105,0.185,-0.0769,0.0559,0.794,0.0183,-0.0129,-3.16,-1.58e-05,-5.84e-05,1.38e-07,1.17e-05,7.22e-06,-0.00118,0.204,0.002,0.435,0,0,0,0,0,2.03e-06,8.22e-05,8.22e-05,5.5e-05,0.0138,0.0138,0.00806,0.0411,0.0411,0.0355,3.65e-11,3.65e-11,1.71e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 -27990000,0.983,-0.00739,-0.0109,0.185,-0.0772,0.0574,0.781,0.0129,-0.0111,-3.09,-1.57e-05,-5.83e-05,9.79e-08,9.43e-06,1.12e-05,-0.00117,0.204,0.002,0.435,0,0,0,0,0,2.02e-06,8.23e-05,8.22e-05,5.47e-05,0.0128,0.0128,0.00799,0.0375,0.0375,0.0352,3.58e-11,3.57e-11,1.69e-10,2.83e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -28090000,0.983,-0.00766,-0.0109,0.185,-0.0808,0.0581,0.787,0.00504,-0.00526,-3.01,-1.57e-05,-5.83e-05,1.94e-07,9.44e-06,1.11e-05,-0.00117,0.204,0.002,0.435,0,0,0,0,0,2.01e-06,8.25e-05,8.24e-05,5.45e-05,0.0137,0.0137,0.00803,0.041,0.041,0.0353,3.58e-11,3.58e-11,1.67e-10,2.83e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -28190000,0.983,-0.00709,-0.0111,0.185,-0.0814,0.0547,0.793,-0.00163,-0.0047,-2.93,-1.56e-05,-5.83e-05,1.52e-07,8.33e-06,1.53e-05,-0.00117,0.204,0.002,0.435,0,0,0,0,0,2.01e-06,8.25e-05,8.25e-05,5.43e-05,0.0128,0.0128,0.008,0.0374,0.0374,0.0354,3.52e-11,3.52e-11,1.65e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -28290000,0.983,-0.00659,-0.0114,0.185,-0.0867,0.0582,0.792,-0.01,0.000996,-2.86,-1.56e-05,-5.83e-05,2.31e-07,8.84e-06,1.43e-05,-0.00116,0.204,0.002,0.435,0,0,0,0,0,2e-06,8.27e-05,8.27e-05,5.41e-05,0.0137,0.0137,0.00804,0.0409,0.0409,0.0354,3.53e-11,3.53e-11,1.63e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -28390000,0.983,-0.00659,-0.012,0.185,-0.0872,0.061,0.793,-0.0148,0.00405,-2.79,-1.55e-05,-5.82e-05,2.77e-07,6.86e-06,1.6e-05,-0.00116,0.204,0.002,0.435,0,0,0,0,0,1.99e-06,8.28e-05,8.27e-05,5.38e-05,0.0127,0.0127,0.00798,0.0373,0.0373,0.0352,3.46e-11,3.46e-11,1.61e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -28490000,0.983,-0.0069,-0.0125,0.185,-0.0889,0.0651,0.793,-0.0235,0.0103,-2.71,-1.55e-05,-5.82e-05,2.39e-07,7.19e-06,1.5e-05,-0.00116,0.204,0.002,0.435,0,0,0,0,0,1.99e-06,8.3e-05,8.29e-05,5.37e-05,0.0136,0.0136,0.00806,0.0408,0.0408,0.0355,3.47e-11,3.47e-11,1.59e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -28590000,0.983,-0.00693,-0.0125,0.185,-0.0823,0.0602,0.791,-0.0269,0.00815,-2.64,-1.53e-05,-5.82e-05,2.79e-07,6.12e-06,1.87e-05,-0.00116,0.204,0.002,0.435,0,0,0,0,0,1.98e-06,8.3e-05,8.29e-05,5.34e-05,0.0127,0.0127,0.00799,0.0372,0.0372,0.0353,3.4e-11,3.4e-11,1.57e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -28690000,0.983,-0.0067,-0.0118,0.185,-0.0826,0.0612,0.791,-0.0352,0.0142,-2.57,-1.53e-05,-5.82e-05,2.18e-07,6.4e-06,1.78e-05,-0.00115,0.204,0.002,0.435,0,0,0,0,0,1.97e-06,8.32e-05,8.31e-05,5.31e-05,0.0136,0.0136,0.00803,0.0407,0.0407,0.0353,3.41e-11,3.41e-11,1.55e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -28790000,0.983,-0.00603,-0.0116,0.185,-0.0792,0.0612,0.789,-0.0377,0.0161,-2.49,-1.52e-05,-5.81e-05,2.89e-07,5.68e-06,1.78e-05,-0.00115,0.204,0.002,0.435,0,0,0,0,0,1.96e-06,8.32e-05,8.31e-05,5.29e-05,0.0127,0.0127,0.00796,0.0372,0.0372,0.0351,3.35e-11,3.35e-11,1.53e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -28890000,0.983,-0.00587,-0.0114,0.185,-0.0835,0.0633,0.787,-0.0458,0.0223,-2.42,-1.52e-05,-5.81e-05,3.55e-07,6.13e-06,1.68e-05,-0.00115,0.204,0.002,0.435,0,0,0,0,0,1.95e-06,8.34e-05,8.33e-05,5.28e-05,0.0136,0.0135,0.00804,0.0407,0.0407,0.0355,3.36e-11,3.36e-11,1.51e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -28990000,0.983,-0.00564,-0.0116,0.185,-0.0794,0.06,0.786,-0.0453,0.0215,-2.35,-1.51e-05,-5.8e-05,3.25e-07,5.44e-06,1.67e-05,-0.00114,0.204,0.002,0.435,0,0,0,0,0,1.95e-06,8.33e-05,8.33e-05,5.25e-05,0.0126,0.0126,0.00798,0.0371,0.0371,0.0352,3.3e-11,3.3e-11,1.5e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29090000,0.983,-0.00549,-0.0116,0.185,-0.0822,0.0623,0.785,-0.0534,0.0276,-2.27,-1.51e-05,-5.8e-05,3.18e-07,5.66e-06,1.61e-05,-0.00114,0.204,0.002,0.435,0,0,0,0,0,1.94e-06,8.35e-05,8.35e-05,5.23e-05,0.0135,0.0135,0.00802,0.0406,0.0406,0.0353,3.31e-11,3.31e-11,1.48e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29190000,0.983,-0.00544,-0.0118,0.185,-0.0785,0.0609,0.78,-0.0512,0.0269,-2.2,-1.49e-05,-5.8e-05,3.83e-07,5.57e-06,1.5e-05,-0.00114,0.204,0.002,0.435,0,0,0,0,0,1.94e-06,8.35e-05,8.35e-05,5.21e-05,0.0126,0.0126,0.00799,0.0371,0.0371,0.0353,3.25e-11,3.25e-11,1.46e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29290000,0.983,-0.00571,-0.0118,0.185,-0.0806,0.0669,0.782,-0.0591,0.0333,-2.13,-1.49e-05,-5.8e-05,4.01e-07,5.74e-06,1.46e-05,-0.00114,0.204,0.002,0.435,0,0,0,0,0,1.93e-06,8.37e-05,8.36e-05,5.19e-05,0.0135,0.0135,0.00803,0.0405,0.0405,0.0354,3.26e-11,3.26e-11,1.44e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29390000,0.983,-0.00615,-0.0113,0.185,-0.076,0.0653,0.784,-0.0574,0.0342,-2.05,-1.48e-05,-5.79e-05,4.42e-07,5.65e-06,1.37e-05,-0.00113,0.204,0.002,0.435,0,0,0,0,0,1.92e-06,8.36e-05,8.36e-05,5.16e-05,0.0126,0.0126,0.00796,0.037,0.037,0.0352,3.21e-11,3.21e-11,1.43e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29490000,0.983,-0.00615,-0.0112,0.185,-0.0788,0.0661,0.784,-0.0651,0.0408,-1.98,-1.48e-05,-5.79e-05,5.52e-07,5.98e-06,1.31e-05,-0.00113,0.204,0.002,0.435,0,0,0,0,0,1.92e-06,8.38e-05,8.38e-05,5.15e-05,0.0135,0.0135,0.00804,0.0405,0.0405,0.0355,3.22e-11,3.22e-11,1.41e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29590000,0.983,-0.00606,-0.0112,0.185,-0.0743,0.0638,0.786,-0.0625,0.0399,-1.9,-1.47e-05,-5.78e-05,6.57e-07,6.34e-06,1.16e-05,-0.00113,0.204,0.002,0.435,0,0,0,0,0,1.91e-06,8.37e-05,8.37e-05,5.13e-05,0.0126,0.0126,0.00797,0.037,0.037,0.0353,3.16e-11,3.17e-11,1.4e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29690000,0.983,-0.0061,-0.011,0.185,-0.0787,0.0627,0.78,-0.0702,0.0463,-1.83,-1.47e-05,-5.78e-05,7.5e-07,6.9e-06,1.03e-05,-0.00113,0.204,0.002,0.435,0,0,0,0,0,1.9e-06,8.39e-05,8.39e-05,5.1e-05,0.0135,0.0135,0.00802,0.0405,0.0405,0.0353,3.17e-11,3.18e-11,1.38e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29790000,0.983,-0.00593,-0.0115,0.185,-0.0744,0.056,0.777,-0.0654,0.0435,-1.75,-1.45e-05,-5.77e-05,8.46e-07,7.93e-06,8.26e-06,-0.00113,0.204,0.002,0.435,0,0,0,0,0,1.9e-06,8.38e-05,8.37e-05,5.09e-05,0.0126,0.0126,0.00799,0.037,0.037,0.0354,3.12e-11,3.12e-11,1.37e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29890000,0.983,-0.00541,-0.0119,0.185,-0.0752,0.0573,0.773,-0.0728,0.0491,-1.68,-1.45e-05,-5.77e-05,9.32e-07,8.6e-06,6.76e-06,-0.00112,0.204,0.002,0.435,0,0,0,0,0,1.89e-06,8.39e-05,8.39e-05,5.07e-05,0.0135,0.0135,0.00803,0.0404,0.0404,0.0354,3.13e-11,3.13e-11,1.35e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -29990000,0.983,-0.00558,-0.0119,0.185,-0.0697,0.0522,0.769,-0.0683,0.0444,-1.61,-1.44e-05,-5.76e-05,9.44e-07,9.85e-06,2.99e-06,-0.00112,0.204,0.002,0.435,0,0,0,0,0,1.88e-06,8.38e-05,8.38e-05,5.05e-05,0.0126,0.0126,0.00796,0.0369,0.0369,0.0352,3.08e-11,3.08e-11,1.33e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -30090000,0.983,-0.0057,-0.012,0.185,-0.0703,0.0531,0.767,-0.0754,0.0497,-1.54,-1.44e-05,-5.76e-05,7.95e-07,9.96e-06,2.53e-06,-0.00112,0.204,0.002,0.435,0,0,0,0,0,1.87e-06,8.4e-05,8.4e-05,5.02e-05,0.0134,0.0134,0.008,0.0404,0.0404,0.0352,3.09e-11,3.09e-11,1.32e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -30190000,0.983,-0.00568,-0.0121,0.185,-0.0642,0.0498,0.767,-0.0687,0.0478,-1.47,-1.43e-05,-5.75e-05,6.75e-07,1.16e-05,5.47e-07,-0.00111,0.204,0.002,0.435,0,0,0,0,0,1.87e-06,8.38e-05,8.38e-05,5.01e-05,0.0125,0.0125,0.00797,0.0369,0.0369,0.0353,3.04e-11,3.04e-11,1.31e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -30290000,0.983,-0.00569,-0.0121,0.186,-0.0633,0.0501,0.765,-0.0751,0.0528,-1.4,-1.43e-05,-5.75e-05,6.95e-07,1.23e-05,-9.32e-07,-0.00111,0.204,0.002,0.435,0,0,0,0,0,1.87e-06,8.4e-05,8.4e-05,4.99e-05,0.0134,0.0134,0.00801,0.0403,0.0403,0.0354,3.05e-11,3.05e-11,1.29e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 -30390000,0.983,-0.0057,-0.012,0.186,-0.0561,0.0444,0.762,-0.0669,0.0495,-1.34,-1.42e-05,-5.74e-05,8.32e-07,1.57e-05,-5.32e-06,-0.00111,0.204,0.002,0.435,0,0,0,0,0,1.86e-06,8.37e-05,8.37e-05,4.97e-05,0.0125,0.0125,0.00794,0.0369,0.0369,0.0351,3e-11,3.01e-11,1.28e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -30490000,0.983,-0.0057,-0.0121,0.185,-0.059,0.0445,0.764,-0.0726,0.0539,-1.26,-1.42e-05,-5.74e-05,9.16e-07,1.61e-05,-5.99e-06,-0.0011,0.204,0.002,0.435,0,0,0,0,0,1.86e-06,8.39e-05,8.39e-05,4.96e-05,0.0134,0.0134,0.00803,0.0403,0.0403,0.0355,3.01e-11,3.02e-11,1.27e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -30590000,0.983,-0.00603,-0.0124,0.185,-0.0545,0.0413,0.763,-0.0655,0.0498,-1.19,-1.4e-05,-5.73e-05,1.02e-06,1.89e-05,-1e-05,-0.0011,0.204,0.002,0.435,0,0,0,0,0,1.85e-06,8.37e-05,8.37e-05,4.93e-05,0.0125,0.0125,0.00796,0.0369,0.0369,0.0352,2.97e-11,2.97e-11,1.25e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -30690000,0.983,-0.0064,-0.0126,0.185,-0.0525,0.0403,0.762,-0.0709,0.0539,-1.12,-1.4e-05,-5.73e-05,1.03e-06,1.94e-05,-1.1e-05,-0.0011,0.204,0.002,0.435,0,0,0,0,0,1.84e-06,8.39e-05,8.39e-05,4.91e-05,0.0134,0.0134,0.008,0.0403,0.0403,0.0353,2.98e-11,2.98e-11,1.24e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -30790000,0.983,-0.0061,-0.0123,0.185,-0.0455,0.0348,0.76,-0.0636,0.0524,-1.05,-1.4e-05,-5.73e-05,1.04e-06,2.23e-05,-1.26e-05,-0.00109,0.204,0.002,0.435,0,0,0,0,0,1.83e-06,8.36e-05,8.36e-05,4.9e-05,0.0125,0.0125,0.00797,0.0368,0.0368,0.0354,2.93e-11,2.93e-11,1.23e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -30890000,0.983,-0.00546,-0.0122,0.185,-0.0458,0.0318,0.756,-0.0681,0.0557,-0.982,-1.4e-05,-5.73e-05,9.59e-07,2.26e-05,-1.32e-05,-0.00109,0.204,0.002,0.435,0,0,0,0,0,1.83e-06,8.38e-05,8.38e-05,4.88e-05,0.0134,0.0134,0.00801,0.0403,0.0403,0.0354,2.94e-11,2.94e-11,1.21e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -30990000,0.983,-0.00565,-0.0121,0.185,-0.0382,0.0263,0.757,-0.058,0.0486,-0.913,-1.38e-05,-5.72e-05,9.52e-07,2.58e-05,-1.81e-05,-0.00109,0.204,0.002,0.435,0,0,0,0,0,1.82e-06,8.35e-05,8.35e-05,4.86e-05,0.0125,0.0125,0.00794,0.0368,0.0368,0.0352,2.9e-11,2.9e-11,1.2e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -31090000,0.983,-0.00579,-0.0122,0.186,-0.0372,0.0254,0.756,-0.0617,0.0511,-0.84,-1.38e-05,-5.72e-05,8.99e-07,2.59e-05,-1.83e-05,-0.00109,0.204,0.002,0.435,0,0,0,0,0,1.82e-06,8.37e-05,8.37e-05,4.85e-05,0.0133,0.0133,0.00803,0.0402,0.0402,0.0355,2.91e-11,2.91e-11,1.19e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -31190000,0.983,-0.00598,-0.0123,0.185,-0.0325,0.0206,0.758,-0.0532,0.046,-0.771,-1.38e-05,-5.71e-05,1.04e-06,2.9e-05,-2.19e-05,-0.00108,0.204,0.002,0.435,0,0,0,0,0,1.81e-06,8.34e-05,8.34e-05,4.83e-05,0.0125,0.0125,0.00796,0.0368,0.0368,0.0353,2.87e-11,2.87e-11,1.18e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -31290000,0.983,-0.00621,-0.0124,0.185,-0.0302,0.018,0.761,-0.0562,0.048,-0.701,-1.38e-05,-5.71e-05,1.12e-06,2.95e-05,-2.26e-05,-0.00108,0.204,0.002,0.435,0,0,0,0,0,1.81e-06,8.35e-05,8.35e-05,4.81e-05,0.0133,0.0133,0.008,0.0402,0.0402,0.0353,2.88e-11,2.88e-11,1.16e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -31390000,0.983,-0.00599,-0.0122,0.185,-0.0241,0.0119,0.76,-0.0473,0.0422,-0.628,-1.37e-05,-5.71e-05,1.04e-06,3.15e-05,-2.51e-05,-0.00108,0.204,0.002,0.435,0,0,0,0,0,1.8e-06,8.32e-05,8.32e-05,4.79e-05,0.0124,0.0124,0.00793,0.0368,0.0368,0.0351,2.84e-11,2.84e-11,1.15e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -31490000,0.983,-0.00572,-0.0126,0.186,-0.0242,0.0091,0.757,-0.0498,0.0432,-0.555,-1.37e-05,-5.71e-05,1.02e-06,3.17e-05,-2.54e-05,-0.00108,0.204,0.002,0.435,0,0,0,0,0,1.8e-06,8.34e-05,8.34e-05,4.78e-05,0.0133,0.0133,0.00801,0.0402,0.0402,0.0354,2.85e-11,2.85e-11,1.14e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -31590000,0.983,-0.00559,-0.013,0.185,-0.0201,0.00687,0.761,-0.0387,0.0388,-0.484,-1.36e-05,-5.7e-05,1.11e-06,3.58e-05,-2.77e-05,-0.00108,0.204,0.002,0.435,0,0,0,0,0,1.79e-06,8.3e-05,8.3e-05,4.76e-05,0.0124,0.0124,0.00794,0.0367,0.0367,0.0352,2.81e-11,2.81e-11,1.13e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -31690000,0.983,-0.00558,-0.0135,0.185,-0.0222,0.0058,0.757,-0.0409,0.0394,-0.415,-1.36e-05,-5.7e-05,1.22e-06,3.65e-05,-2.85e-05,-0.00107,0.204,0.002,0.435,0,0,0,0,0,1.78e-06,8.32e-05,8.32e-05,4.74e-05,0.0133,0.0133,0.00799,0.0402,0.0402,0.0352,2.82e-11,2.82e-11,1.12e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -31790000,0.983,-0.0058,-0.0141,0.185,-0.013,0.00322,0.757,-0.0293,0.0375,-0.343,-1.36e-05,-5.69e-05,1.29e-06,4.17e-05,-2.85e-05,-0.00107,0.204,0.002,0.435,0,0,0,0,0,1.78e-06,8.28e-05,8.28e-05,4.73e-05,0.0124,0.0124,0.00796,0.0367,0.0367,0.0353,2.78e-11,2.78e-11,1.11e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -31890000,0.983,-0.00552,-0.0139,0.185,-0.00988,0.000947,0.754,-0.0304,0.0377,-0.276,-1.36e-05,-5.69e-05,1.35e-06,4.23e-05,-2.91e-05,-0.00107,0.204,0.002,0.435,0,0,0,0,0,1.77e-06,8.3e-05,8.3e-05,4.71e-05,0.0132,0.0132,0.008,0.0401,0.0401,0.0354,2.79e-11,2.79e-11,1.1e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 -31990000,0.983,-0.00579,-0.0135,0.185,-0.00191,0.00028,0.751,-0.0184,0.0346,-0.21,-1.36e-05,-5.68e-05,1.3e-06,4.69e-05,-3e-05,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.77e-06,8.26e-05,8.26e-05,4.69e-05,0.0123,0.0124,0.00793,0.0367,0.0367,0.0351,2.75e-11,2.75e-11,1.08e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -32090000,0.983,-0.00616,-0.0131,0.185,-0.00253,-0.00312,0.753,-0.0186,0.0345,-0.14,-1.36e-05,-5.68e-05,1.31e-06,4.72e-05,-3.02e-05,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.76e-06,8.28e-05,8.28e-05,4.68e-05,0.0132,0.0132,0.00802,0.0401,0.0401,0.0355,2.76e-11,2.76e-11,1.08e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -32190000,0.983,-0.00634,-0.0134,0.185,0.00288,-0.00634,0.752,-0.00731,0.0331,-0.073,-1.36e-05,-5.67e-05,1.28e-06,5.14e-05,-2.87e-05,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.75e-06,8.24e-05,8.24e-05,4.66e-05,0.0123,0.0123,0.00795,0.0367,0.0367,0.0352,2.73e-11,2.73e-11,1.06e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -32290000,0.983,-0.00625,-0.0136,0.185,0.00439,-0.00903,0.75,-0.00699,0.0322,-0.00506,-1.36e-05,-5.67e-05,1.34e-06,5.2e-05,-2.9e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.75e-06,8.26e-05,8.26e-05,4.64e-05,0.0132,0.0132,0.00799,0.0401,0.0401,0.0353,2.74e-11,2.74e-11,1.05e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -32390000,0.983,-0.00636,-0.0138,0.185,0.0107,-0.0103,0.75,0.0044,0.0297,0.0689,-1.35e-05,-5.67e-05,1.31e-06,5.51e-05,-2.8e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.75e-06,8.22e-05,8.22e-05,4.63e-05,0.0123,0.0123,0.00796,0.0367,0.0367,0.0354,2.7e-11,2.7e-11,1.04e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -32490000,0.983,-0.00921,-0.0117,0.185,0.0354,-0.0731,-0.123,0.00728,0.0235,0.0719,-1.35e-05,-5.67e-05,1.27e-06,5.51e-05,-2.79e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.73e-06,8.24e-05,8.24e-05,4.61e-05,0.0152,0.0152,0.00784,0.0401,0.0401,0.0354,2.71e-11,2.71e-11,1.03e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -32590000,0.983,-0.00915,-0.0116,0.185,0.0358,-0.0742,-0.126,0.0195,0.0198,0.0522,-1.36e-05,-5.66e-05,1.35e-06,5.51e-05,-2.79e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.73e-06,8.11e-05,8.11e-05,4.59e-05,0.0156,0.0156,0.00754,0.0368,0.0368,0.0351,2.67e-11,2.67e-11,1.02e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -32690000,0.983,-0.00913,-0.0115,0.185,0.0315,-0.0798,-0.128,0.0229,0.0121,0.0366,-1.36e-05,-5.66e-05,1.34e-06,5.51e-05,-2.79e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.72e-06,8.13e-05,8.13e-05,4.57e-05,0.0186,0.0187,0.00736,0.0404,0.0404,0.0351,2.68e-11,2.68e-11,1.01e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -32790000,0.983,-0.00882,-0.0116,0.185,0.0301,-0.0774,-0.129,0.0327,0.0102,0.0208,-1.37e-05,-5.66e-05,1.42e-06,5.51e-05,-2.79e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.72e-06,7.86e-05,7.86e-05,4.57e-05,0.0195,0.0195,0.00713,0.037,0.037,0.0351,2.64e-11,2.64e-11,1.01e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -32890000,0.983,-0.00878,-0.0116,0.185,0.0297,-0.0832,-0.13,0.0357,0.00215,0.00492,-1.37e-05,-5.66e-05,1.45e-06,5.51e-05,-2.79e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.71e-06,7.87e-05,7.87e-05,4.55e-05,0.0235,0.0235,0.00696,0.0408,0.0408,0.035,2.65e-11,2.65e-11,9.97e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -32990000,0.983,-0.00851,-0.0116,0.185,0.0271,-0.0792,-0.129,0.0436,-0.00104,-0.00827,-1.37e-05,-5.65e-05,1.54e-06,5.51e-05,-2.79e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.7e-06,7.43e-05,7.43e-05,4.53e-05,0.0243,0.0243,0.00672,0.0374,0.0374,0.0347,2.61e-11,2.61e-11,9.87e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -33090000,0.983,-0.00847,-0.0116,0.185,0.023,-0.083,-0.126,0.0462,-0.00913,-0.0158,-1.37e-05,-5.65e-05,1.52e-06,5.51e-05,-2.79e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.7e-06,7.44e-05,7.45e-05,4.52e-05,0.029,0.029,0.00661,0.0416,0.0416,0.0349,2.62e-11,2.62e-11,9.79e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -33190000,0.983,-0.00816,-0.0115,0.185,0.0192,-0.0785,-0.125,0.0524,-0.011,-0.0223,-1.38e-05,-5.65e-05,1.47e-06,5.49e-05,-3.18e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.69e-06,6.85e-05,6.85e-05,4.5e-05,0.0295,0.0295,0.0064,0.038,0.038,0.0345,2.59e-11,2.59e-11,9.7e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -33290000,0.983,-0.0082,-0.0115,0.185,0.016,-0.0798,-0.124,0.0541,-0.0189,-0.0302,-1.38e-05,-5.65e-05,1.57e-06,5.49e-05,-3.18e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.69e-06,6.86e-05,6.86e-05,4.49e-05,0.0356,0.0356,0.00629,0.0426,0.0426,0.0344,2.6e-11,2.6e-11,9.61e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 -33390000,0.983,-0.00775,-0.0116,0.185,0.0115,-0.0656,-0.122,0.0574,-0.0139,-0.0388,-1.39e-05,-5.65e-05,1.58e-06,4.91e-05,-5.51e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.68e-06,6.15e-05,6.15e-05,4.48e-05,0.0356,0.0356,0.00616,0.0389,0.0389,0.0343,2.57e-11,2.57e-11,9.53e-11,2.79e-06,2.78e-06,5e-08,0,0,0,0,0,0,0,0 -33490000,0.983,-0.00773,-0.0115,0.185,0.00702,-0.0665,-0.121,0.0583,-0.0205,-0.0484,-1.39e-05,-5.65e-05,1.59e-06,4.91e-05,-5.51e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.67e-06,6.16e-05,6.16e-05,4.46e-05,0.0427,0.0428,0.00608,0.044,0.044,0.0342,2.58e-11,2.58e-11,9.44e-11,2.79e-06,2.78e-06,5e-08,0,0,0,0,0,0,0,0 -33590000,0.983,-0.00736,-0.0116,0.185,0.00366,-0.0572,-0.117,0.061,-0.0167,-0.0553,-1.4e-05,-5.64e-05,1.64e-06,4.09e-05,-7.99e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.67e-06,5.43e-05,5.43e-05,4.44e-05,0.0412,0.0412,0.00596,0.0399,0.0399,0.0338,2.55e-11,2.55e-11,9.36e-11,2.74e-06,2.74e-06,5e-08,0,0,0,0,0,0,0,0 -33690000,0.983,-0.00736,-0.0116,0.185,-0.00098,-0.0576,-0.118,0.0612,-0.0225,-0.0636,-1.4e-05,-5.64e-05,1.65e-06,4.09e-05,-7.99e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.66e-06,5.44e-05,5.44e-05,4.44e-05,0.0489,0.0489,0.00594,0.0456,0.0456,0.0339,2.56e-11,2.56e-11,9.28e-11,2.74e-06,2.74e-06,5.01e-08,0,0,0,0,0,0,0,0 -33790000,0.983,-0.00712,-0.0116,0.185,-0.00359,-0.0468,-0.112,0.0653,-0.0178,-0.0696,-1.4e-05,-5.64e-05,1.6e-06,2.74e-05,-0.000106,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.66e-06,4.76e-05,4.76e-05,4.42e-05,0.0453,0.0453,0.00585,0.0411,0.0411,0.0335,2.55e-11,2.55e-11,9.2e-11,2.67e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0 -33890000,0.983,-0.00713,-0.0116,0.185,-0.00771,-0.0445,-0.111,0.0646,-0.0224,-0.0761,-1.4e-05,-5.64e-05,1.65e-06,2.72e-05,-0.000106,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.65e-06,4.77e-05,4.77e-05,4.4e-05,0.0531,0.0531,0.00584,0.0472,0.0472,0.0334,2.56e-11,2.56e-11,9.12e-11,2.67e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0 +6790000,0.979,-0.00642,-0.0124,0.204,-0.00677,0.0147,-0.0407,-0.00221,0.00645,-0.0528,-1.72e-05,-5.78e-05,2.51e-07,-2.41e-05,1.67e-05,-0.00127,0.203,0.0106,0.434,0,0,0,0,0,1.36e-05,0.000401,0.000402,0.000309,0.223,0.223,0.0323,0.135,0.135,0.067,9.86e-09,9.87e-09,8.73e-09,3.86e-06,3.86e-06,2.8e-07,0,0,0,0,0,0,0,0 +6890000,0.979,-0.00634,-0.0123,0.204,-0.00645,0.0111,-0.0372,-0.00183,0.00487,-0.0503,-1.67e-05,-5.78e-05,2.39e-07,-2.43e-05,1.63e-05,-0.00128,0.203,0.0106,0.434,0,0,0,0,0,1.35e-05,0.000347,0.000347,0.000307,0.177,0.177,0.0311,0.103,0.103,0.0659,8.06e-09,8.07e-09,8.42e-09,3.86e-06,3.86e-06,2.62e-07,0,0,0,0,0,0,0,0 +6990000,0.979,-0.00629,-0.0123,0.204,-0.00687,0.0118,-0.0357,-0.00253,0.00601,-0.05,-1.67e-05,-5.78e-05,2.39e-07,-2.45e-05,1.63e-05,-0.00129,0.203,0.0106,0.434,0,0,0,0,0,1.34e-05,0.000361,0.000361,0.000304,0.203,0.203,0.0299,0.129,0.129,0.0648,8.06e-09,8.07e-09,8.11e-09,3.86e-06,3.86e-06,2.46e-07,0,0,0,0,0,0,0,0 +7090000,0.982,-0.00648,-0.0121,0.188,-0.00699,0.0135,-0.0363,-0.00209,0.00474,-0.0511,-1.63e-05,-5.78e-05,2.27e-07,-2.45e-05,1.59e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,9.01e-05,0.000313,0.000313,0.00241,0.16,0.16,0.0291,0.0991,0.0991,0.0649,6.62e-09,6.62e-09,7.87e-09,3.86e-06,3.86e-06,2.33e-07,0,0,0,0,0,0,0,0 +7190000,0.982,-0.00644,-0.0122,0.188,-0.00773,0.0148,-0.0354,-0.00286,0.00622,-0.0539,-1.63e-05,-5.78e-05,2.21e-07,-2.46e-05,1.59e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,4.77e-05,0.000313,0.000313,0.00128,0.161,0.161,0.028,0.122,0.122,0.0638,6.62e-09,6.62e-09,7.87e-09,3.86e-06,3.86e-06,2.19e-07,0,0,0,0,0,0,0,0 +7290000,0.982,-0.00642,-0.0122,0.188,-0.00723,0.0182,-0.0328,-0.00366,0.00785,-0.05,-1.63e-05,-5.78e-05,2.43e-07,-2.47e-05,1.6e-05,-0.0013,0.204,0.002,0.435,0,0,0,0,0,3.25e-05,0.000314,0.000314,0.000868,0.166,0.166,0.027,0.148,0.148,0.0628,6.61e-09,6.62e-09,7.87e-09,3.86e-06,3.86e-06,2.06e-07,0,0,0,0,0,0,0,0 +7390000,0.982,-0.0063,-0.0122,0.187,-0.00929,0.0204,-0.0309,-0.00447,0.00984,-0.0478,-1.63e-05,-5.78e-05,2.56e-07,-2.49e-05,1.61e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.54e-05,0.000315,0.000315,0.000679,0.176,0.176,0.0263,0.177,0.177,0.0628,6.61e-09,6.62e-09,7.87e-09,3.86e-06,3.86e-06,1.96e-07,0,0,0,0,0,0,0,0 +7490000,0.982,-0.00631,-0.0122,0.187,-0.00727,0.0226,-0.0254,-0.00525,0.012,-0.0417,-1.63e-05,-5.78e-05,3.4e-07,-2.51e-05,1.63e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.04e-05,0.000316,0.000316,0.000544,0.188,0.188,0.0253,0.21,0.21,0.0618,6.61e-09,6.61e-09,7.87e-09,3.86e-06,3.86e-06,1.85e-07,0,0,0,0,0,0,0,0 +7590000,0.982,-0.00639,-0.0121,0.187,-0.00659,0.0248,-0.0222,-0.00594,0.0143,-0.0368,-1.63e-05,-5.78e-05,3.49e-07,-2.53e-05,1.65e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,1.71e-05,0.000318,0.000318,0.000454,0.205,0.205,0.0244,0.247,0.247,0.0609,6.61e-09,6.61e-09,7.87e-09,3.86e-06,3.86e-06,1.74e-07,0,0,0,0,0,0,0,0 +7690000,0.982,-0.00641,-0.0122,0.187,-0.00726,0.0279,-0.0217,-0.00662,0.0171,-0.0324,-1.63e-05,-5.78e-05,3.28e-07,-2.54e-05,1.66e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,1.49e-05,0.000319,0.000319,0.000397,0.225,0.225,0.0239,0.289,0.289,0.0608,6.61e-09,6.61e-09,7.86e-09,3.86e-06,3.86e-06,1.66e-07,0,0,0,0,0,0,0,0 +7790000,0.982,-0.00629,-0.0122,0.187,-0.006,0.0295,-0.0241,-0.00727,0.0198,-0.0373,-1.63e-05,-5.78e-05,2.73e-07,-2.54e-05,1.65e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,1.31e-05,0.000322,0.000322,0.000348,0.249,0.249,0.023,0.335,0.335,0.0599,6.6e-09,6.6e-09,7.85e-09,3.86e-06,3.86e-06,1.57e-07,0,0,0,0,0,0,0,0 +7890000,0.982,-0.00631,-0.0123,0.187,-0.00769,0.0332,-0.0248,-0.00804,0.0229,-0.0408,-1.63e-05,-5.78e-05,2.44e-07,-2.53e-05,1.65e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,1.17e-05,0.000324,0.000324,0.00031,0.277,0.277,0.0222,0.388,0.388,0.059,6.6e-09,6.6e-09,7.84e-09,3.86e-06,3.86e-06,1.49e-07,0,0,0,0,0,0,0,0 +7990000,0.982,-0.00625,-0.0122,0.187,-0.00776,0.0353,-0.021,-0.00877,0.0262,-0.0377,-1.62e-05,-5.78e-05,2.64e-07,-2.54e-05,1.66e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,1.06e-05,0.000327,0.000327,0.000279,0.308,0.308,0.0215,0.447,0.447,0.0581,6.58e-09,6.59e-09,7.83e-09,3.86e-06,3.86e-06,1.41e-07,0,0,0,0,0,0,0,0 +8090000,0.982,-0.00611,-0.0122,0.187,-0.00664,0.0388,-0.0219,-0.00944,0.0298,-0.04,-1.62e-05,-5.78e-05,2.56e-08,-2.55e-05,1.66e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,9.78e-06,0.00033,0.00033,0.000258,0.343,0.343,0.021,0.515,0.515,0.0581,6.58e-09,6.59e-09,7.82e-09,3.86e-06,3.86e-06,1.34e-07,0,0,0,0,0,0,0,0 +8190000,0.982,-0.00618,-0.0121,0.188,-0.00636,0.0436,-0.0175,-0.01,0.0339,-0.0341,-1.62e-05,-5.78e-05,-1.59e-07,-2.56e-05,1.68e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,9.01e-06,0.000333,0.000333,0.000238,0.381,0.381,0.0203,0.589,0.589,0.0573,6.56e-09,6.57e-09,7.8e-09,3.86e-06,3.86e-06,1.28e-07,0,0,0,0,0,0,0,0 +8290000,0.982,-0.00616,-0.0121,0.188,-0.00454,0.0475,-0.0162,-0.0106,0.0384,-0.034,-1.62e-05,-5.78e-05,-2.01e-07,-2.56e-05,1.68e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,8.38e-06,0.000337,0.000337,0.000221,0.424,0.424,0.0197,0.677,0.677,0.0564,6.56e-09,6.57e-09,7.78e-09,3.86e-06,3.86e-06,1.21e-07,0,0,0,0,0,0,0,0 +8390000,0.982,-0.00611,-0.0121,0.188,-0.00705,0.0487,-0.0153,-0.0111,0.0429,-0.0324,-1.62e-05,-5.78e-05,-2.49e-07,-2.57e-05,1.69e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,7.92e-06,0.000341,0.000341,0.000209,0.469,0.469,0.0193,0.77,0.77,0.0564,6.53e-09,6.54e-09,7.76e-09,3.85e-06,3.85e-06,1.16e-07,0,0,0,0,0,0,0,0 +8490000,0.982,-0.006,-0.0121,0.188,-0.00766,0.0525,-0.0164,-0.0118,0.0479,-0.0371,-1.62e-05,-5.78e-05,-3e-08,-2.56e-05,1.69e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,7.46e-06,0.000345,0.000345,0.000196,0.52,0.52,0.0187,0.882,0.882,0.0556,6.53e-09,6.54e-09,7.73e-09,3.85e-06,3.85e-06,1.1e-07,0,0,0,0,0,0,0,0 +8590000,0.982,-0.00597,-0.0122,0.188,-0.00694,0.0547,-0.0117,-0.0124,0.0528,-0.0323,-1.62e-05,-5.78e-05,-1.38e-07,-2.57e-05,1.71e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,7.07e-06,0.000349,0.000349,0.000186,0.571,0.571,0.0181,0.999,0.999,0.0548,6.5e-09,6.5e-09,7.69e-09,3.85e-06,3.85e-06,1.05e-07,0,0,0,0,0,0,0,0 +8690000,0.982,-0.006,-0.0123,0.187,-0.00735,0.0567,-0.0136,-0.0132,0.0584,-0.0338,-1.62e-05,-5.78e-05,-6.39e-08,-2.57e-05,1.71e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,6.78e-06,0.000354,0.000354,0.000178,0.63,0.63,0.0177,1.14,1.14,0.0548,6.5e-09,6.5e-09,7.66e-09,3.85e-06,3.85e-06,1.01e-07,0,0,0,0,0,0,0,0 +8790000,0.982,-0.00598,-0.0123,0.188,-0.00623,0.0589,-0.0134,-0.0138,0.0634,-0.0311,-1.62e-05,-5.78e-05,-3.03e-07,-2.57e-05,1.74e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,6.48e-06,0.000357,0.000357,0.00017,0.686,0.686,0.0172,1.29,1.29,0.0541,6.46e-09,6.46e-09,7.62e-09,3.85e-06,3.85e-06,9.63e-08,0,0,0,0,0,0,0,0 +8890000,0.982,-0.00602,-0.0123,0.187,-0.00662,0.0621,-0.00913,-0.0144,0.0696,-0.0252,-1.62e-05,-5.78e-05,-3.44e-08,-2.58e-05,1.73e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,6.23e-06,0.000363,0.000363,0.000163,0.752,0.752,0.0167,1.46,1.46,0.0533,6.46e-09,6.46e-09,7.58e-09,3.85e-06,3.85e-06,9.2e-08,0,0,0,0,0,0,0,0 +8990000,0.982,-0.00596,-0.0122,0.187,-0.0078,0.0656,-0.00833,-0.0149,0.0748,-0.0282,-1.61e-05,-5.78e-05,3.35e-07,-2.57e-05,1.77e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,6.05e-06,0.000366,0.000366,0.000159,0.812,0.812,0.0164,1.64,1.64,0.0533,6.41e-09,6.41e-09,7.54e-09,3.85e-06,3.85e-06,8.84e-08,0,0,0,0,0,0,0,0 +9090000,0.982,-0.00595,-0.0123,0.187,-0.00789,0.0702,-0.00936,-0.0157,0.0815,-0.0284,-1.61e-05,-5.78e-05,7.64e-07,-2.57e-05,1.77e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,5.85e-06,0.000372,0.000372,0.000154,0.886,0.886,0.0159,1.86,1.86,0.0526,6.41e-09,6.41e-09,7.48e-09,3.85e-06,3.85e-06,8.46e-08,0,0,0,0,0,0,0,0 +9190000,0.982,-0.00595,-0.0123,0.187,-0.00454,0.0715,-0.00881,-0.016,0.087,-0.0287,-1.6e-05,-5.78e-05,1.14e-06,-2.56e-05,1.83e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,5.68e-06,0.000374,0.000374,0.000149,0.948,0.948,0.0155,2.07,2.07,0.0519,6.35e-09,6.35e-09,7.42e-09,3.84e-06,3.84e-06,8.1e-08,0,0,0,0,0,0,0,0 +9290000,0.982,-0.0058,-0.0121,0.187,-0.00268,0.0744,-0.00726,-0.0163,0.0943,-0.0263,-1.6e-05,-5.78e-05,1.26e-06,-2.56e-05,1.83e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,5.54e-06,0.00038,0.00038,0.000145,1.03,1.03,0.0151,2.34,2.34,0.0512,6.35e-09,6.35e-09,7.36e-09,3.84e-06,3.84e-06,7.77e-08,0,0,0,0,0,0,0,0 +9390000,0.982,-0.00572,-0.0122,0.187,-0.00278,0.0754,-0.00612,-0.0161,0.0993,-0.0267,-1.59e-05,-5.78e-05,8.39e-07,-2.55e-05,1.91e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,5.44e-06,0.000381,0.000381,0.000143,1.09,1.09,0.0148,2.57,2.57,0.0512,6.28e-09,6.28e-09,7.3e-09,3.84e-06,3.84e-06,7.49e-08,0,0,0,0,0,0,0,0 +9490000,0.982,-0.00574,-0.0122,0.187,-0.0033,0.0774,-0.00444,-0.0164,0.107,-0.0238,-1.59e-05,-5.78e-05,1.01e-06,-2.55e-05,1.91e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.33e-06,0.000388,0.000388,0.00014,1.18,1.18,0.0144,2.9,2.9,0.0506,6.28e-09,6.28e-09,7.23e-09,3.84e-06,3.84e-06,7.19e-08,0,0,0,0,0,0,0,0 +9590000,0.982,-0.00582,-0.0122,0.187,-0.00354,0.0769,-0.00436,-0.0163,0.111,-0.0251,-1.58e-05,-5.78e-05,1.48e-07,-2.53e-05,2.02e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.23e-06,0.000387,0.000387,0.000137,1.24,1.24,0.014,3.16,3.16,0.05,6.2e-09,6.2e-09,7.16e-09,3.83e-06,3.83e-06,6.91e-08,0,0,0,0,0,0,0,0 +9690000,0.982,-0.00581,-0.0122,0.187,-0.00403,0.0794,-0.00146,-0.0166,0.119,-0.0239,-1.59e-05,-5.78e-05,-8.57e-08,-2.53e-05,2.02e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.17e-06,0.000395,0.000395,0.000136,1.33,1.33,0.0138,3.55,3.55,0.05,6.2e-09,6.2e-09,7.09e-09,3.83e-06,3.83e-06,6.68e-08,0,0,0,0,0,0,0,0 +9790000,0.982,-0.00578,-0.0121,0.187,-0.00313,0.0826,-0.0028,-0.017,0.127,-0.0247,-1.59e-05,-5.78e-05,-9.63e-07,-2.53e-05,2.03e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.09e-06,0.000402,0.000402,0.000134,1.43,1.43,0.0135,3.98,3.98,0.0493,6.2e-09,6.2e-09,7e-09,3.83e-06,3.83e-06,6.42e-08,0,0,0,0,0,0,0,0 +9890000,0.982,-0.00578,-0.0121,0.187,-0.000924,0.0817,-0.0015,-0.0165,0.13,-0.0252,-1.58e-05,-5.79e-05,-7.89e-07,-2.5e-05,2.16e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.03e-06,0.000399,0.000399,0.000132,1.48,1.48,0.0131,4.29,4.29,0.0487,6.11e-09,6.11e-09,6.92e-09,3.81e-06,3.81e-06,6.19e-08,0,0,0,0,0,0,0,0 +9990000,0.982,-0.00577,-0.0121,0.187,0.000378,0.0833,-0.000786,-0.0166,0.138,-0.0272,-1.58e-05,-5.78e-05,-1.51e-06,-2.5e-05,2.17e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,5.01e-06,0.000407,0.000407,0.000131,1.58,1.58,0.0129,4.79,4.79,0.0488,6.11e-09,6.11e-09,6.83e-09,3.81e-06,3.81e-06,5.99e-08,0,0,0,0,0,0,0,0 +10090000,0.982,-0.00577,-0.0123,0.188,-0.0013,0.0796,0.000421,-0.0158,0.14,-0.0254,-1.56e-05,-5.79e-05,-2.36e-06,-2.46e-05,2.34e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.95e-06,0.000401,0.000402,0.00013,1.62,1.62,0.0126,5.09,5.09,0.0482,6.01e-09,6.01e-09,6.74e-09,3.8e-06,3.8e-06,5.78e-08,0,0,0,0,0,0,0,0 +10190000,0.982,-0.00573,-0.0122,0.188,-0.00331,0.0822,0.0013,-0.016,0.148,-0.0266,-1.57e-05,-5.78e-05,-3.37e-06,-2.46e-05,2.35e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.91e-06,0.00041,0.00041,0.000129,1.73,1.73,0.0123,5.66,5.67,0.0476,6.01e-09,6.01e-09,6.64e-09,3.8e-06,3.8e-06,5.58e-08,0,0,0,0,0,0,0,0 +10290000,0.982,-0.00583,-0.0121,0.188,-0.00277,0.0801,0.000229,-0.0154,0.147,-0.0258,-1.55e-05,-5.79e-05,-3e-06,-2.4e-05,2.54e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.9e-06,0.000401,0.000401,0.000129,1.75,1.75,0.0122,5.95,5.95,0.0476,5.9e-09,5.91e-09,6.55e-09,3.78e-06,3.78e-06,5.41e-08,0,0,0,0,0,0,0,0 +10390000,0.982,-0.00582,-0.012,0.188,0.00658,0.00423,-0.00275,0.000735,0.000107,-0.0249,-1.55e-05,-5.79e-05,-2.75e-06,-2.4e-05,2.54e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.87e-06,0.00041,0.00041,0.000128,0.0416,0.0416,0.0401,0.25,0.25,0.0441,5.9e-09,5.91e-09,6.44e-09,3.78e-06,3.78e-06,5.24e-08,0,0,0,0,0,0,0,0 +10490000,0.982,-0.00572,-0.012,0.188,0.00747,0.00566,-0.00119,0.00141,0.000565,-0.021,-1.55e-05,-5.79e-05,-3.52e-06,-2.41e-05,2.53e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.85e-06,0.000418,0.000419,0.000128,0.0467,0.0467,0.0402,0.251,0.251,0.0416,5.9e-09,5.91e-09,6.34e-09,3.78e-06,3.78e-06,5.09e-08,0,0,0,0,0,0,0,0 +10590000,0.982,-0.00567,-0.0118,0.188,0.00416,0.00601,0.000274,0.00066,-0.00483,-0.0209,-1.55e-05,-5.81e-05,-3.02e-06,-2.02e-05,2.52e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.82e-06,0.000419,0.000419,0.000127,0.0468,0.0468,0.0375,0.126,0.126,0.0399,5.87e-09,5.87e-09,6.22e-09,3.77e-06,3.77e-06,5e-08,0,0,0,0,0,0,0,0 +10690000,0.982,-0.00562,-0.0119,0.188,0.00472,0.00621,0.00114,0.00111,-0.00422,-0.0194,-1.55e-05,-5.81e-05,-3.27e-06,-2.03e-05,2.51e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.83e-06,0.000428,0.000428,0.000127,0.0581,0.0581,0.0373,0.128,0.128,0.0395,5.87e-09,5.88e-09,6.13e-09,3.77e-06,3.77e-06,5e-08,0,0,0,0,0,0,0,0 +10790000,0.982,-0.00574,-0.0119,0.188,0.00488,0.00458,0.00178,0.000908,-0.00313,-0.0177,-1.53e-05,-5.83e-05,-3.32e-06,-1.65e-05,2.97e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.81e-06,0.00041,0.00041,0.000127,0.0589,0.0589,0.0347,0.0865,0.0865,0.0389,5.77e-09,5.77e-09,6.01e-09,3.73e-06,3.73e-06,5e-08,0,0,0,0,0,0,0,0 +10890000,0.982,-0.00571,-0.012,0.188,0.00429,0.00697,0.00118,0.00137,-0.00261,-0.0199,-1.53e-05,-5.83e-05,-2.39e-06,-1.65e-05,2.97e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.8e-06,0.000419,0.000419,0.000126,0.0748,0.0748,0.0343,0.0899,0.0899,0.0391,5.77e-09,5.77e-09,5.89e-09,3.73e-06,3.73e-06,5e-08,0,0,0,0,0,0,0,0 +10990000,0.982,-0.00578,-0.012,0.188,0.00247,0.0121,0.00335,0.00104,-0.00159,-0.0164,-1.51e-05,-5.84e-05,-2.65e-06,-1.38e-05,3.19e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.8e-06,0.000381,0.000381,0.000127,0.0714,0.0714,0.0319,0.0684,0.0684,0.0395,5.58e-09,5.59e-09,5.79e-09,3.67e-06,3.67e-06,5e-08,0,0,0,0,0,0,0,0 +11090000,0.982,-0.0059,-0.012,0.188,0.00268,0.0161,0.00571,0.00126,-0.000235,-0.0141,-1.52e-05,-5.84e-05,-3.6e-06,-1.38e-05,3.19e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.8e-06,0.00039,0.00039,0.000127,0.0896,0.0896,0.0313,0.0732,0.0732,0.0402,5.58e-09,5.59e-09,5.67e-09,3.67e-06,3.67e-06,5e-08,0,0,0,0,0,0,0,0 +11190000,0.982,-0.00614,-0.012,0.188,0.00296,0.0158,0.00988,0.00205,-0.000295,-0.00976,-1.47e-05,-5.84e-05,-4.07e-06,-1.38e-05,3.95e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.77e-06,0.00034,0.00034,0.000126,0.0796,0.0796,0.0289,0.0592,0.0592,0.0403,5.35e-09,5.35e-09,5.55e-09,3.61e-06,3.61e-06,5e-08,0,0,0,0,0,0,0,0 +11290000,0.982,-0.00612,-0.012,0.188,0.00231,0.016,0.0109,0.00228,0.00134,-0.00964,-1.47e-05,-5.84e-05,-4.3e-06,-1.38e-05,3.95e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.79e-06,0.000349,0.000349,0.000127,0.0978,0.0978,0.0282,0.0653,0.0653,0.0417,5.35e-09,5.35e-09,5.44e-09,3.61e-06,3.61e-06,5e-08,0,0,0,0,0,0,0,0 +11390000,0.982,-0.00621,-0.012,0.188,0.000535,0.0138,0.00781,0.00166,0.000538,-0.0139,-1.43e-05,-5.86e-05,-4.16e-06,-1.02e-05,4.54e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.77e-06,0.0003,0.0003,0.000127,0.0824,0.0824,0.026,0.0543,0.0543,0.0418,5.12e-09,5.12e-09,5.32e-09,3.55e-06,3.55e-06,5e-08,0,0,0,0,0,0,0,0 +11490000,0.982,-0.00614,-0.0119,0.188,-0.00117,0.0142,0.0105,0.00156,0.00195,-0.00982,-1.43e-05,-5.86e-05,-3.98e-06,-1.02e-05,4.54e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.75e-06,0.000307,0.000307,0.000126,0.0994,0.0994,0.0251,0.0615,0.0615,0.0427,5.12e-09,5.12e-09,5.2e-09,3.55e-06,3.55e-06,5e-08,0,0,0,0,0,0,0,0 +11590000,0.982,-0.00638,-0.0119,0.188,0.000726,0.0111,0.0108,0.00141,0.000875,-0.00937,-1.4e-05,-5.87e-05,-3.95e-06,-8.52e-06,5.03e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.76e-06,0.000265,0.000265,0.000127,0.081,0.081,0.0232,0.0516,0.0516,0.0431,4.9e-09,4.9e-09,5.09e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 +11690000,0.982,-0.00636,-0.0118,0.188,0.000463,0.0145,0.012,0.00149,0.00213,-0.0102,-1.4e-05,-5.88e-05,-3.65e-06,-8.51e-06,5.03e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.75e-06,0.000272,0.000272,0.000127,0.0961,0.0961,0.0223,0.0595,0.0595,0.0439,4.9e-09,4.9e-09,4.97e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0 +11790000,0.982,-0.00663,-0.0118,0.188,-0.00042,0.00974,0.0131,0.00112,-0.00066,-0.0079,-1.34e-05,-5.9e-05,-2.72e-06,-5.55e-06,5.7e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.74e-06,0.000238,0.000238,0.000126,0.0773,0.0773,0.0205,0.0502,0.0502,0.0437,4.71e-09,4.71e-09,4.85e-09,3.47e-06,3.47e-06,5e-08,0,0,0,0,0,0,0,0 +11890000,0.982,-0.00672,-0.0117,0.188,0.00163,0.0109,0.0112,0.00113,0.000327,-0.00753,-1.34e-05,-5.9e-05,-2.92e-06,-5.56e-06,5.7e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.73e-06,0.000245,0.000245,0.000126,0.0906,0.0906,0.0196,0.0584,0.0584,0.0443,4.71e-09,4.71e-09,4.73e-09,3.47e-06,3.47e-06,5e-08,0,0,0,0,0,0,0,0 +11990000,0.982,-0.00685,-0.0118,0.188,0.00474,0.0108,0.01,0.00242,-0.000879,-0.0101,-1.33e-05,-5.89e-05,-2.64e-06,-6.6e-06,5.91e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.73e-06,0.000218,0.000219,0.000127,0.0726,0.0726,0.0182,0.0493,0.0493,0.0444,4.55e-09,4.55e-09,4.63e-09,3.45e-06,3.45e-06,5e-08,0,0,0,0,0,0,0,0 +12090000,0.982,-0.00676,-0.0118,0.188,0.00573,0.0106,0.0125,0.00293,0.000175,-0.00602,-1.33e-05,-5.89e-05,-2.68e-06,-6.59e-06,5.91e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.73e-06,0.000225,0.000225,0.000126,0.0841,0.0841,0.0174,0.0576,0.0576,0.0448,4.55e-09,4.55e-09,4.51e-09,3.45e-06,3.45e-06,5e-08,0,0,0,0,0,0,0,0 +12190000,0.982,-0.00666,-0.0118,0.188,0.00482,0.00993,0.0116,0.00202,0.00115,-0.00459,-1.33e-05,-5.9e-05,-3.04e-06,-5.38e-06,5.86e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.7e-06,0.000205,0.000205,0.000126,0.0676,0.0676,0.0161,0.0488,0.0488,0.0443,4.4e-09,4.4e-09,4.39e-09,3.44e-06,3.44e-06,5e-08,0,0,0,0,0,0,0,0 +12290000,0.982,-0.00673,-0.0118,0.188,0.00207,0.0091,0.0103,0.00239,0.00211,-0.00409,-1.33e-05,-5.9e-05,-3.35e-06,-5.39e-06,5.86e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.72e-06,0.000211,0.000211,0.000126,0.0778,0.0778,0.0154,0.0571,0.0571,0.045,4.4e-09,4.4e-09,4.29e-09,3.44e-06,3.44e-06,5e-08,0,0,0,0,0,0,0,0 +12390000,0.982,-0.00681,-0.0117,0.188,0.00135,0.00642,0.00962,0.00185,0.00115,-0.00871,-1.32e-05,-5.91e-05,-3.4e-06,-4.57e-06,5.97e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.7e-06,0.000196,0.000196,0.000126,0.0629,0.0629,0.0143,0.0485,0.0485,0.0444,4.26e-09,4.27e-09,4.18e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +12490000,0.982,-0.0068,-0.0117,0.188,0.000993,0.00735,0.0139,0.00201,0.00184,-0.00724,-1.32e-05,-5.91e-05,-3.5e-06,-4.57e-06,5.97e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.69e-06,0.000202,0.000202,0.000126,0.0718,0.0718,0.0136,0.0567,0.0567,0.0444,4.26e-09,4.27e-09,4.07e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +12590000,0.982,-0.00692,-0.0117,0.188,0.00484,0.00167,0.0153,0.00335,-0.000697,-0.00579,-1.28e-05,-5.91e-05,-3.58e-06,-4.57e-06,6.13e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.7e-06,0.00019,0.00019,0.000126,0.0586,0.0586,0.0128,0.0482,0.0482,0.0442,4.14e-09,4.14e-09,3.97e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +12690000,0.982,-0.00687,-0.0117,0.188,0.00497,-0.00042,0.015,0.0038,-0.000627,-0.00467,-1.28e-05,-5.91e-05,-3.56e-06,-4.58e-06,6.13e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.68e-06,0.000196,0.000196,0.000125,0.0667,0.0667,0.0122,0.0563,0.0563,0.0441,4.14e-09,4.14e-09,3.86e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +12790000,0.982,-0.00707,-0.0116,0.187,0.00645,-0.00292,0.0164,0.00401,-0.00372,-0.00297,-1.23e-05,-5.9e-05,-2.46e-06,-3.88e-06,6.18e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.65e-06,0.000186,0.000186,0.000125,0.0549,0.0549,0.0114,0.048,0.048,0.0433,4.01e-09,4.01e-09,3.76e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +12890000,0.982,-0.00706,-0.0116,0.187,0.00621,-0.00361,0.0174,0.00468,-0.00406,-0.000599,-1.23e-05,-5.9e-05,-1.76e-06,-3.84e-06,6.17e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.66e-06,0.000192,0.000192,0.000125,0.0622,0.0622,0.011,0.0559,0.0559,0.0436,4.01e-09,4.01e-09,3.66e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +12990000,0.982,-0.00704,-0.0116,0.187,0.00505,-0.00199,0.0177,0.00349,-0.00302,0.000451,-1.24e-05,-5.92e-05,-1.14e-06,-3.67e-06,6.14e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.63e-06,0.000184,0.000184,0.000125,0.0517,0.0517,0.0104,0.0478,0.0478,0.0428,3.88e-09,3.89e-09,3.56e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +13090000,0.982,-0.00706,-0.0115,0.187,0.00567,-0.00168,0.0156,0.00401,-0.00314,-0.000661,-1.24e-05,-5.92e-05,-3.12e-07,-3.67e-06,6.14e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.62e-06,0.00019,0.00019,0.000124,0.0584,0.0584,0.00995,0.0555,0.0555,0.0426,3.88e-09,3.89e-09,3.46e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +13190000,0.982,-0.00707,-0.0114,0.187,0.00148,-0.0032,0.0149,0.00089,-0.00402,-0.000171,-1.24e-05,-5.94e-05,1.9e-07,-3.4e-06,6.09e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.6e-06,0.000183,0.000183,0.000124,0.049,0.049,0.00943,0.0476,0.0476,0.0418,3.75e-09,3.75e-09,3.37e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +13290000,0.982,-0.0071,-0.0114,0.187,0.000915,-0.0039,0.0124,0.000962,-0.00435,-0.000948,-1.24e-05,-5.94e-05,2.22e-07,-3.42e-06,6.09e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.6e-06,0.000189,0.000189,0.000124,0.0554,0.0554,0.00916,0.0551,0.0551,0.0419,3.75e-09,3.75e-09,3.28e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +13390000,0.982,-0.00703,-0.0115,0.187,0.000503,-0.00224,0.0123,0.000758,-0.0033,-0.000412,-1.25e-05,-5.94e-05,-1.29e-07,-3.43e-06,6.1e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.57e-06,0.000183,0.000183,0.000123,0.0468,0.0468,0.00873,0.0474,0.0474,0.0411,3.61e-09,3.62e-09,3.19e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +13490000,0.982,-0.007,-0.0115,0.187,0.00079,-0.000358,0.012,0.000837,-0.00337,-0.00398,-1.25e-05,-5.94e-05,7.86e-08,-3.49e-06,6.1e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.55e-06,0.000189,0.000189,0.000122,0.0528,0.0528,0.00847,0.0547,0.0547,0.0408,3.61e-09,3.62e-09,3.1e-09,3.43e-06,3.43e-06,5e-08,0,0,0,0,0,0,0,0 +13590000,0.982,-0.007,-0.0116,0.187,0.00504,-0.000722,0.0137,0.00371,-0.0028,-0.00527,-1.23e-05,-5.9e-05,-1.59e-07,-1.76e-06,6.03e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.55e-06,0.000183,0.000183,0.000122,0.045,0.045,0.00817,0.0472,0.0472,0.0404,3.47e-09,3.47e-09,3.02e-09,3.42e-06,3.42e-06,5e-08,0,0,0,0,0,0,0,0 +13690000,0.982,-0.00695,-0.0115,0.187,0.00485,-0.00193,0.0138,0.00419,-0.00292,-0.00286,-1.23e-05,-5.9e-05,2.72e-07,-1.73e-06,6.03e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.52e-06,0.000189,0.000189,0.000122,0.0508,0.0508,0.00797,0.0544,0.0544,0.04,3.47e-09,3.47e-09,2.94e-09,3.42e-06,3.42e-06,5e-08,0,0,0,0,0,0,0,0 +13790000,0.982,-0.0069,-0.0117,0.187,0.0116,0.00176,0.0139,0.00776,-0.000716,-0.00333,-1.24e-05,-5.84e-05,1.62e-08,1.8e-06,6.05e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.49e-06,0.000183,0.000183,0.000121,0.0436,0.0436,0.00769,0.0469,0.0469,0.0393,3.32e-09,3.32e-09,2.85e-09,3.42e-06,3.42e-06,5e-08,0,0,0,0,0,0,0,0 +13890000,0.982,-0.00681,-0.0116,0.187,0.0125,0.00268,0.0149,0.00894,-0.000486,-0.00138,-1.24e-05,-5.84e-05,5.69e-07,1.81e-06,6.05e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.49e-06,0.000189,0.000189,0.000121,0.0492,0.0492,0.00759,0.054,0.054,0.0393,3.32e-09,3.32e-09,2.78e-09,3.42e-06,3.42e-06,5e-08,0,0,0,0,0,0,0,0 +13990000,0.982,-0.00687,-0.0114,0.186,0.0127,0.00309,0.0138,0.00695,-0.00197,-0.0025,-1.22e-05,-5.89e-05,1.14e-06,-7.08e-07,5.92e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.46e-06,0.000183,0.000183,0.00012,0.0425,0.0425,0.00737,0.0467,0.0467,0.0386,3.16e-09,3.16e-09,2.7e-09,3.41e-06,3.41e-06,5e-08,0,0,0,0,0,0,0,0 +14090000,0.982,-0.00687,-0.0113,0.187,0.0101,-0.00108,0.0152,0.00819,-0.00188,-0.00599,-1.23e-05,-5.89e-05,-2.08e-07,-8.27e-07,5.93e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.44e-06,0.000189,0.000189,0.000119,0.048,0.048,0.00727,0.0537,0.0537,0.0383,3.16e-09,3.16e-09,2.62e-09,3.41e-06,3.41e-06,5e-08,0,0,0,0,0,0,0,0 +14190000,0.982,-0.00684,-0.0113,0.187,0.00798,7.37e-05,0.0149,0.00764,-0.00143,-0.006,-1.23e-05,-5.89e-05,-8.31e-07,-8.36e-07,5.97e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.43e-06,0.000183,0.000183,0.000119,0.0416,0.0416,0.00714,0.0465,0.0465,0.038,2.99e-09,2.99e-09,2.56e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 +14290000,0.982,-0.00678,-0.0113,0.187,0.00953,0.000269,0.0133,0.0084,-0.00146,-0.00226,-1.23e-05,-5.89e-05,-7.77e-07,-7.86e-07,5.96e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.41e-06,0.000188,0.000188,0.000119,0.0471,0.0471,0.00707,0.0534,0.0534,0.0376,2.99e-09,2.99e-09,2.48e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0 +14390000,0.982,-0.00687,-0.0112,0.187,0.00996,-0.0027,0.0144,0.00803,-0.00269,0.00163,-1.21e-05,-5.9e-05,-4.03e-07,-1.44e-06,5.77e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.38e-06,0.000182,0.000182,0.000118,0.041,0.041,0.00694,0.0463,0.0463,0.037,2.82e-09,2.82e-09,2.41e-09,3.39e-06,3.39e-06,5e-08,0,0,0,0,0,0,0,0 +14490000,0.982,-0.00698,-0.0112,0.187,0.00834,-0.00219,0.0181,0.00889,-0.00295,0.00363,-1.21e-05,-5.9e-05,-1.08e-06,-1.45e-06,5.77e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.35e-06,0.000187,0.000187,0.000117,0.0464,0.0464,0.00691,0.0531,0.0531,0.0367,2.82e-09,2.82e-09,2.34e-09,3.39e-06,3.39e-06,5e-08,0,0,0,0,0,0,0,0 +14590000,0.982,-0.00705,-0.011,0.187,0.0067,-0.00235,0.0159,0.00564,-0.00374,-0.000473,-1.22e-05,-5.95e-05,-1.2e-06,-6.17e-06,5.78e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.34e-06,0.000181,0.000181,0.000117,0.0406,0.0406,0.00685,0.0462,0.0462,0.0365,2.64e-09,2.64e-09,2.29e-09,3.37e-06,3.37e-06,5e-08,0,0,0,0,0,0,0,0 +14690000,0.982,-0.00704,-0.011,0.187,0.00587,-0.00207,0.0157,0.00626,-0.00394,-0.000458,-1.22e-05,-5.95e-05,-9.71e-07,-6.21e-06,5.78e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.31e-06,0.000186,0.000186,0.000116,0.0459,0.0459,0.00685,0.0529,0.0529,0.0362,2.64e-09,2.64e-09,2.22e-09,3.37e-06,3.37e-06,5e-08,0,0,0,0,0,0,0,0 +14790000,0.982,-0.00697,-0.011,0.187,0.00787,0.00435,0.0161,0.00508,0.00104,0.00204,-1.29e-05,-5.94e-05,-2.5e-07,-4.7e-06,6.53e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.28e-06,0.000179,0.000179,0.000115,0.0402,0.0402,0.00678,0.046,0.046,0.0357,2.46e-09,2.46e-09,2.16e-09,3.36e-06,3.36e-06,5e-08,0,0,0,0,0,0,0,0 +14890000,0.982,-0.00688,-0.011,0.187,0.00652,0.00222,0.0202,0.00575,0.00138,0.00265,-1.29e-05,-5.94e-05,2.63e-07,-4.73e-06,6.54e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.27e-06,0.000184,0.000184,0.000115,0.0455,0.0455,0.00683,0.0527,0.0527,0.0357,2.46e-09,2.46e-09,2.1e-09,3.36e-06,3.36e-06,5e-08,0,0,0,0,0,0,0,0 +14990000,0.982,-0.00704,-0.0108,0.187,0.0055,0.000566,0.0228,0.00457,-0.000328,0.00451,-1.27e-05,-5.97e-05,5.57e-07,-7.63e-06,6.33e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.24e-06,0.000176,0.000176,0.000114,0.0399,0.0399,0.00679,0.0459,0.0459,0.0352,2.28e-09,2.28e-09,2.05e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0 +15090000,0.982,-0.00698,-0.0109,0.187,0.00554,0.00191,0.0265,0.00513,-0.000246,0.0068,-1.27e-05,-5.97e-05,5.34e-07,-7.63e-06,6.33e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.21e-06,0.000181,0.000181,0.000113,0.0451,0.0451,0.00683,0.0525,0.0525,0.035,2.28e-09,2.28e-09,1.99e-09,3.34e-06,3.34e-06,5e-08,0,0,0,0,0,0,0,0 +15190000,0.982,-0.00712,-0.011,0.187,0.00385,0.000689,0.0271,0.00406,-0.000353,0.00823,-1.27e-05,-5.99e-05,3.03e-07,-9.35e-06,6.35e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.2e-06,0.000174,0.000174,0.000113,0.0396,0.0396,0.00683,0.0458,0.0458,0.0349,2.11e-09,2.11e-09,1.94e-09,3.32e-06,3.32e-06,5e-08,0,0,0,0,0,0,0,0 +15290000,0.982,-0.0072,-0.011,0.187,0.00437,-9.47e-05,0.0266,0.00449,-0.000296,0.00497,-1.27e-05,-5.99e-05,8.28e-07,-9.56e-06,6.37e-05,-0.00137,0.204,0.002,0.435,0,0,0,0,0,4.17e-06,0.000178,0.000178,0.000112,0.0447,0.0447,0.00689,0.0524,0.0524,0.0347,2.11e-09,2.11e-09,1.89e-09,3.32e-06,3.32e-06,5e-08,0,0,0,0,0,0,0,0 +15390000,0.982,-0.00729,-0.011,0.187,0.00469,0.00213,0.0261,0.00361,-0.000199,0.00515,-1.28e-05,-6e-05,7.29e-07,-1.11e-05,6.43e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.14e-06,0.00017,0.00017,0.000111,0.0393,0.0393,0.00687,0.0457,0.0457,0.0343,1.93e-09,1.94e-09,1.83e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 +15490000,0.982,-0.0073,-0.011,0.187,0.00407,-0.000123,0.0261,0.00404,-6.74e-05,0.00583,-1.28e-05,-6e-05,7.24e-07,-1.11e-05,6.43e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.13e-06,0.000175,0.000175,0.000111,0.0443,0.0443,0.00698,0.0522,0.0522,0.0345,1.93e-09,1.94e-09,1.79e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0 +15590000,0.982,-0.00751,-0.011,0.187,0.00762,-0.00403,0.0257,0.00603,-0.00412,0.00437,-1.2e-05,-6e-05,1.04e-06,-1.09e-05,5.59e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.1e-06,0.000167,0.000167,0.00011,0.039,0.039,0.00697,0.0456,0.0456,0.0341,1.77e-09,1.77e-09,1.74e-09,3.28e-06,3.28e-06,5e-08,0,0,0,0,0,0,0,0 +15690000,0.982,-0.00746,-0.0109,0.187,0.00939,-0.00684,0.0262,0.00687,-0.00464,0.0051,-1.2e-05,-6e-05,1.48e-06,-1.14e-05,5.64e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.07e-06,0.000171,0.000171,0.000109,0.0439,0.0439,0.00705,0.0522,0.0522,0.034,1.77e-09,1.77e-09,1.69e-09,3.28e-06,3.28e-06,5e-08,0,0,0,0,0,0,0,0 +15790000,0.982,-0.00746,-0.0108,0.186,0.00598,-0.00641,0.0261,0.00528,-0.00367,0.00649,-1.23e-05,-6.02e-05,2.1e-06,-1.4e-05,6.01e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.03e-06,0.000163,0.000163,0.000108,0.0386,0.0386,0.00706,0.0456,0.0456,0.0337,1.61e-09,1.61e-09,1.64e-09,3.26e-06,3.26e-06,5e-08,0,0,0,0,0,0,0,0 +15890000,0.982,-0.00751,-0.0109,0.186,0.00481,-0.00453,0.0268,0.0058,-0.00423,0.00594,-1.23e-05,-6.02e-05,1.62e-06,-1.37e-05,5.98e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,4.02e-06,0.000167,0.000167,0.000108,0.0434,0.0434,0.00718,0.0521,0.0521,0.0339,1.61e-09,1.61e-09,1.61e-09,3.26e-06,3.26e-06,5e-08,0,0,0,0,0,0,0,0 +15990000,0.982,-0.00731,-0.0108,0.186,0.00282,-0.00328,0.0238,0.00457,-0.0033,0.00523,-1.25e-05,-6.03e-05,1.56e-06,-1.53e-05,6.2e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,3.99e-06,0.000159,0.000159,0.000107,0.0382,0.0382,0.00718,0.0455,0.0455,0.0336,1.47e-09,1.47e-09,1.56e-09,3.24e-06,3.24e-06,5e-08,0,0,0,0,0,0,0,0 +16090000,0.982,-0.00728,-0.0108,0.186,0.00213,-0.00426,0.0216,0.00475,-0.00367,0.0051,-1.25e-05,-6.03e-05,1.29e-06,-1.54e-05,6.22e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,3.95e-06,0.000162,0.000162,0.000106,0.0429,0.0429,0.00728,0.052,0.052,0.0335,1.47e-09,1.47e-09,1.52e-09,3.24e-06,3.24e-06,5e-08,0,0,0,0,0,0,0,0 +16190000,0.982,-0.00718,-0.0107,0.187,-0.00177,-0.00215,0.0204,0.00245,-0.00272,0.00193,-1.27e-05,-6.05e-05,9.19e-07,-1.84e-05,6.52e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,3.93e-06,0.000155,0.000155,0.000106,0.0377,0.0377,0.00731,0.0455,0.0455,0.0336,1.33e-09,1.33e-09,1.48e-09,3.21e-06,3.22e-06,5e-08,0,0,0,0,0,0,0,0 +16290000,0.982,-0.0072,-0.0106,0.187,-0.00148,-0.0034,0.0203,0.00226,-0.00303,0.0033,-1.27e-05,-6.05e-05,1.06e-06,-1.85e-05,6.53e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,3.91e-06,0.000158,0.000158,0.000105,0.0423,0.0423,0.00741,0.0519,0.0519,0.0335,1.33e-09,1.33e-09,1.44e-09,3.21e-06,3.22e-06,5e-08,0,0,0,0,0,0,0,0 +16390000,0.982,-0.00717,-0.0106,0.186,0.00101,-0.00297,0.0208,0.00333,-0.00234,0.0034,-1.27e-05,-6.03e-05,1.43e-06,-1.57e-05,6.54e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.88e-06,0.000151,0.000151,0.000104,0.0371,0.0371,0.00742,0.0454,0.0454,0.0333,1.2e-09,1.2e-09,1.41e-09,3.19e-06,3.19e-06,5e-08,0,0,0,0,0,0,0,0 +16490000,0.982,-0.00729,-0.0106,0.186,0.00302,-0.00433,0.0232,0.00356,-0.00276,0.00758,-1.27e-05,-6.03e-05,1.28e-06,-1.55e-05,6.53e-05,-0.00136,0.204,0.002,0.435,0,0,0,0,0,3.86e-06,0.000154,0.000154,0.000104,0.0416,0.0416,0.00755,0.0519,0.0519,0.0336,1.2e-09,1.2e-09,1.37e-09,3.19e-06,3.19e-06,5e-08,0,0,0,0,0,0,0,0 +16590000,0.982,-0.00726,-0.0106,0.186,0.00713,-0.00464,0.027,0.00312,-0.00216,0.00779,-1.28e-05,-6.03e-05,1.28e-06,-1.61e-05,6.7e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.83e-06,0.000146,0.000146,0.000103,0.0365,0.0365,0.00755,0.0454,0.0454,0.0334,1.08e-09,1.08e-09,1.34e-09,3.17e-06,3.18e-06,5e-08,0,0,0,0,0,0,0,0 +16690000,0.982,-0.00731,-0.0105,0.186,0.00855,-0.00896,0.0271,0.0039,-0.00282,0.00849,-1.28e-05,-6.03e-05,1.51e-06,-1.64e-05,6.73e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.8e-06,0.000149,0.000149,0.000102,0.0408,0.0408,0.00765,0.0518,0.0518,0.0334,1.08e-09,1.08e-09,1.3e-09,3.17e-06,3.18e-06,5e-08,0,0,0,0,0,0,0,0 +16790000,0.982,-0.00714,-0.0104,0.186,0.00945,-0.00807,0.0259,0.00301,-0.00201,0.00839,-1.31e-05,-6.04e-05,1.67e-06,-1.82e-05,7.09e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.78e-06,0.000142,0.000142,0.000102,0.0358,0.0358,0.00768,0.0453,0.0453,0.0335,9.78e-10,9.79e-10,1.27e-09,3.16e-06,3.16e-06,5e-08,0,0,0,0,0,0,0,0 +16890000,0.982,-0.00711,-0.0105,0.186,0.00838,-0.00826,0.027,0.00388,-0.0028,0.0071,-1.31e-05,-6.04e-05,2.15e-06,-1.85e-05,7.12e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.75e-06,0.000145,0.000145,0.000101,0.04,0.04,0.00778,0.0517,0.0517,0.0336,9.78e-10,9.79e-10,1.24e-09,3.16e-06,3.16e-06,5e-08,0,0,0,0,0,0,0,0 +16990000,0.982,-0.00713,-0.0105,0.186,0.00804,-0.00789,0.0268,0.00369,-0.00208,0.00574,-1.32e-05,-6.03e-05,2.25e-06,-1.65e-05,7.28e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.72e-06,0.000138,0.000138,0.000101,0.0351,0.0351,0.00778,0.0453,0.0453,0.0334,8.82e-10,8.82e-10,1.21e-09,3.14e-06,3.14e-06,5e-08,0,0,0,0,0,0,0,0 +17090000,0.982,-0.00722,-0.0105,0.186,0.00954,-0.0103,0.0264,0.0046,-0.00304,0.00514,-1.32e-05,-6.03e-05,2.13e-06,-1.66e-05,7.28e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.69e-06,0.000141,0.000141,9.97e-05,0.0392,0.0392,0.00787,0.0516,0.0516,0.0335,8.82e-10,8.82e-10,1.18e-09,3.14e-06,3.14e-06,5e-08,0,0,0,0,0,0,0,0 +17190000,0.982,-0.00734,-0.0104,0.186,0.00847,-0.0157,0.0282,0.003,-0.00676,0.00839,-1.31e-05,-6.04e-05,1.61e-06,-1.83e-05,7.04e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.68e-06,0.000135,0.000135,9.94e-05,0.0344,0.0344,0.00789,0.0452,0.0452,0.0336,7.95e-10,7.95e-10,1.15e-09,3.12e-06,3.12e-06,5e-08,0,0,0,0,0,0,0,0 +17290000,0.982,-0.0073,-0.0104,0.186,0.00933,-0.0159,0.0278,0.00389,-0.00829,0.00826,-1.31e-05,-6.04e-05,1.25e-06,-1.83e-05,7.02e-05,-0.00135,0.204,0.002,0.435,0,0,0,0,0,3.65e-06,0.000137,0.000137,9.86e-05,0.0383,0.0383,0.00798,0.0515,0.0515,0.0337,7.95e-10,7.95e-10,1.12e-09,3.12e-06,3.12e-06,5e-08,0,0,0,0,0,0,0,0 +17390000,0.982,-0.00717,-0.0104,0.186,0.00601,-0.0159,0.0273,0.0053,-0.00514,0.00806,-1.34e-05,-6.02e-05,1.58e-06,-1.47e-05,7.59e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.62e-06,0.000131,0.000131,9.78e-05,0.0336,0.0336,0.00796,0.0451,0.0451,0.0336,7.16e-10,7.17e-10,1.09e-09,3.11e-06,3.11e-06,5e-08,0,0,0,0,0,0,0,0 +17490000,0.982,-0.00719,-0.0105,0.186,0.00404,-0.0165,0.0271,0.00576,-0.00675,0.00986,-1.34e-05,-6.02e-05,1.4e-06,-1.46e-05,7.58e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.6e-06,0.000133,0.000133,9.74e-05,0.0374,0.0374,0.00809,0.0513,0.0513,0.034,7.16e-10,7.17e-10,1.07e-09,3.11e-06,3.11e-06,5e-08,0,0,0,0,0,0,0,0 +17590000,0.982,-0.0071,-0.0103,0.186,0.000345,-0.0128,0.0264,0.00206,-0.00503,0.00771,-1.38e-05,-6.04e-05,1.39e-06,-1.86e-05,8.17e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.57e-06,0.000128,0.000128,9.67e-05,0.0329,0.0329,0.00806,0.045,0.045,0.0338,6.46e-10,6.46e-10,1.04e-09,3.09e-06,3.09e-06,5e-08,0,0,0,0,0,0,0,0 +17690000,0.982,-0.00719,-0.0102,0.186,-0.000619,-0.0133,0.0275,0.00207,-0.00636,0.0102,-1.38e-05,-6.04e-05,1.45e-06,-1.86e-05,8.18e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.54e-06,0.000129,0.000129,9.59e-05,0.0364,0.0365,0.00814,0.0512,0.0512,0.034,6.46e-10,6.46e-10,1.02e-09,3.09e-06,3.09e-06,5e-08,0,0,0,0,0,0,0,0 +17790000,0.982,-0.00716,-0.0102,0.186,0.0021,-0.0118,0.028,0.00312,-0.00548,0.0155,-1.41e-05,-6.02e-05,1.5e-06,-1.5e-05,8.48e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.52e-06,0.000124,0.000124,9.56e-05,0.0321,0.0321,0.00814,0.0449,0.0449,0.0341,5.83e-10,5.83e-10,9.96e-10,3.08e-06,3.08e-06,5e-08,0,0,0,0,0,0,0,0 +17890000,0.982,-0.00708,-0.0103,0.186,0.00424,-0.0136,0.0278,0.0035,-0.00677,0.0199,-1.4e-05,-6.02e-05,1.63e-06,-1.49e-05,8.48e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.49e-06,0.000126,0.000126,9.48e-05,0.0355,0.0355,0.00822,0.051,0.051,0.0342,5.83e-10,5.83e-10,9.72e-10,3.08e-06,3.08e-06,5e-08,0,0,0,0,0,0,0,0 +17990000,0.982,-0.00689,-0.0103,0.186,0.00372,-0.00742,0.0276,0.00276,-0.00135,0.0206,-1.46e-05,-6e-05,1.59e-06,-1.29e-05,9.36e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.46e-06,0.000121,0.000121,9.41e-05,0.0313,0.0313,0.00817,0.0448,0.0448,0.0341,5.27e-10,5.27e-10,9.48e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0 +18090000,0.982,-0.00697,-0.0103,0.186,0.00314,-0.00781,0.0269,0.00314,-0.00213,0.0188,-1.46e-05,-6e-05,1.54e-06,-1.33e-05,9.38e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.45e-06,0.000123,0.000123,9.37e-05,0.0346,0.0346,0.00828,0.0509,0.0509,0.0345,5.27e-10,5.27e-10,9.29e-10,3.07e-06,3.07e-06,5e-08,0,0,0,0,0,0,0,0 +18190000,0.983,-0.00698,-0.0103,0.186,0.00315,-0.00699,0.0273,0.00375,-0.00155,0.0169,-1.47e-05,-5.99e-05,2.03e-06,-1.18e-05,9.49e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.42e-06,0.000118,0.000118,9.3e-05,0.0305,0.0305,0.00823,0.0447,0.0447,0.0344,4.77e-10,4.77e-10,9.06e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0 +18290000,0.983,-0.00701,-0.0103,0.186,0.00396,-0.00734,0.0262,0.00404,-0.00224,0.0154,-1.47e-05,-5.99e-05,2.05e-06,-1.21e-05,9.51e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.4e-06,0.00012,0.00012,9.22e-05,0.0337,0.0337,0.0083,0.0507,0.0507,0.0345,4.77e-10,4.77e-10,8.85e-10,3.06e-06,3.06e-06,5e-08,0,0,0,0,0,0,0,0 +18390000,0.983,-0.00693,-0.0103,0.186,0.00481,-0.00628,0.0261,0.00569,-0.00169,0.015,-1.47e-05,-5.98e-05,1.87e-06,-9.72e-06,9.58e-05,-0.00134,0.204,0.002,0.435,0,0,0,0,0,3.37e-06,0.000116,0.000116,9.15e-05,0.0297,0.0297,0.00824,0.0446,0.0446,0.0343,4.32e-10,4.32e-10,8.64e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0 +18490000,0.983,-0.00697,-0.0104,0.186,0.00752,-0.0062,0.0253,0.00639,-0.00234,0.0167,-1.47e-05,-5.98e-05,2.05e-06,-9.68e-06,9.57e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.36e-06,0.000117,0.000117,9.12e-05,0.0328,0.0328,0.00834,0.0505,0.0505,0.0348,4.32e-10,4.32e-10,8.46e-10,3.05e-06,3.05e-06,5e-08,0,0,0,0,0,0,0,0 +18590000,0.982,-0.0068,-0.0102,0.186,0.00606,-0.00576,0.0252,0.00515,-0.00179,0.0195,-1.48e-05,-5.98e-05,1.77e-06,-1.1e-05,9.77e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.34e-06,0.000113,0.000113,9.05e-05,0.029,0.029,0.00828,0.0445,0.0445,0.0346,3.92e-10,3.92e-10,8.27e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0 +18690000,0.983,-0.00676,-0.0102,0.186,0.00603,-0.00461,0.0237,0.00575,-0.0023,0.0183,-1.48e-05,-5.98e-05,1.99e-06,-1.12e-05,9.78e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.31e-06,0.000115,0.000115,8.98e-05,0.0319,0.0319,0.00834,0.0503,0.0503,0.0347,3.92e-10,3.92e-10,8.07e-10,3.04e-06,3.04e-06,5e-08,0,0,0,0,0,0,0,0 +18790000,0.983,-0.00673,-0.0101,0.186,0.00504,-0.00447,0.0234,0.00576,-0.00187,0.0162,-1.49e-05,-5.98e-05,1.93e-06,-1.12e-05,9.89e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.3e-06,0.000111,0.000111,8.95e-05,0.0282,0.0282,0.00831,0.0443,0.0443,0.0349,3.56e-10,3.56e-10,7.91e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 +18890000,0.982,-0.00669,-0.0101,0.186,0.00361,-0.00397,0.0215,0.00615,-0.00236,0.0125,-1.49e-05,-5.98e-05,1.77e-06,-1.17e-05,9.93e-05,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.27e-06,0.000112,0.000112,8.88e-05,0.031,0.031,0.00836,0.0501,0.0501,0.035,3.56e-10,3.56e-10,7.73e-10,3.03e-06,3.03e-06,5e-08,0,0,0,0,0,0,0,0 +18990000,0.982,-0.00667,-0.0101,0.186,0.00209,-0.00428,0.0223,0.00507,-0.00189,0.0162,-1.5e-05,-5.99e-05,1.73e-06,-1.23e-05,0.0001,-0.00133,0.204,0.002,0.435,0,0,0,0,0,3.25e-06,0.000109,0.000109,8.81e-05,0.0275,0.0275,0.00829,0.0442,0.0442,0.0348,3.24e-10,3.24e-10,7.56e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 +19090000,0.982,-0.00673,-0.0101,0.186,-9.26e-06,-0.00467,0.0228,0.00522,-0.00229,0.0123,-1.5e-05,-5.99e-05,1.9e-06,-1.27e-05,0.000101,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.24e-06,0.00011,0.00011,8.78e-05,0.0302,0.0302,0.00838,0.0499,0.0499,0.0352,3.24e-10,3.24e-10,7.41e-10,3.02e-06,3.02e-06,5e-08,0,0,0,0,0,0,0,0 +19190000,0.982,-0.00663,-0.0102,0.186,-0.00143,-0.00448,0.0224,0.00432,-0.00189,0.0116,-1.5e-05,-5.99e-05,1.46e-06,-1.32e-05,0.000102,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.22e-06,0.000107,0.000107,8.71e-05,0.0268,0.0268,0.0083,0.0441,0.0441,0.035,2.96e-10,2.96e-10,7.24e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 +19290000,0.982,-0.00659,-0.0102,0.186,-0.00235,-0.00425,0.0229,0.00417,-0.00232,0.0109,-1.5e-05,-5.99e-05,1.38e-06,-1.34e-05,0.000102,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.19e-06,0.000108,0.000108,8.64e-05,0.0293,0.0293,0.00835,0.0496,0.0496,0.0352,2.96e-10,2.96e-10,7.08e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 +19390000,0.982,-0.00667,-0.0101,0.186,-0.00274,-0.000986,0.0241,0.00357,-0.000596,0.00995,-1.52e-05,-5.98e-05,1.26e-06,-1.31e-05,0.000104,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.18e-06,0.000105,0.000105,8.61e-05,0.0261,0.0261,0.00831,0.0439,0.0439,0.0353,2.7e-10,2.7e-10,6.94e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 +19490000,0.982,-0.0067,-0.00999,0.186,-0.00364,-0.000894,0.0236,0.00324,-0.000678,0.00945,-1.52e-05,-5.98e-05,9.5e-07,-1.34e-05,0.000105,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.16e-06,0.000106,0.000106,8.55e-05,0.0285,0.0285,0.00835,0.0494,0.0494,0.0354,2.7e-10,2.71e-10,6.79e-10,3.01e-06,3.01e-06,5e-08,0,0,0,0,0,0,0,0 +19590000,0.982,-0.00665,-0.0101,0.187,-0.00472,-0.00389,0.0256,0.00384,-0.00179,0.00996,-1.51e-05,-5.97e-05,8.52e-07,-1.26e-05,0.000103,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.14e-06,0.000103,0.000103,8.48e-05,0.0254,0.0254,0.00827,0.0437,0.0437,0.0352,2.48e-10,2.48e-10,6.64e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +19690000,0.982,-0.00667,-0.0101,0.186,-0.00646,-0.00234,0.0241,0.00331,-0.00209,0.0096,-1.51e-05,-5.97e-05,1.01e-06,-1.27e-05,0.000103,-0.00132,0.204,0.002,0.435,0,0,0,0,0,3.12e-06,0.000104,0.000104,8.42e-05,0.0278,0.0278,0.00831,0.0492,0.0492,0.0353,2.48e-10,2.48e-10,6.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +19790000,0.982,-0.00675,-0.0102,0.187,-0.00656,-0.00103,0.0226,0.00573,-0.00172,0.00584,-1.5e-05,-5.96e-05,7.7e-07,-1.08e-05,0.000103,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.1e-06,0.000102,0.000102,8.39e-05,0.0248,0.0248,0.00827,0.0436,0.0436,0.0354,2.27e-10,2.27e-10,6.37e-10,2.99e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +19890000,0.982,-0.00677,-0.0102,0.187,-0.00666,-0.000697,0.0229,0.00503,-0.00176,0.00477,-1.5e-05,-5.96e-05,6.57e-07,-1.12e-05,0.000103,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.08e-06,0.000103,0.000103,8.33e-05,0.027,0.027,0.00831,0.0489,0.0489,0.0355,2.27e-10,2.28e-10,6.24e-10,2.99e-06,3e-06,5e-08,0,0,0,0,0,0,0,0 +19990000,0.982,-0.00678,-0.0104,0.187,-0.00639,-0.000823,0.0203,0.00542,-0.000352,0.00186,-1.51e-05,-5.95e-05,6.94e-07,-9.56e-06,0.000104,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.06e-06,0.0001,0.0001,8.26e-05,0.0241,0.0241,0.00822,0.0434,0.0434,0.0352,2.09e-10,2.09e-10,6.11e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 +20090000,0.982,-0.00679,-0.0104,0.186,-0.00592,-0.00299,0.0207,0.00479,-0.000554,0.00547,-1.51e-05,-5.95e-05,6.69e-07,-9.45e-06,0.000104,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.05e-06,0.000101,0.000101,8.24e-05,0.0263,0.0263,0.0083,0.0487,0.0487,0.0356,2.09e-10,2.09e-10,5.99e-10,2.99e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 +20190000,0.982,-0.00678,-0.0105,0.187,-0.00483,-0.00056,0.0217,0.00588,-0.000369,0.00553,-1.51e-05,-5.94e-05,4.26e-07,-8.59e-06,0.000104,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3.02e-06,9.92e-05,9.91e-05,8.17e-05,0.0235,0.0235,0.00822,0.0432,0.0432,0.0354,1.93e-10,1.93e-10,5.87e-10,2.98e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 +20290000,0.982,-0.00677,-0.0105,0.186,-0.00809,-0.00158,0.0219,0.00526,-0.000415,0.00649,-1.51e-05,-5.94e-05,3.45e-07,-8.72e-06,0.000104,-0.00131,0.204,0.002,0.435,0,0,0,0,0,3e-06,9.98e-05,9.98e-05,8.12e-05,0.0256,0.0256,0.00825,0.0484,0.0484,0.0355,1.93e-10,1.93e-10,5.74e-10,2.98e-06,2.99e-06,5e-08,0,0,0,0,0,0,0,0 +20390000,0.982,-0.00674,-0.0105,0.187,-0.00872,-0.00052,0.0222,0.00622,-0.000255,0.00795,-1.51e-05,-5.93e-05,4.9e-07,-7.53e-06,0.000104,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.99e-06,9.79e-05,9.79e-05,8.09e-05,0.023,0.023,0.00821,0.043,0.043,0.0356,1.78e-10,1.78e-10,5.64e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 +20490000,0.982,-0.00673,-0.0105,0.186,-0.0134,-0.00142,0.0221,0.0051,-0.000325,0.00648,-1.51e-05,-5.93e-05,4.69e-07,-7.8e-06,0.000104,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.97e-06,9.86e-05,9.85e-05,8.03e-05,0.025,0.025,0.00824,0.0482,0.0482,0.0356,1.78e-10,1.78e-10,5.52e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 +20590000,0.982,-0.00672,-0.0105,0.186,-0.0125,-0.00247,0.0217,0.00621,-0.000282,0.00509,-1.5e-05,-5.92e-05,7.26e-07,-6.21e-06,0.000104,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.95e-06,9.68e-05,9.67e-05,7.97e-05,0.0224,0.0224,0.00816,0.0429,0.0429,0.0354,1.65e-10,1.65e-10,5.41e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 +20690000,0.982,-0.00663,-0.0105,0.186,-0.0142,-0.0012,0.0227,0.00489,-0.000413,0.0059,-1.5e-05,-5.92e-05,5.08e-07,-6.4e-06,0.000104,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.93e-06,9.74e-05,9.73e-05,7.94e-05,0.0244,0.0244,0.00823,0.0479,0.0479,0.0358,1.65e-10,1.65e-10,5.32e-10,2.98e-06,2.98e-06,5e-08,0,0,0,0,0,0,0,0 +20790000,0.982,-0.00604,-0.0104,0.186,-0.0167,0.00127,0.00765,0.00408,-0.000311,0.00478,-1.5e-05,-5.92e-05,5.89e-07,-5.52e-06,0.000104,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.91e-06,9.57e-05,9.57e-05,7.89e-05,0.0219,0.0219,0.00815,0.0427,0.0427,0.0356,1.53e-10,1.53e-10,5.21e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 +20890000,0.982,0.00309,-0.00641,0.186,-0.023,0.0133,-0.111,0.00204,0.000461,-0.00116,-1.5e-05,-5.92e-05,5.94e-07,-5.51e-06,0.000104,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.88e-06,9.63e-05,9.62e-05,7.83e-05,0.0241,0.0241,0.00818,0.0477,0.0477,0.0356,1.53e-10,1.53e-10,5.1e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 +20990000,0.982,0.00642,-0.00298,0.186,-0.0338,0.0313,-0.25,0.00142,0.00105,-0.0158,-1.49e-05,-5.91e-05,5.54e-07,-3.52e-06,0.000101,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.87e-06,9.46e-05,9.46e-05,7.78e-05,0.0219,0.0219,0.0081,0.0425,0.0425,0.0354,1.42e-10,1.42e-10,5e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 +21090000,0.982,0.00483,-0.00336,0.187,-0.0475,0.0474,-0.368,-0.00264,0.00503,-0.0461,-1.49e-05,-5.91e-05,5.45e-07,-3.52e-06,0.000101,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.86e-06,9.52e-05,9.51e-05,7.75e-05,0.0241,0.0241,0.00817,0.0475,0.0475,0.0357,1.42e-10,1.42e-10,4.91e-10,2.97e-06,2.97e-06,5e-08,0,0,0,0,0,0,0,0 +21190000,0.982,0.00195,-0.00503,0.187,-0.0512,0.0516,-0.495,-0.00219,0.00417,-0.082,-1.46e-05,-5.89e-05,6.11e-07,8.42e-07,9.21e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.85e-06,9.34e-05,9.33e-05,7.69e-05,0.0219,0.0219,0.00809,0.0424,0.0424,0.0355,1.32e-10,1.32e-10,4.82e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 +21290000,0.982,-0.00021,-0.00636,0.187,-0.0516,0.0553,-0.625,-0.00732,0.00954,-0.14,-1.46e-05,-5.89e-05,3.22e-07,9.54e-07,9.23e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.84e-06,9.39e-05,9.38e-05,7.64e-05,0.0241,0.0241,0.00813,0.0474,0.0474,0.0355,1.32e-10,1.33e-10,4.72e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 +21390000,0.982,-0.0017,-0.00708,0.187,-0.0469,0.0511,-0.75,-0.00607,0.0118,-0.205,-1.44e-05,-5.88e-05,3.31e-07,6.13e-06,8.68e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.83e-06,9.2e-05,9.2e-05,7.61e-05,0.0219,0.0219,0.00809,0.0423,0.0423,0.0356,1.23e-10,1.23e-10,4.64e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 +21490000,0.982,-0.0025,-0.00749,0.187,-0.0427,0.0486,-0.886,-0.0106,0.0168,-0.29,-1.44e-05,-5.88e-05,4.58e-07,5.88e-06,8.69e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.82e-06,9.25e-05,9.24e-05,7.56e-05,0.024,0.024,0.00812,0.0473,0.0473,0.0356,1.23e-10,1.23e-10,4.55e-10,2.96e-06,2.96e-06,5e-08,0,0,0,0,0,0,0,0 +21590000,0.982,-0.003,-0.00751,0.187,-0.0341,0.044,-1.01,-0.00905,0.0172,-0.379,-1.43e-05,-5.87e-05,5.75e-07,8.67e-06,8.3e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.8e-06,9.05e-05,9.05e-05,7.51e-05,0.0218,0.0218,0.00805,0.0422,0.0422,0.0354,1.15e-10,1.15e-10,4.47e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 +21690000,0.982,-0.00333,-0.00737,0.187,-0.0324,0.0401,-1.14,-0.0124,0.0214,-0.493,-1.43e-05,-5.87e-05,7.49e-07,8.26e-06,8.33e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.8e-06,9.1e-05,9.09e-05,7.48e-05,0.0238,0.0238,0.00812,0.0472,0.0472,0.0358,1.15e-10,1.15e-10,4.39e-10,2.95e-06,2.95e-06,5e-08,0,0,0,0,0,0,0,0 +21790000,0.982,-0.00371,-0.00758,0.187,-0.024,0.0338,-1.27,-0.005,0.0186,-0.612,-1.41e-05,-5.85e-05,9.7e-07,1.49e-05,7.95e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.78e-06,8.89e-05,8.89e-05,7.43e-05,0.0216,0.0216,0.00804,0.0421,0.0421,0.0355,1.07e-10,1.07e-10,4.31e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0 +21890000,0.982,-0.004,-0.00772,0.187,-0.0209,0.0297,-1.39,-0.00725,0.0218,-0.751,-1.41e-05,-5.85e-05,8.5e-07,1.46e-05,7.99e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.76e-06,8.93e-05,8.93e-05,7.38e-05,0.0236,0.0236,0.00808,0.0471,0.0471,0.0355,1.07e-10,1.07e-10,4.23e-10,2.94e-06,2.94e-06,5e-08,0,0,0,0,0,0,0,0 +21990000,0.982,-0.00471,-0.00802,0.187,-0.017,0.0237,-1.37,-0.00152,0.0173,-0.887,-1.4e-05,-5.85e-05,9.55e-07,1.38e-05,8.02e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.75e-06,8.73e-05,8.73e-05,7.35e-05,0.021,0.021,0.00805,0.042,0.042,0.0356,1e-10,1e-10,4.16e-10,2.92e-06,2.92e-06,5e-08,0,0,0,0,0,0,0,0 +22090000,0.982,-0.00543,-0.00882,0.187,-0.0147,0.0199,-1.36,-0.00315,0.0194,-1.03,-1.4e-05,-5.85e-05,1.15e-06,1.35e-05,8.05e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.73e-06,8.77e-05,8.76e-05,7.3e-05,0.0226,0.0226,0.00808,0.0469,0.0469,0.0357,1e-10,1.01e-10,4.08e-10,2.92e-06,2.92e-06,5e-08,0,0,0,0,0,0,0,0 +22190000,0.982,-0.00589,-0.00909,0.187,-0.00602,0.0141,-1.37,0.00485,0.0134,-1.17,-1.39e-05,-5.84e-05,1.31e-06,1.37e-05,8.15e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.71e-06,8.58e-05,8.58e-05,7.26e-05,0.0203,0.0203,0.00801,0.0419,0.0419,0.0354,9.42e-11,9.43e-11,4.01e-10,2.91e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 +22290000,0.982,-0.0066,-0.00934,0.187,-0.000933,0.00892,-1.37,0.00449,0.0146,-1.31,-1.39e-05,-5.84e-05,1.22e-06,1.34e-05,8.19e-05,-0.00132,0.204,0.002,0.435,0,0,0,0,0,2.7e-06,8.62e-05,8.61e-05,7.21e-05,0.0218,0.0218,0.00804,0.0467,0.0467,0.0354,9.43e-11,9.44e-11,3.93e-10,2.91e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 +22390000,0.982,-0.00696,-0.00951,0.187,0.00446,-0.000694,-1.37,0.012,0.00471,-1.45,-1.38e-05,-5.85e-05,1.02e-06,9.51e-06,8.05e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.69e-06,8.45e-05,8.45e-05,7.18e-05,0.0196,0.0196,0.00801,0.0418,0.0418,0.0355,8.87e-11,8.88e-11,3.87e-10,2.91e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 +22490000,0.982,-0.0071,-0.00997,0.187,0.0083,-0.00663,-1.37,0.0126,0.0043,-1.59,-1.38e-05,-5.85e-05,8.76e-07,9.48e-06,8.05e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.67e-06,8.48e-05,8.48e-05,7.14e-05,0.021,0.021,0.00805,0.0465,0.0465,0.0355,8.88e-11,8.89e-11,3.8e-10,2.91e-06,2.91e-06,5e-08,0,0,0,0,0,0,0,0 +22590000,0.982,-0.00703,-0.0106,0.187,0.0178,-0.0157,-1.37,0.0247,-0.00482,-1.74,-1.37e-05,-5.84e-05,1.05e-06,1.21e-05,7.97e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.66e-06,8.34e-05,8.33e-05,7.09e-05,0.0189,0.0189,0.00798,0.0416,0.0416,0.0353,8.38e-11,8.39e-11,3.73e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22690000,0.982,-0.00694,-0.0108,0.187,0.0199,-0.0201,-1.38,0.0266,-0.00665,-1.88,-1.37e-05,-5.84e-05,9.61e-07,1.16e-05,8.02e-05,-0.00131,0.204,0.002,0.435,0,0,0,0,0,2.66e-06,8.37e-05,8.36e-05,7.07e-05,0.0204,0.0204,0.00806,0.0462,0.0462,0.0356,8.39e-11,8.4e-11,3.67e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0 +22790000,0.982,-0.00694,-0.0112,0.187,0.0263,-0.0281,-1.38,0.037,-0.0168,-2.02,-1.37e-05,-5.84e-05,8.29e-07,9.7e-06,8.1e-05,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.63e-06,8.23e-05,8.23e-05,7.02e-05,0.0184,0.0184,0.00798,0.0414,0.0414,0.0354,7.94e-11,7.94e-11,3.61e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0 +22890000,0.982,-0.0071,-0.0115,0.187,0.0297,-0.0336,-1.38,0.0398,-0.0198,-2.17,-1.37e-05,-5.84e-05,1.02e-06,9.43e-06,8.15e-05,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.61e-06,8.26e-05,8.26e-05,6.98e-05,0.0197,0.0197,0.00802,0.0459,0.0459,0.0354,7.95e-11,7.95e-11,3.54e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0 +22990000,0.982,-0.00706,-0.0119,0.186,0.0343,-0.0389,-1.39,0.0499,-0.0305,-2.32,-1.37e-05,-5.84e-05,1.2e-06,7.29e-06,8.25e-05,-0.0013,0.204,0.002,0.435,0,0,0,0,0,2.59e-06,8.14e-05,8.14e-05,6.96e-05,0.0178,0.0178,0.00799,0.0412,0.0412,0.0355,7.54e-11,7.55e-11,3.49e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0 +23090000,0.982,-0.00708,-0.0122,0.186,0.0393,-0.0436,-1.38,0.0536,-0.0346,-2.46,-1.37e-05,-5.84e-05,1.2e-06,7.13e-06,8.27e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,2.57e-06,8.17e-05,8.16e-05,6.91e-05,0.0192,0.0192,0.00803,0.0456,0.0456,0.0355,7.55e-11,7.56e-11,3.43e-10,2.89e-06,2.89e-06,5e-08,0,0,0,0,0,0,0,0 +23190000,0.982,-0.0071,-0.0125,0.186,0.0459,-0.0453,-1.39,0.0653,-0.0449,-2.6,-1.36e-05,-5.84e-05,1.09e-06,6.68e-06,8.23e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,2.55e-06,8.06e-05,8.06e-05,6.87e-05,0.0174,0.0174,0.00796,0.041,0.041,0.0353,7.18e-11,7.19e-11,3.37e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 +23290000,0.983,-0.00757,-0.0126,0.186,0.0508,-0.0502,-1.38,0.0701,-0.0497,-2.75,-1.36e-05,-5.84e-05,1.15e-06,6.33e-06,8.29e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,2.53e-06,8.09e-05,8.08e-05,6.85e-05,0.0186,0.0186,0.00804,0.0454,0.0454,0.0356,7.19e-11,7.2e-11,3.32e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 +23390000,0.983,-0.00749,-0.0127,0.186,0.0564,-0.0526,-1.38,0.0812,-0.055,-2.88,-1.37e-05,-5.84e-05,9.59e-07,7.64e-06,8.49e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,2.51e-06,7.99e-05,7.99e-05,6.8e-05,0.0169,0.0169,0.00797,0.0408,0.0408,0.0354,6.85e-11,6.86e-11,3.26e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 +23490000,0.983,-0.00757,-0.013,0.185,0.0606,-0.0549,-1.38,0.087,-0.0604,-3.03,-1.37e-05,-5.84e-05,1.11e-06,7.41e-06,8.53e-05,-0.00129,0.204,0.002,0.435,0,0,0,0,0,2.5e-06,8.01e-05,8.01e-05,6.76e-05,0.0182,0.0182,0.00801,0.0451,0.0451,0.0354,6.86e-11,6.87e-11,3.21e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 +23590000,0.983,-0.00784,-0.0129,0.185,0.0637,-0.0579,-1.38,0.0948,-0.0703,-3.17,-1.38e-05,-5.85e-05,1.18e-06,5.71e-06,8.51e-05,-0.00128,0.204,0.002,0.435,0,0,0,0,0,2.48e-06,7.93e-05,7.93e-05,6.72e-05,0.0165,0.0165,0.00794,0.0405,0.0405,0.0352,6.56e-11,6.56e-11,3.15e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 +23690000,0.983,-0.00849,-0.0135,0.185,0.062,-0.0603,-1.28,0.101,-0.0763,-3.31,-1.38e-05,-5.85e-05,1.32e-06,5.7e-06,8.53e-05,-0.00128,0.204,0.002,0.435,0,0,0,0,0,2.48e-06,7.95e-05,7.95e-05,6.7e-05,0.0176,0.0176,0.00802,0.0448,0.0448,0.0355,6.57e-11,6.57e-11,3.11e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 +23790000,0.983,-0.0103,-0.0163,0.185,0.0575,-0.0578,-0.948,0.111,-0.081,-3.43,-1.39e-05,-5.84e-05,1.48e-06,6.93e-06,8.59e-05,-0.00128,0.204,0.002,0.435,0,0,0,0,0,2.47e-06,7.88e-05,7.88e-05,6.66e-05,0.0157,0.0157,0.00795,0.0403,0.0403,0.0353,6.29e-11,6.29e-11,3.05e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 +23890000,0.982,-0.0137,-0.0204,0.185,0.0538,-0.0585,-0.516,0.116,-0.0868,-3.5,-1.39e-05,-5.84e-05,1.5e-06,6.85e-06,8.61e-05,-0.00128,0.204,0.002,0.435,0,0,0,0,0,2.47e-06,7.9e-05,7.9e-05,6.62e-05,0.0165,0.0165,0.00799,0.0444,0.0444,0.0353,6.3e-11,6.3e-11,3e-10,2.88e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 +23990000,0.982,-0.0158,-0.0228,0.185,0.0563,-0.058,-0.133,0.125,-0.0894,-3.56,-1.4e-05,-5.84e-05,1.49e-06,7.57e-06,8.56e-05,-0.00126,0.204,0.002,0.435,0,0,0,0,0,2.47e-06,7.87e-05,7.86e-05,6.6e-05,0.015,0.015,0.00796,0.04,0.04,0.0354,6.05e-11,6.05e-11,2.96e-10,2.87e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 +24090000,0.982,-0.0153,-0.0216,0.185,0.0632,-0.0664,0.0994,0.131,-0.0956,-3.56,-1.4e-05,-5.84e-05,1.39e-06,7.64e-06,8.53e-05,-0.00126,0.204,0.002,0.435,0,0,0,0,0,2.45e-06,7.89e-05,7.88e-05,6.56e-05,0.016,0.016,0.008,0.0439,0.0439,0.0354,6.06e-11,6.06e-11,2.91e-10,2.87e-06,2.88e-06,5e-08,0,0,0,0,0,0,0,0 +24190000,0.983,-0.0125,-0.0179,0.185,0.0741,-0.0717,0.0865,0.138,-0.0998,-3.57,-1.4e-05,-5.84e-05,1.48e-06,1.1e-05,8.16e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.42e-06,7.87e-05,7.86e-05,6.52e-05,0.0148,0.0148,0.00794,0.0396,0.0396,0.0352,5.83e-11,5.84e-11,2.87e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0 +24290000,0.983,-0.0101,-0.0145,0.185,0.0779,-0.0751,0.0649,0.146,-0.107,-3.56,-1.4e-05,-5.84e-05,1.49e-06,1.09e-05,8.18e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.4e-06,7.89e-05,7.88e-05,6.5e-05,0.0159,0.0159,0.00802,0.0435,0.0435,0.0355,5.84e-11,5.85e-11,2.82e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0 +24390000,0.983,-0.00923,-0.0136,0.185,0.0714,-0.0697,0.0812,0.153,-0.108,-3.56,-1.42e-05,-5.84e-05,1.69e-06,1.14e-05,7.31e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.38e-06,7.87e-05,7.87e-05,6.46e-05,0.0146,0.0146,0.00795,0.0393,0.0393,0.0353,5.64e-11,5.64e-11,2.78e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0 +24490000,0.983,-0.00947,-0.0137,0.185,0.0669,-0.0666,0.0791,0.16,-0.115,-3.55,-1.42e-05,-5.84e-05,1.94e-06,1.16e-05,7.3e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.37e-06,7.89e-05,7.89e-05,6.42e-05,0.0157,0.0157,0.00799,0.0432,0.0432,0.0353,5.65e-11,5.65e-11,2.74e-10,2.87e-06,2.87e-06,5e-08,0,0,0,0,0,0,0,0 +24590000,0.983,-0.0102,-0.0137,0.185,0.0635,-0.0626,0.0748,0.163,-0.112,-3.54,-1.44e-05,-5.84e-05,1.93e-06,9.4e-06,6.5e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.37e-06,7.89e-05,7.88e-05,6.4e-05,0.0145,0.0145,0.00797,0.0391,0.0391,0.0354,5.45e-11,5.45e-11,2.7e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0 +24690000,0.983,-0.0106,-0.0135,0.185,0.0613,-0.062,0.0743,0.169,-0.118,-3.53,-1.44e-05,-5.84e-05,1.93e-06,9.42e-06,6.49e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.35e-06,7.91e-05,7.9e-05,6.36e-05,0.0156,0.0156,0.00801,0.043,0.043,0.0354,5.46e-11,5.46e-11,2.65e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0 +24790000,0.983,-0.0107,-0.0129,0.185,0.058,-0.0596,0.0658,0.172,-0.114,-3.53,-1.46e-05,-5.84e-05,1.97e-06,9.22e-06,5.82e-05,-0.00124,0.204,0.002,0.435,0,0,0,0,0,2.34e-06,7.9e-05,7.9e-05,6.33e-05,0.0144,0.0144,0.00794,0.0389,0.0389,0.0352,5.28e-11,5.28e-11,2.61e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0 +24890000,0.983,-0.0105,-0.0124,0.185,0.0564,-0.063,0.0552,0.177,-0.12,-3.53,-1.46e-05,-5.84e-05,2.05e-06,9.06e-06,5.85e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.32e-06,7.92e-05,7.92e-05,6.29e-05,0.0155,0.0155,0.00799,0.0427,0.0427,0.0352,5.29e-11,5.29e-11,2.57e-10,2.86e-06,2.86e-06,5e-08,0,0,0,0,0,0,0,0 +24990000,0.983,-0.0103,-0.0121,0.185,0.0475,-0.0587,0.0479,0.177,-0.112,-3.52,-1.48e-05,-5.83e-05,2.05e-06,7.2e-06,5.01e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.32e-06,7.92e-05,7.92e-05,6.27e-05,0.0144,0.0144,0.00796,0.0388,0.0388,0.0353,5.12e-11,5.12e-11,2.54e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 +25090000,0.983,-0.0106,-0.0122,0.185,0.044,-0.0578,0.0452,0.182,-0.117,-3.52,-1.48e-05,-5.83e-05,2.02e-06,7.19e-06,5.04e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.31e-06,7.94e-05,7.94e-05,6.24e-05,0.0154,0.0154,0.00801,0.0426,0.0426,0.0353,5.13e-11,5.13e-11,2.5e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 +25190000,0.983,-0.0108,-0.012,0.185,0.0391,-0.0512,0.045,0.182,-0.109,-3.52,-1.5e-05,-5.83e-05,1.91e-06,4.73e-06,4.44e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.3e-06,7.94e-05,7.94e-05,6.2e-05,0.0143,0.0143,0.00794,0.0386,0.0386,0.0351,4.96e-11,4.96e-11,2.46e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 +25290000,0.983,-0.0109,-0.0114,0.185,0.0342,-0.0525,0.0397,0.186,-0.114,-3.52,-1.5e-05,-5.83e-05,1.75e-06,4.93e-06,4.43e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.29e-06,7.96e-05,7.96e-05,6.18e-05,0.0153,0.0153,0.00802,0.0424,0.0424,0.0355,4.97e-11,4.97e-11,2.43e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 +25390000,0.983,-0.011,-0.0112,0.185,0.0259,-0.0454,0.038,0.181,-0.103,-3.52,-1.52e-05,-5.83e-05,1.74e-06,3.62e-06,3.59e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.28e-06,7.96e-05,7.96e-05,6.15e-05,0.0142,0.0142,0.00796,0.0385,0.0385,0.0352,4.82e-11,4.82e-11,2.39e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 +25490000,0.983,-0.011,-0.0109,0.185,0.0208,-0.0451,0.0372,0.184,-0.108,-3.52,-1.52e-05,-5.83e-05,1.67e-06,3.75e-06,3.59e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.27e-06,7.98e-05,7.98e-05,6.11e-05,0.0152,0.0152,0.008,0.0423,0.0423,0.0353,4.83e-11,4.83e-11,2.36e-10,2.85e-06,2.85e-06,5e-08,0,0,0,0,0,0,0,0 +25590000,0.983,-0.0112,-0.0107,0.185,0.0155,-0.041,0.0381,0.18,-0.0992,-3.52,-1.54e-05,-5.83e-05,1.57e-06,2.87e-06,3.18e-05,-0.00123,0.204,0.002,0.435,0,0,0,0,0,2.26e-06,7.99e-05,7.98e-05,6.09e-05,0.0141,0.0141,0.00798,0.0384,0.0384,0.0353,4.69e-11,4.69e-11,2.32e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +25690000,0.983,-0.0106,-0.0103,0.185,0.0146,-0.0401,0.0272,0.181,-0.103,-3.52,-1.54e-05,-5.83e-05,1.57e-06,2.97e-06,3.18e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.25e-06,8.01e-05,8e-05,6.06e-05,0.0151,0.0151,0.00802,0.0422,0.0422,0.0354,4.7e-11,4.7e-11,2.29e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +25790000,0.983,-0.0104,-0.00964,0.185,0.00354,-0.0318,0.0264,0.174,-0.0936,-3.52,-1.56e-05,-5.83e-05,1.52e-06,2.49e-06,2.63e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.23e-06,8.01e-05,8e-05,6.03e-05,0.014,0.014,0.00796,0.0383,0.0383,0.0351,4.56e-11,4.56e-11,2.26e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +25890000,0.983,-0.0105,-0.00973,0.186,-0.00218,-0.0296,0.0287,0.174,-0.0966,-3.52,-1.56e-05,-5.83e-05,1.31e-06,2.74e-06,2.61e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.23e-06,8.03e-05,8.02e-05,6.01e-05,0.015,0.015,0.00804,0.0421,0.0421,0.0355,4.57e-11,4.57e-11,2.23e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +25990000,0.983,-0.0105,-0.00983,0.186,-0.0112,-0.0228,0.0219,0.163,-0.087,-3.51,-1.57e-05,-5.83e-05,1.24e-06,4.86e-06,2.08e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.21e-06,8.03e-05,8.03e-05,5.98e-05,0.0139,0.0139,0.00798,0.0382,0.0382,0.0353,4.44e-11,4.44e-11,2.2e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +26090000,0.983,-0.0102,-0.00982,0.185,-0.0164,-0.0226,0.0204,0.162,-0.0893,-3.51,-1.57e-05,-5.83e-05,1.33e-06,4.88e-06,2.08e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.2e-06,8.05e-05,8.05e-05,5.94e-05,0.0149,0.0149,0.00802,0.042,0.042,0.0353,4.45e-11,4.45e-11,2.16e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +26190000,0.983,-0.0101,-0.0103,0.185,-0.0229,-0.0159,0.0153,0.151,-0.0821,-3.52,-1.58e-05,-5.83e-05,1.38e-06,5.45e-06,1.82e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.19e-06,8.05e-05,8.05e-05,5.91e-05,0.0138,0.0138,0.00795,0.0382,0.0382,0.0351,4.33e-11,4.33e-11,2.13e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +26290000,0.983,-0.0101,-0.0106,0.185,-0.0244,-0.0146,0.00942,0.149,-0.0836,-3.52,-1.58e-05,-5.83e-05,1.25e-06,5.63e-06,1.8e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.18e-06,8.07e-05,8.07e-05,5.9e-05,0.0148,0.0148,0.00804,0.0419,0.0419,0.0354,4.34e-11,4.34e-11,2.11e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +26390000,0.983,-0.00953,-0.0105,0.185,-0.0305,-0.0074,0.0132,0.136,-0.0755,-3.52,-1.59e-05,-5.84e-05,1.12e-06,8.09e-06,1.47e-05,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.17e-06,8.07e-05,8.07e-05,5.86e-05,0.0138,0.0138,0.00797,0.0381,0.0381,0.0352,4.22e-11,4.22e-11,2.08e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +26490000,0.983,-0.00929,-0.0104,0.185,-0.0337,-0.0043,0.0226,0.132,-0.076,-3.52,-1.59e-05,-5.84e-05,1.06e-06,8.08e-06,1.47e-05,-0.00122,0.204,0.002,0.435,0,0,0,0,0,2.15e-06,8.09e-05,8.09e-05,5.83e-05,0.0147,0.0147,0.00802,0.0418,0.0418,0.0352,4.23e-11,4.23e-11,2.05e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +26590000,0.983,-0.00873,-0.0107,0.185,-0.0353,0.00373,0.0223,0.122,-0.0688,-3.52,-1.59e-05,-5.84e-05,9.36e-07,9.02e-06,1.21e-05,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.15e-06,8.09e-05,8.09e-05,5.82e-05,0.0137,0.0137,0.00799,0.038,0.038,0.0353,4.12e-11,4.12e-11,2.02e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +26690000,0.983,-0.00859,-0.0104,0.185,-0.0372,0.00877,0.0206,0.118,-0.0682,-3.51,-1.59e-05,-5.84e-05,7.38e-07,9.24e-06,1.19e-05,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.14e-06,8.11e-05,8.1e-05,5.79e-05,0.0147,0.0147,0.00803,0.0417,0.0417,0.0354,4.13e-11,4.13e-11,1.99e-10,2.84e-06,2.84e-06,5e-08,0,0,0,0,0,0,0,0 +26790000,0.983,-0.00838,-0.00984,0.185,-0.0446,0.0124,0.0196,0.106,-0.0626,-3.52,-1.6e-05,-5.84e-05,6.41e-07,1.13e-05,9.99e-06,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.12e-06,8.11e-05,8.1e-05,5.76e-05,0.0136,0.0136,0.00797,0.0379,0.0379,0.0351,4.03e-11,4.03e-11,1.97e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +26890000,0.983,-0.00773,-0.00999,0.185,-0.0503,0.0156,0.0146,0.101,-0.0612,-3.52,-1.6e-05,-5.84e-05,6.85e-07,1.14e-05,9.89e-06,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.12e-06,8.13e-05,8.12e-05,5.74e-05,0.0146,0.0146,0.00805,0.0416,0.0416,0.0355,4.04e-11,4.04e-11,1.94e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +26990000,0.983,-0.0072,-0.0104,0.185,-0.0573,0.0223,0.0135,0.0885,-0.055,-3.52,-1.6e-05,-5.85e-05,6.02e-07,1.32e-05,7.45e-06,-0.00121,0.204,0.002,0.435,0,0,0,0,0,2.1e-06,8.12e-05,8.12e-05,5.71e-05,0.0135,0.0135,0.00799,0.0379,0.0379,0.0352,3.94e-11,3.94e-11,1.92e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27090000,0.983,-0.00705,-0.0107,0.185,-0.0595,0.0293,0.016,0.0826,-0.0524,-3.53,-1.6e-05,-5.85e-05,5.42e-07,1.36e-05,6.75e-06,-0.0012,0.204,0.002,0.435,0,0,0,0,0,2.09e-06,8.14e-05,8.14e-05,5.68e-05,0.0145,0.0145,0.00803,0.0415,0.0415,0.0353,3.95e-11,3.95e-11,1.89e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27190000,0.983,-0.00708,-0.0106,0.185,-0.0658,0.0348,0.0177,0.0717,-0.0462,-3.53,-1.59e-05,-5.85e-05,4.75e-07,1.45e-05,5.23e-06,-0.0012,0.204,0.002,0.435,0,0,0,0,0,2.09e-06,8.14e-05,8.13e-05,5.67e-05,0.0135,0.0135,0.008,0.0378,0.0378,0.0354,3.85e-11,3.85e-11,1.87e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27290000,0.983,-0.00726,-0.0116,0.185,-0.0722,0.0407,0.131,0.0648,-0.0424,-3.53,-1.59e-05,-5.85e-05,4.33e-07,1.47e-05,4.87e-06,-0.0012,0.204,0.002,0.435,0,0,0,0,0,2.08e-06,8.16e-05,8.15e-05,5.64e-05,0.0143,0.0143,0.00805,0.0414,0.0414,0.0354,3.86e-11,3.86e-11,1.84e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27390000,0.983,-0.00864,-0.0141,0.185,-0.077,0.0466,0.454,0.0553,-0.0352,-3.51,-1.59e-05,-5.84e-05,3.89e-07,1.47e-05,2.42e-06,-0.0012,0.204,0.002,0.435,0,0,0,0,0,2.07e-06,8.15e-05,8.15e-05,5.61e-05,0.0131,0.0131,0.00798,0.0377,0.0377,0.0352,3.77e-11,3.77e-11,1.82e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27490000,0.982,-0.00999,-0.016,0.185,-0.0798,0.052,0.765,0.0474,-0.0302,-3.45,-1.59e-05,-5.84e-05,2.14e-07,1.44e-05,2.29e-06,-0.00119,0.204,0.002,0.435,0,0,0,0,0,2.07e-06,8.17e-05,8.17e-05,5.58e-05,0.0139,0.0139,0.00802,0.0413,0.0413,0.0352,3.78e-11,3.78e-11,1.79e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27590000,0.983,-0.00986,-0.0148,0.185,-0.0737,0.0545,0.859,0.039,-0.026,-3.38,-1.59e-05,-5.84e-05,1.83e-07,1.35e-05,2.34e-06,-0.00118,0.204,0.002,0.435,0,0,0,0,0,2.06e-06,8.18e-05,8.17e-05,5.56e-05,0.0129,0.0129,0.008,0.0376,0.0376,0.0353,3.7e-11,3.7e-11,1.77e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27690000,0.983,-0.00864,-0.0119,0.185,-0.0706,0.0511,0.762,0.0319,-0.0207,-3.3,-1.59e-05,-5.84e-05,1.72e-07,1.4e-05,1.38e-06,-0.00118,0.204,0.002,0.435,0,0,0,0,0,2.04e-06,8.2e-05,8.19e-05,5.54e-05,0.0138,0.0138,0.00804,0.0412,0.0412,0.0354,3.71e-11,3.71e-11,1.75e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27790000,0.983,-0.00731,-0.0104,0.185,-0.0699,0.0489,0.755,0.0257,-0.0181,-3.23,-1.58e-05,-5.84e-05,1.72e-07,1.15e-05,7.75e-06,-0.00118,0.204,0.002,0.435,0,0,0,0,0,2.03e-06,8.2e-05,8.2e-05,5.51e-05,0.0129,0.0129,0.00797,0.0375,0.0375,0.0351,3.64e-11,3.64e-11,1.73e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27890000,0.983,-0.00694,-0.0105,0.185,-0.0769,0.0559,0.794,0.0183,-0.0129,-3.16,-1.58e-05,-5.84e-05,1.36e-07,1.17e-05,7.22e-06,-0.00118,0.204,0.002,0.435,0,0,0,0,0,2.02e-06,8.22e-05,8.22e-05,5.5e-05,0.0138,0.0138,0.00806,0.0411,0.0411,0.0355,3.65e-11,3.65e-11,1.71e-10,2.83e-06,2.83e-06,5e-08,0,0,0,0,0,0,0,0 +27990000,0.983,-0.00739,-0.0109,0.185,-0.0772,0.0574,0.781,0.0129,-0.0111,-3.09,-1.57e-05,-5.83e-05,9.67e-08,9.44e-06,1.12e-05,-0.00117,0.204,0.002,0.435,0,0,0,0,0,2.02e-06,8.23e-05,8.22e-05,5.47e-05,0.0128,0.0128,0.00799,0.0375,0.0375,0.0352,3.58e-11,3.57e-11,1.68e-10,2.83e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +28090000,0.983,-0.00766,-0.0109,0.185,-0.0808,0.0581,0.787,0.00504,-0.00526,-3.01,-1.57e-05,-5.83e-05,1.93e-07,9.44e-06,1.11e-05,-0.00117,0.204,0.002,0.435,0,0,0,0,0,2.01e-06,8.25e-05,8.24e-05,5.44e-05,0.0137,0.0137,0.00803,0.041,0.041,0.0353,3.59e-11,3.58e-11,1.66e-10,2.83e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +28190000,0.983,-0.00709,-0.0111,0.185,-0.0814,0.0547,0.793,-0.00163,-0.0047,-2.93,-1.56e-05,-5.83e-05,1.51e-07,8.33e-06,1.53e-05,-0.00117,0.204,0.002,0.435,0,0,0,0,0,2e-06,8.25e-05,8.25e-05,5.43e-05,0.0128,0.0128,0.008,0.0374,0.0374,0.0354,3.52e-11,3.52e-11,1.64e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +28290000,0.983,-0.00659,-0.0114,0.185,-0.0867,0.0582,0.792,-0.01,0.000996,-2.86,-1.56e-05,-5.83e-05,2.29e-07,8.85e-06,1.43e-05,-0.00116,0.204,0.002,0.435,0,0,0,0,0,1.99e-06,8.27e-05,8.27e-05,5.4e-05,0.0137,0.0137,0.00804,0.0409,0.0409,0.0354,3.53e-11,3.52e-11,1.62e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +28390000,0.983,-0.00659,-0.012,0.185,-0.0872,0.061,0.793,-0.0148,0.00405,-2.79,-1.55e-05,-5.82e-05,2.76e-07,6.86e-06,1.6e-05,-0.00116,0.204,0.002,0.435,0,0,0,0,0,1.99e-06,8.28e-05,8.27e-05,5.37e-05,0.0127,0.0127,0.00798,0.0373,0.0373,0.0352,3.46e-11,3.46e-11,1.6e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +28490000,0.983,-0.0069,-0.0125,0.185,-0.0889,0.0651,0.793,-0.0235,0.0103,-2.71,-1.55e-05,-5.82e-05,2.38e-07,7.19e-06,1.5e-05,-0.00116,0.204,0.002,0.435,0,0,0,0,0,1.98e-06,8.3e-05,8.29e-05,5.36e-05,0.0136,0.0136,0.00806,0.0408,0.0408,0.0355,3.47e-11,3.47e-11,1.59e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +28590000,0.983,-0.00693,-0.0125,0.185,-0.0823,0.0602,0.791,-0.0269,0.00815,-2.64,-1.53e-05,-5.82e-05,2.78e-07,6.13e-06,1.87e-05,-0.00116,0.204,0.002,0.435,0,0,0,0,0,1.97e-06,8.3e-05,8.29e-05,5.33e-05,0.0127,0.0127,0.00799,0.0372,0.0372,0.0353,3.4e-11,3.4e-11,1.57e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +28690000,0.983,-0.0067,-0.0118,0.185,-0.0826,0.0611,0.791,-0.0352,0.0142,-2.57,-1.53e-05,-5.82e-05,2.16e-07,6.4e-06,1.78e-05,-0.00115,0.204,0.002,0.435,0,0,0,0,0,1.96e-06,8.32e-05,8.31e-05,5.31e-05,0.0136,0.0136,0.00803,0.0407,0.0407,0.0353,3.41e-11,3.41e-11,1.55e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +28790000,0.983,-0.00603,-0.0116,0.185,-0.0792,0.0612,0.789,-0.0377,0.0161,-2.49,-1.52e-05,-5.81e-05,2.88e-07,5.68e-06,1.78e-05,-0.00115,0.204,0.002,0.435,0,0,0,0,0,1.95e-06,8.32e-05,8.31e-05,5.28e-05,0.0127,0.0127,0.00796,0.0372,0.0372,0.0351,3.35e-11,3.35e-11,1.53e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +28890000,0.983,-0.00587,-0.0114,0.185,-0.0835,0.0633,0.787,-0.0458,0.0223,-2.42,-1.52e-05,-5.81e-05,3.54e-07,6.13e-06,1.68e-05,-0.00115,0.204,0.002,0.435,0,0,0,0,0,1.95e-06,8.34e-05,8.33e-05,5.27e-05,0.0136,0.0135,0.00804,0.0407,0.0407,0.0355,3.36e-11,3.36e-11,1.51e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +28990000,0.983,-0.00564,-0.0116,0.185,-0.0794,0.06,0.786,-0.0453,0.0215,-2.35,-1.51e-05,-5.8e-05,3.23e-07,5.45e-06,1.67e-05,-0.00114,0.204,0.002,0.435,0,0,0,0,0,1.94e-06,8.33e-05,8.33e-05,5.25e-05,0.0126,0.0126,0.00798,0.0371,0.0371,0.0352,3.3e-11,3.3e-11,1.49e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29090000,0.983,-0.00549,-0.0116,0.185,-0.0822,0.0623,0.785,-0.0534,0.0276,-2.27,-1.51e-05,-5.8e-05,3.17e-07,5.67e-06,1.61e-05,-0.00114,0.204,0.002,0.435,0,0,0,0,0,1.93e-06,8.35e-05,8.35e-05,5.22e-05,0.0135,0.0135,0.00802,0.0406,0.0406,0.0353,3.31e-11,3.31e-11,1.48e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29190000,0.983,-0.00544,-0.0118,0.185,-0.0785,0.0609,0.78,-0.0512,0.0269,-2.2,-1.49e-05,-5.8e-05,3.81e-07,5.57e-06,1.5e-05,-0.00114,0.204,0.002,0.435,0,0,0,0,0,1.93e-06,8.35e-05,8.35e-05,5.21e-05,0.0126,0.0126,0.00799,0.0371,0.0371,0.0353,3.25e-11,3.25e-11,1.46e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29290000,0.983,-0.00571,-0.0118,0.185,-0.0806,0.0669,0.782,-0.0591,0.0333,-2.13,-1.49e-05,-5.8e-05,3.99e-07,5.74e-06,1.46e-05,-0.00114,0.204,0.002,0.435,0,0,0,0,0,1.92e-06,8.37e-05,8.36e-05,5.18e-05,0.0135,0.0135,0.00803,0.0405,0.0405,0.0354,3.26e-11,3.26e-11,1.44e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29390000,0.983,-0.00615,-0.0113,0.185,-0.076,0.0653,0.784,-0.0574,0.0342,-2.05,-1.48e-05,-5.79e-05,4.41e-07,5.65e-06,1.37e-05,-0.00113,0.204,0.002,0.435,0,0,0,0,0,1.91e-06,8.36e-05,8.36e-05,5.16e-05,0.0126,0.0126,0.00796,0.037,0.037,0.0352,3.21e-11,3.21e-11,1.43e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29490000,0.983,-0.00615,-0.0112,0.185,-0.0788,0.0661,0.784,-0.0651,0.0408,-1.98,-1.48e-05,-5.79e-05,5.5e-07,5.98e-06,1.31e-05,-0.00113,0.204,0.002,0.435,0,0,0,0,0,1.91e-06,8.38e-05,8.38e-05,5.15e-05,0.0135,0.0135,0.00804,0.0405,0.0405,0.0355,3.22e-11,3.22e-11,1.41e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29590000,0.983,-0.00606,-0.0112,0.185,-0.0743,0.0638,0.786,-0.0625,0.0399,-1.9,-1.47e-05,-5.78e-05,6.55e-07,6.34e-06,1.16e-05,-0.00113,0.204,0.002,0.435,0,0,0,0,0,1.9e-06,8.37e-05,8.37e-05,5.12e-05,0.0126,0.0126,0.00797,0.037,0.037,0.0353,3.16e-11,3.17e-11,1.39e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29690000,0.983,-0.0061,-0.011,0.185,-0.0787,0.0627,0.78,-0.0702,0.0463,-1.83,-1.47e-05,-5.78e-05,7.48e-07,6.9e-06,1.03e-05,-0.00113,0.204,0.002,0.435,0,0,0,0,0,1.89e-06,8.39e-05,8.39e-05,5.1e-05,0.0135,0.0135,0.00802,0.0405,0.0405,0.0353,3.17e-11,3.18e-11,1.38e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29790000,0.983,-0.00593,-0.0115,0.185,-0.0744,0.056,0.777,-0.0654,0.0435,-1.75,-1.45e-05,-5.77e-05,8.44e-07,7.93e-06,8.25e-06,-0.00113,0.204,0.002,0.435,0,0,0,0,0,1.89e-06,8.38e-05,8.37e-05,5.09e-05,0.0126,0.0126,0.00799,0.037,0.037,0.0354,3.12e-11,3.12e-11,1.36e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29890000,0.983,-0.00541,-0.0119,0.185,-0.0752,0.0573,0.773,-0.0728,0.0491,-1.68,-1.45e-05,-5.77e-05,9.3e-07,8.6e-06,6.75e-06,-0.00112,0.204,0.002,0.435,0,0,0,0,0,1.88e-06,8.39e-05,8.39e-05,5.06e-05,0.0135,0.0135,0.00803,0.0404,0.0404,0.0354,3.13e-11,3.13e-11,1.35e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +29990000,0.983,-0.00558,-0.0119,0.185,-0.0697,0.0522,0.769,-0.0683,0.0444,-1.61,-1.44e-05,-5.76e-05,9.42e-07,9.85e-06,2.98e-06,-0.00112,0.204,0.002,0.435,0,0,0,0,0,1.88e-06,8.38e-05,8.38e-05,5.04e-05,0.0126,0.0126,0.00796,0.0369,0.0369,0.0352,3.08e-11,3.08e-11,1.33e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +30090000,0.983,-0.0057,-0.012,0.185,-0.0703,0.0531,0.767,-0.0754,0.0497,-1.54,-1.44e-05,-5.76e-05,7.93e-07,9.96e-06,2.52e-06,-0.00112,0.204,0.002,0.435,0,0,0,0,0,1.87e-06,8.4e-05,8.4e-05,5.02e-05,0.0134,0.0134,0.008,0.0404,0.0404,0.0352,3.09e-11,3.09e-11,1.32e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +30190000,0.983,-0.00568,-0.0121,0.185,-0.0642,0.0498,0.767,-0.0687,0.0478,-1.47,-1.43e-05,-5.75e-05,6.73e-07,1.16e-05,5.37e-07,-0.00111,0.204,0.002,0.435,0,0,0,0,0,1.86e-06,8.38e-05,8.38e-05,5.01e-05,0.0125,0.0125,0.00797,0.0369,0.0369,0.0353,3.04e-11,3.04e-11,1.31e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +30290000,0.983,-0.00569,-0.0121,0.186,-0.0633,0.0501,0.765,-0.0751,0.0528,-1.4,-1.43e-05,-5.75e-05,6.94e-07,1.23e-05,-9.41e-07,-0.00111,0.204,0.002,0.435,0,0,0,0,0,1.86e-06,8.4e-05,8.4e-05,4.98e-05,0.0134,0.0134,0.00801,0.0403,0.0403,0.0354,3.05e-11,3.05e-11,1.29e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +30390000,0.983,-0.0057,-0.012,0.186,-0.0561,0.0444,0.762,-0.0669,0.0495,-1.34,-1.42e-05,-5.74e-05,8.31e-07,1.57e-05,-5.33e-06,-0.00111,0.204,0.002,0.435,0,0,0,0,0,1.85e-06,8.38e-05,8.37e-05,4.96e-05,0.0125,0.0125,0.00794,0.0369,0.0369,0.0351,3e-11,3.01e-11,1.28e-10,2.82e-06,2.82e-06,5e-08,0,0,0,0,0,0,0,0 +30490000,0.983,-0.0057,-0.0121,0.185,-0.059,0.0445,0.764,-0.0726,0.0539,-1.26,-1.42e-05,-5.74e-05,9.14e-07,1.61e-05,-6e-06,-0.0011,0.204,0.002,0.435,0,0,0,0,0,1.85e-06,8.39e-05,8.39e-05,4.95e-05,0.0134,0.0134,0.00803,0.0403,0.0403,0.0355,3.01e-11,3.02e-11,1.26e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +30590000,0.983,-0.00603,-0.0124,0.185,-0.0545,0.0413,0.763,-0.0655,0.0498,-1.19,-1.4e-05,-5.73e-05,1.02e-06,1.89e-05,-1e-05,-0.0011,0.204,0.002,0.435,0,0,0,0,0,1.84e-06,8.37e-05,8.37e-05,4.93e-05,0.0125,0.0125,0.00796,0.0369,0.0369,0.0352,2.97e-11,2.97e-11,1.25e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +30690000,0.983,-0.0064,-0.0126,0.185,-0.0525,0.0403,0.762,-0.0709,0.0539,-1.12,-1.4e-05,-5.73e-05,1.03e-06,1.94e-05,-1.1e-05,-0.0011,0.204,0.002,0.435,0,0,0,0,0,1.83e-06,8.39e-05,8.39e-05,4.91e-05,0.0134,0.0134,0.008,0.0403,0.0403,0.0353,2.98e-11,2.98e-11,1.24e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +30790000,0.983,-0.0061,-0.0123,0.185,-0.0455,0.0348,0.76,-0.0636,0.0524,-1.05,-1.4e-05,-5.73e-05,1.04e-06,2.23e-05,-1.26e-05,-0.00109,0.204,0.002,0.435,0,0,0,0,0,1.83e-06,8.36e-05,8.36e-05,4.9e-05,0.0125,0.0125,0.00797,0.0368,0.0368,0.0354,2.93e-11,2.93e-11,1.22e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +30890000,0.983,-0.00546,-0.0122,0.185,-0.0458,0.0318,0.756,-0.0681,0.0557,-0.982,-1.4e-05,-5.73e-05,9.57e-07,2.26e-05,-1.32e-05,-0.00109,0.204,0.002,0.435,0,0,0,0,0,1.82e-06,8.38e-05,8.38e-05,4.88e-05,0.0134,0.0134,0.00801,0.0403,0.0403,0.0354,2.94e-11,2.94e-11,1.21e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +30990000,0.983,-0.00565,-0.0121,0.185,-0.0382,0.0263,0.757,-0.058,0.0486,-0.913,-1.38e-05,-5.72e-05,9.5e-07,2.58e-05,-1.82e-05,-0.00109,0.204,0.002,0.435,0,0,0,0,0,1.81e-06,8.35e-05,8.35e-05,4.86e-05,0.0125,0.0125,0.00794,0.0368,0.0368,0.0352,2.9e-11,2.9e-11,1.2e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +31090000,0.983,-0.00579,-0.0122,0.186,-0.0372,0.0254,0.756,-0.0617,0.0511,-0.84,-1.38e-05,-5.72e-05,8.97e-07,2.59e-05,-1.83e-05,-0.00109,0.204,0.002,0.435,0,0,0,0,0,1.81e-06,8.37e-05,8.37e-05,4.84e-05,0.0133,0.0133,0.00803,0.0402,0.0402,0.0355,2.91e-11,2.91e-11,1.19e-10,2.82e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +31190000,0.983,-0.00598,-0.0123,0.185,-0.0325,0.0206,0.758,-0.0532,0.046,-0.771,-1.38e-05,-5.71e-05,1.04e-06,2.9e-05,-2.19e-05,-0.00108,0.204,0.002,0.435,0,0,0,0,0,1.81e-06,8.34e-05,8.34e-05,4.82e-05,0.0125,0.0125,0.00796,0.0368,0.0368,0.0353,2.87e-11,2.87e-11,1.17e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +31290000,0.983,-0.00621,-0.0124,0.185,-0.0302,0.018,0.761,-0.0562,0.048,-0.701,-1.38e-05,-5.71e-05,1.12e-06,2.95e-05,-2.26e-05,-0.00108,0.204,0.002,0.435,0,0,0,0,0,1.8e-06,8.35e-05,8.35e-05,4.8e-05,0.0133,0.0133,0.008,0.0402,0.0402,0.0353,2.88e-11,2.88e-11,1.16e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +31390000,0.983,-0.00599,-0.0122,0.185,-0.0241,0.0119,0.76,-0.0473,0.0422,-0.628,-1.37e-05,-5.71e-05,1.04e-06,3.15e-05,-2.52e-05,-0.00108,0.204,0.002,0.435,0,0,0,0,0,1.79e-06,8.32e-05,8.32e-05,4.78e-05,0.0124,0.0124,0.00793,0.0368,0.0368,0.0351,2.84e-11,2.84e-11,1.15e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +31490000,0.983,-0.00572,-0.0126,0.186,-0.0242,0.0091,0.757,-0.0498,0.0432,-0.555,-1.37e-05,-5.71e-05,1.02e-06,3.17e-05,-2.54e-05,-0.00108,0.204,0.002,0.435,0,0,0,0,0,1.79e-06,8.34e-05,8.34e-05,4.77e-05,0.0133,0.0133,0.00801,0.0402,0.0402,0.0354,2.85e-11,2.85e-11,1.14e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +31590000,0.983,-0.00559,-0.013,0.185,-0.0201,0.00687,0.761,-0.0387,0.0388,-0.484,-1.36e-05,-5.7e-05,1.11e-06,3.58e-05,-2.77e-05,-0.00108,0.204,0.002,0.435,0,0,0,0,0,1.78e-06,8.3e-05,8.3e-05,4.75e-05,0.0124,0.0124,0.00794,0.0367,0.0367,0.0352,2.81e-11,2.81e-11,1.13e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +31690000,0.983,-0.00558,-0.0135,0.185,-0.0222,0.0058,0.757,-0.0409,0.0394,-0.415,-1.36e-05,-5.7e-05,1.22e-06,3.65e-05,-2.85e-05,-0.00107,0.204,0.002,0.435,0,0,0,0,0,1.77e-06,8.32e-05,8.32e-05,4.73e-05,0.0133,0.0133,0.00799,0.0402,0.0402,0.0352,2.82e-11,2.82e-11,1.12e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +31790000,0.983,-0.0058,-0.0141,0.185,-0.013,0.00322,0.757,-0.0293,0.0375,-0.343,-1.36e-05,-5.69e-05,1.29e-06,4.17e-05,-2.85e-05,-0.00107,0.204,0.002,0.435,0,0,0,0,0,1.77e-06,8.28e-05,8.28e-05,4.72e-05,0.0124,0.0124,0.00796,0.0367,0.0367,0.0353,2.78e-11,2.78e-11,1.11e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +31890000,0.983,-0.00552,-0.0139,0.185,-0.00988,0.000947,0.754,-0.0304,0.0377,-0.276,-1.36e-05,-5.69e-05,1.35e-06,4.23e-05,-2.91e-05,-0.00107,0.204,0.002,0.435,0,0,0,0,0,1.77e-06,8.3e-05,8.3e-05,4.7e-05,0.0132,0.0132,0.008,0.0401,0.0401,0.0354,2.79e-11,2.79e-11,1.09e-10,2.81e-06,2.81e-06,5e-08,0,0,0,0,0,0,0,0 +31990000,0.983,-0.00579,-0.0135,0.185,-0.00191,0.00028,0.751,-0.0184,0.0346,-0.21,-1.36e-05,-5.68e-05,1.3e-06,4.69e-05,-3e-05,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.76e-06,8.26e-05,8.26e-05,4.68e-05,0.0123,0.0124,0.00793,0.0367,0.0367,0.0351,2.75e-11,2.75e-11,1.08e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +32090000,0.983,-0.00616,-0.0131,0.185,-0.00253,-0.00312,0.753,-0.0186,0.0345,-0.14,-1.36e-05,-5.68e-05,1.31e-06,4.72e-05,-3.02e-05,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.75e-06,8.28e-05,8.28e-05,4.68e-05,0.0132,0.0132,0.00802,0.0401,0.0401,0.0355,2.76e-11,2.76e-11,1.07e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +32190000,0.983,-0.00634,-0.0134,0.185,0.00288,-0.00634,0.752,-0.00731,0.0331,-0.073,-1.36e-05,-5.67e-05,1.27e-06,5.14e-05,-2.87e-05,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.75e-06,8.24e-05,8.24e-05,4.66e-05,0.0123,0.0123,0.00795,0.0367,0.0367,0.0352,2.73e-11,2.73e-11,1.06e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +32290000,0.983,-0.00625,-0.0136,0.185,0.00439,-0.00903,0.75,-0.00699,0.0322,-0.00506,-1.36e-05,-5.67e-05,1.34e-06,5.2e-05,-2.9e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.74e-06,8.26e-05,8.26e-05,4.64e-05,0.0132,0.0132,0.00799,0.0401,0.0401,0.0353,2.74e-11,2.74e-11,1.05e-10,2.81e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +32390000,0.983,-0.00636,-0.0138,0.185,0.0107,-0.0103,0.75,0.0044,0.0297,0.0689,-1.35e-05,-5.67e-05,1.31e-06,5.51e-05,-2.8e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.74e-06,8.22e-05,8.22e-05,4.63e-05,0.0123,0.0123,0.00796,0.0367,0.0367,0.0354,2.7e-11,2.7e-11,1.04e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +32490000,0.983,-0.00921,-0.0117,0.185,0.0354,-0.0731,-0.123,0.00728,0.0235,0.0719,-1.35e-05,-5.67e-05,1.26e-06,5.51e-05,-2.8e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.73e-06,8.24e-05,8.24e-05,4.61e-05,0.0152,0.0152,0.00784,0.0401,0.0401,0.0354,2.71e-11,2.71e-11,1.03e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +32590000,0.983,-0.00915,-0.0116,0.185,0.0358,-0.0742,-0.126,0.0195,0.0198,0.0522,-1.36e-05,-5.66e-05,1.35e-06,5.51e-05,-2.8e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.72e-06,8.11e-05,8.11e-05,4.59e-05,0.0156,0.0156,0.00754,0.0368,0.0368,0.0351,2.67e-11,2.67e-11,1.02e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +32690000,0.983,-0.00913,-0.0115,0.185,0.0315,-0.0798,-0.128,0.0229,0.0121,0.0366,-1.36e-05,-5.66e-05,1.34e-06,5.51e-05,-2.8e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.71e-06,8.13e-05,8.13e-05,4.57e-05,0.0186,0.0187,0.00736,0.0404,0.0404,0.0351,2.68e-11,2.68e-11,1.01e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +32790000,0.983,-0.00882,-0.0116,0.185,0.0301,-0.0774,-0.129,0.0327,0.0102,0.0208,-1.37e-05,-5.66e-05,1.41e-06,5.51e-05,-2.8e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.71e-06,7.86e-05,7.86e-05,4.56e-05,0.0195,0.0195,0.00713,0.037,0.037,0.0351,2.64e-11,2.64e-11,1.01e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +32890000,0.983,-0.00878,-0.0116,0.185,0.0297,-0.0832,-0.13,0.0357,0.00215,0.00492,-1.37e-05,-5.66e-05,1.45e-06,5.51e-05,-2.8e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.7e-06,7.87e-05,7.87e-05,4.55e-05,0.0235,0.0235,0.00696,0.0408,0.0408,0.035,2.65e-11,2.65e-11,9.96e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +32990000,0.983,-0.00851,-0.0116,0.185,0.0271,-0.0792,-0.129,0.0436,-0.00104,-0.00827,-1.37e-05,-5.65e-05,1.54e-06,5.51e-05,-2.8e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.7e-06,7.43e-05,7.43e-05,4.53e-05,0.0243,0.0243,0.00672,0.0374,0.0374,0.0347,2.61e-11,2.61e-11,9.86e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +33090000,0.983,-0.00847,-0.0116,0.185,0.023,-0.083,-0.126,0.0462,-0.00913,-0.0158,-1.37e-05,-5.65e-05,1.52e-06,5.51e-05,-2.8e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.69e-06,7.45e-05,7.45e-05,4.52e-05,0.029,0.029,0.00661,0.0416,0.0416,0.0349,2.62e-11,2.62e-11,9.78e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +33190000,0.983,-0.00816,-0.0115,0.185,0.0192,-0.0785,-0.125,0.0524,-0.011,-0.0223,-1.38e-05,-5.65e-05,1.47e-06,5.49e-05,-3.18e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.69e-06,6.85e-05,6.85e-05,4.5e-05,0.0295,0.0295,0.0064,0.038,0.038,0.0345,2.59e-11,2.59e-11,9.69e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +33290000,0.983,-0.0082,-0.0115,0.185,0.016,-0.0798,-0.124,0.0541,-0.0189,-0.0302,-1.38e-05,-5.65e-05,1.57e-06,5.49e-05,-3.18e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.68e-06,6.86e-05,6.86e-05,4.48e-05,0.0356,0.0356,0.00629,0.0426,0.0426,0.0344,2.6e-11,2.6e-11,9.6e-11,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0 +33390000,0.983,-0.00775,-0.0116,0.185,0.0115,-0.0656,-0.122,0.0574,-0.0139,-0.0388,-1.39e-05,-5.65e-05,1.58e-06,4.91e-05,-5.52e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.67e-06,6.15e-05,6.15e-05,4.48e-05,0.0356,0.0356,0.00616,0.0389,0.0389,0.0343,2.57e-11,2.57e-11,9.52e-11,2.79e-06,2.78e-06,5e-08,0,0,0,0,0,0,0,0 +33490000,0.983,-0.00773,-0.0115,0.185,0.00702,-0.0665,-0.121,0.0583,-0.0205,-0.0484,-1.39e-05,-5.65e-05,1.58e-06,4.91e-05,-5.51e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.67e-06,6.16e-05,6.16e-05,4.46e-05,0.0427,0.0428,0.00608,0.044,0.044,0.0342,2.58e-11,2.58e-11,9.44e-11,2.79e-06,2.78e-06,5e-08,0,0,0,0,0,0,0,0 +33590000,0.983,-0.00736,-0.0116,0.185,0.00366,-0.0572,-0.117,0.061,-0.0167,-0.0553,-1.4e-05,-5.64e-05,1.64e-06,4.09e-05,-7.99e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.66e-06,5.43e-05,5.43e-05,4.44e-05,0.0412,0.0412,0.00596,0.0399,0.0399,0.0338,2.55e-11,2.55e-11,9.35e-11,2.74e-06,2.74e-06,5e-08,0,0,0,0,0,0,0,0 +33690000,0.983,-0.00736,-0.0116,0.185,-0.00098,-0.0576,-0.118,0.0612,-0.0225,-0.0636,-1.4e-05,-5.64e-05,1.65e-06,4.08e-05,-7.99e-05,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.66e-06,5.44e-05,5.44e-05,4.43e-05,0.0489,0.0489,0.00594,0.0456,0.0456,0.0339,2.56e-11,2.56e-11,9.28e-11,2.74e-06,2.74e-06,5.01e-08,0,0,0,0,0,0,0,0 +33790000,0.983,-0.00712,-0.0116,0.185,-0.00359,-0.0468,-0.112,0.0653,-0.0178,-0.0696,-1.4e-05,-5.64e-05,1.59e-06,2.74e-05,-0.000106,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.65e-06,4.76e-05,4.76e-05,4.42e-05,0.0453,0.0453,0.00585,0.0411,0.0411,0.0335,2.55e-11,2.55e-11,9.19e-11,2.67e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0 +33890000,0.983,-0.00713,-0.0116,0.185,-0.00771,-0.0445,-0.111,0.0646,-0.0224,-0.0761,-1.4e-05,-5.64e-05,1.65e-06,2.72e-05,-0.000106,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.64e-06,4.77e-05,4.77e-05,4.4e-05,0.0531,0.0531,0.00584,0.0472,0.0472,0.0334,2.56e-11,2.56e-11,9.11e-11,2.67e-06,2.67e-06,5e-08,0,0,0,0,0,0,0,0 33990000,0.983,-0.00684,-0.0118,0.185,-0.00683,-0.0302,-0.107,0.0681,-0.0149,-0.0788,-1.4e-05,-5.63e-05,1.58e-06,2.22e-06,-0.000136,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.64e-06,4.18e-05,4.18e-05,4.38e-05,0.0477,0.0477,0.00578,0.0422,0.0422,0.033,2.55e-11,2.55e-11,9.03e-11,2.57e-06,2.57e-06,5e-08,0,0,0,0,0,0,0,0 -34090000,0.983,-0.00679,-0.0118,0.185,-0.011,-0.0303,-0.105,0.0673,-0.018,-0.0832,-1.4e-05,-5.63e-05,1.55e-06,1.8e-06,-0.000136,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.64e-06,4.19e-05,4.19e-05,4.38e-05,0.0552,0.0552,0.00582,0.0487,0.0487,0.0331,2.56e-11,2.56e-11,8.96e-11,2.57e-06,2.57e-06,5e-08,0,0,0,0,0,0,0,0 -34190000,0.983,-0.00671,-0.0119,0.185,-0.0113,-0.0197,-0.102,0.071,-0.0125,-0.0857,-1.4e-05,-5.63e-05,1.57e-06,-1.65e-05,-0.000155,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.63e-06,3.73e-05,3.73e-05,4.36e-05,0.0484,0.0484,0.00579,0.0432,0.0432,0.0327,2.56e-11,2.56e-11,8.89e-11,2.47e-06,2.46e-06,5e-08,0,0,0,0,0,0,0,0 -34290000,0.983,-0.00658,-0.0119,0.185,-0.0117,-0.0189,-0.101,0.0699,-0.0145,-0.0913,-1.4e-05,-5.63e-05,1.58e-06,-1.69e-05,-0.000155,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.63e-06,3.74e-05,3.74e-05,4.34e-05,0.0553,0.0553,0.00583,0.05,0.05,0.0326,2.57e-11,2.57e-11,8.81e-11,2.47e-06,2.46e-06,5e-08,0,0,0,0,0,0,0,0 -34390000,0.983,-0.00648,-0.0119,0.185,-0.0125,-0.00944,-0.0957,0.0716,-0.00979,-0.0953,-1.41e-05,-5.63e-05,1.57e-06,-3.26e-05,-0.000168,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.62e-06,3.39e-05,3.39e-05,4.34e-05,0.0477,0.0477,0.00585,0.044,0.044,0.0325,2.57e-11,2.57e-11,8.74e-11,2.35e-06,2.35e-06,5e-08,0,0,0,0,0,0,0,0 -34490000,0.983,-0.00655,-0.0119,0.185,-0.0152,-0.00849,-0.0936,0.0703,-0.0108,-0.0976,-1.41e-05,-5.63e-05,1.6e-06,-3.35e-05,-0.000168,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.62e-06,3.4e-05,3.4e-05,4.32e-05,0.054,0.054,0.00591,0.051,0.051,0.0324,2.58e-11,2.58e-11,8.66e-11,2.35e-06,2.35e-06,5e-08,0,0,0,0,0,0,0,0 -34590000,0.983,-0.0065,-0.0117,0.185,-0.0119,-0.00457,0.702,0.0723,-0.00855,-0.0685,-1.41e-05,-5.63e-05,1.57e-06,-4.68e-05,-0.000169,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.61e-06,3.14e-05,3.14e-05,4.3e-05,0.0444,0.0444,0.00592,0.0446,0.0446,0.0321,2.58e-11,2.58e-11,8.59e-11,2.25e-06,2.24e-06,5e-08,0,0,0,0,0,0,0,0 -34690000,0.983,-0.00649,-0.0114,0.185,-0.0123,-0.00272,1.69,0.0711,-0.0089,0.0498,-1.41e-05,-5.63e-05,1.55e-06,-4.66e-05,-0.000169,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.61e-06,3.15e-05,3.15e-05,4.3e-05,0.0479,0.0479,0.00602,0.0514,0.0514,0.0322,2.59e-11,2.59e-11,8.53e-11,2.25e-06,2.24e-06,5e-08,0,0,0,0,0,0,0,0 +34090000,0.983,-0.00679,-0.0118,0.185,-0.011,-0.0303,-0.105,0.0673,-0.018,-0.0832,-1.4e-05,-5.63e-05,1.55e-06,1.79e-06,-0.000136,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.63e-06,4.19e-05,4.19e-05,4.37e-05,0.0552,0.0552,0.00582,0.0487,0.0487,0.0331,2.56e-11,2.56e-11,8.96e-11,2.57e-06,2.57e-06,5e-08,0,0,0,0,0,0,0,0 +34190000,0.983,-0.00671,-0.0119,0.185,-0.0113,-0.0197,-0.102,0.071,-0.0125,-0.0857,-1.4e-05,-5.63e-05,1.57e-06,-1.65e-05,-0.000155,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.63e-06,3.73e-05,3.73e-05,4.36e-05,0.0484,0.0484,0.00579,0.0432,0.0432,0.0327,2.56e-11,2.56e-11,8.88e-11,2.47e-06,2.46e-06,5e-08,0,0,0,0,0,0,0,0 +34290000,0.983,-0.00658,-0.0119,0.185,-0.0117,-0.0189,-0.101,0.0699,-0.0145,-0.0913,-1.4e-05,-5.63e-05,1.58e-06,-1.69e-05,-0.000155,-0.00105,0.204,0.002,0.435,0,0,0,0,0,1.62e-06,3.74e-05,3.74e-05,4.34e-05,0.0553,0.0553,0.00583,0.05,0.05,0.0326,2.57e-11,2.57e-11,8.8e-11,2.47e-06,2.46e-06,5e-08,0,0,0,0,0,0,0,0 +34390000,0.983,-0.00648,-0.0119,0.185,-0.0125,-0.00944,-0.0957,0.0716,-0.00979,-0.0953,-1.41e-05,-5.63e-05,1.57e-06,-3.26e-05,-0.000168,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.62e-06,3.39e-05,3.39e-05,4.33e-05,0.0477,0.0477,0.00585,0.044,0.044,0.0325,2.57e-11,2.57e-11,8.73e-11,2.35e-06,2.35e-06,5e-08,0,0,0,0,0,0,0,0 +34490000,0.983,-0.00655,-0.0119,0.185,-0.0152,-0.00849,-0.0936,0.0703,-0.0108,-0.0976,-1.41e-05,-5.63e-05,1.59e-06,-3.35e-05,-0.000168,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.61e-06,3.4e-05,3.4e-05,4.32e-05,0.054,0.054,0.00591,0.051,0.051,0.0324,2.58e-11,2.58e-11,8.66e-11,2.35e-06,2.35e-06,5e-08,0,0,0,0,0,0,0,0 +34590000,0.983,-0.0065,-0.0117,0.185,-0.0119,-0.00457,0.702,0.0723,-0.00855,-0.0685,-1.41e-05,-5.63e-05,1.57e-06,-4.68e-05,-0.000169,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.61e-06,3.14e-05,3.14e-05,4.3e-05,0.0444,0.0444,0.00592,0.0446,0.0446,0.0321,2.58e-11,2.58e-11,8.58e-11,2.25e-06,2.24e-06,5e-08,0,0,0,0,0,0,0,0 +34690000,0.983,-0.00649,-0.0114,0.185,-0.0123,-0.00272,1.69,0.0711,-0.0089,0.0497,-1.41e-05,-5.63e-05,1.55e-06,-4.66e-05,-0.000169,-0.00106,0.204,0.002,0.435,0,0,0,0,0,1.6e-06,3.15e-05,3.15e-05,4.3e-05,0.0479,0.0479,0.00602,0.0514,0.0514,0.0322,2.59e-11,2.59e-11,8.52e-11,2.25e-06,2.24e-06,5e-08,0,0,0,0,0,0,0,0 34790000,0.983,-0.00647,-0.0112,0.185,-0.0121,0.00161,2.66,0.0721,-0.00658,0.225,-1.41e-05,-5.63e-05,1.53e-06,-3.14e-05,-0.000186,-0.00103,0.204,0.002,0.435,0,0,0,0,0,1.6e-06,3.01e-05,3.01e-05,4.28e-05,0.0403,0.0403,0.00605,0.045,0.045,0.0319,2.6e-11,2.6e-11,8.45e-11,2.13e-06,2.12e-06,5e-08,0,0,0,0,0,0,0,0 -34890000,0.983,-0.00645,-0.0109,0.185,-0.0131,0.00378,3.64,0.0708,-0.00615,0.514,-1.41e-05,-5.63e-05,1.51e-06,-2.71e-05,-0.000188,-0.00103,0.204,0.002,0.435,0,0,0,0,0,1.6e-06,3.02e-05,3.02e-05,4.27e-05,0.044,0.044,0.00614,0.0514,0.0514,0.0318,2.61e-11,2.61e-11,8.38e-11,2.13e-06,2.12e-06,5e-08,0,0,0,0,0,0,0,0 +34890000,0.983,-0.00645,-0.0109,0.185,-0.0131,0.00378,3.64,0.0708,-0.00615,0.514,-1.41e-05,-5.63e-05,1.5e-06,-2.71e-05,-0.000188,-0.00103,0.204,0.002,0.435,0,0,0,0,0,1.59e-06,3.02e-05,3.02e-05,4.26e-05,0.044,0.044,0.00614,0.0514,0.0514,0.0318,2.61e-11,2.61e-11,8.38e-11,2.13e-06,2.12e-06,5e-08,0,0,0,0,0,0,0,0 diff --git a/src/modules/ekf2/test/sensor_simulator/imu.h b/src/modules/ekf2/test/sensor_simulator/imu.h index 9921b60fe4..64df1b3b7a 100644 --- a/src/modules/ekf2/test/sensor_simulator/imu.h +++ b/src/modules/ekf2/test/sensor_simulator/imu.h @@ -55,6 +55,11 @@ public: void setAccelData(const Vector3f &accel); void setGyroData(const Vector3f &gyro); + bool moving() + { + return ((fabsf(_accel_data.norm() - CONSTANTS_ONE_G) > 0.01f) || (_gyro_data.norm() > 0.01f)); + } + private: Vector3f _accel_data; Vector3f _gyro_data; diff --git a/src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp b/src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp index 44d92170c3..90c691ed06 100644 --- a/src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp +++ b/src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp @@ -154,6 +154,7 @@ void SensorSimulator::runMicroseconds(uint32_t duration) if (update_imu) { // Update at IMU rate + _ekf->set_vehicle_at_rest(!_imu.moving()); _ekf->update(); } } @@ -193,6 +194,7 @@ void SensorSimulator::runReplayMicroseconds(uint32_t duration) updateSensors(); if (update_imu) { + _ekf->set_vehicle_at_rest(!_imu.moving()); _ekf->update(); } } @@ -316,6 +318,7 @@ void SensorSimulator::runTrajectoryMicroseconds(uint32_t duration) updateSensors(); if (update_imu) { + _ekf->set_vehicle_at_rest(!_imu.moving()); _ekf->update(); } } diff --git a/src/modules/ekf2/test/test_EKF_initialization.cpp b/src/modules/ekf2/test/test_EKF_initialization.cpp index 0758bc96cb..967f4f6590 100644 --- a/src/modules/ekf2/test/test_EKF_initialization.cpp +++ b/src/modules/ekf2/test/test_EKF_initialization.cpp @@ -50,7 +50,7 @@ public: SensorSimulator _sensor_simulator; EkfWrapper _ekf_wrapper; - const float _init_tilt_period = 1.0; // seconds + const float _init_tilt_period = 0.3f; // seconds // GTests is calling this void SetUp() override @@ -106,12 +106,12 @@ public: const Vector3f pos_var = _ekf->getPositionVariance(); const Vector3f vel_var = _ekf->getVelocityVariance(); - const float pos_variance_limit = 0.1f; + const float pos_variance_limit = 0.01f; // Fake fusion obs var when at rest EXPECT_TRUE(pos_var(0) > pos_variance_limit) << "pos_var(0)" << pos_var(0); EXPECT_TRUE(pos_var(1) > pos_variance_limit) << "pos_var(1)" << pos_var(1); EXPECT_TRUE(pos_var(2) > pos_variance_limit) << "pos_var(2)" << pos_var(2); - const float vel_variance_limit = 0.3f; + const float vel_variance_limit = 0.16f; EXPECT_TRUE(vel_var(0) > vel_variance_limit) << "vel_var(0)" << vel_var(0); EXPECT_TRUE(vel_var(1) > vel_variance_limit) << "vel_var(1)" << vel_var(1); EXPECT_TRUE(vel_var(2) > vel_variance_limit) << "vel_var(2)" << vel_var(2); diff --git a/src/modules/land_detector/LandDetector.cpp b/src/modules/land_detector/LandDetector.cpp index 85746874f5..f16e8ed383 100644 --- a/src/modules/land_detector/LandDetector.cpp +++ b/src/modules/land_detector/LandDetector.cpp @@ -48,7 +48,18 @@ namespace land_detector LandDetector::LandDetector() : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::nav_and_controllers) -{} +{ + _land_detected.ground_contact = true; + _land_detected.maybe_landed = true; + _land_detected.landed = true; + _land_detected.in_ground_effect = true; + _land_detected.in_descend = false; + _land_detected.has_low_throttle = false; + _land_detected.vertical_movement = false; + _land_detected.horizontal_movement = false; + _land_detected.close_to_ground_or_skipped_check = true; + _land_detected.at_rest = true; +} LandDetector::~LandDetector() { @@ -91,6 +102,18 @@ void LandDetector::Run() _acceleration = matrix::Vector3f{vehicle_acceleration.xyz}; } + vehicle_angular_velocity_s vehicle_angular_velocity{}; + + if (_vehicle_angular_velocity_sub.update(&vehicle_angular_velocity)) { + _angular_velocity = matrix::Vector3f{vehicle_angular_velocity.xyz}; + + static constexpr float GYRO_NORM_MAX = math::radians(3.f); // 3 degrees/second + + if (_angular_velocity.norm() > GYRO_NORM_MAX) { + _time_last_move_detect_us = vehicle_angular_velocity.timestamp_sample; + } + } + _vehicle_local_position_sub.update(&_vehicle_local_position); _vehicle_status_sub.update(&_vehicle_status); @@ -124,13 +147,18 @@ void LandDetector::Run() const bool landDetected = _landed_hysteresis.get_state(); const bool in_ground_effect = _ground_effect_hysteresis.get_state(); + UpdateVehicleAtRest(); + + const bool at_rest = landDetected && _at_rest; + // publish at 1 Hz, very first time, or when the result has changed if ((hrt_elapsed_time(&_land_detected.timestamp) >= 1_s) || (_land_detected.landed != landDetected) || (_land_detected.freefall != freefallDetected) || (_land_detected.maybe_landed != maybe_landedDetected) || (_land_detected.ground_contact != ground_contactDetected) || - (_land_detected.in_ground_effect != in_ground_effect)) { + (_land_detected.in_ground_effect != in_ground_effect) || + (_land_detected.at_rest != at_rest)) { if (!landDetected && _land_detected.landed && _takeoff_time == 0) { /* only set take off time once, until disarming */ // We did take off @@ -147,6 +175,7 @@ void LandDetector::Run() _land_detected.horizontal_movement = _get_horizontal_movement(); _land_detected.vertical_movement = _get_vertical_movement(); _land_detected.close_to_ground_or_skipped_check = _get_close_to_ground_or_skipped_check(); + _land_detected.at_rest = at_rest; _land_detected.timestamp = hrt_absolute_time(); _vehicle_land_detected_pub.publish(_land_detected); } @@ -178,4 +207,51 @@ void LandDetector::Run() } } +void LandDetector::UpdateVehicleAtRest() +{ + if (_sensor_selection_sub.updated()) { + sensor_selection_s sensor_selection{}; + _sensor_selection_sub.copy(&sensor_selection); + + if (sensor_selection.gyro_device_id != _device_id_gyro) { + + bool gyro_status_found = false; + + // find corresponding vehicle_imu_status instance + for (uint8_t imu_instance = 0; imu_instance < 4; imu_instance++) { + uORB::Subscription imu_status_sub{ORB_ID(vehicle_imu_status), imu_instance}; + + vehicle_imu_status_s imu_status{}; + imu_status_sub.copy(&imu_status); + + if ((imu_status.gyro_device_id != 0) && (imu_status.gyro_device_id == sensor_selection.gyro_device_id)) { + _vehicle_imu_status_sub.ChangeInstance(imu_instance); + _device_id_gyro = sensor_selection.gyro_device_id; + gyro_status_found = true; + break; + } + } + + if (!gyro_status_found) { + PX4_WARN("IMU status not found for gyro %" PRId32, sensor_selection.gyro_device_id); + } + } + } + + vehicle_imu_status_s imu_status; + + if (_vehicle_imu_status_sub.update(&imu_status)) { + static constexpr float GYRO_VIBE_METRIC_MAX = 0.02f; // gyro_vibration_metric * dt * 4.0e4f > is_moving_scaler) + static constexpr float ACCEL_VIBE_METRIC_MAX = 1.2f; // accel_vibration_metric * dt * 2.1e2f > is_moving_scaler + + if ((imu_status.gyro_vibration_metric > GYRO_VIBE_METRIC_MAX) + || (imu_status.accel_vibration_metric > ACCEL_VIBE_METRIC_MAX)) { + + _time_last_move_detect_us = imu_status.timestamp; + } + } + + _at_rest = (hrt_elapsed_time(&_time_last_move_detect_us) > 1_s); +} + } // namespace land_detector diff --git a/src/modules/land_detector/LandDetector.h b/src/modules/land_detector/LandDetector.h index dc25d4fb69..26e74eacd4 100644 --- a/src/modules/land_detector/LandDetector.h +++ b/src/modules/land_detector/LandDetector.h @@ -59,7 +59,10 @@ #include #include #include +#include #include +#include +#include #include #include #include @@ -148,6 +151,7 @@ protected: vehicle_status_s _vehicle_status{}; matrix::Vector3f _acceleration{}; + matrix::Vector3f _angular_velocity{}; bool _armed{false}; bool _previous_armed_state{false}; ///< stores the previous actuator_armed.armed state @@ -156,17 +160,14 @@ protected: private: void Run() override; - vehicle_land_detected_s _land_detected = { - .timestamp = 0, - .freefall = false, - .ground_contact = true, - .maybe_landed = true, - .landed = true, - }; + void UpdateVehicleAtRest(); + vehicle_land_detected_s _land_detected{}; hrt_abstime _takeoff_time{0}; hrt_abstime _total_flight_time{0}; ///< total vehicle flight time in microseconds + hrt_abstime _time_last_move_detect_us{0}; // timestamp of last movement detection event in microseconds + perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")}; uORB::Publication _vehicle_land_detected_pub{ORB_ID(vehicle_land_detected)}; @@ -174,11 +175,18 @@ private: uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; uORB::Subscription _actuator_armed_sub{ORB_ID(actuator_armed)}; + uORB::Subscription _sensor_selection_sub{ORB_ID(sensor_selection)}; uORB::Subscription _vehicle_acceleration_sub{ORB_ID(vehicle_acceleration)}; + uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; + uORB::Subscription _vehicle_imu_status_sub{ORB_ID(vehicle_imu_status)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; uORB::SubscriptionCallbackWorkItem _vehicle_local_position_sub{this, ORB_ID(vehicle_local_position)}; + uint32_t _device_id_gyro{0}; + + bool _at_rest{true}; + DEFINE_PARAMETERS_CUSTOM_PARENT( ModuleParams, (ParamInt) _param_total_flight_time_high, diff --git a/src/modules/land_detector/MulticopterLandDetector.cpp b/src/modules/land_detector/MulticopterLandDetector.cpp index 9ffbd2aa35..95cdd652b1 100644 --- a/src/modules/land_detector/MulticopterLandDetector.cpp +++ b/src/modules/land_detector/MulticopterLandDetector.cpp @@ -285,11 +285,10 @@ bool MulticopterLandDetector::_get_maybe_landed_state() } // Next look if all rotation angles are not moving. - vehicle_angular_velocity_s vehicle_angular_velocity{}; - _vehicle_angular_velocity_sub.copy(&vehicle_angular_velocity); - const Vector2f angular_velocity{vehicle_angular_velocity.xyz[0], vehicle_angular_velocity.xyz[1]}; const float max_rotation_scaled = math::radians(_param_lndmc_rot_max.get()) * landThresholdFactor; + matrix::Vector2f angular_velocity{_angular_velocity(0), _angular_velocity(1)}; + if (angular_velocity.norm() > max_rotation_scaled) { return false; } diff --git a/src/modules/land_detector/MulticopterLandDetector.h b/src/modules/land_detector/MulticopterLandDetector.h index 0e7680d945..33f4fd2729 100644 --- a/src/modules/land_detector/MulticopterLandDetector.h +++ b/src/modules/land_detector/MulticopterLandDetector.h @@ -44,7 +44,6 @@ #include #include -#include #include #include #include @@ -110,7 +109,7 @@ private: uORB::Subscription _actuator_controls_sub{ORB_ID(actuator_controls_0)}; uORB::Subscription _hover_thrust_estimate_sub{ORB_ID(hover_thrust_estimate)}; uORB::Subscription _trajectory_setpoint_sub{ORB_ID(trajectory_setpoint)}; - uORB::Subscription _vehicle_angular_velocity_sub{ORB_ID(vehicle_angular_velocity)}; + uORB::Subscription _vehicle_control_mode_sub{ORB_ID(vehicle_control_mode)}; uORB::Subscription _takeoff_status_sub{ORB_ID(takeoff_status)};