mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 05:04:08 +08:00
ekf2: handle GPS vel/pos timeouts individually
- in a system with good EV + GPS it's possible that horizontal vel/pos fusion continues successfully, but GPS fusion is failing due to mediocre yaw alignment
This commit is contained in:
parent
3d61ab84c4
commit
db51bfc9e8
@ -723,7 +723,6 @@ private:
|
||||
|
||||
// height sensor status
|
||||
bool _baro_hgt_faulty{false}; ///< true if baro data have been declared faulty TODO: move to fault flags
|
||||
bool _gps_intermittent{true}; ///< true if data into the buffer is intermittent
|
||||
|
||||
// imu fault status
|
||||
uint64_t _time_bad_vert_accel{0}; ///< last time a bad vertical accel was detected (uSec)
|
||||
@ -1014,7 +1013,6 @@ private:
|
||||
|
||||
// control fusion of GPS observations
|
||||
void controlGpsFusion(const imuSample &imu_delayed);
|
||||
bool shouldResetGpsFusion() const;
|
||||
bool isYawFailure() const;
|
||||
|
||||
// control fusion of magnetometer observations
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2021-2022 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2021-2023 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -46,8 +46,6 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
|
||||
return;
|
||||
}
|
||||
|
||||
_gps_intermittent = !isNewestSampleRecent(_time_last_gps_buffer_push, 2 * GNSS_MAX_INTERVAL);
|
||||
|
||||
// check for arrival of new sensor data at the fusion time horizon
|
||||
_gps_data_ready = _gps_buffer->pop_first_older_than(imu_delayed.time_us, &_gps_sample_delayed);
|
||||
|
||||
@ -90,6 +88,7 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
|
||||
const Vector3f velocity{gps_sample.vel};
|
||||
const float vel_var = sq(math::max(gps_sample.sacc, _params.gps_vel_noise));
|
||||
const Vector3f vel_obs_var(vel_var, vel_var, vel_var * sq(1.5f));
|
||||
const bool vel_good = velocity.isAllFinite() && (gps_sample.sacc > 0.f) && (gps_sample.sacc < _params.req_sacc);
|
||||
updateVelocityAidSrcStatus(gps_sample.time_us,
|
||||
velocity, // observation
|
||||
vel_obs_var, // observation variance
|
||||
@ -112,6 +111,7 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
|
||||
|
||||
const float pos_var = sq(pos_noise);
|
||||
const Vector2f pos_obs_var(pos_var, pos_var);
|
||||
const bool pos_good = position.isAllFinite() && (gps_sample.hacc > 0.f) && (gps_sample.hacc < _params.req_hacc);
|
||||
updateHorizontalPositionAidSrcStatus(gps_sample.time_us,
|
||||
position, // observation
|
||||
pos_obs_var, // observation variance
|
||||
@ -141,7 +141,12 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
|
||||
}
|
||||
|
||||
const bool continuing_conditions_passing = mandatory_conditions_passing && !gps_checks_failing;
|
||||
const bool starting_conditions_passing = continuing_conditions_passing && gps_checks_passing;
|
||||
|
||||
const bool starting_conditions_passing = continuing_conditions_passing
|
||||
&& isNewestSampleRecent(_time_last_gps_buffer_push, GNSS_MAX_INTERVAL)
|
||||
&& _gps_checks_passed
|
||||
&& gps_checks_passing
|
||||
&& !gps_checks_failing;
|
||||
|
||||
if (_control_status.flags.gps) {
|
||||
if (mandatory_conditions_passing) {
|
||||
@ -151,7 +156,11 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
|
||||
fuseVelocity(_aid_src_gnss_vel);
|
||||
fuseHorizontalPosition(_aid_src_gnss_pos);
|
||||
|
||||
bool do_vel_pos_reset = shouldResetGpsFusion();
|
||||
const bool vel_fusion_failing = isTimedOut(_aid_src_gnss_vel.time_last_fuse, _params.reset_timeout_max);
|
||||
const bool pos_fusion_failing = isTimedOut(_aid_src_gnss_pos.time_last_fuse, _params.reset_timeout_max);
|
||||
|
||||
bool vel_reset = vel_fusion_failing && vel_good;
|
||||
bool pos_reset = pos_fusion_failing && pos_good;
|
||||
|
||||
if (isYawFailure()
|
||||
&& _control_status.flags.in_air
|
||||
@ -189,19 +198,23 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
|
||||
|
||||
#endif // CONFIG_EKF2_EXTERNAL_VISION
|
||||
|
||||
do_vel_pos_reset = true;
|
||||
vel_reset = true;
|
||||
pos_reset = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (do_vel_pos_reset) {
|
||||
ECL_WARN("GPS fusion timeout, resetting velocity and position");
|
||||
|
||||
if (vel_reset) {
|
||||
// reset velocity
|
||||
ECL_WARN("GPS fusion timeout, resetting velocity to GPS (%.3f, %.3f, %.3f)",
|
||||
(double)velocity(0), (double)velocity(1), (double)velocity(2));
|
||||
_information_events.flags.reset_vel_to_gps = true;
|
||||
resetVelocityTo(velocity, vel_obs_var);
|
||||
_aid_src_gnss_vel.time_last_fuse = _time_delayed_us;
|
||||
}
|
||||
|
||||
if (pos_reset) {
|
||||
// reset position
|
||||
ECL_WARN("GPS fusion timeout, resetting position to GPS (%.3f, %.3f)", (double)position(0), (double)position(1));
|
||||
_information_events.flags.reset_pos_to_gps = true;
|
||||
resetHorizontalPositionTo(position, pos_obs_var);
|
||||
_aid_src_gnss_pos.time_last_fuse = _time_delayed_us;
|
||||
@ -258,37 +271,6 @@ void Ekf::controlGpsFusion(const imuSample &imu_delayed)
|
||||
}
|
||||
}
|
||||
|
||||
bool Ekf::shouldResetGpsFusion() const
|
||||
{
|
||||
/* We are relying on aiding to constrain drift so after a specified time
|
||||
* with no aiding we need to do something
|
||||
*/
|
||||
bool has_horizontal_aiding_timed_out = isTimedOut(_time_last_hor_pos_fuse, _params.reset_timeout_max)
|
||||
&& isTimedOut(_time_last_hor_vel_fuse, _params.reset_timeout_max);
|
||||
|
||||
#if defined(CONFIG_EKF2_OPTICAL_FLOW)
|
||||
|
||||
if (has_horizontal_aiding_timed_out) {
|
||||
// horizontal aiding hasn't timed out if optical flow still active
|
||||
if (_control_status.flags.opt_flow && isRecent(_aid_src_optical_flow.time_last_fuse, _params.reset_timeout_max)) {
|
||||
has_horizontal_aiding_timed_out = false;
|
||||
}
|
||||
}
|
||||
|
||||
#endif // CONFIG_EKF2_OPTICAL_FLOW
|
||||
|
||||
const bool is_reset_required = has_horizontal_aiding_timed_out
|
||||
|| isTimedOut(_time_last_hor_pos_fuse, 2 * _params.reset_timeout_max);
|
||||
|
||||
const bool is_inflight_nav_failure = _control_status.flags.in_air
|
||||
&& isTimedOut(_time_last_hor_vel_fuse, _params.reset_timeout_max)
|
||||
&& isTimedOut(_time_last_hor_pos_fuse, _params.reset_timeout_max)
|
||||
&& (_time_last_hor_vel_fuse > _time_last_on_ground_us)
|
||||
&& (_time_last_hor_pos_fuse > _time_last_on_ground_us);
|
||||
|
||||
return (is_reset_required || is_inflight_nav_failure);
|
||||
}
|
||||
|
||||
bool Ekf::isYawFailure() const
|
||||
{
|
||||
if (!isYawEmergencyEstimateAvailable()) {
|
||||
@ -325,8 +307,7 @@ void Ekf::controlGpsYawFusion(const gpsSample &gps_sample, bool gps_checks_passi
|
||||
const bool starting_conditions_passing = continuing_conditions_passing
|
||||
&& _control_status.flags.tilt_align
|
||||
&& gps_checks_passing
|
||||
&& !is_gps_yaw_data_intermittent
|
||||
&& !_gps_intermittent;
|
||||
&& !is_gps_yaw_data_intermittent;
|
||||
|
||||
if (_control_status.flags.gps_yaw) {
|
||||
|
||||
|
||||
@ -341,51 +341,51 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
||||
33890000,-0.23,-0.0057,-0.0079,0.97,-1,-0.7,0.77,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-8.9e-05,-0.019,0.0056,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.2e-05,8.2e-05,8.4e-05,0.032,0.038,0.0072,0.38,0.41,0.036,2.8e-07,2.8e-07,3e-06,0.027,0.025,0.0005,0.0025,8.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
33990000,-0.38,-0.0039,-0.012,0.92,-0.96,-0.65,0.74,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.0001,-0.019,0.0056,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00096,6.9e-05,7.8e-05,0.00019,0.032,0.038,0.007,0.37,0.41,0.035,2.7e-07,2.7e-07,3e-06,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34090000,-0.49,-0.0029,-0.013,0.87,-0.91,-0.61,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.0001,-0.019,0.0056,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00085,6.9e-05,7.8e-05,0.00029,0.037,0.043,0.0069,0.39,0.42,0.036,2.7e-07,2.7e-07,3e-06,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34190000,-0.56,-0.0023,-0.012,0.83,-0.89,-0.56,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00011,-0.022,0.0078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00075,6.5e-05,7.3e-05,0.00037,0.037,0.042,0.0067,0.38,0.42,0.035,2.7e-07,2.7e-07,3e-06,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34290000,-0.6,-0.0032,-0.0091,0.8,-0.84,-0.51,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00011,-0.022,0.0078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0007,6.5e-05,7.2e-05,0.00043,0.043,0.049,0.0066,0.4,0.43,0.035,2.7e-07,2.7e-07,3e-06,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34390000,-0.63,-0.0033,-0.0066,0.78,-0.83,-0.47,0.74,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00012,-0.027,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00064,6.1e-05,6.7e-05,0.00045,0.042,0.047,0.0065,0.39,0.43,0.035,2.7e-07,2.7e-07,3e-06,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34490000,-0.65,-0.0042,-0.0045,0.76,-0.77,-0.43,0.74,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00012,-0.027,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00062,6.1e-05,6.6e-05,0.00047,0.049,0.055,0.0064,0.4,0.44,0.035,2.7e-07,2.7e-07,3e-06,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34590000,-0.66,-0.0035,-0.0035,0.76,-0.78,-0.41,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00013,-0.037,0.022,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0006,5.6e-05,6e-05,0.00048,0.048,0.052,0.0063,0.4,0.44,0.034,2.7e-07,2.7e-07,3e-06,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34690000,-0.66,-0.0039,-0.0027,0.75,-0.72,-0.37,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00013,-0.037,0.022,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00059,5.6e-05,6e-05,0.00049,0.055,0.06,0.0063,0.41,0.45,0.034,2.7e-07,2.7e-07,3e-06,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34790000,-0.67,-0.0027,-0.0025,0.75,-0.73,-0.35,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00013,-0.048,0.034,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00058,5.1e-05,5.5e-05,0.00048,0.052,0.055,0.0062,0.41,0.45,0.034,2.6e-07,2.7e-07,3e-06,0.025,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34890000,-0.67,-0.0027,-0.0024,0.74,-0.68,-0.32,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00013,-0.048,0.034,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00057,5.1e-05,5.5e-05,0.00049,0.059,0.063,0.0062,0.42,0.46,0.034,2.7e-07,2.7e-07,3e-06,0.025,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34990000,-0.67,-0.009,-0.0051,0.74,0.34,0.27,-0.13,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00013,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,4.6e-05,5e-05,0.00049,0.06,0.069,0.0068,0.42,0.45,0.034,2.6e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35090000,-0.67,-0.0091,-0.0051,0.74,0.47,0.3,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00013,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,4.6e-05,5e-05,0.00049,0.065,0.076,0.0068,0.43,0.46,0.034,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35190000,-0.67,-0.0091,-0.0052,0.74,0.49,0.33,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00013,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00057,4.6e-05,5e-05,0.00049,0.07,0.081,0.0067,0.44,0.47,0.034,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35290000,-0.67,-0.0091,-0.0052,0.74,0.51,0.36,-0.18,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00013,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00057,4.6e-05,5e-05,0.00049,0.076,0.087,0.0066,0.46,0.48,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35390000,-0.67,-0.0092,-0.0052,0.74,0.54,0.4,-0.18,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00013,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00057,4.6e-05,5e-05,0.00049,0.082,0.093,0.0066,0.47,0.49,0.034,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35490000,-0.67,-0.0092,-0.0052,0.74,0.56,0.43,-0.18,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00013,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00057,4.6e-05,5e-05,0.00049,0.088,0.099,0.0065,0.49,0.51,0.034,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35590000,-0.67,-0.0061,-0.0053,0.74,0.45,0.36,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00012,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00054,3.9e-05,4.3e-05,0.00046,0.07,0.076,0.0062,0.48,0.5,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35690000,-0.67,-0.0061,-0.0053,0.74,0.47,0.39,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00012,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00054,3.9e-05,4.3e-05,0.00047,0.075,0.081,0.0062,0.5,0.52,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35790000,-0.67,-0.0038,-0.0053,0.74,0.38,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00011,-0.064,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00053,3.4e-05,3.8e-05,0.00045,0.062,0.066,0.0059,0.49,0.51,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35890000,-0.67,-0.0038,-0.0053,0.74,0.4,0.36,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00011,-0.064,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00053,3.4e-05,3.8e-05,0.00045,0.067,0.071,0.0059,0.5,0.53,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35990000,-0.67,-0.0019,-0.0053,0.74,0.33,0.3,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00011,-0.072,0.057,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00052,3e-05,3.4e-05,0.00045,0.058,0.06,0.0057,0.5,0.52,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36090000,-0.67,-0.002,-0.0052,0.74,0.34,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00011,-0.072,0.057,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00052,3e-05,3.4e-05,0.00045,0.063,0.066,0.0057,0.51,0.53,0.032,2.7e-07,2.8e-07,3e-06,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36190000,-0.67,-0.00046,-0.0051,0.74,0.28,0.28,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.0001,-0.084,0.066,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00052,2.7e-05,3.1e-05,0.00045,0.055,0.057,0.0056,0.51,0.53,0.032,2.7e-07,2.8e-07,3e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36290000,-0.67,-0.00059,-0.0051,0.74,0.29,0.3,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.0001,-0.084,0.066,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00052,2.7e-05,3.1e-05,0.00045,0.061,0.062,0.0056,0.52,0.54,0.032,2.8e-07,2.8e-07,3e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36390000,-0.67,0.00052,-0.0049,0.74,0.24,0.26,-0.18,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.0001,-0.097,0.076,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00052,2.4e-05,2.9e-05,0.00044,0.054,0.055,0.0055,0.51,0.54,0.032,2.8e-07,2.8e-07,3e-06,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36490000,-0.67,0.00043,-0.0049,0.74,0.25,0.28,-0.18,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.0001,-0.097,0.076,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00052,2.4e-05,2.9e-05,0.00045,0.059,0.061,0.0055,0.53,0.55,0.032,2.8e-07,2.8e-07,3e-06,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36590000,-0.67,0.0013,-0.0047,0.74,0.21,0.24,-0.18,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.0001,-0.11,0.086,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00052,2.2e-05,2.7e-05,0.00045,0.053,0.054,0.0055,0.52,0.55,0.031,2.8e-07,2.8e-07,3e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36690000,-0.67,0.0012,-0.0047,0.74,0.21,0.26,-0.17,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.0001,-0.11,0.086,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00052,2.2e-05,2.7e-05,0.00045,0.058,0.06,0.0055,0.54,0.56,0.031,2.8e-07,2.8e-07,3e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36790000,-0.67,0.0019,-0.0045,0.74,0.18,0.22,-0.17,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.0001,-0.12,0.096,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00052,2.1e-05,2.6e-05,0.00045,0.052,0.053,0.0055,0.53,0.56,0.031,2.8e-07,2.8e-07,3e-06,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36890000,-0.67,0.0018,-0.0045,0.74,0.18,0.24,-0.16,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.0001,-0.13,0.096,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00052,2.1e-05,2.6e-05,0.00045,0.057,0.059,0.0056,0.55,0.57,0.031,2.8e-07,2.8e-07,3e-06,0.022,0.021,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36990000,-0.67,0.0023,-0.0043,0.74,0.15,0.2,-0.16,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00011,-0.14,0.1,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00052,2e-05,2.5e-05,0.00045,0.051,0.052,0.0056,0.54,0.57,0.031,2.8e-07,2.8e-07,3e-06,0.021,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37090000,-0.67,0.0022,-0.0042,0.74,0.15,0.21,-0.15,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00011,-0.14,0.1,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00053,2e-05,2.5e-05,0.00045,0.056,0.058,0.0057,0.56,0.58,0.031,2.8e-07,2.8e-07,3e-06,0.021,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37190000,-0.67,0.0026,-0.0041,0.74,0.12,0.18,-0.14,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00011,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.9e-05,2.4e-05,0.00045,0.05,0.052,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,3e-06,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37290000,-0.67,0.0025,-0.0041,0.74,0.12,0.19,-0.14,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00011,-0.15,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.9e-05,2.4e-05,0.00045,0.055,0.057,0.0059,0.56,0.59,0.031,2.8e-07,2.9e-07,3e-06,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37390000,-0.67,0.0028,-0.0039,0.74,0.1,0.16,-0.13,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00011,-0.16,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.3e-05,0.00045,0.05,0.051,0.0059,0.56,0.59,0.031,2.9e-07,2.9e-07,3e-06,0.02,0.018,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37490000,-0.67,0.0027,-0.0038,0.74,0.099,0.17,-0.13,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00011,-0.16,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.3e-05,0.00045,0.054,0.056,0.006,0.57,0.6,0.031,2.9e-07,2.9e-07,3e-06,0.02,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37590000,-0.67,0.0029,-0.0037,0.74,0.08,0.14,-0.12,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00012,-0.17,0.12,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.049,0.05,0.0061,0.57,0.6,0.031,2.9e-07,2.9e-07,3e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37690000,-0.67,0.0028,-0.0037,0.74,0.078,0.15,-0.11,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00012,-0.17,0.12,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.3e-05,0.00045,0.053,0.055,0.0062,0.58,0.61,0.031,2.9e-07,2.9e-07,3e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37790000,-0.67,0.003,-0.0036,0.74,0.061,0.13,-0.1,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00012,-0.18,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.048,0.049,0.0063,0.58,0.61,0.03,2.9e-07,2.9e-07,3e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37890000,-0.67,0.003,-0.0036,0.74,0.058,0.13,-0.094,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00012,-0.18,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.052,0.053,0.0064,0.59,0.62,0.03,2.9e-07,2.9e-07,3e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37990000,-0.67,0.003,-0.0036,0.74,0.044,0.11,-0.085,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00012,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.047,0.048,0.0065,0.59,0.62,0.031,2.9e-07,2.9e-07,3e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38090000,-0.67,0.003,-0.0036,0.74,0.04,0.12,-0.075,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00012,-0.19,0.13,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.051,0.052,0.0066,0.6,0.63,0.031,2.9e-07,2.9e-07,3e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38190000,-0.67,0.003,-0.0034,0.74,0.027,0.1,-0.067,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00013,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.7e-05,2.2e-05,0.00045,0.045,0.047,0.0067,0.6,0.63,0.031,2.9e-07,3e-07,3e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38290000,-0.67,0.003,-0.0034,0.74,0.024,0.1,-0.06,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00013,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.049,0.051,0.0068,0.61,0.64,0.031,2.9e-07,3e-07,3e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38390000,-0.67,0.003,-0.0033,0.74,0.015,0.087,-0.052,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00013,-0.2,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.044,0.046,0.0069,0.61,0.64,0.031,2.9e-07,3e-07,3e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38490000,-0.67,0.003,-0.0033,0.74,0.012,0.09,-0.045,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00013,-0.2,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.048,0.049,0.007,0.62,0.65,0.031,3e-07,3e-07,3e-06,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38590000,-0.67,0.003,-0.0032,0.74,0.0076,0.076,-0.038,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00013,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.043,0.044,0.0071,0.62,0.65,0.031,3e-07,3e-07,3e-06,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38690000,-0.67,0.0029,-0.0031,0.74,0.0033,0.076,-0.031,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00013,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.047,0.048,0.0072,0.63,0.66,0.031,3e-07,3e-07,3e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38790000,-0.67,0.0029,-0.0031,0.74,-0.0019,0.063,-0.023,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00013,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.042,0.043,0.0073,0.63,0.66,0.031,3e-07,3e-07,3e-06,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38890000,-0.67,0.0027,-0.0031,0.74,-0.012,0.053,0.48,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00013,-0.21,0.14,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00053,1.8e-05,2.2e-05,0.00045,0.045,0.046,0.0075,0.64,0.67,0.032,3e-07,3e-07,3e-06,0.014,0.014,0.0005,0.0025,4.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34190000,-0.56,-0.0023,-0.012,0.83,-0.89,-0.56,0.74,-11,-16,-3.7e+02,-0.0015,-0.0057,-0.00011,-0.022,0.0078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00075,6.5e-05,7.3e-05,0.00037,0.037,0.042,0.0067,0.25,0.25,0.035,2.7e-07,2.7e-07,3e-06,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34290000,-0.6,-0.0032,-0.0091,0.8,-0.84,-0.51,0.74,-11,-16,-3.7e+02,-0.0015,-0.0057,-0.00011,-0.022,0.0078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0007,6.5e-05,7.2e-05,0.00043,0.043,0.049,0.0066,0.25,0.25,0.035,2.7e-07,2.7e-07,3e-06,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34390000,-0.63,-0.0031,-0.0066,0.78,-0.83,-0.47,0.74,-11,-16,-3.7e+02,-0.0016,-0.0057,-0.00012,-0.027,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00064,6.1e-05,6.6e-05,0.00045,0.042,0.047,0.0065,0.13,0.13,0.035,2.7e-07,2.7e-07,3e-06,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34490000,-0.65,-0.0041,-0.0044,0.76,-0.78,-0.43,0.73,-11,-16,-3.7e+02,-0.0016,-0.0057,-0.00012,-0.027,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00062,6.1e-05,6.6e-05,0.00047,0.049,0.055,0.0064,0.13,0.13,0.035,2.7e-07,2.7e-07,3e-06,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34590000,-0.66,-0.0034,-0.0033,0.76,-0.77,-0.41,0.73,-11,-16,-3.7e+02,-0.0016,-0.0057,-0.00012,-0.037,0.022,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0006,5.5e-05,6e-05,0.00048,0.047,0.051,0.0063,0.086,0.087,0.034,2.6e-07,2.7e-07,3e-06,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34690000,-0.66,-0.0038,-0.0025,0.75,-0.72,-0.37,0.73,-11,-16,-3.7e+02,-0.0016,-0.0057,-0.00012,-0.037,0.022,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00059,5.5e-05,6e-05,0.00048,0.054,0.059,0.0063,0.089,0.09,0.034,2.7e-07,2.7e-07,3e-06,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34790000,-0.67,-0.0024,-0.0021,0.75,-0.73,-0.38,0.72,-11,-17,-3.7e+02,-0.0016,-0.0057,-0.00012,-0.051,0.033,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00057,5e-05,5.4e-05,0.00048,0.051,0.054,0.0062,0.068,0.068,0.034,2.6e-07,2.7e-07,3e-06,0.025,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34890000,-0.67,-0.0024,-0.002,0.74,-0.68,-0.34,0.72,-11,-17,-3.7e+02,-0.0016,-0.0057,-0.00012,-0.051,0.033,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00057,5e-05,5.4e-05,0.00049,0.058,0.062,0.0062,0.072,0.072,0.034,2.7e-07,2.7e-07,3e-06,0.025,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
34990000,-0.67,-0.0087,-0.0046,0.74,0.35,0.23,-0.13,-11,-17,-3.7e+02,-0.0017,-0.0057,-0.00012,-0.066,0.046,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,4.6e-05,4.9e-05,0.00048,0.058,0.066,0.0068,0.058,0.059,0.034,2.6e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35090000,-0.67,-0.0087,-0.0046,0.74,0.48,0.26,-0.19,-11,-17,-3.7e+02,-0.0017,-0.0057,-0.00012,-0.066,0.046,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,4.6e-05,4.9e-05,0.00049,0.062,0.073,0.0068,0.063,0.064,0.034,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35190000,-0.67,-0.0079,-0.0042,0.74,0.48,0.23,-0.19,-11,-17,-3.7e+02,-0.0017,-0.0057,-9.7e-05,-0.066,0.046,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,4.5e-05,4.8e-05,0.00048,0.065,0.074,0.0067,0.055,0.057,0.034,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35290000,-0.67,-0.008,-0.0043,0.74,0.51,0.26,-0.18,-11,-17,-3.7e+02,-0.0017,-0.0057,-9.7e-05,-0.066,0.046,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,4.5e-05,4.8e-05,0.00048,0.07,0.08,0.0066,0.062,0.064,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35390000,-0.67,-0.007,-0.0038,0.74,0.5,0.23,-0.19,-11,-17,-3.7e+02,-0.0017,-0.0058,-7.6e-05,-0.066,0.046,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,4.4e-05,4.7e-05,0.00048,0.071,0.079,0.0065,0.056,0.058,0.034,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35490000,-0.67,-0.0071,-0.0038,0.74,0.52,0.26,-0.18,-11,-17,-3.7e+02,-0.0017,-0.0058,-7.6e-05,-0.066,0.046,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00056,4.4e-05,4.7e-05,0.00048,0.076,0.085,0.0064,0.065,0.068,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35590000,-0.67,-0.0038,-0.0042,0.74,0.39,0.18,-0.2,-11,-17,-3.7e+02,-0.0017,-0.0058,-7.1e-05,-0.066,0.046,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00053,3.7e-05,4e-05,0.00046,0.058,0.063,0.0061,0.054,0.055,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35690000,-0.67,-0.0038,-0.0042,0.74,0.41,0.21,-0.2,-11,-17,-3.7e+02,-0.0017,-0.0058,-7.1e-05,-0.066,0.046,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00053,3.7e-05,4.1e-05,0.00046,0.063,0.067,0.0061,0.061,0.064,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35790000,-0.67,-0.0016,-0.0044,0.74,0.32,0.15,-0.2,-11,-17,-3.7e+02,-0.0017,-0.0058,-6.6e-05,-0.067,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00052,3.2e-05,3.6e-05,0.00044,0.05,0.053,0.0058,0.052,0.053,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35890000,-0.67,-0.0016,-0.0044,0.74,0.34,0.17,-0.2,-11,-17,-3.7e+02,-0.0017,-0.0058,-6.6e-05,-0.067,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00052,3.2e-05,3.6e-05,0.00045,0.055,0.057,0.0058,0.059,0.061,0.033,2.7e-07,2.7e-07,3e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
35990000,-0.67,0.00017,-0.0046,0.74,0.26,0.13,-0.2,-11,-17,-3.7e+02,-0.0018,-0.0058,-6.3e-05,-0.071,0.054,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00051,2.8e-05,3.3e-05,0.00044,0.046,0.047,0.0056,0.05,0.051,0.032,2.7e-07,2.7e-07,3e-06,0.024,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36090000,-0.67,7.1e-05,-0.0045,0.74,0.27,0.15,-0.2,-11,-17,-3.7e+02,-0.0018,-0.0058,-6.3e-05,-0.071,0.054,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00051,2.8e-05,3.3e-05,0.00044,0.051,0.052,0.0056,0.057,0.058,0.032,2.7e-07,2.7e-07,3e-06,0.024,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36190000,-0.67,0.0014,-0.0046,0.74,0.21,0.12,-0.2,-11,-17,-3.7e+02,-0.0018,-0.0058,-6.1e-05,-0.077,0.062,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00051,2.5e-05,3e-05,0.00044,0.043,0.044,0.0055,0.049,0.05,0.032,2.7e-07,2.7e-07,3e-06,0.024,0.022,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36290000,-0.67,0.0013,-0.0045,0.74,0.22,0.14,-0.19,-11,-17,-3.7e+02,-0.0018,-0.0058,-6.1e-05,-0.077,0.062,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00051,2.5e-05,3e-05,0.00044,0.048,0.049,0.0055,0.056,0.057,0.032,2.7e-07,2.8e-07,3e-06,0.024,0.022,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36390000,-0.67,0.0022,-0.0046,0.74,0.17,0.11,-0.19,-11,-17,-3.7e+02,-0.0018,-0.0058,-5.9e-05,-0.085,0.071,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00051,2.3e-05,2.8e-05,0.00044,0.042,0.043,0.0054,0.048,0.049,0.032,2.7e-07,2.8e-07,3e-06,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36490000,-0.67,0.0021,-0.0046,0.74,0.18,0.12,-0.19,-11,-17,-3.7e+02,-0.0018,-0.0058,-5.9e-05,-0.085,0.071,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00051,2.3e-05,2.8e-05,0.00044,0.047,0.048,0.0055,0.055,0.055,0.032,2.8e-07,2.8e-07,3e-06,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36590000,-0.67,0.0027,-0.0045,0.74,0.14,0.1,-0.18,-11,-17,-3.7e+02,-0.0018,-0.0058,-5.8e-05,-0.093,0.079,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00051,2.1e-05,2.6e-05,0.00044,0.041,0.042,0.0054,0.047,0.048,0.031,2.8e-07,2.8e-07,3e-06,0.023,0.021,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36690000,-0.67,0.0027,-0.0045,0.74,0.14,0.12,-0.18,-11,-17,-3.7e+02,-0.0018,-0.0058,-5.8e-05,-0.093,0.08,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00051,2.1e-05,2.6e-05,0.00044,0.046,0.048,0.0055,0.054,0.054,0.031,2.8e-07,2.8e-07,3e-06,0.023,0.021,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36790000,-0.67,0.0032,-0.0044,0.74,0.11,0.097,-0.17,-11,-17,-3.7e+02,-0.0018,-0.0058,-5.8e-05,-0.1,0.088,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.9e-05,2.5e-05,0.00044,0.041,0.042,0.0055,0.047,0.047,0.031,2.8e-07,2.8e-07,3e-06,0.022,0.02,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36890000,-0.67,0.0031,-0.0044,0.74,0.11,0.11,-0.17,-11,-17,-3.7e+02,-0.0018,-0.0058,-5.8e-05,-0.1,0.088,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.9e-05,2.5e-05,0.00044,0.046,0.047,0.0056,0.053,0.054,0.031,2.8e-07,2.8e-07,3e-06,0.022,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
36990000,-0.67,0.0035,-0.0043,0.74,0.084,0.091,-0.16,-11,-17,-3.7e+02,-0.0018,-0.0058,-5.9e-05,-0.11,0.095,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.8e-05,2.3e-05,0.00044,0.04,0.042,0.0056,0.046,0.047,0.031,2.8e-07,2.8e-07,3e-06,0.021,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37090000,-0.67,0.0034,-0.0042,0.74,0.085,0.1,-0.15,-11,-17,-3.7e+02,-0.0018,-0.0058,-5.9e-05,-0.11,0.095,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.8e-05,2.4e-05,0.00044,0.045,0.047,0.0057,0.053,0.053,0.031,2.8e-07,2.8e-07,3e-06,0.021,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37190000,-0.67,0.0037,-0.0041,0.74,0.062,0.084,-0.15,-11,-17,-3.7e+02,-0.0018,-0.0058,-6e-05,-0.12,0.1,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.7e-05,2.3e-05,0.00044,0.04,0.041,0.0057,0.046,0.046,0.031,2.8e-07,2.8e-07,3e-06,0.02,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37290000,-0.67,0.0037,-0.0041,0.74,0.062,0.094,-0.14,-11,-17,-3.7e+02,-0.0018,-0.0058,-6e-05,-0.12,0.1,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.8e-05,2.3e-05,0.00044,0.044,0.046,0.0058,0.052,0.053,0.031,2.8e-07,2.9e-07,3e-06,0.02,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37390000,-0.67,0.0039,-0.004,0.74,0.042,0.077,-0.14,-12,-17,-3.7e+02,-0.0018,-0.0058,-6.2e-05,-0.13,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.7e-05,2.2e-05,0.00044,0.039,0.041,0.0059,0.046,0.046,0.031,2.8e-07,2.9e-07,3e-06,0.019,0.018,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37490000,-0.67,0.0038,-0.0039,0.74,0.041,0.087,-0.13,-12,-17,-3.7e+02,-0.0018,-0.0058,-6.2e-05,-0.13,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.7e-05,2.2e-05,0.00044,0.043,0.045,0.006,0.052,0.052,0.031,2.8e-07,2.9e-07,3e-06,0.019,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37590000,-0.67,0.0039,-0.0038,0.74,0.025,0.072,-0.12,-12,-17,-3.7e+02,-0.0018,-0.0058,-6.5e-05,-0.13,0.11,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.7e-05,2.2e-05,0.00044,0.038,0.04,0.0061,0.046,0.046,0.031,2.9e-07,2.9e-07,3e-06,0.018,0.017,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37690000,-0.67,0.0038,-0.0038,0.74,0.023,0.081,-0.11,-12,-17,-3.7e+02,-0.0018,-0.0058,-6.5e-05,-0.13,0.11,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.7e-05,2.2e-05,0.00044,0.042,0.044,0.0062,0.052,0.052,0.031,2.9e-07,2.9e-07,3e-06,0.018,0.017,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37790000,-0.67,0.004,-0.0038,0.74,0.01,0.068,-0.1,-12,-17,-3.7e+02,-0.0018,-0.0058,-6.8e-05,-0.14,0.11,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.6e-05,2.1e-05,0.00044,0.037,0.038,0.0063,0.045,0.046,0.03,2.9e-07,2.9e-07,3e-06,0.017,0.016,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37890000,-0.67,0.0039,-0.0038,0.74,0.0074,0.075,-0.096,-12,-17,-3.7e+02,-0.0018,-0.0058,-6.7e-05,-0.14,0.11,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.6e-05,2.1e-05,0.00044,0.041,0.042,0.0064,0.052,0.052,0.03,2.9e-07,2.9e-07,3e-06,0.017,0.016,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
37990000,-0.67,0.004,-0.0037,0.74,-0.003,0.063,-0.087,-12,-17,-3.7e+02,-0.0018,-0.0058,-7e-05,-0.15,0.12,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.6e-05,2.1e-05,0.00044,0.035,0.037,0.0065,0.045,0.046,0.031,2.9e-07,2.9e-07,3e-06,0.016,0.015,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38090000,-0.67,0.0039,-0.0037,0.74,-0.0066,0.07,-0.077,-12,-17,-3.7e+02,-0.0018,-0.0058,-7e-05,-0.15,0.12,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.6e-05,2.1e-05,0.00044,0.039,0.041,0.0066,0.051,0.052,0.031,2.9e-07,2.9e-07,3e-06,0.016,0.015,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38190000,-0.67,0.004,-0.0036,0.74,-0.016,0.059,-0.069,-12,-17,-3.7e+02,-0.0018,-0.0058,-7.3e-05,-0.15,0.12,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.6e-05,2.1e-05,0.00044,0.034,0.036,0.0067,0.045,0.045,0.031,2.9e-07,2.9e-07,3e-06,0.015,0.014,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38290000,-0.67,0.0039,-0.0036,0.74,-0.018,0.064,-0.061,-12,-17,-3.7e+02,-0.0018,-0.0058,-7.3e-05,-0.15,0.12,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.6e-05,2.1e-05,0.00044,0.037,0.039,0.0068,0.051,0.052,0.031,2.9e-07,2.9e-07,3e-06,0.015,0.014,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38390000,-0.67,0.004,-0.0035,0.74,-0.023,0.055,-0.054,-12,-17,-3.7e+02,-0.0018,-0.0058,-7.7e-05,-0.16,0.12,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.6e-05,2.1e-05,0.00043,0.033,0.034,0.0069,0.045,0.045,0.031,2.9e-07,3e-07,3e-06,0.014,0.013,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38490000,-0.67,0.0039,-0.0035,0.74,-0.026,0.06,-0.046,-12,-17,-3.7e+02,-0.0018,-0.0058,-7.7e-05,-0.16,0.12,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.6e-05,2.1e-05,0.00044,0.036,0.037,0.007,0.051,0.051,0.031,2.9e-07,3e-07,3e-06,0.014,0.013,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38590000,-0.67,0.0039,-0.0033,0.74,-0.027,0.052,-0.039,-12,-17,-3.7e+02,-0.0018,-0.0058,-8e-05,-0.16,0.12,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.6e-05,2.1e-05,0.00043,0.031,0.032,0.0071,0.045,0.045,0.031,2.9e-07,3e-07,3e-06,0.013,0.012,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38690000,-0.67,0.0039,-0.0033,0.74,-0.031,0.055,-0.032,-12,-17,-3.7e+02,-0.0018,-0.0058,-8e-05,-0.16,0.12,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.7e-05,2.1e-05,0.00043,0.034,0.035,0.0073,0.051,0.051,0.031,2.9e-07,3e-07,3e-06,0.013,0.012,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38790000,-0.67,0.0038,-0.0033,0.74,-0.032,0.046,-0.024,-12,-17,-3.7e+02,-0.0018,-0.0058,-8.4e-05,-0.17,0.12,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.7e-05,2.1e-05,0.00043,0.03,0.031,0.0073,0.045,0.045,0.031,3e-07,3e-07,3e-06,0.013,0.012,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
38890000,-0.67,0.0036,-0.0033,0.74,-0.041,0.04,0.48,-12,-17,-3.7e+02,-0.0018,-0.0058,-8.4e-05,-0.17,0.12,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00051,1.7e-05,2.1e-05,0.00043,0.032,0.033,0.0075,0.05,0.051,0.032,3e-07,3e-07,3e-06,0.013,0.012,0.0005,0.0025,4.2e-05,0.0025,0.0025,0.0025,0.0025,0,0
|
||||
|
||||
|
Loading…
x
Reference in New Issue
Block a user