From a9cdb36d7c47685ec1d90395b075357a8db14c6a Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Tue, 3 Sep 2024 09:31:39 +0200 Subject: [PATCH 01/40] differential: reset integrators when disarmed (#23637) --- src/modules/rover_differential/RoverDifferential.cpp | 5 +++++ src/modules/rover_differential/RoverDifferential.hpp | 1 + .../RoverDifferentialControl/RoverDifferentialControl.cpp | 7 +++++++ .../RoverDifferentialControl/RoverDifferentialControl.hpp | 5 +++++ 4 files changed, 18 insertions(+) diff --git a/src/modules/rover_differential/RoverDifferential.cpp b/src/modules/rover_differential/RoverDifferential.cpp index 20cbf7d9e3e2..502c38de2a44 100644 --- a/src/modules/rover_differential/RoverDifferential.cpp +++ b/src/modules/rover_differential/RoverDifferential.cpp @@ -115,6 +115,10 @@ void RoverDifferential::Run() break; } + if (!_armed) { // Reset on disarm + _rover_differential_control.resetControllers(); + } + _rover_differential_control.computeMotorCommands(_vehicle_yaw, _vehicle_yaw_rate, _vehicle_forward_speed); } @@ -132,6 +136,7 @@ void RoverDifferential::updateSubscriptions() vehicle_status_s vehicle_status{}; _vehicle_status_sub.copy(&vehicle_status); _nav_state = vehicle_status.nav_state; + _armed = vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED; } if (_vehicle_angular_velocity_sub.updated()) { diff --git a/src/modules/rover_differential/RoverDifferential.hpp b/src/modules/rover_differential/RoverDifferential.hpp index 897a7199ef4d..8dfd4f7affff 100644 --- a/src/modules/rover_differential/RoverDifferential.hpp +++ b/src/modules/rover_differential/RoverDifferential.hpp @@ -111,6 +111,7 @@ class RoverDifferential : public ModuleBase, public ModulePar float _vehicle_yaw{0.f}; float _max_yaw_rate{0.f}; int _nav_state{0}; + bool _armed{false}; DEFINE_PARAMETERS( (ParamFloat) _param_rd_man_yaw_scale, diff --git a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp index c1f96c0ce066..8b16020a0a05 100644 --- a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp +++ b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp @@ -174,3 +174,10 @@ matrix::Vector2f RoverDifferentialControl::computeInverseKinematics(float forwar return Vector2f(forward_speed_normalized - speed_diff_normalized, forward_speed_normalized + speed_diff_normalized); } + +void RoverDifferentialControl::resetControllers() +{ + pid_reset_integral(&_pid_throttle); + pid_reset_integral(&_pid_yaw_rate); + pid_reset_integral(&_pid_yaw); +} diff --git a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp index d3ef7a076fd6..9f49186ad8b6 100644 --- a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp +++ b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp @@ -72,6 +72,11 @@ class RoverDifferentialControl : public ModuleParams */ void computeMotorCommands(float vehicle_yaw, float vehicle_yaw_rate, float vehicle_forward_speed); + /** + * @brief Reset PID controllers + */ + void resetControllers(); + protected: /** * @brief Update the parameters of the module. From 80d4fad624f399c889ba8bd55f9a49bc062bc237 Mon Sep 17 00:00:00 2001 From: Konrad Date: Wed, 28 Aug 2024 18:00:10 +0200 Subject: [PATCH 02/40] DistanceSensorCheck: do not raise a distance sensor failure if the SFXX_MODE is set to 2 and we are in a VTOL FX flight phase --- msg/DistanceSensor.msg | 5 +++++ .../lightware_laser_i2c/lightware_laser_i2c.cpp | 13 ++++++++++++- src/lib/drivers/rangefinder/PX4Rangefinder.cpp | 1 + src/lib/drivers/rangefinder/PX4Rangefinder.hpp | 2 ++ .../checks/distanceSensorChecks.cpp | 3 ++- 5 files changed, 22 insertions(+), 2 deletions(-) diff --git a/msg/DistanceSensor.msg b/msg/DistanceSensor.msg index dd08e4b5898b..88bd8ca81906 100644 --- a/msg/DistanceSensor.msg +++ b/msg/DistanceSensor.msg @@ -40,3 +40,8 @@ uint8 ROTATION_UPWARD_FACING = 24 # MAV_SENSOR_ROTATION_PITCH_90 uint8 ROTATION_DOWNWARD_FACING = 25 # MAV_SENSOR_ROTATION_PITCH_270 uint8 ROTATION_CUSTOM = 100 # MAV_SENSOR_ROTATION_CUSTOM + +uint8 mode # mode of operation +uint8 DISTANCE_SENSOR_MODE_UNKNOWN = 0 # Unknown mode +uint8 DISTANCE_SENSOR_MODE_RUN = 1 # sensor is running continuosly +uint8 DISTANCE_SENSOR_MODE_DISABLED = 2 # sensor is disabled per request diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp index 8e0815bff561..0bc0f55a772a 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp +++ b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp @@ -145,6 +145,7 @@ class LightwareLaser : public device::I2C, public I2CSPIDriver, typeof(px4::msg::VehicleStatus::vehicle_type) _vehicle_type{px4::msg::VehicleStatus::VEHICLE_TYPE_UNKNOWN}; bool _restriction{false}; bool _auto_restriction{false}; + bool _prev_restriction{false}; }; LightwareLaser::LightwareLaser(const I2CSPIDriverConfig &config) : @@ -438,7 +439,7 @@ int LightwareLaser::updateRestriction() updateParams(); } - bool _prev_restriction{_restriction}; + _prev_restriction = _restriction; switch (_param_sf1xx_mode.get()) { case 0: // Sensor disabled @@ -498,6 +499,8 @@ void LightwareLaser::RunImpl() case State::Running: if (!_restriction) { + _px4_rangefinder.set_mode(distance_sensor_s::DISTANCE_SENSOR_MODE_RUN); + if (PX4_OK != collect()) { PX4_DEBUG("collection error"); @@ -506,6 +509,14 @@ void LightwareLaser::RunImpl() _consecutive_errors = 0; } } + + } else { + _px4_rangefinder.set_mode(distance_sensor_s::DISTANCE_SENSOR_MODE_DISABLED); + + if (!_prev_restriction) { // Publish disabled status once + _px4_rangefinder.update(hrt_absolute_time(), -1.f, 0); + } + } ScheduleDelayed(_conversion_interval); diff --git a/src/lib/drivers/rangefinder/PX4Rangefinder.cpp b/src/lib/drivers/rangefinder/PX4Rangefinder.cpp index 63937f8f59e3..b3297a75fad8 100644 --- a/src/lib/drivers/rangefinder/PX4Rangefinder.cpp +++ b/src/lib/drivers/rangefinder/PX4Rangefinder.cpp @@ -40,6 +40,7 @@ PX4Rangefinder::PX4Rangefinder(const uint32_t device_id, const uint8_t device_or set_device_id(device_id); set_orientation(device_orientation); set_rangefinder_type(distance_sensor_s::MAV_DISTANCE_SENSOR_LASER); // Default to type LASER + set_mode(UINT8_C(0)); } PX4Rangefinder::~PX4Rangefinder() diff --git a/src/lib/drivers/rangefinder/PX4Rangefinder.hpp b/src/lib/drivers/rangefinder/PX4Rangefinder.hpp index 6c6b87c0eb01..1005242abaa8 100644 --- a/src/lib/drivers/rangefinder/PX4Rangefinder.hpp +++ b/src/lib/drivers/rangefinder/PX4Rangefinder.hpp @@ -60,6 +60,8 @@ class PX4Rangefinder void set_orientation(const uint8_t device_orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING); + void set_mode(const uint8_t mode) {_distance_sensor_pub.get().mode = mode; } + void update(const hrt_abstime ×tamp_sample, const float distance, const int8_t quality = -1); int get_instance() { return _distance_sensor_pub.get_instance(); }; diff --git a/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp b/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp index b09cde4632a9..02b0a390fd22 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp @@ -48,7 +48,8 @@ void DistanceSensorChecks::checkAndReport(const Context &context, Report &report if (exists) { distance_sensor_s dist_sens; - valid = _distance_sensor_sub[instance].copy(&dist_sens) && hrt_elapsed_time(&dist_sens.timestamp) < 1_s; + valid = _distance_sensor_sub[instance].copy(&dist_sens) && ((hrt_elapsed_time(&dist_sens.timestamp) < 1_s) + || (dist_sens.mode == distance_sensor_s::DISTANCE_SENSOR_MODE_DISABLED)); reporter.setIsPresent(health_component_t::distance_sensor); } From 6fa6360aef492297a23c8ae164d5da26b541c311 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 3 Sep 2024 18:10:37 +0200 Subject: [PATCH 03/40] Commander: always allow to switch to LAND mode (#23580) Special handling for LAND mode: always allow to switch into it such that if used as emergency mode it is always available. When triggering it the user generally wants the vehicle to descend immediately, and if that means to switch to DESCEND it is fine. Signed-off-by: Silvan Fuhrer --- src/modules/commander/Commander.cpp | 17 +++++++++++++++-- 1 file changed, 15 insertions(+), 2 deletions(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index fe0b89e8b2f4..ff29ad04819a 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -887,7 +887,14 @@ Commander::handle_command(const vehicle_command_s &cmd) } if (desired_nav_state != vehicle_status_s::NAVIGATION_STATE_MAX) { - if (_user_mode_intention.change(desired_nav_state, getSourceFromCommand(cmd))) { + + // Special handling for LAND mode: always allow to switch into it such that if used + // as emergency mode it is always available. When triggering it the user generally wants + // the vehicle to descend immediately, and if that means to switch to DESCEND it is fine. + + const bool force = desired_nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND; + + if (_user_mode_intention.change(desired_nav_state, getSourceFromCommand(cmd), false, force)) { main_ret = TRANSITION_CHANGED; } else { @@ -1062,7 +1069,13 @@ Commander::handle_command(const vehicle_command_s &cmd) break; case vehicle_command_s::VEHICLE_CMD_NAV_LAND: { - if (_user_mode_intention.change(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND, getSourceFromCommand(cmd))) { + // Special handling for LAND mode: always allow to switch into it such that if used + // as emergency mode it is always available. When triggering it the user generally wants + // the vehicle to descend immediately, and if that means to switch to DESCEND it is fine. + const bool force = true; + + if (_user_mode_intention.change(vehicle_status_s::NAVIGATION_STATE_AUTO_LAND, getSourceFromCommand(cmd), false, + force)) { mavlink_log_info(&_mavlink_log_pub, "Landing at current position\t"); events::send(events::ID("commander_landing_current_pos"), events::Log::Info, "Landing at current position"); From 81cf6a736db89e3600b14dff303bfc1a5c6ab3c3 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 5 Sep 2024 11:20:39 +0200 Subject: [PATCH 04/40] Commander: add VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE to list of externaly handled commands (#23642) Signed-off-by: Silvan Fuhrer --- src/modules/commander/Commander.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index ff29ad04819a..6b898d158d46 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -1512,6 +1512,7 @@ Commander::handle_command(const vehicle_command_s &cmd) case vehicle_command_s::VEHICLE_CMD_REQUEST_MESSAGE: case vehicle_command_s::VEHICLE_CMD_DO_WINCH: case vehicle_command_s::VEHICLE_CMD_DO_GRIPPER: + case vehicle_command_s::VEHICLE_CMD_EXTERNAL_POSITION_ESTIMATE: /* ignore commands that are handled by other parts of the system */ break; From f7c35291eefabef228cbbadb1a898f3637a0055a Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 3 Sep 2024 16:35:26 +0200 Subject: [PATCH 05/40] Rover Differential: remove RC keyword from params Signed-off-by: Silvan Fuhrer --- src/modules/rover_differential/module.yaml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/rover_differential/module.yaml b/src/modules/rover_differential/module.yaml index edc3f8e5ba7f..6602497685db 100644 --- a/src/modules/rover_differential/module.yaml +++ b/src/modules/rover_differential/module.yaml @@ -20,7 +20,7 @@ parameters: description: short: Manual yaw rate scale long: | - In manual mode the setpoint for the yaw rate received from the rc remote + In manual mode the setpoint for the yaw rate received from the yaw stick is scaled by this value. type: float min: 0.001 From 556a302a09043bd7582102da284cd2791a4a97a2 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 3 Sep 2024 16:36:43 +0200 Subject: [PATCH 06/40] Logger: replace RC keyword by 'manual control' Signed-off-by: Silvan Fuhrer --- src/modules/logger/params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/logger/params.c b/src/modules/logger/params.c index 93bf9ae5e5cd..9ab1d8ee2445 100644 --- a/src/modules/logger/params.c +++ b/src/modules/logger/params.c @@ -59,7 +59,7 @@ PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0); * @value 0 when armed until disarm (default) * @value 1 from boot until disarm * @value 2 from boot until shutdown - * @value 3 depending on AUX1 RC channel + * @value 3 depending on manual control switch AUX1 * @value 4 from 1st armed until shutdown * * @reboot_required true From d967cdbb483f6e5e8b66ab88963bfce9342f91c4 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 3 Sep 2024 18:20:04 +0200 Subject: [PATCH 07/40] Manual control: rename SOURCE_RC_STICK_GESTURE to SOURCE_MANUAL_CONTROL_GESTURE Signed-off-by: Silvan Fuhrer --- msg/ActionRequest.msg | 2 +- src/modules/commander/Commander.cpp | 4 ++-- src/modules/manual_control/ManualControl.cpp | 6 +++--- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/msg/ActionRequest.msg b/msg/ActionRequest.msg index 888814e0cc7d..4493708a869f 100644 --- a/msg/ActionRequest.msg +++ b/msg/ActionRequest.msg @@ -11,7 +11,7 @@ uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 uint8 source # how the request was triggered -uint8 SOURCE_RC_STICK_GESTURE = 0 +uint8 SOURCE_MANUAL_CONTROL_GESTURE = 0 uint8 SOURCE_RC_SWITCH = 1 uint8 SOURCE_RC_BUTTON = 2 uint8 SOURCE_RC_MODE_SLOT = 3 diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 6b898d158d46..5f69ee5ff5c4 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -1629,7 +1629,7 @@ void Commander::executeActionRequest(const action_request_s &action_request) // Silently ignore RC actions during RC calibration if (_vehicle_status.rc_calibration_in_progress - && (action_request.source == action_request_s::SOURCE_RC_STICK_GESTURE + && (action_request.source == action_request_s::SOURCE_MANUAL_CONTROL_GESTURE || action_request.source == action_request_s::SOURCE_RC_SWITCH || action_request.source == action_request_s::SOURCE_RC_BUTTON || action_request.source == action_request_s::SOURCE_RC_MODE_SLOT)) { @@ -1637,7 +1637,7 @@ void Commander::executeActionRequest(const action_request_s &action_request) } switch (action_request.source) { - case action_request_s::SOURCE_RC_STICK_GESTURE: arm_disarm_reason = arm_disarm_reason_t::rc_stick; break; + case action_request_s::SOURCE_MANUAL_CONTROL_GESTURE: arm_disarm_reason = arm_disarm_reason_t::rc_stick; break; case action_request_s::SOURCE_RC_SWITCH: arm_disarm_reason = arm_disarm_reason_t::rc_switch; break; diff --git a/src/modules/manual_control/ManualControl.cpp b/src/modules/manual_control/ManualControl.cpp index 7633a9d16363..ecc932fd5c3c 100644 --- a/src/modules/manual_control/ManualControl.cpp +++ b/src/modules/manual_control/ManualControl.cpp @@ -356,7 +356,7 @@ void ManualControl::processStickArming(const manual_control_setpoint_s &input) _stick_arm_hysteresis.set_state_and_update(left_stick_lower_right && right_stick_centered, input.timestamp); if (_param_man_arm_gesture.get() && !previous_stick_arm_hysteresis && _stick_arm_hysteresis.get_state()) { - sendActionRequest(action_request_s::ACTION_ARM, action_request_s::SOURCE_RC_STICK_GESTURE); + sendActionRequest(action_request_s::ACTION_ARM, action_request_s::SOURCE_MANUAL_CONTROL_GESTURE); } // Disarm gesture @@ -366,7 +366,7 @@ void ManualControl::processStickArming(const manual_control_setpoint_s &input) _stick_disarm_hysteresis.set_state_and_update(left_stick_lower_left && right_stick_centered, input.timestamp); if (_param_man_arm_gesture.get() && !previous_stick_disarm_hysteresis && _stick_disarm_hysteresis.get_state()) { - sendActionRequest(action_request_s::ACTION_DISARM, action_request_s::SOURCE_RC_STICK_GESTURE); + sendActionRequest(action_request_s::ACTION_DISARM, action_request_s::SOURCE_MANUAL_CONTROL_GESTURE); } // Kill gesture @@ -377,7 +377,7 @@ void ManualControl::processStickArming(const manual_control_setpoint_s &input) _stick_kill_hysteresis.set_state_and_update(left_stick_lower_left && right_stick_lower_right, input.timestamp); if (!previous_stick_kill_hysteresis && _stick_kill_hysteresis.get_state()) { - sendActionRequest(action_request_s::ACTION_KILL, action_request_s::SOURCE_RC_STICK_GESTURE); + sendActionRequest(action_request_s::ACTION_KILL, action_request_s::SOURCE_MANUAL_CONTROL_GESTURE); } } } From 8eaf93468e320849f5663dfbe1054d113173ffbb Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Tue, 3 Sep 2024 18:22:28 +0200 Subject: [PATCH 08/40] Commander: feedback string for arming/disarming: make clear when from gesture Signed-off-by: Silvan Fuhrer --- src/lib/events/enums.json | 2 +- src/modules/commander/Commander.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/src/lib/events/enums.json b/src/lib/events/enums.json index 1a0817c8adbb..29a44bed4f45 100644 --- a/src/lib/events/enums.json +++ b/src/lib/events/enums.json @@ -448,7 +448,7 @@ }, "1": { "name": "rc_stick", - "description": "RC" + "description": "Stick gesture" }, "2": { "name": "rc_switch", diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 5f69ee5ff5c4..5a23b02f1f45 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -503,7 +503,7 @@ static constexpr const char *arm_disarm_reason_str(arm_disarm_reason_t calling_r switch (calling_reason) { case arm_disarm_reason_t::transition_to_standby: return ""; - case arm_disarm_reason_t::rc_stick: return "RC"; + case arm_disarm_reason_t::rc_stick: return "Stick gesture"; case arm_disarm_reason_t::rc_switch: return "RC (switch)"; From e4d25df58a3a55e2f7b95b630c54f433a59a2ee7 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 5 Sep 2024 15:21:03 +0200 Subject: [PATCH 09/40] Consistently use "stick gesture" for "rc stick gesture" --- msg/ActionRequest.msg | 2 +- msg/VehicleStatus.msg | 2 +- src/lib/events/enums.json | 4 ++-- src/modules/commander/Commander.cpp | 14 +++++++------- src/modules/manual_control/ManualControl.cpp | 8 ++++---- 5 files changed, 15 insertions(+), 15 deletions(-) diff --git a/msg/ActionRequest.msg b/msg/ActionRequest.msg index 4493708a869f..c8a79c69b943 100644 --- a/msg/ActionRequest.msg +++ b/msg/ActionRequest.msg @@ -11,7 +11,7 @@ uint8 ACTION_VTOL_TRANSITION_TO_MULTICOPTER = 6 uint8 ACTION_VTOL_TRANSITION_TO_FIXEDWING = 7 uint8 source # how the request was triggered -uint8 SOURCE_MANUAL_CONTROL_GESTURE = 0 +uint8 SOURCE_STICK_GESTURE = 0 uint8 SOURCE_RC_SWITCH = 1 uint8 SOURCE_RC_BUTTON = 2 uint8 SOURCE_RC_MODE_SLOT = 3 diff --git a/msg/VehicleStatus.msg b/msg/VehicleStatus.msg index 4c711b9763e1..6756da812977 100644 --- a/msg/VehicleStatus.msg +++ b/msg/VehicleStatus.msg @@ -12,7 +12,7 @@ uint8 ARMING_STATE_ARMED = 2 uint8 latest_arming_reason uint8 latest_disarming_reason uint8 ARM_DISARM_REASON_TRANSITION_TO_STANDBY = 0 -uint8 ARM_DISARM_REASON_RC_STICK = 1 +uint8 ARM_DISARM_REASON_STICK_GESTURE = 1 uint8 ARM_DISARM_REASON_RC_SWITCH = 2 uint8 ARM_DISARM_REASON_COMMAND_INTERNAL = 3 uint8 ARM_DISARM_REASON_COMMAND_EXTERNAL = 4 diff --git a/src/lib/events/enums.json b/src/lib/events/enums.json index 29a44bed4f45..dece82e5bb2b 100644 --- a/src/lib/events/enums.json +++ b/src/lib/events/enums.json @@ -447,12 +447,12 @@ "description": "Transition to standby" }, "1": { - "name": "rc_stick", + "name": "stick_gesture", "description": "Stick gesture" }, "2": { "name": "rc_switch", - "description": "RC (switch)" + "description": "RC switch" }, "3": { "name": "command_internal", diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 5a23b02f1f45..eed543fe2df5 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -503,9 +503,9 @@ static constexpr const char *arm_disarm_reason_str(arm_disarm_reason_t calling_r switch (calling_reason) { case arm_disarm_reason_t::transition_to_standby: return ""; - case arm_disarm_reason_t::rc_stick: return "Stick gesture"; + case arm_disarm_reason_t::stick_gesture: return "Stick gesture"; - case arm_disarm_reason_t::rc_switch: return "RC (switch)"; + case arm_disarm_reason_t::rc_switch: return "RC switch"; case arm_disarm_reason_t::command_internal: return "internal command"; @@ -583,7 +583,7 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_ return TRANSITION_DENIED; } - } else if (calling_reason == arm_disarm_reason_t::rc_stick + } else if (calling_reason == arm_disarm_reason_t::stick_gesture || calling_reason == arm_disarm_reason_t::rc_switch || calling_reason == arm_disarm_reason_t::rc_button) { @@ -634,12 +634,12 @@ transition_result_t Commander::disarm(arm_disarm_reason_t calling_reason, bool f const bool mc_manual_thrust_mode = _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && _vehicle_control_mode.flag_control_manual_enabled && !_vehicle_control_mode.flag_control_climb_rate_enabled; - const bool commanded_by_rc = (calling_reason == arm_disarm_reason_t::rc_stick) + const bool commanded_by_rc = (calling_reason == arm_disarm_reason_t::stick_gesture) || (calling_reason == arm_disarm_reason_t::rc_switch) || (calling_reason == arm_disarm_reason_t::rc_button); if (!landed && !(mc_manual_thrust_mode && commanded_by_rc && _param_com_disarm_man.get())) { - if (calling_reason != arm_disarm_reason_t::rc_stick) { + if (calling_reason != arm_disarm_reason_t::stick_gesture) { mavlink_log_critical(&_mavlink_log_pub, "Disarming denied: not landed\t"); events::send(events::ID("commander_disarm_denied_not_landed"), {events::Log::Critical, events::LogInternal::Info}, @@ -1629,7 +1629,7 @@ void Commander::executeActionRequest(const action_request_s &action_request) // Silently ignore RC actions during RC calibration if (_vehicle_status.rc_calibration_in_progress - && (action_request.source == action_request_s::SOURCE_MANUAL_CONTROL_GESTURE + && (action_request.source == action_request_s::SOURCE_STICK_GESTURE || action_request.source == action_request_s::SOURCE_RC_SWITCH || action_request.source == action_request_s::SOURCE_RC_BUTTON || action_request.source == action_request_s::SOURCE_RC_MODE_SLOT)) { @@ -1637,7 +1637,7 @@ void Commander::executeActionRequest(const action_request_s &action_request) } switch (action_request.source) { - case action_request_s::SOURCE_MANUAL_CONTROL_GESTURE: arm_disarm_reason = arm_disarm_reason_t::rc_stick; break; + case action_request_s::SOURCE_STICK_GESTURE: arm_disarm_reason = arm_disarm_reason_t::stick_gesture; break; case action_request_s::SOURCE_RC_SWITCH: arm_disarm_reason = arm_disarm_reason_t::rc_switch; break; diff --git a/src/modules/manual_control/ManualControl.cpp b/src/modules/manual_control/ManualControl.cpp index ecc932fd5c3c..53383fbb4a52 100644 --- a/src/modules/manual_control/ManualControl.cpp +++ b/src/modules/manual_control/ManualControl.cpp @@ -316,7 +316,7 @@ void ManualControl::updateParams() /* EVENT * @description MAN_ARM_GESTURE is now set to disable arm/disarm stick gesture. */ - events::send(events::ID("rc_update_arm_stick_gesture_disabled_with_switch"), {events::Log::Info, events::LogInternal::Disabled}, + events::send(events::ID("stick_gesture_disabled_by_arm_switch"), {events::Log::Info, events::LogInternal::Disabled}, "Arm stick gesture disabled if arm switch in use"); } } @@ -356,7 +356,7 @@ void ManualControl::processStickArming(const manual_control_setpoint_s &input) _stick_arm_hysteresis.set_state_and_update(left_stick_lower_right && right_stick_centered, input.timestamp); if (_param_man_arm_gesture.get() && !previous_stick_arm_hysteresis && _stick_arm_hysteresis.get_state()) { - sendActionRequest(action_request_s::ACTION_ARM, action_request_s::SOURCE_MANUAL_CONTROL_GESTURE); + sendActionRequest(action_request_s::ACTION_ARM, action_request_s::SOURCE_STICK_GESTURE); } // Disarm gesture @@ -366,7 +366,7 @@ void ManualControl::processStickArming(const manual_control_setpoint_s &input) _stick_disarm_hysteresis.set_state_and_update(left_stick_lower_left && right_stick_centered, input.timestamp); if (_param_man_arm_gesture.get() && !previous_stick_disarm_hysteresis && _stick_disarm_hysteresis.get_state()) { - sendActionRequest(action_request_s::ACTION_DISARM, action_request_s::SOURCE_MANUAL_CONTROL_GESTURE); + sendActionRequest(action_request_s::ACTION_DISARM, action_request_s::SOURCE_STICK_GESTURE); } // Kill gesture @@ -377,7 +377,7 @@ void ManualControl::processStickArming(const manual_control_setpoint_s &input) _stick_kill_hysteresis.set_state_and_update(left_stick_lower_left && right_stick_lower_right, input.timestamp); if (!previous_stick_kill_hysteresis && _stick_kill_hysteresis.get_state()) { - sendActionRequest(action_request_s::ACTION_KILL, action_request_s::SOURCE_MANUAL_CONTROL_GESTURE); + sendActionRequest(action_request_s::ACTION_KILL, action_request_s::SOURCE_STICK_GESTURE); } } } From f98eb067be145cc847c5c617a909f09d25b65745 Mon Sep 17 00:00:00 2001 From: Matthias Grob Date: Thu, 5 Sep 2024 15:28:10 +0200 Subject: [PATCH 10/40] logger params: clarify AUX1 logging trigger --- src/modules/logger/params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/logger/params.c b/src/modules/logger/params.c index 9ab1d8ee2445..727aad54d4ee 100644 --- a/src/modules/logger/params.c +++ b/src/modules/logger/params.c @@ -59,7 +59,7 @@ PARAM_DEFINE_INT32(SDLOG_UTC_OFFSET, 0); * @value 0 when armed until disarm (default) * @value 1 from boot until disarm * @value 2 from boot until shutdown - * @value 3 depending on manual control switch AUX1 + * @value 3 while manual input AUX1 >30% * @value 4 from 1st armed until shutdown * * @reboot_required true From 3d36c8519de83afd7b4617c3496d0304fb17cc28 Mon Sep 17 00:00:00 2001 From: Alexander Lerach Date: Fri, 6 Sep 2024 05:09:01 +0200 Subject: [PATCH 11/40] drivers/power_monitor: Implement temperature sensor support for INA228 / INA238 --- msg/BatteryStatus.msg | 100 +++++++++--------- src/drivers/power_monitor/ina228/ina228.cpp | 4 + src/drivers/power_monitor/ina228/ina228.h | 2 + src/drivers/power_monitor/ina238/ina238.cpp | 5 + src/drivers/power_monitor/ina238/ina238.h | 1 + .../power_monitor/ina238/ina238_registers.hpp | 1 + src/lib/battery/battery.cpp | 7 +- src/lib/battery/battery.h | 2 + 8 files changed, 71 insertions(+), 51 deletions(-) diff --git a/msg/BatteryStatus.msg b/msg/BatteryStatus.msg index b5155308f229..f87d4132d858 100644 --- a/msg/BatteryStatus.msg +++ b/msg/BatteryStatus.msg @@ -1,67 +1,67 @@ -uint64 timestamp # time since system start (microseconds) -bool connected # Whether or not a battery is connected, based on a voltage threshold -float32 voltage_v # Battery voltage in volts, 0 if unknown -float32 current_a # Battery current in amperes, -1 if unknown -float32 current_average_a # Battery current average in amperes (for FW average in level flight), -1 if unknown -float32 discharged_mah # Discharged amount in mAh, -1 if unknown -float32 remaining # From 1 to 0, -1 if unknown -float32 scale # Power scaling factor, >= 1, or -1 if unknown -float32 time_remaining_s # predicted time in seconds remaining until battery is empty under previous averaged load, NAN if unknown -float32 temperature # temperature of the battery. NaN if unknown -uint8 cell_count # Number of cells, 0 if unknown +uint64 timestamp # time since system start (microseconds) +bool connected # Whether or not a battery is connected, based on a voltage threshold +float32 voltage_v # Battery voltage in volts, 0 if unknown +float32 current_a # Battery current in amperes, -1 if unknown +float32 current_average_a # Battery current average in amperes (for FW average in level flight), -1 if unknown +float32 discharged_mah # Discharged amount in mAh, -1 if unknown +float32 remaining # From 1 to 0, -1 if unknown +float32 scale # Power scaling factor, >= 1, or -1 if unknown +float32 time_remaining_s # predicted time in seconds remaining until battery is empty under previous averaged load, NAN if unknown +float32 temperature # Temperature of the battery in degrees Celcius, NaN if unknown +uint8 cell_count # Number of cells, 0 if unknown uint8 BATTERY_SOURCE_POWER_MODULE = 0 uint8 BATTERY_SOURCE_EXTERNAL = 1 uint8 BATTERY_SOURCE_ESCS = 2 -uint8 source # Battery source -uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 -uint16 capacity # actual capacity of the battery -uint16 cycle_count # number of discharge cycles the battery has experienced -uint16 average_time_to_empty # predicted remaining battery capacity based on the average rate of discharge in min -uint16 serial_number # serial number of the battery pack -uint16 manufacture_date # manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 -uint16 state_of_health # state of health. FullChargeCapacity/DesignCapacity, 0-100%. -uint16 max_error # max error, expected margin of error in % in the state-of-charge calculation with a range of 1 to 100% +uint8 source # Battery source +uint8 priority # Zero based priority is the connection on the Power Controller V1..Vn AKA BrickN-1 +uint16 capacity # actual capacity of the battery +uint16 cycle_count # number of discharge cycles the battery has experienced +uint16 average_time_to_empty # predicted remaining battery capacity based on the average rate of discharge in min +uint16 serial_number # serial number of the battery pack +uint16 manufacture_date # manufacture date, part of serial number of the battery pack. Formatted as: Day + Month×32 + (Year–1980)×512 +uint16 state_of_health # state of health. FullChargeCapacity/DesignCapacity, 0-100%. +uint16 max_error # max error, expected margin of error in % in the state-of-charge calculation with a range of 1 to 100% uint8 id # ID number of a battery. Should be unique and consistent for the lifetime of a vehicle. 1-indexed. -uint16 interface_error # interface error counter +uint16 interface_error # interface error counter -float32[14] voltage_cell_v # Battery individual cell voltages, 0 if unknown -float32 max_cell_voltage_delta # Max difference between individual cell voltages +float32[14] voltage_cell_v # Battery individual cell voltages, 0 if unknown +float32 max_cell_voltage_delta # Max difference between individual cell voltages -bool is_powering_off # Power off event imminent indication, false if unknown -bool is_required # Set if the battery is explicitly required before arming +bool is_powering_off # Power off event imminent indication, false if unknown +bool is_required # Set if the battery is explicitly required before arming -uint8 BATTERY_WARNING_NONE = 0 # no battery low voltage warning active -uint8 BATTERY_WARNING_LOW = 1 # warning of low voltage -uint8 BATTERY_WARNING_CRITICAL = 2 # critical voltage, return / abort immediately -uint8 BATTERY_WARNING_EMERGENCY = 3 # immediate landing required -uint8 BATTERY_WARNING_FAILED = 4 # the battery has failed completely -uint8 BATTERY_STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field. -uint8 BATTERY_STATE_CHARGING = 7 # Battery is charging +uint8 BATTERY_WARNING_NONE = 0 # no battery low voltage warning active +uint8 BATTERY_WARNING_LOW = 1 # warning of low voltage +uint8 BATTERY_WARNING_CRITICAL = 2 # critical voltage, return / abort immediately +uint8 BATTERY_WARNING_EMERGENCY = 3 # immediate landing required +uint8 BATTERY_WARNING_FAILED = 4 # the battery has failed completely +uint8 BATTERY_STATE_UNHEALTHY = 6 # Battery is diagnosed to be defective or an error occurred, usage is discouraged / prohibited. Possible causes (faults) are listed in faults field. +uint8 BATTERY_STATE_CHARGING = 7 # Battery is charging -uint8 BATTERY_FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged -uint8 BATTERY_FAULT_SPIKES = 1 # Voltage spikes -uint8 BATTERY_FAULT_CELL_FAIL= 2 # One or more cells have failed -uint8 BATTERY_FAULT_OVER_CURRENT = 3 # Over-current -uint8 BATTERY_FAULT_OVER_TEMPERATURE = 4 # Over-temperature -uint8 BATTERY_FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault -uint8 BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with battery one -uint8 BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware -uint8 BATTERY_FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system -uint8 BATTERY_FAULT_HARDWARE_FAILURE = 9 # hardware problem -uint8 BATTERY_FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming -uint8 BATTERY_FAULT_COUNT = 11 # Counter - keep it as last element! +uint8 BATTERY_FAULT_DEEP_DISCHARGE = 0 # Battery has deep discharged +uint8 BATTERY_FAULT_SPIKES = 1 # Voltage spikes +uint8 BATTERY_FAULT_CELL_FAIL= 2 # One or more cells have failed +uint8 BATTERY_FAULT_OVER_CURRENT = 3 # Over-current +uint8 BATTERY_FAULT_OVER_TEMPERATURE = 4 # Over-temperature +uint8 BATTERY_FAULT_UNDER_TEMPERATURE = 5 # Under-temperature fault +uint8 BATTERY_FAULT_INCOMPATIBLE_VOLTAGE = 6 # Vehicle voltage is not compatible with battery one +uint8 BATTERY_FAULT_INCOMPATIBLE_FIRMWARE = 7 # Battery firmware is not compatible with current autopilot firmware +uint8 BATTERY_FAULT_INCOMPATIBLE_MODEL = 8 # Battery model is not supported by the system +uint8 BATTERY_FAULT_HARDWARE_FAILURE = 9 # hardware problem +uint8 BATTERY_FAULT_FAILED_TO_ARM = 10 # Battery had a problem while arming +uint8 BATTERY_FAULT_COUNT = 11 # Counter - keep it as last element! -uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication. -uint8 warning # Current battery warning +uint16 faults # Smart battery supply status/fault flags (bitmask) for health indication. +uint8 warning # Current battery warning uint8 MAX_INSTANCES = 4 -float32 full_charge_capacity_wh # The compensated battery capacity -float32 remaining_capacity_wh # The compensated battery capacity remaining -uint16 over_discharge_count # Number of battery overdischarge -float32 nominal_voltage # Nominal voltage of the battery pack +float32 full_charge_capacity_wh # The compensated battery capacity +float32 remaining_capacity_wh # The compensated battery capacity remaining +uint16 over_discharge_count # Number of battery overdischarge +float32 nominal_voltage # Nominal voltage of the battery pack float32 internal_resistance_estimate # [Ohm] Internal resistance per cell estimate float32 ocv_estimate # [V] Open circuit voltage estimate diff --git a/src/drivers/power_monitor/ina228/ina228.cpp b/src/drivers/power_monitor/ina228/ina228.cpp index 581dcbdd7026..8c0207b3f2ce 100644 --- a/src/drivers/power_monitor/ina228/ina228.cpp +++ b/src/drivers/power_monitor/ina228/ina228.cpp @@ -88,6 +88,7 @@ INA228::INA228(const I2CSPIDriverConfig &config, int battery_index) : _battery.setConnected(false); _battery.updateVoltage(0.f); _battery.updateCurrent(0.f); + _battery.updateTemperature(0.f); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); } @@ -306,6 +307,7 @@ INA228::collect() // success = success && (read(INA228_REG_POWER, _power) == PX4_OK); success = success && (read(INA228_REG_CURRENT, _current) == PX4_OK); //success = success && (read(INA228_REG_VSHUNT, _shunt) == PX4_OK); + success = success && (read(INA228_REG_DIETEMP, _temperature) == PX4_OK); if (!success) { PX4_DEBUG("error reading from sensor"); @@ -315,6 +317,7 @@ INA228::collect() _battery.setConnected(success); _battery.updateVoltage(static_cast(_bus_voltage * INA228_VSCALE)); _battery.updateCurrent(static_cast(_current * _current_lsb)); + _battery.updateTemperature(static_cast(_temperature * INA228_TSCALE)); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); perf_end(_sample_perf); @@ -381,6 +384,7 @@ INA228::RunImpl() _battery.setConnected(false); _battery.updateVoltage(0.f); _battery.updateCurrent(0.f); + _battery.updateTemperature(0.f); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); if (init() != PX4_OK) { diff --git a/src/drivers/power_monitor/ina228/ina228.h b/src/drivers/power_monitor/ina228/ina228.h index 9b57e5011af3..ee15f75eab13 100644 --- a/src/drivers/power_monitor/ina228/ina228.h +++ b/src/drivers/power_monitor/ina228/ina228.h @@ -291,6 +291,7 @@ using namespace time_literals; #define INA228_CONST 13107.2e6f /* is an internal fixed value used to ensure scaling is maintained properly */ #define INA228_SHUNT 0.0005f /* Shunt is 500 uOhm */ #define INA228_VSCALE 1.95e-04f /* LSB of voltage is 195.3125 uV/LSB */ +#define INA228_TSCALE 7.8125e-03f /* LSB of temperature is 7.8125 mDegC/LSB */ #define swap16(w) __builtin_bswap16((w)) #define swap32(d) __builtin_bswap32((d)) @@ -339,6 +340,7 @@ class INA228 : public device::I2C, public ModuleParams, public I2CSPIDriver 100_ms) { // check configuration registers periodically or immediately following any failure @@ -250,6 +253,7 @@ int INA238::collect() _battery.setConnected(success); _battery.updateVoltage(static_cast(bus_voltage * INA238_VSCALE)); _battery.updateCurrent(static_cast(current * _current_lsb)); + _battery.updateTemperature(static_cast(temperature * INA238_TSCALE)); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); perf_end(_sample_perf); @@ -309,6 +313,7 @@ void INA238::RunImpl() _battery.setConnected(false); _battery.updateVoltage(0.f); _battery.updateCurrent(0.f); + _battery.updateTemperature(0.f); _battery.updateAndPublishBatteryStatus(hrt_absolute_time()); if (init() != PX4_OK) { diff --git a/src/drivers/power_monitor/ina238/ina238.h b/src/drivers/power_monitor/ina238/ina238.h index c40514ad58a7..9d260fd7119c 100644 --- a/src/drivers/power_monitor/ina238/ina238.h +++ b/src/drivers/power_monitor/ina238/ina238.h @@ -73,6 +73,7 @@ using namespace ina238; #define INA238_DN_MAX 32768.0f /* 2^15 */ #define INA238_CONST 819.2e6f /* is an internal fixed value used to ensure scaling is maintained properly */ #define INA238_VSCALE 3.125e-03f /* LSB of voltage is 3.1255 mV/LSB */ +#define INA238_TSCALE 7.8125e-03f /* LSB of temperature is 7.8125 mDegC/LSB */ #define DEFAULT_MAX_CURRENT 327.68f /* Amps */ #define DEFAULT_SHUNT 0.0003f /* Shunt is 300 uOhm */ diff --git a/src/drivers/power_monitor/ina238/ina238_registers.hpp b/src/drivers/power_monitor/ina238/ina238_registers.hpp index 3f1689fcff67..8f170a7cb6ad 100644 --- a/src/drivers/power_monitor/ina238/ina238_registers.hpp +++ b/src/drivers/power_monitor/ina238/ina238_registers.hpp @@ -14,6 +14,7 @@ enum class Register : uint8_t { ADCCONFIG = 0x01, // ADC Configuration Register SHUNT_CAL = 0x02, // Shunt Calibration Register VS_BUS = 0x05, + DIETEMP = 0x06, CURRENT = 0x07, MANUFACTURER_ID = 0x3e, DEVICE_ID = 0x3f diff --git a/src/lib/battery/battery.cpp b/src/lib/battery/battery.cpp index 5b41dde3b846..21421d592d60 100644 --- a/src/lib/battery/battery.cpp +++ b/src/lib/battery/battery.cpp @@ -106,6 +106,11 @@ void Battery::updateCurrent(const float current_a) _current_a = current_a; } +void Battery::updateTemperature(const float temperature_c) +{ + _temperature_c = temperature_c; +} + void Battery::updateBatteryStatus(const hrt_abstime ×tamp) { // Require minimum voltage otherwise override connected status @@ -149,7 +154,7 @@ battery_status_s Battery::getBatteryStatus() battery_status.remaining = _state_of_charge; battery_status.scale = _scale; battery_status.time_remaining_s = computeRemainingTime(_current_a); - battery_status.temperature = NAN; + battery_status.temperature = _temperature_c; battery_status.cell_count = _params.n_cells; battery_status.connected = _connected; battery_status.source = _source; diff --git a/src/lib/battery/battery.h b/src/lib/battery/battery.h index 04d018960256..64649c3c08fe 100644 --- a/src/lib/battery/battery.h +++ b/src/lib/battery/battery.h @@ -91,6 +91,7 @@ class Battery : public ModuleParams void setStateOfCharge(const float soc) { _state_of_charge = soc; _external_state_of_charge = true; } void updateVoltage(const float voltage_v); void updateCurrent(const float current_a); + void updateTemperature(const float temperature_c); /** * Update state of charge calculations @@ -168,6 +169,7 @@ class Battery : public ModuleParams float _current_a{-1}; AlphaFilter _current_average_filter_a; ///< averaging filter for current. For FW, it is the current in level flight. + float _temperature_c{NAN}; float _discharged_mah{0.f}; float _discharged_mah_loop{0.f}; float _state_of_charge_volt_based{-1.f}; // [0,1] From 1337fca4d0ca410cd7630201f285a67d9c33afa9 Mon Sep 17 00:00:00 2001 From: RomanBapst Date: Thu, 5 Sep 2024 17:00:18 +0300 Subject: [PATCH 12/40] vtol backtransition: removed downscaling of fw controls during the backtransition Signed-off-by: RomanBapst --- src/modules/vtol_att_control/standard.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/vtol_att_control/standard.cpp b/src/modules/vtol_att_control/standard.cpp index 105ee1ee6efa..d8d640790e75 100644 --- a/src/modules/vtol_att_control/standard.cpp +++ b/src/modules/vtol_att_control/standard.cpp @@ -334,9 +334,9 @@ void Standard::fill_actuator_outputs() _thrust_setpoint_0->xyz[2] = _vehicle_thrust_setpoint_virtual_mc->xyz[2] * _mc_throttle_weight; // FW actuators - _torque_setpoint_1->xyz[0] = _vehicle_torque_setpoint_virtual_fw->xyz[0] * (1.f - _mc_roll_weight); - _torque_setpoint_1->xyz[1] = _vehicle_torque_setpoint_virtual_fw->xyz[1] * (1.f - _mc_pitch_weight); - _torque_setpoint_1->xyz[2] = _vehicle_torque_setpoint_virtual_fw->xyz[2] * (1.f - _mc_yaw_weight); + _torque_setpoint_1->xyz[0] = _vehicle_torque_setpoint_virtual_fw->xyz[0]; + _torque_setpoint_1->xyz[1] = _vehicle_torque_setpoint_virtual_fw->xyz[1]; + _torque_setpoint_1->xyz[2] = _vehicle_torque_setpoint_virtual_fw->xyz[2]; _thrust_setpoint_0->xyz[0] = _pusher_throttle; break; From 44967bdaabc99cdc8d0b57c95bb39bda07433f80 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Fri, 6 Sep 2024 14:51:15 +0200 Subject: [PATCH 13/40] ekf2: uncorrelate position covariance after velocity reset (#23644) --- src/modules/ekf2/EKF/velocity_fusion.cpp | 5 + .../test/change_indication/ekf_gsf_reset.csv | 488 ++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 492 +++++++++--------- 3 files changed, 495 insertions(+), 490 deletions(-) diff --git a/src/modules/ekf2/EKF/velocity_fusion.cpp b/src/modules/ekf2/EKF/velocity_fusion.cpp index 349a40092fd4..8a1ae8518b9a 100644 --- a/src/modules/ekf2/EKF/velocity_fusion.cpp +++ b/src/modules/ekf2/EKF/velocity_fusion.cpp @@ -91,6 +91,9 @@ void Ekf::resetHorizontalVelocityTo(const Vector2f &new_horz_vel, const Vector2f P.uncorrelateCovarianceSetVariance<1>(State::vel.idx + 1, math::max(sq(0.01f), new_horz_vel_var(1))); } + P.uncorrelateCovarianceSetVariance<1>(State::pos.idx, P(State::pos.idx, State::pos.idx)); + P.uncorrelateCovarianceSetVariance<1>(State::pos.idx + 1, P(State::pos.idx + 1, State::pos.idx + 1)); + _output_predictor.resetHorizontalVelocityTo(delta_horz_vel); // record the state change @@ -117,6 +120,8 @@ void Ekf::resetVerticalVelocityTo(float new_vert_vel, float new_vert_vel_var) P.uncorrelateCovarianceSetVariance<1>(State::vel.idx + 2, math::max(sq(0.01f), new_vert_vel_var)); } + P.uncorrelateCovarianceSetVariance<1>(State::pos.idx + 2, P(State::pos.idx + 2, State::pos.idx + 2)); + _output_predictor.resetVerticalVelocityTo(delta_vert_vel); // record the state change diff --git a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv index f12f21d9dd01..02d18bc9eea1 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -103,289 +103,289 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 10090000,0.71,0.002,-0.014,0.71,-0.022,0.025,-0.096,-0.015,0.042,-3.7e+02,-0.0015,-0.0056,-6.9e-05,-0.0017,0.0013,-0.091,0.21,-4.6e-06,0.43,-0.00029,0.00079,-0.00012,0,0,-3.6e+02,0.0013,0.0012,0.039,25,25,0.08,1.6e+02,1.6e+02,0.085,2.9e-05,4.6e-05,2.4e-06,0.04,0.04,0.016,0.0013,4.1e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 10190000,0.71,0.002,-0.013,0.71,-0.033,0.022,-0.096,-0.025,0.04,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-0.0019,0.0013,-0.093,0.21,-4.5e-06,0.43,-0.00027,0.00065,-0.00015,0,0,-3.6e+02,0.0012,0.0012,0.039,25,25,0.078,1.7e+02,1.7e+02,0.084,2.7e-05,4.4e-05,2.4e-06,0.04,0.04,0.014,0.0013,4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 10290000,0.71,0.002,-0.013,0.71,-0.04,0.017,-0.084,-0.033,0.038,-3.7e+02,-0.0015,-0.0058,-7.8e-05,-0.0021,0.0014,-0.098,0.21,-4.2e-06,0.43,-0.00026,0.00058,-0.00017,0,0,-3.6e+02,0.0012,0.0012,0.039,25,25,0.076,1.8e+02,1.8e+02,0.085,2.6e-05,4.2e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 -10390000,0.71,0.0018,-0.013,0.71,0.0091,-0.02,0.0096,0.00085,-0.0018,-3.7e+02,-0.0015,-0.0058,-7.9e-05,-0.0022,0.0014,-0.1,0.21,-3.7e-06,0.43,-0.00023,0.0006,-0.00014,0,0,-3.6e+02,0.0012,0.0012,0.039,0.25,0.25,0.56,0.25,0.25,0.078,2.4e-05,4.1e-05,2.3e-06,0.04,0.04,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 -10490000,0.71,0.0018,-0.013,0.71,0.0071,-0.019,0.023,0.0016,-0.0038,-3.7e+02,-0.0014,-0.0059,-8.3e-05,-0.0024,0.0014,-0.1,0.21,-3.3e-06,0.43,-0.00021,0.00053,-0.00016,0,0,-3.6e+02,0.0012,0.0012,0.039,0.26,0.26,0.55,0.26,0.26,0.08,2.3e-05,3.9e-05,2.3e-06,0.04,0.04,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10590000,0.71,0.0022,-0.013,0.71,0.006,-0.0081,0.026,0.0018,-0.00082,-3.7e+02,-0.0016,-0.0059,-7.9e-05,-0.0026,0.002,-0.11,0.21,-4.5e-06,0.43,-0.00029,0.00053,-0.00017,0,0,-3.6e+02,0.0012,0.0011,0.039,0.13,0.13,0.27,0.13,0.13,0.073,2.2e-05,3.8e-05,2.3e-06,0.04,0.04,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10690000,0.71,0.0021,-0.013,0.71,0.0032,-0.009,0.03,0.0023,-0.0017,-3.7e+02,-0.0015,-0.0059,-8.1e-05,-0.0026,0.0019,-0.11,0.21,-4.1e-06,0.43,-0.00027,0.00052,-0.00017,0,0,-3.6e+02,0.0012,0.0011,0.039,0.14,0.14,0.26,0.14,0.14,0.078,2.1e-05,3.6e-05,2.3e-06,0.04,0.04,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10790000,0.71,0.002,-0.013,0.71,0.0033,-0.0063,0.024,0.0026,-0.00085,-3.7e+02,-0.0015,-0.0059,-8e-05,-0.0027,0.0023,-0.11,0.21,-4e-06,0.43,-0.00026,0.00056,-0.00016,0,0,-3.6e+02,0.0012,0.0011,0.038,0.093,0.093,0.17,0.09,0.09,0.072,1.9e-05,3.4e-05,2.3e-06,0.039,0.039,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 -10890000,0.71,0.0019,-0.013,0.71,0.0021,-0.0065,0.02,0.0029,-0.0015,-3.7e+02,-0.0015,-0.0058,-8.1e-05,-0.0027,0.0022,-0.11,0.21,-3.7e-06,0.43,-0.00024,0.00057,-0.00015,0,0,-3.6e+02,0.0011,0.0011,0.038,0.1,0.1,0.16,0.096,0.096,0.075,1.8e-05,3.3e-05,2.3e-06,0.039,0.039,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -10990000,0.71,0.0017,-0.014,0.71,0.0067,-0.0015,0.014,0.0048,-0.0026,-3.7e+02,-0.0013,-0.0057,-7.9e-05,-0.0027,0.0032,-0.11,0.21,-3.2e-06,0.43,-0.00022,0.00071,-0.00011,0,0,-3.6e+02,0.0011,0.001,0.038,0.079,0.08,0.12,0.072,0.072,0.071,1.7e-05,3.1e-05,2.3e-06,0.038,0.038,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -11090000,0.71,0.0017,-0.014,0.71,0.0067,0.0018,0.019,0.0057,-0.0023,-3.7e+02,-0.0014,-0.0056,-7.5e-05,-0.0026,0.0031,-0.11,0.21,-3.3e-06,0.43,-0.00023,0.00078,-6.8e-05,0,0,-3.6e+02,0.0011,0.00099,0.038,0.09,0.091,0.11,0.078,0.078,0.074,1.6e-05,2.9e-05,2.3e-06,0.038,0.038,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -11190000,0.71,0.0017,-0.014,0.71,0.01,0.0033,0.0077,0.0067,-0.0032,-3.7e+02,-0.0013,-0.0056,-7.8e-05,-0.0025,0.0042,-0.11,0.21,-3.4e-06,0.43,-0.00024,0.00079,-8.6e-05,0,0,-3.6e+02,0.00098,0.00091,0.038,0.073,0.074,0.084,0.062,0.062,0.069,1.5e-05,2.7e-05,2.3e-06,0.036,0.036,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 -11290000,0.71,0.0016,-0.014,0.71,0.0093,0.0017,0.0074,0.0076,-0.0034,-3.7e+02,-0.0013,-0.0057,-8.3e-05,-0.0029,0.0045,-0.11,0.21,-3e-06,0.43,-0.00022,0.00073,-0.00011,0,0,-3.6e+02,0.00098,0.00091,0.038,0.085,0.087,0.078,0.068,0.068,0.072,1.4e-05,2.6e-05,2.3e-06,0.036,0.036,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11390000,0.71,0.0016,-0.013,0.71,0.0047,0.00081,0.0017,0.0055,-0.003,-3.7e+02,-0.0013,-0.0058,-8.6e-05,-0.0035,0.0043,-0.11,0.21,-3e-06,0.43,-0.00021,0.00066,-0.00016,0,0,-3.6e+02,0.00086,0.00082,0.038,0.071,0.073,0.063,0.056,0.056,0.068,1.3e-05,2.4e-05,2.3e-06,0.034,0.034,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11490000,0.71,0.0014,-0.013,0.71,0.00093,-0.0021,0.0025,0.0055,-0.0039,-3.7e+02,-0.0012,-0.0059,-9.3e-05,-0.0041,0.0051,-0.11,0.21,-2.7e-06,0.43,-0.00018,0.00056,-0.00022,0,0,-3.6e+02,0.00086,0.00081,0.038,0.083,0.085,0.058,0.062,0.062,0.069,1.3e-05,2.3e-05,2.3e-06,0.034,0.034,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11590000,0.71,0.0013,-0.013,0.71,-0.0022,-0.0016,-0.0034,0.0044,-0.0032,-3.7e+02,-0.0012,-0.0059,-9.4e-05,-0.0047,0.0053,-0.11,0.21,-2.5e-06,0.43,-0.00016,0.00054,-0.00023,0,0,-3.6e+02,0.00075,0.00072,0.038,0.07,0.072,0.049,0.052,0.052,0.066,1.2e-05,2.1e-05,2.3e-06,0.031,0.032,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 -11690000,0.71,0.0011,-0.013,0.71,-0.0037,-0.0027,-0.0079,0.0044,-0.004,-3.7e+02,-0.0011,-0.006,-9.8e-05,-0.0055,0.0054,-0.11,0.21,-2e-06,0.43,-0.0001,0.00053,-0.00026,0,0,-3.6e+02,0.00075,0.00071,0.038,0.081,0.084,0.046,0.059,0.059,0.066,1.1e-05,2e-05,2.3e-06,0.031,0.032,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -11790000,0.71,0.0011,-0.013,0.71,-0.0077,-0.0009,-0.0098,0.0024,-0.002,-3.7e+02,-0.0011,-0.006,-9.9e-05,-0.0073,0.0056,-0.11,0.21,-2e-06,0.43,-8.7e-05,0.0005,-0.00027,0,0,-3.6e+02,0.00065,0.00063,0.038,0.068,0.07,0.039,0.05,0.05,0.063,1e-05,1.8e-05,2.3e-06,0.028,0.03,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -11890000,0.71,0.00095,-0.013,0.71,-0.0087,-0.0038,-0.011,0.0016,-0.0027,-3.7e+02,-0.001,-0.006,-0.0001,-0.008,0.0061,-0.11,0.21,-1.9e-06,0.43,-5.5e-05,0.00047,-0.00032,0,0,-3.6e+02,0.00065,0.00062,0.038,0.079,0.082,0.037,0.057,0.057,0.063,9.8e-06,1.8e-05,2.3e-06,0.028,0.029,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -11990000,0.71,0.0013,-0.013,0.71,-0.012,0.0011,-0.016,-0.0001,-7.7e-05,-3.7e+02,-0.0011,-0.006,-9.9e-05,-0.0076,0.0067,-0.11,0.21,-2.9e-06,0.43,-0.00013,0.00048,-0.00032,0,0,-3.6e+02,0.00056,0.00055,0.037,0.066,0.068,0.033,0.049,0.049,0.061,9.2e-06,1.6e-05,2.3e-06,0.026,0.027,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 -12090000,0.71,0.0014,-0.013,0.71,-0.013,0.0043,-0.022,-0.0014,0.00091,-3.7e+02,-0.0012,-0.0059,-9.5e-05,-0.0065,0.0059,-0.11,0.21,-3e-06,0.43,-0.00016,0.00053,-0.00028,0,0,-3.6e+02,0.00056,0.00055,0.037,0.077,0.079,0.031,0.056,0.056,0.061,8.8e-06,1.6e-05,2.3e-06,0.026,0.027,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12190000,0.71,0.0012,-0.013,0.71,-0.0069,0.0039,-0.017,0.0015,0.00037,-3.7e+02,-0.0011,-0.0059,-9.6e-05,-0.0064,0.0062,-0.11,0.21,-2.4e-06,0.43,-0.00011,0.0006,-0.00026,0,0,-3.6e+02,0.00048,0.00048,0.037,0.064,0.066,0.028,0.048,0.048,0.059,8.2e-06,1.4e-05,2.3e-06,0.023,0.026,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12290000,0.71,0.001,-0.013,0.71,-0.0081,0.0044,-0.016,0.0011,0.00073,-3.7e+02,-0.0011,-0.0059,-9.6e-05,-0.0069,0.0058,-0.11,0.21,-2e-06,0.43,-8.2e-05,0.0006,-0.00026,0,0,-3.6e+02,0.00048,0.00048,0.037,0.073,0.076,0.028,0.055,0.056,0.059,7.9e-06,1.4e-05,2.3e-06,0.023,0.025,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12390000,0.71,0.001,-0.013,0.71,-0.0054,0.0032,-0.015,0.0025,0.00024,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.0055,0.0075,-0.11,0.21,-2.5e-06,0.43,-0.00012,0.00061,-0.00025,0,0,-3.6e+02,0.00042,0.00043,0.037,0.061,0.063,0.026,0.048,0.048,0.057,7.4e-06,1.3e-05,2.3e-06,0.021,0.024,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 -12490000,0.71,0.00093,-0.013,0.71,-0.0071,0.0027,-0.018,0.0017,3.7e-05,-3.7e+02,-0.0011,-0.0059,-0.0001,-0.006,0.0087,-0.11,0.21,-2.7e-06,0.43,-0.00015,0.00054,-0.00025,0,0,-3.6e+02,0.00042,0.00042,0.037,0.069,0.072,0.026,0.055,0.055,0.057,7.1e-06,1.3e-05,2.3e-06,0.021,0.024,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12590000,0.71,0.0011,-0.013,0.71,-0.014,0.0037,-0.023,-0.0033,0.00021,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0053,0.008,-0.11,0.21,-3e-06,0.43,-0.00019,0.00051,-0.00024,0,0,-3.6e+02,0.00037,0.00038,0.037,0.058,0.059,0.025,0.047,0.047,0.055,6.8e-06,1.2e-05,2.3e-06,0.019,0.022,0.0099,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12690000,0.71,0.0014,-0.013,0.71,-0.017,0.0046,-0.027,-0.0058,0.00079,-3.7e+02,-0.0012,-0.006,-0.0001,-0.0035,0.0094,-0.11,0.21,-3.9e-06,0.43,-0.00026,0.0005,-0.00025,0,0,-3.6e+02,0.00037,0.00038,0.037,0.065,0.067,0.025,0.055,0.055,0.055,6.5e-06,1.1e-05,2.3e-06,0.019,0.022,0.0098,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12790000,0.71,0.0012,-0.013,0.71,-0.02,0.0027,-0.03,-0.0081,0.00026,-3.7e+02,-0.0012,-0.006,-0.0001,-0.0051,0.0082,-0.11,0.21,-3.3e-06,0.43,-0.0002,0.00048,-0.00027,0,0,-3.6e+02,0.00033,0.00034,0.037,0.054,0.056,0.024,0.047,0.047,0.053,6.2e-06,1.1e-05,2.3e-06,0.018,0.021,0.0097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 -12890000,0.71,0.0011,-0.013,0.71,-0.02,0.0014,-0.029,-0.0096,0.0002,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0064,0.0078,-0.11,0.21,-2.8e-06,0.43,-0.00017,0.00047,-0.00026,0,0,-3.6e+02,0.00033,0.00034,0.037,0.061,0.063,0.025,0.054,0.055,0.054,6e-06,1e-05,2.3e-06,0.018,0.021,0.0096,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -12990000,0.71,0.001,-0.013,0.71,-0.009,0.0019,-0.03,-0.0018,0.0005,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.004,0.0082,-0.11,0.21,-2.7e-06,0.43,-0.00018,0.00058,-0.0002,0,0,-3.6e+02,0.0003,0.00031,0.037,0.051,0.053,0.025,0.047,0.047,0.052,5.7e-06,9.9e-06,2.3e-06,0.016,0.02,0.0094,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -13090000,0.71,0.00094,-0.013,0.71,-0.0097,-0.00014,-0.03,-0.0029,-6.9e-05,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0051,0.0098,-0.11,0.21,-3.1e-06,0.43,-0.0002,0.00052,-0.00023,0,0,-3.6e+02,0.0003,0.00031,0.037,0.057,0.059,0.025,0.054,0.054,0.052,5.5e-06,9.6e-06,2.3e-06,0.016,0.02,0.0094,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -13190000,0.71,0.00094,-0.013,0.71,-0.0023,0.00081,-0.027,0.0028,0.00014,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0033,0.011,-0.11,0.21,-3.4e-06,0.43,-0.00023,0.00056,-0.00021,0,0,-3.6e+02,0.00027,0.00028,0.037,0.048,0.05,0.025,0.047,0.047,0.051,5.2e-06,9.1e-06,2.3e-06,0.015,0.019,0.0091,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 -13290000,0.71,0.00079,-0.013,0.71,-0.00079,0.0015,-0.024,0.0034,0.0003,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0048,0.0097,-0.11,0.21,-2.5e-06,0.43,-0.00018,0.00058,-0.0002,0,0,-3.6e+02,0.00027,0.00028,0.037,0.054,0.055,0.027,0.054,0.054,0.051,5.1e-06,8.9e-06,2.3e-06,0.015,0.018,0.0091,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13390000,0.71,0.0007,-0.013,0.71,0.00023,0.0023,-0.02,0.0025,0.00042,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0042,0.009,-0.11,0.21,-2.3e-06,0.43,-0.00016,0.00063,-0.00019,0,0,-3.6e+02,0.00025,0.00026,0.037,0.045,0.047,0.026,0.047,0.047,0.05,4.8e-06,8.5e-06,2.3e-06,0.014,0.018,0.0088,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13490000,0.71,0.00071,-0.013,0.71,0.00021,0.0024,-0.019,0.0027,0.0008,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0043,0.0082,-0.11,0.21,-2e-06,0.43,-0.00015,0.00063,-0.00017,0,0,-3.6e+02,0.00025,0.00026,0.037,0.05,0.052,0.028,0.054,0.054,0.05,4.7e-06,8.2e-06,2.3e-06,0.014,0.017,0.0087,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13590000,0.71,0.00072,-0.013,0.71,-2.8e-05,0.0028,-0.021,0.0015,0.00038,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0041,0.0094,-0.11,0.21,-2.4e-06,0.43,-0.00017,0.00062,-0.00019,0,0,-3.6e+02,0.00023,0.00025,0.037,0.042,0.044,0.028,0.046,0.047,0.05,4.5e-06,7.9e-06,2.3e-06,0.013,0.017,0.0084,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 -13690000,0.71,0.0007,-0.013,0.71,0.00091,0.0053,-0.025,0.0017,0.0011,-3.7e+02,-0.001,-0.0059,-9.9e-05,-0.0035,0.0082,-0.11,0.21,-2.1e-06,0.43,-0.00016,0.00064,-0.00016,0,0,-3.6e+02,0.00023,0.00024,0.037,0.047,0.049,0.029,0.053,0.054,0.05,4.3e-06,7.7e-06,2.3e-06,0.013,0.017,0.0083,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -13790000,0.71,0.00075,-0.013,0.71,0.0006,0.0021,-0.027,0.0024,-0.00073,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.0021,0.009,-0.11,0.21,-2.5e-06,0.43,-0.00019,0.00065,-0.00015,0,0,-3.6e+02,0.00022,0.00023,0.037,0.04,0.041,0.029,0.046,0.046,0.049,4.2e-06,7.3e-06,2.3e-06,0.012,0.016,0.0079,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -13890000,0.71,0.00059,-0.013,0.71,0.0024,0.0022,-0.031,0.003,-0.00056,-3.7e+02,-0.001,-0.0059,-9.8e-05,-0.0035,0.0079,-0.11,0.21,-1.8e-06,0.43,-0.00015,0.00065,-0.00015,0,0,-3.6e+02,0.00022,0.00023,0.037,0.044,0.045,0.03,0.053,0.053,0.05,4e-06,7.1e-06,2.3e-06,0.012,0.016,0.0078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -13990000,0.71,0.00066,-0.013,0.71,0.0019,0.00054,-0.03,0.0036,-0.0019,-3.7e+02,-0.001,-0.0059,-9.8e-05,-0.0022,0.0084,-0.12,0.21,-2e-06,0.43,-0.00018,0.00065,-0.00013,0,0,-3.6e+02,0.00021,0.00022,0.037,0.037,0.039,0.03,0.046,0.046,0.05,3.9e-06,6.8e-06,2.3e-06,0.012,0.015,0.0074,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 -14090000,0.71,0.00072,-0.013,0.71,0.0014,0.0019,-0.031,0.0036,-0.0013,-3.7e+02,-0.0011,-0.0059,-9.4e-05,-0.00071,0.0073,-0.12,0.21,-1.8e-06,0.43,-0.00018,0.00069,-9.7e-05,0,0,-3.6e+02,0.00021,0.00022,0.037,0.041,0.043,0.031,0.053,0.053,0.05,3.8e-06,6.7e-06,2.3e-06,0.012,0.015,0.0073,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14190000,0.71,0.00068,-0.013,0.71,0.0044,0.0019,-0.033,0.0057,-0.001,-3.7e+02,-0.0011,-0.0059,-9.3e-05,-0.00025,0.0071,-0.12,0.21,-1.6e-06,0.43,-0.00018,0.00071,-8e-05,0,0,-3.6e+02,0.0002,0.00021,0.037,0.035,0.037,0.03,0.046,0.046,0.05,3.6e-06,6.4e-06,2.3e-06,0.011,0.015,0.0069,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14290000,0.71,0.00075,-0.013,0.71,0.0046,0.0032,-0.032,0.0059,-0.00065,-3.7e+02,-0.0011,-0.0058,-9.2e-05,0.0006,0.007,-0.12,0.21,-1.8e-06,0.43,-0.00019,0.00071,-6.2e-05,0,0,-3.6e+02,0.0002,0.0002,0.037,0.038,0.04,0.031,0.052,0.052,0.051,3.5e-06,6.2e-06,2.3e-06,0.011,0.014,0.0067,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14390000,0.71,0.00063,-0.014,0.71,0.0071,0.005,-0.034,0.0077,-0.00036,-3.7e+02,-0.0011,-0.0058,-8.9e-05,0.00028,0.0055,-0.12,0.21,-9.2e-07,0.43,-0.00015,0.00074,-4.6e-05,0,0,-3.6e+02,0.00019,0.0002,0.037,0.033,0.035,0.031,0.046,0.046,0.05,3.4e-06,6e-06,2.3e-06,0.011,0.014,0.0063,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 -14490000,0.71,0.00052,-0.013,0.71,0.008,0.0065,-0.037,0.0088,0.00011,-3.7e+02,-0.001,-0.0058,-8.9e-05,-0.001,0.005,-0.12,0.21,-4.3e-07,0.43,-0.00013,0.0007,-4.6e-05,0,0,-3.6e+02,0.00019,0.00019,0.037,0.036,0.038,0.032,0.052,0.052,0.051,3.3e-06,5.8e-06,2.3e-06,0.01,0.014,0.0062,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14590000,0.71,0.00042,-0.013,0.71,0.0061,0.005,-0.037,0.006,-0.0015,-3.7e+02,-0.001,-0.0058,-8.9e-05,-0.0019,0.0048,-0.12,0.21,-3.4e-07,0.43,-0.00012,0.00067,-5.9e-05,0,0,-3.6e+02,0.00018,0.00019,0.037,0.031,0.033,0.031,0.045,0.045,0.051,3.2e-06,5.6e-06,2.3e-06,0.01,0.014,0.0058,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14690000,0.71,0.00037,-0.013,0.71,0.0079,0.0031,-0.034,0.0068,-0.00088,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0019,0.0039,-0.12,0.21,4.2e-08,0.43,-0.0001,0.00068,-4.5e-05,0,0,-3.6e+02,0.00018,0.00019,0.037,0.034,0.036,0.032,0.051,0.052,0.051,3.1e-06,5.5e-06,2.3e-06,0.01,0.013,0.0056,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14790000,0.71,0.00035,-0.013,0.71,0.0056,0.0016,-0.03,0.0042,-0.0021,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.002,0.0038,-0.12,0.21,-1.5e-08,0.43,-0.00011,0.00066,-4.6e-05,0,0,-3.6e+02,0.00017,0.00018,0.037,0.03,0.031,0.031,0.045,0.045,0.051,3e-06,5.2e-06,2.3e-06,0.0097,0.013,0.0052,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 -14890000,0.71,0.00032,-0.013,0.71,0.0077,0.0034,-0.033,0.005,-0.0018,-3.7e+02,-0.001,-0.0058,-8.6e-05,-0.0023,0.0032,-0.12,0.21,2.5e-07,0.43,-9.1e-05,0.00067,-4.3e-05,0,0,-3.6e+02,0.00017,0.00018,0.037,0.032,0.034,0.031,0.051,0.051,0.052,2.9e-06,5.1e-06,2.3e-06,0.0096,0.013,0.0051,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -14990000,0.71,0.00027,-0.013,0.71,0.0068,0.0024,-0.029,0.004,-0.0017,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0028,0.0037,-0.12,0.21,5.1e-08,0.43,-0.0001,0.00064,-5.6e-05,0,0,-3.6e+02,0.00017,0.00017,0.037,0.028,0.03,0.03,0.045,0.045,0.051,2.8e-06,4.9e-06,2.3e-06,0.0094,0.012,0.0048,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -15090000,0.71,0.0002,-0.013,0.71,0.0075,0.0025,-0.032,0.0047,-0.0016,-3.7e+02,-0.001,-0.0058,-8.8e-05,-0.0029,0.0041,-0.12,0.21,-5.2e-08,0.43,-0.00011,0.00063,-5.7e-05,0,0,-3.6e+02,0.00017,0.00017,0.037,0.03,0.032,0.031,0.05,0.051,0.052,2.7e-06,4.8e-06,2.3e-06,0.0092,0.012,0.0046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -15190000,0.71,0.00016,-0.013,0.7,0.0073,0.003,-0.029,0.0039,-0.0015,-3.7e+02,-0.001,-0.0058,-9e-05,-0.0036,0.0044,-0.12,0.21,-4.8e-08,0.43,-0.00012,0.00059,-6.4e-05,0,0,-3.6e+02,0.00016,0.00017,0.037,0.027,0.028,0.03,0.044,0.045,0.052,2.6e-06,4.6e-06,2.3e-06,0.009,0.012,0.0043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 -15290000,0.71,0.00019,-0.013,0.7,0.0078,0.0041,-0.027,0.0044,-0.00097,-3.7e+02,-0.001,-0.0058,-8.8e-05,-0.0026,0.0042,-0.12,0.21,-3.8e-09,0.43,-0.00014,0.00059,-3.9e-05,0,0,-3.6e+02,0.00016,0.00017,0.037,0.029,0.031,0.03,0.05,0.05,0.052,2.6e-06,4.5e-06,2.3e-06,0.0089,0.012,0.0041,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15390000,0.71,0.0002,-0.013,0.7,0.0071,0.0054,-0.025,0.0017,-0.00041,-3.7e+02,-0.001,-0.0058,-8.3e-05,-0.0018,0.0028,-0.12,0.21,3.5e-07,0.43,-0.00012,0.00062,-1.6e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.025,0.027,0.029,0.044,0.044,0.051,2.5e-06,4.4e-06,2.3e-06,0.0087,0.012,0.0038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15490000,0.71,0.00022,-0.013,0.7,0.0086,0.0045,-0.025,0.0024,-0.00036,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0022,0.0041,-0.12,0.21,-1.1e-07,0.43,-0.00014,0.00059,-3.5e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.027,0.029,0.029,0.049,0.05,0.053,2.4e-06,4.3e-06,2.3e-06,0.0086,0.011,0.0037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15590000,0.71,0.00018,-0.013,0.71,0.0072,0.0036,-0.023,8.4e-05,-0.00068,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0029,0.0048,-0.12,0.21,-4.5e-07,0.43,-0.00014,0.00058,-6.1e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.024,0.026,0.028,0.044,0.044,0.052,2.3e-06,4.1e-06,2.3e-06,0.0084,0.011,0.0034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 -15690000,0.71,0.00022,-0.013,0.71,0.0075,0.0037,-0.024,0.00059,-0.00037,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0024,0.0052,-0.12,0.21,-7.6e-07,0.43,-0.00015,0.00059,-6.4e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.026,0.028,0.028,0.049,0.049,0.052,2.3e-06,4e-06,2.3e-06,0.0083,0.011,0.0033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -15790000,0.71,0.00019,-0.013,0.7,0.0081,0.0021,-0.026,0.00049,-0.0016,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0026,0.0054,-0.12,0.21,-8.7e-07,0.43,-0.00016,0.00057,-6.8e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.023,0.025,0.027,0.043,0.044,0.051,2.2e-06,3.9e-06,2.3e-06,0.0081,0.011,0.0031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -15890000,0.71,0.0002,-0.013,0.71,0.0088,0.0021,-0.024,0.0011,-0.0014,-3.7e+02,-0.0011,-0.0059,-8.8e-05,-0.0019,0.0057,-0.12,0.21,-1.1e-06,0.43,-0.00018,0.00057,-6e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.025,0.027,0.027,0.048,0.049,0.052,2.1e-06,3.8e-06,2.3e-06,0.008,0.011,0.003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -15990000,0.71,0.00018,-0.013,0.71,0.0086,0.0022,-0.02,0.00076,-0.0019,-3.7e+02,-0.0011,-0.0059,-8.4e-05,-0.0013,0.005,-0.12,0.21,-9.8e-07,0.43,-0.00018,0.00058,-4.2e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.022,0.024,0.026,0.043,0.043,0.051,2.1e-06,3.6e-06,2.3e-06,0.0079,0.01,0.0028,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 -16090000,0.71,0.00021,-0.013,0.71,0.011,0.0039,-0.016,0.0017,-0.0011,-3.7e+02,-0.0011,-0.0058,-8e-05,-0.00049,0.0037,-0.12,0.21,-7.1e-07,0.43,-0.00016,0.00063,-2.6e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.024,0.026,0.025,0.048,0.048,0.052,2e-06,3.6e-06,2.3e-06,0.0078,0.01,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16190000,0.71,0.00026,-0.013,0.71,0.01,0.0041,-0.015,0.001,-0.00095,-3.7e+02,-0.0011,-0.0058,-7.9e-05,0.00025,0.0039,-0.13,0.21,-1e-06,0.43,-0.00017,0.00063,-2.1e-05,0,0,-3.6e+02,0.00015,0.00014,0.037,0.021,0.023,0.025,0.043,0.043,0.051,2e-06,3.4e-06,2.3e-06,0.0077,0.01,0.0025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16290000,0.71,0.00028,-0.014,0.71,0.012,0.0052,-0.016,0.0023,5.7e-05,-3.7e+02,-0.0011,-0.0058,-7.5e-05,0.00057,0.0026,-0.13,0.21,-5.6e-07,0.43,-0.00015,0.00064,-5.9e-06,0,0,-3.6e+02,0.00015,0.00014,0.037,0.023,0.025,0.024,0.047,0.048,0.052,1.9e-06,3.4e-06,2.3e-06,0.0076,0.01,0.0024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16390000,0.71,0.00033,-0.013,0.71,0.01,0.0037,-0.015,0.0013,-0.00022,-3.7e+02,-0.0011,-0.0058,-7.6e-05,0.0017,0.0038,-0.13,0.21,-1.3e-06,0.43,-0.00018,0.00064,-2.1e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.02,0.022,0.023,0.042,0.043,0.051,1.9e-06,3.2e-06,2.3e-06,0.0074,0.0098,0.0022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 -16490000,0.71,0.00042,-0.013,0.71,0.0088,0.005,-0.018,0.0018,0.00032,-3.7e+02,-0.0011,-0.0058,-7.5e-05,0.0026,0.004,-0.13,0.21,-1.6e-06,0.43,-0.00019,0.00064,1.2e-05,0,0,-3.6e+02,0.00014,0.00014,0.037,0.022,0.024,0.023,0.047,0.048,0.052,1.8e-06,3.2e-06,2.3e-06,0.0074,0.0097,0.0021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16590000,0.71,0.00053,-0.013,0.71,0.0068,0.0059,-0.018,-0.00051,0.0023,-3.7e+02,-0.0012,-0.0058,-7.6e-05,0.0027,0.0037,-0.13,0.21,-1.6e-06,0.43,-0.00017,0.00063,7.8e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.02,0.022,0.022,0.042,0.042,0.051,1.8e-06,3.1e-06,2.3e-06,0.0073,0.0095,0.002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16690000,0.71,0.00049,-0.013,0.71,0.0077,0.0062,-0.015,0.00033,0.0026,-3.7e+02,-0.0012,-0.0058,-7.9e-05,0.0021,0.0044,-0.13,0.21,-1.8e-06,0.43,-0.00018,0.00062,-3.4e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.021,0.024,0.022,0.047,0.047,0.051,1.7e-06,3e-06,2.3e-06,0.0072,0.0094,0.0019,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16790000,0.71,0.00049,-0.013,0.71,0.0058,0.0069,-0.014,-0.0016,0.0042,-3.7e+02,-0.0012,-0.0058,-8e-05,0.0019,0.004,-0.13,0.21,-1.7e-06,0.43,-0.00016,0.00063,-1.6e-05,0,0,-3.6e+02,0.00014,0.00013,0.037,0.019,0.021,0.021,0.042,0.042,0.05,1.7e-06,2.9e-06,2.3e-06,0.0071,0.0092,0.0018,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 -16890000,0.71,0.00054,-0.013,0.71,0.0055,0.0078,-0.011,-0.0013,0.0047,-3.7e+02,-0.0012,-0.0058,-8.2e-05,0.0023,0.0046,-0.13,0.21,-2e-06,0.43,-0.00017,0.00062,-1.2e-05,0,0,-3.6e+02,0.00014,0.00013,0.037,0.02,0.023,0.021,0.046,0.047,0.051,1.6e-06,2.8e-06,2.3e-06,0.007,0.0091,0.0017,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -16990000,0.71,0.00051,-0.013,0.71,0.0055,0.0056,-0.01,-0.0021,0.0025,-3.7e+02,-0.0012,-0.0059,-8.2e-05,0.0022,0.0057,-0.13,0.21,-2.5e-06,0.43,-0.00019,0.00061,-2.2e-05,0,0,-3.6e+02,0.00013,0.00013,0.037,0.018,0.021,0.02,0.041,0.042,0.05,1.6e-06,2.7e-06,2.3e-06,0.0069,0.009,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -17090000,0.71,0.00055,-0.013,0.71,0.0058,0.0071,-0.01,-0.002,0.0032,-3.7e+02,-0.0012,-0.0059,-8.1e-05,0.0031,0.006,-0.13,0.21,-2.8e-06,0.43,-0.0002,0.00061,-1e-05,0,0,-3.6e+02,0.00014,0.00013,0.037,0.02,0.022,0.02,0.046,0.047,0.05,1.5e-06,2.7e-06,2.3e-06,0.0068,0.0089,0.0015,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -17190000,0.71,0.00061,-0.013,0.71,0.0059,0.008,-0.011,-0.0028,0.0021,-3.7e+02,-0.0012,-0.0059,-7.7e-05,0.0039,0.0059,-0.13,0.21,-3.1e-06,0.43,-0.0002,0.00062,-7.9e-06,0,0,-3.6e+02,0.00013,0.00013,0.037,0.018,0.02,0.019,0.041,0.042,0.049,1.5e-06,2.6e-06,2.3e-06,0.0067,0.0087,0.0015,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 -17290000,0.71,0.00063,-0.013,0.71,0.0077,0.0088,-0.0067,-0.0026,0.0025,-3.7e+02,-0.0012,-0.0059,-7.9e-05,0.0042,0.0069,-0.13,0.21,-3.5e-06,0.43,-0.00022,0.00061,-5.4e-06,0,0,-3.6e+02,0.00013,0.00013,0.037,0.019,0.022,0.019,0.045,0.046,0.049,1.5e-06,2.5e-06,2.3e-06,0.0067,0.0086,0.0014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17390000,0.71,0.00068,-0.013,0.71,0.0075,0.0092,-0.0047,-0.0024,0.0016,-3.7e+02,-0.0012,-0.0059,-7.3e-05,0.005,0.0066,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00061,1.3e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.017,0.02,0.018,0.041,0.041,0.048,1.4e-06,2.4e-06,2.2e-06,0.0066,0.0085,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17490000,0.71,0.00063,-0.013,0.71,0.0092,0.0093,-0.003,-0.0012,0.0025,-3.7e+02,-0.0012,-0.0059,-7.3e-05,0.0045,0.0064,-0.13,0.21,-3.4e-06,0.43,-0.00023,0.00061,7.6e-06,0,0,-3.6e+02,0.00013,0.00012,0.037,0.019,0.021,0.018,0.045,0.046,0.049,1.4e-06,2.4e-06,2.2e-06,0.0065,0.0084,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17590000,0.71,0.0006,-0.013,0.71,0.0099,0.0085,0.0025,-0.001,0.0013,-3.7e+02,-0.0012,-0.0059,-7e-05,0.0048,0.0067,-0.13,0.21,-3.7e-06,0.43,-0.00024,0.00061,4.9e-06,0,0,-3.6e+02,0.00013,0.00012,0.037,0.017,0.019,0.017,0.04,0.041,0.048,1.4e-06,2.3e-06,2.2e-06,0.0064,0.0082,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 -17690000,0.71,0.00058,-0.013,0.71,0.011,0.01,0.0019,1.8e-05,0.0023,-3.7e+02,-0.0012,-0.0059,-6.9e-05,0.0049,0.0064,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00061,1.3e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.018,0.021,0.017,0.045,0.046,0.048,1.3e-06,2.3e-06,2.2e-06,0.0064,0.0082,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -17790000,0.71,0.00056,-0.013,0.71,0.012,0.011,0.00058,1.4e-05,0.0029,-3.7e+02,-0.0012,-0.0058,-6e-05,0.0058,0.0053,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00064,2.2e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.016,0.019,0.016,0.04,0.041,0.048,1.3e-06,2.2e-06,2.2e-06,0.0063,0.008,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -17890000,0.71,0.00055,-0.013,0.71,0.015,0.012,0.00068,0.0016,0.0045,-3.7e+02,-0.0012,-0.0058,-5.7e-05,0.0057,0.0047,-0.13,0.21,-3.3e-06,0.43,-0.00024,0.00064,2.7e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.018,0.02,0.016,0.044,0.045,0.048,1.3e-06,2.2e-06,2.2e-06,0.0062,0.008,0.001,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -17990000,0.71,0.00049,-0.013,0.71,0.016,0.0091,0.0019,0.0018,0.0036,-3.7e+02,-0.0012,-0.0058,-5.6e-05,0.0054,0.005,-0.13,0.21,-3.4e-06,0.43,-0.00024,0.00064,2.4e-05,0,0,-3.6e+02,0.00012,0.00012,0.037,0.016,0.019,0.016,0.04,0.041,0.047,1.2e-06,2.1e-06,2.2e-06,0.0062,0.0078,0.00098,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 -18090000,0.71,0.00048,-0.013,0.71,0.017,0.0083,0.0043,0.0035,0.0037,-3.7e+02,-0.0012,-0.0059,-6.2e-05,0.0049,0.006,-0.13,0.21,-3.5e-06,0.43,-0.00026,0.00061,1.9e-05,0,0,-3.6e+02,0.00012,0.00012,0.037,0.017,0.02,0.016,0.044,0.045,0.047,1.2e-06,2.1e-06,2.2e-06,0.0061,0.0078,0.00095,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18190000,0.71,0.00044,-0.013,0.71,0.018,0.0093,0.0056,0.0041,0.0036,-3.7e+02,-0.0012,-0.0059,-5.7e-05,0.0051,0.0056,-0.13,0.21,-3.6e-06,0.43,-0.00025,0.00062,2e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.018,0.015,0.04,0.04,0.047,1.2e-06,2e-06,2.2e-06,0.0061,0.0076,0.0009,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18290000,0.71,0.00035,-0.013,0.71,0.018,0.0088,0.0068,0.0061,0.0041,-3.7e+02,-0.0012,-0.0059,-6e-05,0.0046,0.0059,-0.13,0.21,-3.6e-06,0.43,-0.00025,0.00061,1.4e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.017,0.02,0.015,0.044,0.045,0.046,1.2e-06,2e-06,2.2e-06,0.006,0.0076,0.00087,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18390000,0.71,0.00031,-0.013,0.71,0.02,0.011,0.008,0.0068,0.0042,-3.7e+02,-0.0012,-0.0059,-5.4e-05,0.0044,0.0051,-0.13,0.21,-3.4e-06,0.43,-0.00024,0.00062,1.6e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.015,0.018,0.014,0.039,0.04,0.046,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.00082,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 -18490000,0.71,0.00038,-0.013,0.71,0.021,0.012,0.0076,0.0085,0.0055,-3.7e+02,-0.0012,-0.0059,-5.3e-05,0.005,0.0052,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00063,1.9e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.02,0.014,0.043,0.045,0.046,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.0008,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18590000,0.71,0.00039,-0.013,0.71,0.02,0.013,0.0058,0.0074,0.0054,-3.7e+02,-0.0012,-0.0058,-4.5e-05,0.0057,0.0047,-0.13,0.21,-3.7e-06,0.43,-0.00025,0.00065,2.4e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.015,0.018,0.014,0.039,0.04,0.045,1.1e-06,1.8e-06,2.2e-06,0.0058,0.0073,0.00076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18690000,0.71,0.00031,-0.013,0.71,0.022,0.013,0.0039,0.01,0.0065,-3.7e+02,-0.0012,-0.0059,-4.7e-05,0.0051,0.0047,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00064,1.8e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.045,1e-06,1.8e-06,2.2e-06,0.0058,0.0072,0.00073,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18790000,0.71,0.00032,-0.013,0.71,0.021,0.012,0.0035,0.0087,0.0054,-3.7e+02,-0.0012,-0.0059,-4.6e-05,0.0053,0.0053,-0.13,0.21,-3.8e-06,0.43,-0.00025,0.00063,1.5e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.045,1e-06,1.7e-06,2.2e-06,0.0057,0.0071,0.0007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 -18890000,0.71,0.00041,-0.013,0.71,0.021,0.014,0.0042,0.01,0.0075,-3.7e+02,-0.0012,-0.0058,-4e-05,0.0062,0.0048,-0.13,0.21,-3.9e-06,0.43,-0.00026,0.00065,2.9e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.045,1e-06,1.7e-06,2.2e-06,0.0057,0.007,0.00068,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -18990000,0.71,0.00046,-0.013,0.71,0.021,0.015,0.0028,0.01,0.0068,-3.7e+02,-0.0013,-0.0058,-3.4e-05,0.0068,0.0049,-0.13,0.21,-4.2e-06,0.43,-0.00027,0.00066,3e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.015,0.017,0.012,0.039,0.04,0.044,9.7e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.00065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -19090000,0.71,0.00051,-0.013,0.71,0.021,0.016,0.0059,0.012,0.0084,-3.7e+02,-0.0013,-0.0058,-3.4e-05,0.0074,0.0052,-0.13,0.21,-4.4e-06,0.43,-0.00028,0.00066,3.4e-05,0,0,-3.6e+02,0.00011,0.0001,0.037,0.016,0.019,0.012,0.042,0.044,0.044,9.6e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.00063,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -19190000,0.71,0.00056,-0.013,0.71,0.02,0.016,0.0059,0.012,0.0076,-3.7e+02,-0.0013,-0.0059,-2.7e-05,0.0079,0.0054,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00066,3.7e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.014,0.017,0.012,0.038,0.04,0.044,9.3e-07,1.5e-06,2.1e-06,0.0055,0.0068,0.0006,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 -19290000,0.71,0.00058,-0.013,0.71,0.02,0.015,0.0086,0.013,0.0088,-3.7e+02,-0.0013,-0.0059,-3e-05,0.0078,0.0058,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00066,4e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.015,0.019,0.012,0.042,0.044,0.044,9.2e-07,1.5e-06,2.1e-06,0.0055,0.0067,0.00058,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19390000,0.71,0.00054,-0.013,0.71,0.019,0.014,0.012,0.012,0.0079,-3.7e+02,-0.0013,-0.0059,-2.4e-05,0.0077,0.0057,-0.13,0.21,-4.7e-06,0.43,-0.0003,0.00065,3.5e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.014,0.017,0.012,0.038,0.04,0.043,8.9e-07,1.5e-06,2.1e-06,0.0054,0.0066,0.00056,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19490000,0.71,0.00056,-0.013,0.71,0.019,0.015,0.0088,0.014,0.01,-3.7e+02,-0.0013,-0.0058,-1.8e-05,0.0077,0.005,-0.13,0.21,-4.6e-06,0.43,-0.00029,0.00066,3.8e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.015,0.018,0.011,0.042,0.044,0.043,8.8e-07,1.4e-06,2.1e-06,0.0054,0.0066,0.00054,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19590000,0.71,0.00063,-0.013,0.71,0.017,0.015,0.0081,0.012,0.0095,-3.7e+02,-0.0013,-0.0058,-6.7e-06,0.0085,0.0047,-0.13,0.21,-4.7e-06,0.43,-0.0003,0.00068,4.7e-05,0,0,-3.6e+02,0.00011,9.8e-05,0.036,0.014,0.017,0.011,0.038,0.039,0.042,8.5e-07,1.4e-06,2.1e-06,0.0053,0.0065,0.00052,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 -19690000,0.71,0.00067,-0.013,0.71,0.017,0.013,0.0096,0.013,0.01,-3.7e+02,-0.0013,-0.0059,-1e-05,0.0089,0.0053,-0.13,0.21,-5e-06,0.43,-0.00031,0.00068,3.8e-05,0,0,-3.6e+02,0.00011,9.8e-05,0.036,0.015,0.018,0.011,0.042,0.043,0.042,8.4e-07,1.4e-06,2.1e-06,0.0053,0.0064,0.00051,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -19790000,0.71,0.00075,-0.013,0.71,0.014,0.011,0.01,0.011,0.009,-3.7e+02,-0.0013,-0.0059,-5.6e-06,0.0093,0.0057,-0.13,0.21,-5.3e-06,0.43,-0.00031,0.00068,3.7e-05,0,0,-3.6e+02,0.00011,9.6e-05,0.036,0.014,0.017,0.011,0.038,0.039,0.042,8.2e-07,1.3e-06,2.1e-06,0.0053,0.0063,0.00049,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -19890000,0.71,0.00066,-0.013,0.71,0.015,0.013,0.011,0.014,0.011,-3.7e+02,-0.0013,-0.0058,2.6e-06,0.0091,0.0047,-0.13,0.21,-4.9e-06,0.43,-0.00031,0.00069,4.5e-05,0,0,-3.6e+02,0.00011,9.6e-05,0.036,0.015,0.018,0.011,0.041,0.043,0.042,8.1e-07,1.3e-06,2.1e-06,0.0052,0.0063,0.00047,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -19990000,0.71,0.00063,-0.013,0.7,0.013,0.013,0.014,0.012,0.011,-3.7e+02,-0.0013,-0.0058,1.8e-05,0.0095,0.0039,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.0007,5e-05,0,0,-3.6e+02,0.0001,9.4e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.041,7.9e-07,1.2e-06,2.1e-06,0.0052,0.0062,0.00046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 -20090000,0.71,0.00066,-0.013,0.7,0.013,0.013,0.014,0.013,0.013,-3.7e+02,-0.0013,-0.0058,2.8e-05,0.01,0.0031,-0.13,0.21,-4.7e-06,0.43,-0.00032,0.00072,6.1e-05,0,0,-3.6e+02,0.00011,9.4e-05,0.036,0.014,0.018,0.01,0.041,0.043,0.042,7.8e-07,1.2e-06,2.1e-06,0.0052,0.0062,0.00044,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20190000,0.71,0.0007,-0.013,0.7,0.012,0.012,0.017,0.011,0.012,-3.7e+02,-0.0013,-0.0058,3.7e-05,0.0098,0.0028,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00072,6.1e-05,0,0,-3.6e+02,0.0001,9.2e-05,0.036,0.013,0.016,0.01,0.037,0.039,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.0061,0.00043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20290000,0.71,0.0007,-0.013,0.7,0.01,0.012,0.015,0.012,0.013,-3.7e+02,-0.0013,-0.0058,4.1e-05,0.01,0.0027,-0.13,0.21,-4.8e-06,0.43,-0.00032,0.00074,6.2e-05,0,0,-3.6e+02,0.0001,9.2e-05,0.036,0.014,0.018,0.0099,0.041,0.043,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.006,0.00042,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20390000,0.71,0.00066,-0.013,0.7,0.0086,0.0097,0.017,0.01,0.012,-3.7e+02,-0.0013,-0.0058,4.5e-05,0.01,0.0028,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.00073,5.2e-05,0,0,-3.6e+02,0.0001,9.1e-05,0.036,0.013,0.016,0.0097,0.037,0.039,0.041,7.3e-07,1.1e-06,2e-06,0.005,0.0059,0.0004,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 -20490000,0.71,0.00071,-0.013,0.7,0.0087,0.0097,0.016,0.011,0.012,-3.7e+02,-0.0013,-0.0058,4.2e-05,0.01,0.0031,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.00072,5.1e-05,0,0,-3.6e+02,0.0001,9.1e-05,0.036,0.014,0.017,0.0096,0.041,0.043,0.041,7.2e-07,1.1e-06,2e-06,0.005,0.0059,0.00039,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20590000,0.71,0.00074,-0.013,0.7,0.0078,0.0076,0.013,0.0091,0.01,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.01,0.0036,-0.13,0.21,-5e-06,0.43,-0.00031,0.00071,5e-05,0,0,-3.6e+02,9.9e-05,8.9e-05,0.036,0.013,0.016,0.0093,0.037,0.039,0.04,7e-07,1.1e-06,2e-06,0.005,0.0058,0.00038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20690000,0.71,0.00077,-0.013,0.7,0.0084,0.0077,0.015,0.01,0.011,-3.7e+02,-0.0013,-0.0058,4.6e-05,0.01,0.0034,-0.13,0.21,-5e-06,0.43,-0.00031,0.00072,5.2e-05,0,0,-3.6e+02,0.0001,8.9e-05,0.036,0.014,0.017,0.0093,0.041,0.043,0.04,6.9e-07,1.1e-06,2e-06,0.0049,0.0058,0.00037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20790000,0.71,0.00081,-0.013,0.7,0.0063,0.0072,0.015,0.0084,0.01,-3.7e+02,-0.0013,-0.0058,5.1e-05,0.011,0.0036,-0.13,0.21,-5e-06,0.43,-0.00032,0.00073,4.6e-05,0,0,-3.6e+02,9.8e-05,8.7e-05,0.036,0.013,0.016,0.0091,0.037,0.039,0.04,6.7e-07,1e-06,2e-06,0.0049,0.0057,0.00036,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 -20890000,0.71,0.00081,-0.013,0.7,0.0062,0.0068,0.014,0.009,0.011,-3.7e+02,-0.0013,-0.0058,5.9e-05,0.011,0.0031,-0.13,0.21,-5e-06,0.43,-0.00033,0.00074,5.1e-05,0,0,-3.6e+02,9.8e-05,8.8e-05,0.036,0.014,0.017,0.009,0.04,0.043,0.04,6.6e-07,1e-06,2e-06,0.0049,0.0057,0.00035,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -20990000,0.71,0.00084,-0.013,0.7,0.0044,0.0045,0.015,0.009,0.0099,-3.7e+02,-0.0013,-0.0058,6.3e-05,0.011,0.0034,-0.13,0.21,-5e-06,0.43,-0.00034,0.00075,4.9e-05,0,0,-3.6e+02,9.6e-05,8.6e-05,0.036,0.013,0.016,0.0088,0.037,0.039,0.039,6.5e-07,9.9e-07,2e-06,0.0048,0.0056,0.00034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -21090000,0.71,0.00081,-0.013,0.7,0.0054,0.0037,0.015,0.01,0.011,-3.7e+02,-0.0013,-0.0058,6.8e-05,0.011,0.0029,-0.13,0.21,-4.9e-06,0.43,-0.00033,0.00075,4.6e-05,0,0,-3.6e+02,9.7e-05,8.6e-05,0.036,0.014,0.017,0.0088,0.04,0.043,0.039,6.4e-07,9.8e-07,2e-06,0.0048,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -21190000,0.71,0.00082,-0.013,0.7,0.0057,0.0028,0.014,0.011,0.0091,-3.7e+02,-0.0013,-0.0058,6.9e-05,0.011,0.0031,-0.13,0.21,-4.9e-06,0.43,-0.00033,0.00075,4.3e-05,0,0,-3.6e+02,9.4e-05,8.4e-05,0.036,0.013,0.016,0.0086,0.037,0.039,0.039,6.2e-07,9.4e-07,1.9e-06,0.0048,0.0055,0.00032,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 -21290000,0.71,0.0009,-0.013,0.7,0.005,0.0029,0.016,0.011,0.01,-3.7e+02,-0.0013,-0.0058,7.9e-05,0.011,0.0026,-0.13,0.21,-4.9e-06,0.43,-0.00034,0.00077,4.7e-05,0,0,-3.6e+02,9.5e-05,8.5e-05,0.036,0.014,0.017,0.0085,0.04,0.043,0.039,6.2e-07,9.4e-07,1.9e-06,0.0048,0.0055,0.00032,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21390000,0.71,0.00088,-0.013,0.7,0.004,0.00085,0.016,0.0095,0.0093,-3.7e+02,-0.0013,-0.0058,7.4e-05,0.011,0.0028,-0.13,0.21,-5e-06,0.43,-0.00033,0.00076,4.7e-05,0,0,-3.6e+02,9.3e-05,8.3e-05,0.036,0.013,0.016,0.0084,0.037,0.039,0.039,6e-07,9e-07,1.9e-06,0.0047,0.0054,0.00031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21490000,0.71,0.00088,-0.013,0.7,0.0045,0.0013,0.015,0.01,0.0098,-3.7e+02,-0.0013,-0.0058,7.9e-05,0.011,0.0025,-0.13,0.21,-5e-06,0.43,-0.00032,0.00077,5.3e-05,0,0,-3.6e+02,9.4e-05,8.3e-05,0.036,0.014,0.017,0.0083,0.04,0.043,0.038,6e-07,9e-07,1.9e-06,0.0047,0.0054,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21590000,0.71,0.00087,-0.013,0.7,0.0033,0.0017,0.015,0.009,0.0091,-3.7e+02,-0.0013,-0.0058,7.7e-05,0.011,0.0025,-0.13,0.21,-5.1e-06,0.43,-0.00032,0.00076,5e-05,0,0,-3.6e+02,9.1e-05,8.2e-05,0.036,0.013,0.015,0.0081,0.037,0.039,0.038,5.8e-07,8.7e-07,1.9e-06,0.0047,0.0053,0.00029,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 -21690000,0.71,0.00084,-0.013,0.7,0.005,0.0021,0.017,0.01,0.0097,-3.7e+02,-0.0013,-0.0058,8.1e-05,0.011,0.0021,-0.13,0.21,-5e-06,0.43,-0.00031,0.00077,5.1e-05,0,0,-3.6e+02,9.2e-05,8.2e-05,0.036,0.013,0.017,0.0081,0.04,0.042,0.038,5.8e-07,8.6e-07,1.9e-06,0.0047,0.0053,0.00029,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 -21790000,0.71,0.00084,-0.013,0.7,0.003,0.0042,0.015,0.0074,0.01,-3.7e+02,-0.0013,-0.0058,7.2e-05,0.011,0.0023,-0.13,0.21,-5.6e-06,0.43,-0.00033,0.00076,5.3e-05,0,0,-3.6e+02,9e-05,8e-05,0.036,0.012,0.015,0.008,0.036,0.039,0.038,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0052,0.00028,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 -21890000,0.71,0.00083,-0.013,0.7,0.0038,0.0047,0.016,0.0079,0.011,-3.7e+02,-0.0013,-0.0058,7.3e-05,0.011,0.0022,-0.13,0.21,-5.5e-06,0.43,-0.00033,0.00076,5e-05,0,0,-3.6e+02,9.1e-05,8.1e-05,0.036,0.013,0.016,0.0079,0.04,0.042,0.038,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0052,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 -21990000,0.71,0.00085,-0.013,0.7,0.0026,0.0054,0.016,0.006,0.012,-3.7e+02,-0.0013,-0.0058,7e-05,0.012,0.002,-0.13,0.21,-5.9e-06,0.43,-0.00034,0.00076,5.2e-05,0,0,-3.7e+02,8.8e-05,7.9e-05,0.036,0.012,0.015,0.0078,0.036,0.038,0.038,5.4e-07,8e-07,1.9e-06,0.0046,0.0052,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22090000,0.71,0.00088,-0.013,0.7,0.0025,0.007,0.015,0.006,0.013,-3.7e+02,-0.0013,-0.0058,7e-05,0.012,0.0021,-0.13,0.21,-5.9e-06,0.43,-0.00034,0.00076,5.2e-05,0,0,-3.7e+02,8.9e-05,7.9e-05,0.036,0.013,0.016,0.0078,0.04,0.042,0.037,5.4e-07,7.9e-07,1.8e-06,0.0045,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22190000,0.71,0.00085,-0.013,0.7,0.0019,0.007,0.015,0.0053,0.011,-3.7e+02,-0.0013,-0.0058,7.6e-05,0.012,0.0022,-0.13,0.21,-5.7e-06,0.43,-0.00035,0.00077,4.1e-05,0,0,-3.7e+02,8.7e-05,7.8e-05,0.036,0.012,0.015,0.0076,0.036,0.038,0.037,5.3e-07,7.6e-07,1.8e-06,0.0045,0.0051,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22290000,0.71,0.00088,-0.013,0.7,0.0013,0.0067,0.015,0.0057,0.012,-3.7e+02,-0.0013,-0.0058,7.4e-05,0.011,0.0022,-0.13,0.21,-5.8e-06,0.43,-0.00035,0.00076,4.2e-05,0,0,-3.7e+02,8.8e-05,7.8e-05,0.036,0.013,0.016,0.0076,0.04,0.042,0.037,5.2e-07,7.6e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22390000,0.71,0.00089,-0.013,0.7,-0.001,0.0064,0.017,0.0041,0.01,-3.7e+02,-0.0013,-0.0058,8.1e-05,0.012,0.0024,-0.13,0.21,-5.7e-06,0.43,-0.00035,0.00077,4.3e-05,0,0,-3.7e+02,8.6e-05,7.7e-05,0.036,0.012,0.015,0.0075,0.036,0.038,0.037,5.1e-07,7.3e-07,1.8e-06,0.0045,0.005,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22490000,0.71,0.00093,-0.013,0.7,-0.0021,0.0072,0.018,0.0033,0.011,-3.7e+02,-0.0013,-0.0058,8.2e-05,0.012,0.0026,-0.13,0.21,-5.7e-06,0.43,-0.00037,0.00078,4.1e-05,0,0,-3.7e+02,8.6e-05,7.7e-05,0.036,0.013,0.016,0.0074,0.039,0.042,0.037,5.1e-07,7.3e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22590000,0.71,0.00096,-0.013,0.7,-0.0038,0.0065,0.017,0.00096,0.01,-3.7e+02,-0.0014,-0.0058,8.5e-05,0.013,0.0028,-0.13,0.21,-5.6e-06,0.43,-0.00038,0.00079,3.8e-05,0,0,-3.7e+02,8.4e-05,7.5e-05,0.036,0.012,0.015,0.0073,0.036,0.038,0.036,5e-07,7.1e-07,1.8e-06,0.0044,0.0049,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22690000,0.71,0.001,-0.013,0.7,-0.0052,0.008,0.018,0.00022,0.012,-3.7e+02,-0.0014,-0.0058,9.1e-05,0.013,0.0026,-0.13,0.21,-5.5e-06,0.43,-0.00039,0.0008,3.7e-05,0,0,-3.7e+02,8.5e-05,7.6e-05,0.036,0.013,0.016,0.0073,0.039,0.042,0.036,4.9e-07,7e-07,1.8e-06,0.0044,0.0049,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22790000,0.71,0.001,-0.013,0.7,-0.0071,0.0069,0.019,-0.0024,0.0091,-3.7e+02,-0.0014,-0.0058,8.1e-05,0.013,0.0034,-0.13,0.21,-5.7e-06,0.43,-0.00039,0.00078,4.2e-05,0,0,-3.7e+02,8.3e-05,7.4e-05,0.036,0.012,0.015,0.0072,0.036,0.038,0.036,4.8e-07,6.8e-07,1.7e-06,0.0044,0.0049,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22890000,0.71,0.00099,-0.013,0.7,-0.0076,0.0078,0.021,-0.0024,0.0098,-3.7e+02,-0.0014,-0.0058,8e-05,0.013,0.0033,-0.13,0.21,-5.6e-06,0.43,-0.00038,0.00077,3.9e-05,0,0,-3.7e+02,8.4e-05,7.5e-05,0.036,0.013,0.016,0.0072,0.039,0.042,0.036,4.8e-07,6.8e-07,1.7e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -22990000,0.71,0.00097,-0.013,0.7,-0.0077,0.0068,0.022,-0.0036,0.009,-3.7e+02,-0.0014,-0.0058,9e-05,0.013,0.0032,-0.13,0.21,-5.4e-06,0.43,-0.00038,0.00078,3.6e-05,0,0,-3.7e+02,8.2e-05,7.3e-05,0.036,0.012,0.015,0.0071,0.036,0.038,0.036,4.7e-07,6.5e-07,1.7e-06,0.0043,0.0048,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23090000,0.71,0.00092,-0.013,0.7,-0.0081,0.0067,0.022,-0.0043,0.009,-3.7e+02,-0.0014,-0.0058,8.1e-05,0.012,0.0034,-0.13,0.21,-5.5e-06,0.43,-0.00038,0.00076,3.3e-05,0,0,-3.7e+02,8.3e-05,7.4e-05,0.036,0.013,0.016,0.007,0.039,0.042,0.036,4.6e-07,6.5e-07,1.7e-06,0.0043,0.0048,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23190000,0.71,0.00097,-0.013,0.7,-0.0094,0.0047,0.024,-0.0076,0.0078,-3.7e+02,-0.0014,-0.0058,8.4e-05,0.013,0.0036,-0.13,0.21,-5.5e-06,0.43,-0.00037,0.00076,2.5e-05,0,0,-3.7e+02,8.1e-05,7.2e-05,0.036,0.012,0.014,0.0069,0.036,0.038,0.035,4.5e-07,6.3e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23290000,0.71,0.00089,-0.013,0.7,-0.0093,0.0042,0.024,-0.0081,0.0084,-3.7e+02,-0.0014,-0.0058,8.6e-05,0.012,0.0035,-0.13,0.21,-5.5e-06,0.43,-0.00037,0.00076,2.4e-05,0,0,-3.7e+02,8.1e-05,7.3e-05,0.036,0.013,0.016,0.0069,0.039,0.042,0.036,4.5e-07,6.3e-07,1.7e-06,0.0043,0.0047,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23390000,0.71,0.00095,-0.013,0.7,-0.0095,0.003,0.022,-0.01,0.0072,-3.7e+02,-0.0014,-0.0058,8.8e-05,0.012,0.0035,-0.13,0.21,-5.6e-06,0.43,-0.00035,0.00075,2.6e-05,0,0,-3.7e+02,8e-05,7.1e-05,0.036,0.012,0.014,0.0068,0.036,0.038,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 -23490000,0.71,0.0033,-0.01,0.7,-0.016,0.0032,-0.012,-0.011,0.008,-3.7e+02,-0.0014,-0.0058,9.5e-05,0.012,0.0032,-0.13,0.21,-5.5e-06,0.43,-0.00034,0.00078,5.1e-05,0,0,-3.7e+02,8e-05,7.2e-05,0.036,0.013,0.015,0.0068,0.039,0.042,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0012,1,1,0.01 -23590000,0.71,0.0086,-0.0026,0.7,-0.027,0.0032,-0.043,-0.011,0.0075,-3.7e+02,-0.0014,-0.0058,9.1e-05,0.012,0.0033,-0.13,0.21,-5.5e-06,0.43,-0.00034,0.00084,0.00012,0,0,-3.7e+02,7.8e-05,7.1e-05,0.036,0.012,0.014,0.0067,0.036,0.038,0.035,4.3e-07,5.9e-07,1.6e-06,0.0042,0.0046,0.0002,0.0013,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -23690000,0.71,0.0082,0.0032,0.71,-0.058,-0.0046,-0.094,-0.015,0.0075,-3.7e+02,-0.0014,-0.0058,9.1e-05,0.012,0.0032,-0.13,0.21,-5.5e-06,0.43,-0.00034,0.00078,9e-05,0,0,-3.7e+02,7.9e-05,7.1e-05,0.036,0.013,0.015,0.0067,0.039,0.042,0.035,4.3e-07,5.9e-07,1.6e-06,0.0042,0.0046,0.0002,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +10390000,0.71,0.0018,-0.013,0.71,0.0091,-0.02,0.0093,0.00085,-0.0018,-3.7e+02,-0.0015,-0.0058,-7.9e-05,-0.0021,0.0013,-0.098,0.21,-3.7e-06,0.43,-0.00023,0.0006,-0.00014,0,0,-3.6e+02,0.0012,0.0012,0.039,0.25,0.25,0.56,0.25,0.25,0.077,2.4e-05,4.1e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.6 +10490000,0.71,0.0018,-0.013,0.71,0.0071,-0.019,0.022,0.0016,-0.0038,-3.7e+02,-0.0014,-0.0059,-8.3e-05,-0.0022,0.0013,-0.098,0.21,-3.3e-06,0.43,-0.00021,0.00053,-0.00016,0,0,-3.6e+02,0.0012,0.0012,0.039,0.26,0.26,0.55,0.26,0.26,0.079,2.3e-05,3.9e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10590000,0.71,0.0022,-0.013,0.71,0.006,-0.0081,0.024,0.0018,-0.00082,-3.7e+02,-0.0016,-0.0059,-7.9e-05,-0.0024,0.0018,-0.098,0.21,-4.5e-06,0.43,-0.00029,0.00053,-0.00017,0,0,-3.6e+02,0.0012,0.0011,0.039,0.13,0.13,0.27,0.13,0.13,0.072,2.2e-05,3.8e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10690000,0.71,0.0021,-0.013,0.71,0.0032,-0.009,0.027,0.0023,-0.0017,-3.7e+02,-0.0015,-0.0059,-8.1e-05,-0.0024,0.0018,-0.098,0.21,-4.1e-06,0.43,-0.00027,0.00052,-0.00017,0,0,-3.6e+02,0.0012,0.0011,0.039,0.14,0.14,0.26,0.14,0.14,0.077,2.1e-05,3.6e-05,2.3e-06,0.04,0.04,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10790000,0.71,0.002,-0.013,0.71,0.0033,-0.0063,0.021,0.0026,-0.00085,-3.7e+02,-0.0015,-0.0059,-8e-05,-0.0025,0.0021,-0.098,0.21,-4e-06,0.43,-0.00026,0.00056,-0.00016,0,0,-3.6e+02,0.0012,0.0011,0.038,0.093,0.093,0.17,0.09,0.09,0.071,1.9e-05,3.4e-05,2.3e-06,0.039,0.039,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.7 +10890000,0.71,0.0019,-0.013,0.71,0.0021,-0.0065,0.016,0.0029,-0.0015,-3.7e+02,-0.0015,-0.0058,-8.1e-05,-0.0025,0.0021,-0.098,0.21,-3.7e-06,0.43,-0.00025,0.00057,-0.00015,0,0,-3.6e+02,0.0011,0.0011,0.038,0.1,0.1,0.16,0.096,0.096,0.074,1.8e-05,3.3e-05,2.3e-06,0.039,0.039,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +10990000,0.71,0.0017,-0.014,0.71,0.0067,-0.0015,0.011,0.0048,-0.0026,-3.7e+02,-0.0013,-0.0057,-7.9e-05,-0.0025,0.0031,-0.098,0.21,-3.2e-06,0.43,-0.00022,0.00071,-0.00011,0,0,-3.6e+02,0.0011,0.001,0.038,0.079,0.08,0.12,0.072,0.072,0.071,1.7e-05,3.1e-05,2.3e-06,0.038,0.038,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +11090000,0.71,0.0017,-0.014,0.71,0.0067,0.0018,0.014,0.0057,-0.0023,-3.7e+02,-0.0014,-0.0056,-7.5e-05,-0.0023,0.0029,-0.098,0.21,-3.3e-06,0.43,-0.00023,0.00078,-6.8e-05,0,0,-3.6e+02,0.0011,0.00099,0.038,0.09,0.091,0.12,0.078,0.078,0.073,1.6e-05,2.9e-05,2.3e-06,0.038,0.038,0.014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +11190000,0.71,0.0017,-0.014,0.71,0.01,0.0033,0.0027,0.0067,-0.0032,-3.7e+02,-0.0013,-0.0056,-7.8e-05,-0.0022,0.004,-0.098,0.21,-3.4e-06,0.43,-0.00024,0.00079,-8.6e-05,0,0,-3.6e+02,0.00098,0.00091,0.038,0.073,0.074,0.091,0.062,0.062,0.068,1.5e-05,2.7e-05,2.3e-06,0.036,0.036,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.8 +11290000,0.71,0.0016,-0.014,0.71,0.0093,0.0017,0.0014,0.0076,-0.0034,-3.7e+02,-0.0013,-0.0057,-8.3e-05,-0.0026,0.0043,-0.098,0.21,-3e-06,0.43,-0.00022,0.00073,-0.00011,0,0,-3.6e+02,0.00097,0.0009,0.038,0.085,0.087,0.087,0.068,0.068,0.071,1.4e-05,2.6e-05,2.3e-06,0.036,0.036,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11390000,0.71,0.0016,-0.013,0.71,0.0047,0.0008,-0.0044,0.0055,-0.003,-3.7e+02,-0.0013,-0.0058,-8.6e-05,-0.0033,0.0041,-0.098,0.21,-3e-06,0.43,-0.00021,0.00066,-0.00016,0,0,-3.6e+02,0.00086,0.00082,0.038,0.071,0.073,0.072,0.056,0.056,0.067,1.3e-05,2.4e-05,2.3e-06,0.034,0.034,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11490000,0.71,0.0014,-0.013,0.71,0.00093,-0.0021,-0.0044,0.0055,-0.0039,-3.7e+02,-0.0012,-0.0059,-9.3e-05,-0.0039,0.0049,-0.098,0.21,-2.7e-06,0.43,-0.00018,0.00056,-0.00022,0,0,-3.6e+02,0.00086,0.00081,0.038,0.083,0.085,0.069,0.062,0.062,0.068,1.3e-05,2.3e-05,2.3e-06,0.034,0.034,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11590000,0.71,0.0013,-0.013,0.71,-0.0022,-0.0016,-0.01,0.0044,-0.0032,-3.7e+02,-0.0012,-0.0059,-9.4e-05,-0.0045,0.0051,-0.098,0.21,-2.5e-06,0.43,-0.00016,0.00054,-0.00023,0,0,-3.6e+02,0.00075,0.00072,0.038,0.07,0.072,0.059,0.052,0.052,0.066,1.2e-05,2.1e-05,2.3e-06,0.031,0.032,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.9 +11690000,0.71,0.0011,-0.013,0.71,-0.0037,-0.0027,-0.016,0.0044,-0.004,-3.7e+02,-0.0011,-0.006,-9.8e-05,-0.0053,0.0052,-0.098,0.21,-2e-06,0.43,-0.0001,0.00053,-0.00026,0,0,-3.6e+02,0.00075,0.00071,0.038,0.081,0.084,0.057,0.059,0.059,0.066,1.1e-05,2e-05,2.3e-06,0.031,0.032,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +11790000,0.71,0.0011,-0.013,0.71,-0.0077,-0.00091,-0.018,0.0024,-0.002,-3.7e+02,-0.0011,-0.006,-9.9e-05,-0.0071,0.0054,-0.098,0.21,-2e-06,0.43,-8.7e-05,0.0005,-0.00027,0,0,-3.6e+02,0.00065,0.00063,0.038,0.068,0.07,0.051,0.05,0.05,0.063,1e-05,1.8e-05,2.3e-06,0.028,0.03,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +11890000,0.71,0.00095,-0.013,0.71,-0.0087,-0.0038,-0.02,0.0016,-0.0027,-3.7e+02,-0.001,-0.006,-0.0001,-0.0077,0.0059,-0.098,0.21,-2e-06,0.43,-5.6e-05,0.00047,-0.00032,0,0,-3.6e+02,0.00065,0.00062,0.038,0.079,0.082,0.049,0.057,0.057,0.063,9.8e-06,1.8e-05,2.3e-06,0.028,0.029,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +11990000,0.71,0.0013,-0.013,0.71,-0.012,0.0011,-0.026,-0.0001,-7.8e-05,-3.7e+02,-0.0011,-0.006,-9.9e-05,-0.0073,0.0065,-0.097,0.21,-2.9e-06,0.43,-0.00013,0.00048,-0.00032,0,0,-3.6e+02,0.00056,0.00055,0.037,0.066,0.068,0.045,0.049,0.049,0.062,9.2e-06,1.6e-05,2.3e-06,0.026,0.027,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3 +12090000,0.71,0.0014,-0.013,0.71,-0.013,0.0043,-0.032,-0.0014,0.00091,-3.7e+02,-0.0012,-0.0059,-9.5e-05,-0.0063,0.0057,-0.097,0.21,-3e-06,0.43,-0.00016,0.00053,-0.00028,0,0,-3.6e+02,0.00056,0.00055,0.037,0.077,0.079,0.045,0.056,0.056,0.062,8.8e-06,1.6e-05,2.3e-06,0.026,0.027,0.013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12190000,0.71,0.0012,-0.013,0.71,-0.0069,0.0039,-0.026,0.0015,0.00037,-3.7e+02,-0.0011,-0.0059,-9.6e-05,-0.0061,0.006,-0.099,0.21,-2.4e-06,0.43,-0.00011,0.0006,-0.00026,0,0,-3.6e+02,0.00048,0.00048,0.037,0.064,0.066,0.041,0.048,0.048,0.059,8.2e-06,1.4e-05,2.3e-06,0.023,0.026,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12290000,0.71,0.001,-0.013,0.71,-0.0081,0.0044,-0.026,0.0011,0.00072,-3.7e+02,-0.0011,-0.0059,-9.6e-05,-0.0067,0.0056,-0.099,0.21,-2e-06,0.43,-8.3e-05,0.0006,-0.00026,0,0,-3.6e+02,0.00048,0.00048,0.037,0.073,0.076,0.042,0.055,0.056,0.06,7.9e-06,1.4e-05,2.3e-06,0.023,0.025,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12390000,0.71,0.001,-0.013,0.71,-0.0054,0.0032,-0.023,0.0025,0.00024,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.0053,0.0073,-0.1,0.21,-2.5e-06,0.43,-0.00012,0.00061,-0.00025,0,0,-3.6e+02,0.00042,0.00043,0.037,0.061,0.063,0.039,0.048,0.048,0.058,7.4e-06,1.3e-05,2.3e-06,0.021,0.024,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.1 +12490000,0.71,0.00094,-0.013,0.71,-0.0071,0.0027,-0.027,0.0017,3.4e-05,-3.7e+02,-0.0011,-0.0059,-0.0001,-0.0058,0.0085,-0.1,0.21,-2.7e-06,0.43,-0.00015,0.00055,-0.00025,0,0,-3.6e+02,0.00042,0.00042,0.037,0.069,0.072,0.04,0.055,0.055,0.058,7.1e-06,1.3e-05,2.3e-06,0.021,0.024,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12590000,0.71,0.0011,-0.013,0.71,-0.014,0.0037,-0.033,-0.0033,0.00021,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0051,0.0079,-0.1,0.21,-3e-06,0.43,-0.00019,0.00051,-0.00024,0,0,-3.6e+02,0.00037,0.00038,0.037,0.058,0.059,0.038,0.047,0.047,0.057,6.8e-06,1.2e-05,2.3e-06,0.019,0.022,0.012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12690000,0.71,0.0014,-0.013,0.71,-0.017,0.0046,-0.037,-0.0058,0.00079,-3.7e+02,-0.0012,-0.006,-0.0001,-0.0033,0.0092,-0.1,0.21,-3.9e-06,0.43,-0.00026,0.0005,-0.00025,0,0,-3.6e+02,0.00037,0.00038,0.037,0.065,0.067,0.039,0.055,0.055,0.057,6.5e-06,1.1e-05,2.3e-06,0.019,0.022,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12790000,0.71,0.0012,-0.013,0.71,-0.02,0.0027,-0.041,-0.0081,0.00025,-3.7e+02,-0.0012,-0.006,-0.0001,-0.0049,0.008,-0.1,0.21,-3.3e-06,0.43,-0.0002,0.00048,-0.00027,0,0,-3.6e+02,0.00033,0.00034,0.037,0.054,0.056,0.037,0.047,0.047,0.056,6.2e-06,1.1e-05,2.3e-06,0.018,0.021,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.2 +12890000,0.71,0.0011,-0.013,0.71,-0.02,0.0014,-0.039,-0.0096,0.00019,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0062,0.0077,-0.1,0.21,-2.9e-06,0.43,-0.00017,0.00047,-0.00026,0,0,-3.6e+02,0.00033,0.00034,0.037,0.061,0.063,0.038,0.054,0.055,0.057,6e-06,1e-05,2.3e-06,0.018,0.021,0.011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +12990000,0.71,0.001,-0.013,0.71,-0.009,0.0019,-0.039,-0.0018,0.0005,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.0038,0.0081,-0.1,0.21,-2.7e-06,0.43,-0.00018,0.00058,-0.0002,0,0,-3.6e+02,0.0003,0.00031,0.037,0.051,0.053,0.037,0.047,0.047,0.055,5.7e-06,9.9e-06,2.3e-06,0.016,0.02,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +13090000,0.71,0.00095,-0.013,0.71,-0.0097,-0.00015,-0.039,-0.0029,-7.2e-05,-3.7e+02,-0.0011,-0.006,-0.0001,-0.005,0.0097,-0.1,0.21,-3.1e-06,0.43,-0.0002,0.00052,-0.00023,0,0,-3.6e+02,0.0003,0.00031,0.037,0.057,0.059,0.038,0.054,0.054,0.056,5.5e-06,9.6e-06,2.3e-06,0.016,0.02,0.01,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +13190000,0.71,0.00094,-0.013,0.71,-0.0023,0.00081,-0.034,0.0028,0.00014,-3.7e+02,-0.0011,-0.006,-0.00011,-0.0032,0.011,-0.11,0.21,-3.4e-06,0.43,-0.00023,0.00056,-0.00021,0,0,-3.6e+02,0.00027,0.00028,0.037,0.048,0.05,0.037,0.047,0.047,0.054,5.2e-06,9.1e-06,2.3e-06,0.015,0.019,0.0098,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.3 +13290000,0.71,0.00079,-0.013,0.71,-0.00079,0.0015,-0.029,0.0034,0.0003,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0047,0.0096,-0.11,0.21,-2.5e-06,0.43,-0.00018,0.00058,-0.0002,0,0,-3.6e+02,0.00027,0.00028,0.037,0.054,0.055,0.038,0.054,0.054,0.055,5.1e-06,8.9e-06,2.3e-06,0.015,0.018,0.0097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13390000,0.71,0.0007,-0.013,0.71,0.00023,0.0023,-0.024,0.0025,0.00042,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0041,0.0089,-0.11,0.21,-2.3e-06,0.43,-0.00016,0.00063,-0.00019,0,0,-3.6e+02,0.00025,0.00026,0.037,0.045,0.047,0.037,0.047,0.047,0.054,4.8e-06,8.5e-06,2.3e-06,0.014,0.018,0.0091,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13490000,0.71,0.00071,-0.013,0.71,0.00021,0.0024,-0.022,0.0027,0.0008,-3.7e+02,-0.001,-0.0059,-0.0001,-0.0042,0.0081,-0.11,0.21,-2e-06,0.43,-0.00015,0.00063,-0.00017,0,0,-3.6e+02,0.00025,0.00026,0.037,0.05,0.052,0.038,0.054,0.054,0.055,4.7e-06,8.2e-06,2.3e-06,0.014,0.017,0.009,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13590000,0.71,0.00072,-0.013,0.71,-2.7e-05,0.0028,-0.024,0.0015,0.00038,-3.7e+02,-0.001,-0.0059,-0.0001,-0.004,0.0094,-0.11,0.21,-2.4e-06,0.43,-0.00017,0.00062,-0.00019,0,0,-3.6e+02,0.00023,0.00025,0.037,0.042,0.044,0.037,0.046,0.047,0.054,4.5e-06,7.9e-06,2.3e-06,0.013,0.017,0.0085,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.4 +13690000,0.71,0.00071,-0.013,0.71,0.00091,0.0053,-0.029,0.0017,0.0011,-3.7e+02,-0.001,-0.0059,-9.9e-05,-0.0034,0.0082,-0.11,0.21,-2.1e-06,0.43,-0.00016,0.00064,-0.00016,0,0,-3.6e+02,0.00023,0.00024,0.037,0.047,0.049,0.038,0.053,0.054,0.055,4.3e-06,7.7e-06,2.3e-06,0.013,0.017,0.0083,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +13790000,0.71,0.00075,-0.013,0.71,0.0006,0.0021,-0.03,0.0024,-0.00073,-3.7e+02,-0.0011,-0.0059,-9.9e-05,-0.002,0.0089,-0.11,0.21,-2.5e-06,0.43,-0.00019,0.00065,-0.00015,0,0,-3.6e+02,0.00022,0.00023,0.037,0.04,0.041,0.036,0.046,0.046,0.053,4.2e-06,7.3e-06,2.3e-06,0.012,0.016,0.0078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +13890000,0.71,0.00059,-0.013,0.71,0.0024,0.0022,-0.035,0.003,-0.00056,-3.7e+02,-0.001,-0.0059,-9.8e-05,-0.0034,0.0078,-0.11,0.21,-1.8e-06,0.43,-0.00015,0.00065,-0.00015,0,0,-3.6e+02,0.00022,0.00023,0.037,0.044,0.045,0.037,0.053,0.053,0.055,4e-06,7.1e-06,2.3e-06,0.012,0.016,0.0076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +13990000,0.71,0.00066,-0.013,0.71,0.0019,0.00054,-0.034,0.0036,-0.0019,-3.7e+02,-0.001,-0.0059,-9.8e-05,-0.0021,0.0083,-0.11,0.21,-2e-06,0.43,-0.00018,0.00065,-0.00013,0,0,-3.6e+02,0.0002,0.00022,0.037,0.037,0.039,0.036,0.046,0.046,0.054,3.9e-06,6.8e-06,2.3e-06,0.012,0.015,0.0071,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.5 +14090000,0.71,0.00072,-0.013,0.71,0.0014,0.0019,-0.035,0.0036,-0.0013,-3.7e+02,-0.0011,-0.0059,-9.4e-05,-0.00063,0.0073,-0.11,0.21,-1.8e-06,0.43,-0.00018,0.00069,-9.7e-05,0,0,-3.6e+02,0.00021,0.00022,0.037,0.041,0.043,0.036,0.053,0.053,0.054,3.8e-06,6.7e-06,2.3e-06,0.012,0.015,0.007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14190000,0.71,0.00068,-0.013,0.71,0.0044,0.0019,-0.037,0.0057,-0.001,-3.7e+02,-0.0011,-0.0059,-9.3e-05,-0.00017,0.007,-0.11,0.21,-1.6e-06,0.43,-0.00018,0.00071,-8e-05,0,0,-3.6e+02,0.0002,0.00021,0.037,0.035,0.037,0.035,0.046,0.046,0.054,3.6e-06,6.4e-06,2.3e-06,0.011,0.015,0.0065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14290000,0.71,0.00075,-0.013,0.71,0.0046,0.0032,-0.035,0.0059,-0.00065,-3.7e+02,-0.0011,-0.0058,-9.2e-05,0.00068,0.007,-0.11,0.21,-1.8e-06,0.43,-0.00019,0.00071,-6.2e-05,0,0,-3.6e+02,0.0002,0.0002,0.037,0.038,0.04,0.036,0.052,0.052,0.055,3.5e-06,6.2e-06,2.3e-06,0.011,0.014,0.0063,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14390000,0.71,0.00064,-0.014,0.71,0.0071,0.005,-0.037,0.0077,-0.00036,-3.7e+02,-0.0011,-0.0058,-8.9e-05,0.00035,0.0055,-0.11,0.21,-9.2e-07,0.43,-0.00015,0.00074,-4.6e-05,0,0,-3.6e+02,0.00019,0.0002,0.037,0.033,0.035,0.034,0.046,0.046,0.053,3.4e-06,6e-06,2.3e-06,0.011,0.014,0.0059,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.6 +14490000,0.71,0.00053,-0.013,0.71,0.008,0.0065,-0.041,0.0088,0.00011,-3.7e+02,-0.001,-0.0058,-8.9e-05,-0.00096,0.005,-0.11,0.21,-4.4e-07,0.43,-0.00013,0.0007,-4.6e-05,0,0,-3.6e+02,0.00019,0.00019,0.037,0.036,0.038,0.035,0.052,0.052,0.054,3.3e-06,5.8e-06,2.3e-06,0.011,0.014,0.0057,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14590000,0.71,0.00042,-0.013,0.71,0.0061,0.005,-0.041,0.006,-0.0015,-3.7e+02,-0.001,-0.0058,-8.9e-05,-0.0018,0.0047,-0.11,0.21,-3.4e-07,0.43,-0.00012,0.00067,-5.9e-05,0,0,-3.6e+02,0.00018,0.00019,0.037,0.031,0.033,0.033,0.045,0.045,0.054,3.2e-06,5.6e-06,2.3e-06,0.01,0.014,0.0053,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14690000,0.71,0.00037,-0.013,0.71,0.0079,0.0031,-0.038,0.0068,-0.00088,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0018,0.0038,-0.11,0.21,3.8e-08,0.43,-0.0001,0.00068,-4.5e-05,0,0,-3.6e+02,0.00018,0.00019,0.037,0.034,0.036,0.034,0.051,0.052,0.054,3.1e-06,5.5e-06,2.3e-06,0.01,0.013,0.0051,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14790000,0.71,0.00035,-0.013,0.71,0.0055,0.0016,-0.033,0.0042,-0.0021,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.002,0.0037,-0.12,0.21,-2e-08,0.43,-0.00011,0.00066,-4.6e-05,0,0,-3.6e+02,0.00017,0.00018,0.037,0.03,0.031,0.032,0.045,0.045,0.053,3e-06,5.2e-06,2.3e-06,0.0097,0.013,0.0048,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.7 +14890000,0.71,0.00032,-0.013,0.71,0.0077,0.0034,-0.037,0.005,-0.0018,-3.7e+02,-0.001,-0.0058,-8.6e-05,-0.0022,0.0032,-0.12,0.21,2.4e-07,0.43,-9.1e-05,0.00067,-4.3e-05,0,0,-3.6e+02,0.00017,0.00018,0.037,0.032,0.034,0.032,0.051,0.051,0.055,2.9e-06,5.1e-06,2.3e-06,0.0096,0.013,0.0046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +14990000,0.71,0.00027,-0.013,0.71,0.0068,0.0024,-0.032,0.004,-0.0017,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0028,0.0037,-0.12,0.21,4.6e-08,0.43,-0.0001,0.00064,-5.6e-05,0,0,-3.6e+02,0.00017,0.00017,0.037,0.028,0.03,0.031,0.045,0.045,0.053,2.8e-06,4.9e-06,2.3e-06,0.0094,0.012,0.0043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +15090000,0.71,0.0002,-0.013,0.71,0.0075,0.0025,-0.035,0.0047,-0.0016,-3.7e+02,-0.001,-0.0058,-8.8e-05,-0.0028,0.0041,-0.12,0.21,-5.6e-08,0.43,-0.00011,0.00063,-5.7e-05,0,0,-3.6e+02,0.00017,0.00017,0.037,0.03,0.032,0.031,0.05,0.051,0.054,2.7e-06,4.8e-06,2.3e-06,0.0092,0.012,0.0041,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +15190000,0.71,0.00017,-0.013,0.7,0.0073,0.003,-0.033,0.0039,-0.0015,-3.7e+02,-0.001,-0.0058,-9e-05,-0.0035,0.0044,-0.12,0.21,-5.2e-08,0.43,-0.00012,0.00059,-6.4e-05,0,0,-3.6e+02,0.00016,0.00017,0.037,0.027,0.028,0.03,0.044,0.045,0.053,2.6e-06,4.6e-06,2.3e-06,0.009,0.012,0.0038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.8 +15290000,0.71,0.00019,-0.013,0.7,0.0077,0.0041,-0.03,0.0044,-0.00097,-3.7e+02,-0.001,-0.0058,-8.8e-05,-0.0026,0.0042,-0.12,0.21,-8.2e-09,0.43,-0.00014,0.00059,-3.9e-05,0,0,-3.6e+02,0.00016,0.00017,0.037,0.029,0.031,0.03,0.05,0.05,0.054,2.6e-06,4.5e-06,2.3e-06,0.0089,0.012,0.0037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15390000,0.71,0.0002,-0.013,0.7,0.007,0.0054,-0.028,0.0017,-0.00041,-3.7e+02,-0.001,-0.0058,-8.3e-05,-0.0018,0.0027,-0.12,0.21,3.4e-07,0.43,-0.00012,0.00062,-1.6e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.025,0.027,0.028,0.044,0.044,0.053,2.5e-06,4.4e-06,2.3e-06,0.0087,0.012,0.0034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15490000,0.71,0.00022,-0.013,0.7,0.0086,0.0045,-0.028,0.0024,-0.00036,-3.7e+02,-0.001,-0.0058,-8.7e-05,-0.0022,0.004,-0.12,0.21,-1.1e-07,0.43,-0.00014,0.00059,-3.5e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.027,0.029,0.029,0.049,0.05,0.054,2.4e-06,4.3e-06,2.3e-06,0.0086,0.011,0.0033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15590000,0.71,0.00018,-0.013,0.71,0.0072,0.0036,-0.027,8.4e-05,-0.00068,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0028,0.0047,-0.12,0.21,-4.6e-07,0.43,-0.00014,0.00058,-6.1e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.024,0.026,0.027,0.044,0.044,0.053,2.3e-06,4.1e-06,2.3e-06,0.0084,0.011,0.0031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,3.9 +15690000,0.71,0.00022,-0.013,0.71,0.0074,0.0037,-0.028,0.00059,-0.00037,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0023,0.0052,-0.12,0.21,-7.6e-07,0.43,-0.00015,0.00059,-6.4e-05,0,0,-3.6e+02,0.00016,0.00016,0.037,0.026,0.028,0.027,0.049,0.049,0.053,2.3e-06,4e-06,2.3e-06,0.0083,0.011,0.003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +15790000,0.71,0.00019,-0.013,0.7,0.0081,0.0021,-0.03,0.00049,-0.0016,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0026,0.0054,-0.12,0.21,-8.8e-07,0.43,-0.00016,0.00057,-6.8e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.023,0.025,0.026,0.043,0.044,0.052,2.2e-06,3.9e-06,2.3e-06,0.0081,0.011,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +15890000,0.71,0.0002,-0.013,0.71,0.0088,0.0021,-0.028,0.0011,-0.0014,-3.7e+02,-0.0011,-0.0059,-8.8e-05,-0.0018,0.0057,-0.12,0.21,-1.1e-06,0.43,-0.00018,0.00057,-6e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.025,0.027,0.026,0.048,0.049,0.053,2.1e-06,3.8e-06,2.3e-06,0.008,0.011,0.0027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +15990000,0.71,0.00018,-0.013,0.71,0.0086,0.0022,-0.024,0.00076,-0.0019,-3.7e+02,-0.0011,-0.0059,-8.4e-05,-0.0012,0.0049,-0.12,0.21,-9.8e-07,0.43,-0.00018,0.00058,-4.2e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.022,0.024,0.025,0.043,0.043,0.052,2.1e-06,3.6e-06,2.3e-06,0.0079,0.01,0.0025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4 +16090000,0.71,0.00021,-0.013,0.71,0.011,0.0039,-0.02,0.0016,-0.0011,-3.7e+02,-0.0011,-0.0058,-8e-05,-0.00043,0.0037,-0.12,0.21,-7.1e-07,0.43,-0.00016,0.00063,-2.6e-05,0,0,-3.6e+02,0.00015,0.00015,0.037,0.024,0.026,0.024,0.048,0.048,0.052,2e-06,3.6e-06,2.3e-06,0.0078,0.01,0.0024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16190000,0.71,0.00026,-0.013,0.71,0.01,0.0041,-0.019,0.001,-0.00095,-3.7e+02,-0.0011,-0.0058,-7.9e-05,0.00031,0.0039,-0.12,0.21,-1e-06,0.43,-0.00017,0.00063,-2.1e-05,0,0,-3.6e+02,0.00015,0.00014,0.037,0.021,0.023,0.023,0.043,0.043,0.052,2e-06,3.4e-06,2.3e-06,0.0077,0.01,0.0022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16290000,0.71,0.00028,-0.014,0.71,0.012,0.0052,-0.02,0.0023,5.7e-05,-3.7e+02,-0.0011,-0.0058,-7.5e-05,0.00063,0.0026,-0.12,0.21,-5.6e-07,0.43,-0.00015,0.00065,-5.9e-06,0,0,-3.6e+02,0.00015,0.00014,0.037,0.023,0.025,0.023,0.047,0.048,0.052,1.9e-06,3.4e-06,2.3e-06,0.0076,0.01,0.0021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16390000,0.71,0.00033,-0.013,0.71,0.01,0.0037,-0.019,0.0013,-0.00022,-3.7e+02,-0.0011,-0.0058,-7.6e-05,0.0018,0.0038,-0.12,0.21,-1.3e-06,0.43,-0.00018,0.00064,-2e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.02,0.022,0.022,0.042,0.043,0.051,1.9e-06,3.2e-06,2.3e-06,0.0075,0.0098,0.002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.1 +16490000,0.71,0.00042,-0.013,0.71,0.0088,0.005,-0.022,0.0018,0.00032,-3.7e+02,-0.0011,-0.0058,-7.5e-05,0.0026,0.0039,-0.12,0.21,-1.6e-06,0.43,-0.00019,0.00064,1.2e-05,0,0,-3.6e+02,0.00014,0.00014,0.037,0.022,0.024,0.022,0.047,0.048,0.052,1.8e-06,3.2e-06,2.3e-06,0.0074,0.0097,0.0019,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16590000,0.71,0.00053,-0.013,0.71,0.0068,0.0059,-0.023,-0.00051,0.0023,-3.7e+02,-0.0012,-0.0058,-7.6e-05,0.0028,0.0036,-0.12,0.21,-1.6e-06,0.43,-0.00017,0.00063,7.8e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.02,0.022,0.021,0.042,0.042,0.05,1.8e-06,3.1e-06,2.3e-06,0.0073,0.0095,0.0018,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16690000,0.71,0.00049,-0.013,0.71,0.0076,0.0062,-0.019,0.00033,0.0026,-3.7e+02,-0.0012,-0.0058,-7.9e-05,0.0022,0.0043,-0.12,0.21,-1.8e-06,0.43,-0.00018,0.00062,-3.3e-06,0,0,-3.6e+02,0.00014,0.00014,0.037,0.021,0.024,0.021,0.047,0.047,0.051,1.7e-06,3e-06,2.3e-06,0.0072,0.0094,0.0017,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16790000,0.71,0.00049,-0.013,0.71,0.0058,0.0069,-0.018,-0.0016,0.0042,-3.7e+02,-0.0012,-0.0058,-8e-05,0.002,0.004,-0.12,0.21,-1.7e-06,0.43,-0.00016,0.00063,-1.6e-05,0,0,-3.6e+02,0.00014,0.00013,0.037,0.019,0.021,0.02,0.042,0.042,0.05,1.7e-06,2.9e-06,2.3e-06,0.0071,0.0092,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.2 +16890000,0.71,0.00054,-0.013,0.71,0.0055,0.0078,-0.016,-0.0013,0.0047,-3.7e+02,-0.0012,-0.0058,-8.2e-05,0.0023,0.0046,-0.13,0.21,-2e-06,0.43,-0.00017,0.00062,-1.2e-05,0,0,-3.6e+02,0.00014,0.00013,0.037,0.02,0.023,0.02,0.046,0.047,0.05,1.6e-06,2.8e-06,2.3e-06,0.007,0.0091,0.0016,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +16990000,0.71,0.00051,-0.013,0.71,0.0055,0.0055,-0.015,-0.0021,0.0025,-3.7e+02,-0.0012,-0.0059,-8.2e-05,0.0022,0.0056,-0.13,0.21,-2.5e-06,0.43,-0.00019,0.00061,-2.2e-05,0,0,-3.6e+02,0.00013,0.00013,0.037,0.018,0.021,0.019,0.041,0.042,0.049,1.6e-06,2.7e-06,2.3e-06,0.0069,0.009,0.0015,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +17090000,0.71,0.00055,-0.013,0.71,0.0058,0.0071,-0.015,-0.002,0.0032,-3.7e+02,-0.0012,-0.0059,-8.1e-05,0.0032,0.0059,-0.13,0.21,-2.8e-06,0.43,-0.0002,0.00061,-1e-05,0,0,-3.6e+02,0.00014,0.00013,0.037,0.02,0.022,0.019,0.046,0.047,0.049,1.5e-06,2.7e-06,2.3e-06,0.0068,0.0089,0.0014,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +17190000,0.71,0.00061,-0.013,0.71,0.0059,0.008,-0.016,-0.0028,0.0021,-3.7e+02,-0.0012,-0.0059,-7.7e-05,0.004,0.0059,-0.13,0.21,-3.1e-06,0.43,-0.0002,0.00062,-7.9e-06,0,0,-3.6e+02,0.00013,0.00013,0.037,0.018,0.02,0.018,0.041,0.042,0.049,1.5e-06,2.6e-06,2.3e-06,0.0067,0.0087,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.3 +17290000,0.71,0.00063,-0.013,0.71,0.0077,0.0088,-0.011,-0.0026,0.0025,-3.7e+02,-0.0012,-0.0059,-7.9e-05,0.0043,0.0068,-0.13,0.21,-3.5e-06,0.43,-0.00022,0.00061,-5.3e-06,0,0,-3.6e+02,0.00013,0.00013,0.037,0.019,0.022,0.018,0.045,0.046,0.049,1.5e-06,2.5e-06,2.3e-06,0.0067,0.0086,0.0013,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17390000,0.71,0.00068,-0.013,0.71,0.0075,0.0092,-0.0095,-0.0024,0.0016,-3.7e+02,-0.0012,-0.0059,-7.3e-05,0.0051,0.0066,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00061,1.3e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.017,0.02,0.017,0.041,0.041,0.048,1.4e-06,2.4e-06,2.2e-06,0.0066,0.0085,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17490000,0.71,0.00063,-0.013,0.71,0.0091,0.0093,-0.0078,-0.0012,0.0025,-3.7e+02,-0.0012,-0.0059,-7.3e-05,0.0045,0.0064,-0.13,0.21,-3.4e-06,0.43,-0.00023,0.00061,7.6e-06,0,0,-3.6e+02,0.00013,0.00012,0.037,0.019,0.021,0.017,0.045,0.046,0.049,1.4e-06,2.4e-06,2.2e-06,0.0065,0.0084,0.0012,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17590000,0.71,0.0006,-0.013,0.71,0.0099,0.0085,-0.0024,-0.001,0.0013,-3.7e+02,-0.0012,-0.0059,-7e-05,0.0048,0.0066,-0.13,0.21,-3.7e-06,0.43,-0.00024,0.00061,4.9e-06,0,0,-3.6e+02,0.00013,0.00012,0.037,0.017,0.019,0.017,0.04,0.041,0.048,1.4e-06,2.3e-06,2.2e-06,0.0064,0.0082,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.4 +17690000,0.71,0.00058,-0.013,0.71,0.011,0.01,-0.003,1.7e-05,0.0023,-3.7e+02,-0.0012,-0.0059,-6.9e-05,0.0049,0.0064,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00061,1.3e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.018,0.021,0.016,0.045,0.046,0.048,1.3e-06,2.3e-06,2.2e-06,0.0064,0.0082,0.0011,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +17790000,0.71,0.00056,-0.013,0.71,0.012,0.011,-0.0042,1.3e-05,0.0029,-3.7e+02,-0.0012,-0.0058,-6e-05,0.0059,0.0053,-0.13,0.21,-3.6e-06,0.43,-0.00024,0.00064,2.2e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.016,0.019,0.016,0.04,0.041,0.047,1.3e-06,2.2e-06,2.2e-06,0.0063,0.008,0.001,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +17890000,0.71,0.00055,-0.013,0.71,0.015,0.012,-0.0041,0.0016,0.0045,-3.7e+02,-0.0012,-0.0058,-5.7e-05,0.0057,0.0046,-0.13,0.21,-3.3e-06,0.43,-0.00024,0.00064,2.7e-05,0,0,-3.6e+02,0.00013,0.00012,0.037,0.018,0.02,0.016,0.044,0.045,0.047,1.3e-06,2.2e-06,2.2e-06,0.0062,0.008,0.00097,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +17990000,0.71,0.00049,-0.013,0.71,0.016,0.0091,-0.0027,0.0018,0.0036,-3.7e+02,-0.0012,-0.0058,-5.6e-05,0.0054,0.0049,-0.13,0.21,-3.4e-06,0.43,-0.00024,0.00064,2.4e-05,0,0,-3.6e+02,0.00012,0.00012,0.037,0.016,0.019,0.015,0.04,0.041,0.046,1.2e-06,2.1e-06,2.2e-06,0.0062,0.0078,0.00092,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.5 +18090000,0.71,0.00048,-0.013,0.71,0.017,0.0083,-0.00045,0.0035,0.0037,-3.7e+02,-0.0012,-0.0059,-6.2e-05,0.0049,0.0059,-0.13,0.21,-3.5e-06,0.43,-0.00026,0.00061,1.9e-05,0,0,-3.6e+02,0.00012,0.00012,0.037,0.017,0.02,0.015,0.044,0.045,0.047,1.2e-06,2.1e-06,2.2e-06,0.0061,0.0078,0.00089,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18190000,0.71,0.00044,-0.013,0.71,0.018,0.0093,0.001,0.0041,0.0036,-3.7e+02,-0.0012,-0.0059,-5.7e-05,0.0051,0.0056,-0.13,0.21,-3.6e-06,0.43,-0.00025,0.00062,2e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.018,0.014,0.04,0.04,0.046,1.2e-06,2e-06,2.2e-06,0.0061,0.0076,0.00085,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18290000,0.71,0.00035,-0.013,0.71,0.018,0.0088,0.0022,0.0061,0.0041,-3.7e+02,-0.0012,-0.0059,-6e-05,0.0047,0.0059,-0.13,0.21,-3.6e-06,0.43,-0.00025,0.00061,1.4e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.017,0.02,0.014,0.044,0.045,0.046,1.2e-06,2e-06,2.2e-06,0.006,0.0076,0.00082,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18390000,0.71,0.00032,-0.013,0.71,0.02,0.011,0.0035,0.0068,0.0042,-3.7e+02,-0.0012,-0.0059,-5.4e-05,0.0045,0.0051,-0.13,0.21,-3.4e-06,0.43,-0.00024,0.00062,1.6e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.015,0.018,0.014,0.039,0.04,0.045,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.00078,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.6 +18490000,0.71,0.00038,-0.013,0.71,0.021,0.012,0.0031,0.0085,0.0055,-3.7e+02,-0.0012,-0.0059,-5.3e-05,0.005,0.0052,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00063,1.9e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.02,0.014,0.043,0.045,0.045,1.1e-06,1.9e-06,2.2e-06,0.0059,0.0074,0.00076,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18590000,0.71,0.00039,-0.013,0.71,0.02,0.013,0.0014,0.0074,0.0054,-3.7e+02,-0.0012,-0.0058,-4.5e-05,0.0058,0.0047,-0.13,0.21,-3.7e-06,0.43,-0.00025,0.00065,2.5e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.045,1.1e-06,1.8e-06,2.2e-06,0.0058,0.0073,0.00072,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18690000,0.71,0.00031,-0.013,0.71,0.022,0.013,-0.00039,0.01,0.0065,-3.7e+02,-0.0012,-0.0059,-4.7e-05,0.0051,0.0047,-0.13,0.21,-3.5e-06,0.43,-0.00025,0.00064,1.8e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.045,1e-06,1.8e-06,2.2e-06,0.0058,0.0072,0.0007,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18790000,0.71,0.00032,-0.013,0.71,0.021,0.012,-0.00061,0.0087,0.0054,-3.7e+02,-0.0012,-0.0059,-4.6e-05,0.0053,0.0053,-0.13,0.21,-3.8e-06,0.43,-0.00025,0.00063,1.5e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.015,0.018,0.013,0.039,0.04,0.044,1e-06,1.7e-06,2.2e-06,0.0057,0.0071,0.00067,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.7 +18890000,0.71,0.00041,-0.013,0.71,0.021,0.014,1.9e-05,0.01,0.0075,-3.7e+02,-0.0012,-0.0058,-4e-05,0.0062,0.0047,-0.13,0.21,-3.9e-06,0.43,-0.00026,0.00065,2.9e-05,0,0,-3.6e+02,0.00012,0.00011,0.037,0.016,0.019,0.013,0.043,0.044,0.044,1e-06,1.7e-06,2.2e-06,0.0057,0.007,0.00065,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +18990000,0.71,0.00046,-0.013,0.71,0.021,0.015,-0.0012,0.01,0.0068,-3.7e+02,-0.0013,-0.0058,-3.4e-05,0.0069,0.0049,-0.13,0.21,-4.2e-06,0.43,-0.00027,0.00066,3e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.015,0.017,0.012,0.039,0.04,0.044,9.7e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.00062,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +19090000,0.71,0.00051,-0.013,0.71,0.021,0.016,0.0018,0.012,0.0084,-3.7e+02,-0.0013,-0.0058,-3.4e-05,0.0075,0.0052,-0.13,0.21,-4.4e-06,0.43,-0.00028,0.00066,3.4e-05,0,0,-3.6e+02,0.00011,0.0001,0.037,0.016,0.019,0.012,0.042,0.044,0.044,9.6e-07,1.6e-06,2.2e-06,0.0056,0.0069,0.0006,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +19190000,0.71,0.00056,-0.013,0.71,0.02,0.016,0.0019,0.012,0.0076,-3.7e+02,-0.0013,-0.0059,-2.7e-05,0.008,0.0054,-0.13,0.21,-4.6e-06,0.43,-0.0003,0.00067,3.7e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.014,0.017,0.012,0.038,0.04,0.043,9.3e-07,1.5e-06,2.1e-06,0.0055,0.0068,0.00058,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.8 +19290000,0.71,0.00058,-0.013,0.71,0.02,0.015,0.0046,0.013,0.0088,-3.7e+02,-0.0013,-0.0059,-3e-05,0.0078,0.0058,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00066,4e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.015,0.019,0.012,0.042,0.044,0.043,9.2e-07,1.5e-06,2.1e-06,0.0055,0.0067,0.00056,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19390000,0.71,0.00054,-0.013,0.71,0.019,0.014,0.0084,0.012,0.0079,-3.7e+02,-0.0013,-0.0059,-2.4e-05,0.0078,0.0056,-0.13,0.21,-4.7e-06,0.43,-0.0003,0.00065,3.5e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.014,0.017,0.011,0.038,0.04,0.043,8.9e-07,1.5e-06,2.1e-06,0.0054,0.0066,0.00054,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19490000,0.71,0.00056,-0.013,0.71,0.019,0.015,0.0049,0.014,0.01,-3.7e+02,-0.0013,-0.0058,-1.8e-05,0.0078,0.0049,-0.13,0.21,-4.6e-06,0.43,-0.00029,0.00066,3.8e-05,0,0,-3.6e+02,0.00011,0.0001,0.036,0.015,0.018,0.011,0.042,0.044,0.043,8.8e-07,1.4e-06,2.1e-06,0.0054,0.0066,0.00052,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19590000,0.71,0.00063,-0.013,0.71,0.017,0.015,0.0043,0.012,0.0095,-3.7e+02,-0.0013,-0.0058,-6.7e-06,0.0086,0.0047,-0.13,0.21,-4.7e-06,0.43,-0.0003,0.00068,4.7e-05,0,0,-3.6e+02,0.00011,9.8e-05,0.036,0.014,0.017,0.011,0.038,0.039,0.042,8.5e-07,1.4e-06,2.1e-06,0.0053,0.0065,0.0005,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,4.9 +19690000,0.71,0.00067,-0.013,0.71,0.017,0.013,0.0059,0.013,0.01,-3.7e+02,-0.0013,-0.0059,-1e-05,0.0089,0.0053,-0.13,0.21,-5e-06,0.43,-0.00031,0.00068,3.9e-05,0,0,-3.6e+02,0.00011,9.8e-05,0.036,0.015,0.018,0.011,0.042,0.043,0.042,8.4e-07,1.4e-06,2.1e-06,0.0053,0.0064,0.00049,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +19790000,0.71,0.00075,-0.013,0.71,0.014,0.011,0.0064,0.011,0.009,-3.7e+02,-0.0013,-0.0059,-5.6e-06,0.0094,0.0057,-0.13,0.21,-5.3e-06,0.43,-0.00031,0.00068,3.7e-05,0,0,-3.6e+02,0.00011,9.6e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.042,8.2e-07,1.3e-06,2.1e-06,0.0053,0.0063,0.00047,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +19890000,0.71,0.00066,-0.013,0.71,0.015,0.013,0.0076,0.014,0.011,-3.7e+02,-0.0013,-0.0058,2.5e-06,0.0092,0.0046,-0.13,0.21,-4.9e-06,0.43,-0.00031,0.00069,4.5e-05,0,0,-3.6e+02,0.00011,9.6e-05,0.036,0.015,0.018,0.01,0.041,0.043,0.042,8.1e-07,1.3e-06,2.1e-06,0.0052,0.0063,0.00046,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +19990000,0.71,0.00063,-0.013,0.7,0.013,0.013,0.01,0.012,0.011,-3.7e+02,-0.0013,-0.0058,1.8e-05,0.0095,0.0038,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.0007,5e-05,0,0,-3.6e+02,0.0001,9.4e-05,0.036,0.014,0.017,0.01,0.038,0.039,0.041,7.8e-07,1.2e-06,2.1e-06,0.0052,0.0062,0.00044,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5 +20090000,0.71,0.00066,-0.013,0.7,0.013,0.013,0.011,0.013,0.013,-3.7e+02,-0.0013,-0.0058,2.8e-05,0.01,0.0031,-0.13,0.21,-4.8e-06,0.43,-0.00032,0.00072,6.1e-05,0,0,-3.6e+02,0.00011,9.4e-05,0.036,0.014,0.018,0.01,0.041,0.043,0.041,7.8e-07,1.2e-06,2.1e-06,0.0052,0.0062,0.00043,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20190000,0.71,0.0007,-0.013,0.7,0.012,0.012,0.013,0.011,0.012,-3.7e+02,-0.0013,-0.0058,3.7e-05,0.0099,0.0028,-0.13,0.21,-4.7e-06,0.43,-0.00031,0.00072,6.1e-05,0,0,-3.6e+02,0.0001,9.2e-05,0.036,0.013,0.016,0.0098,0.037,0.039,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.0061,0.00042,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20290000,0.71,0.0007,-0.013,0.7,0.01,0.012,0.011,0.012,0.013,-3.7e+02,-0.0013,-0.0058,4.1e-05,0.01,0.0027,-0.13,0.21,-4.8e-06,0.43,-0.00032,0.00074,6.2e-05,0,0,-3.6e+02,0.0001,9.2e-05,0.036,0.014,0.018,0.0097,0.041,0.043,0.041,7.5e-07,1.2e-06,2.1e-06,0.0051,0.006,0.0004,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20390000,0.71,0.00066,-0.013,0.7,0.0086,0.0097,0.013,0.01,0.012,-3.7e+02,-0.0013,-0.0058,4.5e-05,0.01,0.0028,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.00073,5.2e-05,0,0,-3.6e+02,0.0001,9.1e-05,0.036,0.013,0.016,0.0095,0.037,0.039,0.04,7.3e-07,1.1e-06,2e-06,0.005,0.0059,0.00039,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.1 +20490000,0.71,0.00071,-0.013,0.7,0.0087,0.0097,0.013,0.011,0.012,-3.7e+02,-0.0013,-0.0058,4.2e-05,0.01,0.003,-0.13,0.21,-4.8e-06,0.43,-0.00031,0.00072,5.1e-05,0,0,-3.6e+02,0.0001,9.1e-05,0.036,0.014,0.017,0.0094,0.041,0.043,0.04,7.2e-07,1.1e-06,2e-06,0.005,0.0059,0.00038,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20590000,0.71,0.00074,-0.013,0.7,0.0078,0.0076,0.0099,0.0091,0.01,-3.7e+02,-0.0013,-0.0058,4.3e-05,0.01,0.0036,-0.13,0.21,-5e-06,0.43,-0.00031,0.00072,5e-05,0,0,-3.6e+02,9.9e-05,8.9e-05,0.036,0.013,0.016,0.0092,0.037,0.039,0.04,7e-07,1.1e-06,2e-06,0.005,0.0058,0.00037,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20690000,0.71,0.00077,-0.013,0.7,0.0084,0.0077,0.011,0.01,0.011,-3.7e+02,-0.0013,-0.0058,4.6e-05,0.01,0.0034,-0.13,0.21,-5e-06,0.43,-0.00031,0.00072,5.2e-05,0,0,-3.6e+02,0.0001,8.9e-05,0.036,0.014,0.017,0.0092,0.041,0.043,0.04,6.9e-07,1.1e-06,2e-06,0.0049,0.0058,0.00036,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20790000,0.71,0.00081,-0.013,0.7,0.0063,0.0072,0.012,0.0084,0.01,-3.7e+02,-0.0013,-0.0058,5.1e-05,0.011,0.0035,-0.13,0.21,-5e-06,0.43,-0.00032,0.00073,4.6e-05,0,0,-3.6e+02,9.8e-05,8.7e-05,0.036,0.013,0.016,0.009,0.037,0.039,0.039,6.7e-07,1e-06,2e-06,0.0049,0.0057,0.00035,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.2 +20890000,0.71,0.00082,-0.013,0.7,0.0062,0.0068,0.011,0.009,0.011,-3.7e+02,-0.0013,-0.0058,5.9e-05,0.011,0.0031,-0.13,0.21,-5e-06,0.43,-0.00033,0.00074,5.2e-05,0,0,-3.6e+02,9.8e-05,8.8e-05,0.036,0.014,0.017,0.0089,0.04,0.043,0.039,6.6e-07,1e-06,2e-06,0.0049,0.0057,0.00034,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +20990000,0.71,0.00084,-0.013,0.7,0.0044,0.0045,0.011,0.009,0.01,-3.7e+02,-0.0013,-0.0058,6.3e-05,0.011,0.0033,-0.13,0.21,-5e-06,0.43,-0.00034,0.00075,4.9e-05,0,0,-3.6e+02,9.6e-05,8.6e-05,0.036,0.013,0.016,0.0087,0.037,0.039,0.039,6.5e-07,9.9e-07,2e-06,0.0048,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +21090000,0.71,0.00081,-0.013,0.7,0.0054,0.0037,0.012,0.01,0.011,-3.7e+02,-0.0013,-0.0058,6.8e-05,0.011,0.0029,-0.13,0.21,-4.9e-06,0.43,-0.00033,0.00075,4.6e-05,0,0,-3.6e+02,9.7e-05,8.6e-05,0.036,0.014,0.017,0.0087,0.04,0.043,0.039,6.4e-07,9.8e-07,2e-06,0.0048,0.0056,0.00033,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +21190000,0.71,0.00082,-0.013,0.7,0.0057,0.0028,0.011,0.011,0.0091,-3.7e+02,-0.0013,-0.0058,6.8e-05,0.011,0.0031,-0.13,0.21,-4.9e-06,0.43,-0.00033,0.00075,4.3e-05,0,0,-3.6e+02,9.4e-05,8.4e-05,0.036,0.013,0.016,0.0085,0.037,0.039,0.039,6.2e-07,9.4e-07,1.9e-06,0.0048,0.0055,0.00032,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.3 +21290000,0.71,0.0009,-0.013,0.7,0.005,0.0029,0.013,0.011,0.01,-3.7e+02,-0.0013,-0.0058,7.9e-05,0.011,0.0026,-0.13,0.21,-4.9e-06,0.43,-0.00034,0.00077,4.7e-05,0,0,-3.6e+02,9.5e-05,8.5e-05,0.036,0.014,0.017,0.0084,0.04,0.043,0.038,6.2e-07,9.4e-07,1.9e-06,0.0048,0.0055,0.00031,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21390000,0.71,0.00088,-0.013,0.7,0.004,0.00086,0.013,0.0095,0.0093,-3.7e+02,-0.0013,-0.0058,7.4e-05,0.011,0.0028,-0.13,0.21,-5e-06,0.43,-0.00033,0.00076,4.7e-05,0,0,-3.6e+02,9.3e-05,8.3e-05,0.036,0.013,0.016,0.0083,0.037,0.039,0.038,6e-07,9e-07,1.9e-06,0.0047,0.0054,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21490000,0.71,0.00088,-0.013,0.7,0.0045,0.0013,0.013,0.01,0.0098,-3.7e+02,-0.0013,-0.0058,7.9e-05,0.011,0.0024,-0.13,0.21,-5e-06,0.43,-0.00032,0.00077,5.3e-05,0,0,-3.6e+02,9.4e-05,8.3e-05,0.036,0.014,0.017,0.0082,0.04,0.043,0.038,6e-07,9e-07,1.9e-06,0.0047,0.0054,0.0003,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21590000,0.71,0.00087,-0.013,0.7,0.0033,0.0017,0.012,0.009,0.0091,-3.7e+02,-0.0013,-0.0058,7.7e-05,0.011,0.0025,-0.13,0.21,-5.1e-06,0.43,-0.00032,0.00076,5e-05,0,0,-3.6e+02,9.1e-05,8.2e-05,0.036,0.013,0.015,0.0081,0.037,0.039,0.038,5.8e-07,8.7e-07,1.9e-06,0.0047,0.0053,0.00029,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.4 +21690000,0.71,0.00084,-0.013,0.7,0.0049,0.0021,0.014,0.01,0.0097,-3.7e+02,-0.0013,-0.0058,8.1e-05,0.011,0.0021,-0.13,0.21,-5e-06,0.43,-0.00031,0.00077,5.1e-05,0,0,-3.6e+02,9.2e-05,8.2e-05,0.036,0.013,0.017,0.0081,0.04,0.042,0.038,5.8e-07,8.6e-07,1.9e-06,0.0047,0.0053,0.00028,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 +21790000,0.71,0.00084,-0.013,0.7,0.003,0.0042,0.013,0.0074,0.01,-3.7e+02,-0.0013,-0.0058,7.2e-05,0.011,0.0023,-0.13,0.21,-5.6e-06,0.43,-0.00033,0.00076,5.3e-05,0,0,-3.6e+02,9e-05,8e-05,0.036,0.012,0.015,0.0079,0.036,0.039,0.038,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0052,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 +21890000,0.71,0.00083,-0.013,0.7,0.0038,0.0047,0.013,0.0079,0.011,-3.7e+02,-0.0013,-0.0058,7.3e-05,0.011,0.0022,-0.13,0.21,-5.5e-06,0.43,-0.00033,0.00076,5e-05,0,0,-3.6e+02,9.1e-05,8.1e-05,0.036,0.013,0.016,0.0079,0.04,0.042,0.037,5.6e-07,8.3e-07,1.9e-06,0.0046,0.0052,0.00027,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,5.5 +21990000,0.71,0.00085,-0.013,0.7,0.0026,0.0054,0.014,0.006,0.012,-3.7e+02,-0.0013,-0.0058,7e-05,0.012,0.002,-0.13,0.21,-5.9e-06,0.43,-0.00034,0.00076,5.2e-05,0,0,-3.7e+02,8.8e-05,7.9e-05,0.036,0.012,0.015,0.0077,0.036,0.038,0.037,5.4e-07,8e-07,1.9e-06,0.0046,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22090000,0.71,0.00088,-0.013,0.7,0.0025,0.007,0.012,0.006,0.013,-3.7e+02,-0.0013,-0.0058,7e-05,0.012,0.0021,-0.13,0.21,-5.9e-06,0.43,-0.00034,0.00076,5.2e-05,0,0,-3.7e+02,8.9e-05,7.9e-05,0.036,0.013,0.016,0.0077,0.04,0.042,0.037,5.4e-07,7.9e-07,1.8e-06,0.0046,0.0052,0.00026,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22190000,0.71,0.00085,-0.013,0.7,0.0019,0.007,0.013,0.0053,0.011,-3.7e+02,-0.0013,-0.0058,7.6e-05,0.012,0.0021,-0.13,0.21,-5.7e-06,0.43,-0.00035,0.00077,4.1e-05,0,0,-3.7e+02,8.7e-05,7.8e-05,0.036,0.012,0.015,0.0076,0.036,0.038,0.037,5.3e-07,7.6e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22290000,0.71,0.00088,-0.013,0.7,0.0013,0.0067,0.013,0.0057,0.012,-3.7e+02,-0.0013,-0.0058,7.4e-05,0.012,0.0022,-0.13,0.21,-5.8e-06,0.43,-0.00035,0.00076,4.2e-05,0,0,-3.7e+02,8.8e-05,7.8e-05,0.036,0.013,0.016,0.0075,0.04,0.042,0.037,5.2e-07,7.6e-07,1.8e-06,0.0045,0.0051,0.00025,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22390000,0.71,0.00089,-0.013,0.7,-0.001,0.0064,0.015,0.0041,0.01,-3.7e+02,-0.0013,-0.0058,8.1e-05,0.012,0.0024,-0.13,0.21,-5.7e-06,0.43,-0.00035,0.00077,4.3e-05,0,0,-3.7e+02,8.6e-05,7.7e-05,0.036,0.012,0.015,0.0074,0.036,0.038,0.037,5.1e-07,7.3e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22490000,0.71,0.00093,-0.013,0.7,-0.0021,0.0072,0.016,0.0033,0.011,-3.7e+02,-0.0013,-0.0058,8.2e-05,0.012,0.0026,-0.13,0.21,-5.7e-06,0.43,-0.00037,0.00078,4.1e-05,0,0,-3.7e+02,8.6e-05,7.7e-05,0.036,0.013,0.016,0.0074,0.039,0.042,0.037,5.1e-07,7.3e-07,1.8e-06,0.0045,0.005,0.00024,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22590000,0.71,0.00096,-0.013,0.7,-0.0038,0.0065,0.015,0.00096,0.01,-3.7e+02,-0.0014,-0.0058,8.5e-05,0.013,0.0027,-0.13,0.21,-5.6e-06,0.43,-0.00038,0.00079,3.8e-05,0,0,-3.7e+02,8.4e-05,7.5e-05,0.036,0.012,0.015,0.0073,0.036,0.038,0.036,5e-07,7.1e-07,1.8e-06,0.0044,0.0049,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22690000,0.71,0.001,-0.013,0.7,-0.0052,0.008,0.016,0.00022,0.012,-3.7e+02,-0.0014,-0.0058,9.1e-05,0.013,0.0026,-0.13,0.21,-5.5e-06,0.43,-0.00039,0.0008,3.7e-05,0,0,-3.7e+02,8.5e-05,7.6e-05,0.036,0.013,0.016,0.0073,0.039,0.042,0.036,4.9e-07,7e-07,1.8e-06,0.0044,0.0049,0.00023,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22790000,0.71,0.001,-0.013,0.7,-0.0071,0.0069,0.017,-0.0024,0.0091,-3.7e+02,-0.0014,-0.0058,8.1e-05,0.013,0.0034,-0.13,0.21,-5.7e-06,0.43,-0.00039,0.00078,4.3e-05,0,0,-3.7e+02,8.3e-05,7.4e-05,0.036,0.012,0.015,0.0071,0.036,0.038,0.036,4.8e-07,6.8e-07,1.7e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22890000,0.71,0.00099,-0.013,0.7,-0.0076,0.0078,0.019,-0.0024,0.0098,-3.7e+02,-0.0014,-0.0058,8e-05,0.013,0.0033,-0.13,0.21,-5.6e-06,0.43,-0.00038,0.00077,3.9e-05,0,0,-3.7e+02,8.4e-05,7.5e-05,0.036,0.013,0.016,0.0071,0.039,0.042,0.036,4.8e-07,6.8e-07,1.7e-06,0.0044,0.0049,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +22990000,0.71,0.00097,-0.013,0.7,-0.0077,0.0068,0.02,-0.0036,0.009,-3.7e+02,-0.0014,-0.0058,9e-05,0.013,0.0032,-0.13,0.21,-5.4e-06,0.43,-0.00038,0.00078,3.6e-05,0,0,-3.7e+02,8.2e-05,7.3e-05,0.036,0.012,0.015,0.007,0.036,0.038,0.036,4.7e-07,6.5e-07,1.7e-06,0.0043,0.0048,0.00022,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23090000,0.71,0.00092,-0.013,0.7,-0.0081,0.0067,0.02,-0.0043,0.009,-3.7e+02,-0.0014,-0.0058,8.1e-05,0.012,0.0034,-0.13,0.21,-5.5e-06,0.43,-0.00038,0.00077,3.3e-05,0,0,-3.7e+02,8.3e-05,7.4e-05,0.036,0.013,0.016,0.007,0.039,0.042,0.036,4.6e-07,6.5e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23190000,0.71,0.00097,-0.013,0.7,-0.0094,0.0047,0.022,-0.0076,0.0078,-3.7e+02,-0.0014,-0.0058,8.4e-05,0.013,0.0036,-0.13,0.21,-5.5e-06,0.43,-0.00037,0.00076,2.5e-05,0,0,-3.7e+02,8.1e-05,7.2e-05,0.036,0.012,0.014,0.0069,0.036,0.038,0.035,4.5e-07,6.3e-07,1.7e-06,0.0043,0.0048,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23290000,0.71,0.00089,-0.013,0.7,-0.0093,0.0042,0.022,-0.0081,0.0084,-3.7e+02,-0.0014,-0.0058,8.6e-05,0.012,0.0034,-0.13,0.21,-5.5e-06,0.43,-0.00037,0.00076,2.4e-05,0,0,-3.7e+02,8.1e-05,7.3e-05,0.036,0.013,0.016,0.0069,0.039,0.042,0.036,4.5e-07,6.3e-07,1.7e-06,0.0043,0.0047,0.00021,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23390000,0.71,0.00095,-0.013,0.7,-0.0095,0.003,0.02,-0.01,0.0072,-3.7e+02,-0.0014,-0.0058,8.8e-05,0.012,0.0035,-0.13,0.21,-5.6e-06,0.43,-0.00035,0.00075,2.6e-05,0,0,-3.7e+02,8e-05,7.1e-05,0.036,0.012,0.014,0.0068,0.036,0.038,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,0.01 +23490000,0.71,0.0033,-0.01,0.7,-0.016,0.0032,-0.013,-0.011,0.008,-3.7e+02,-0.0014,-0.0058,9.5e-05,0.012,0.0032,-0.13,0.21,-5.5e-06,0.43,-0.00034,0.00079,5.1e-05,0,0,-3.7e+02,8e-05,7.2e-05,0.036,0.013,0.015,0.0068,0.039,0.042,0.035,4.4e-07,6.1e-07,1.7e-06,0.0043,0.0047,0.0002,0.0013,3.9e-05,0.0013,0.0016,0.0013,0.0012,1,1,0.01 +23590000,0.71,0.0086,-0.0026,0.7,-0.027,0.0032,-0.045,-0.011,0.0075,-3.7e+02,-0.0014,-0.0058,9.1e-05,0.012,0.0032,-0.13,0.21,-5.5e-06,0.43,-0.00034,0.00084,0.00012,0,0,-3.7e+02,7.8e-05,7.1e-05,0.036,0.012,0.014,0.0067,0.036,0.038,0.035,4.3e-07,5.9e-07,1.6e-06,0.0042,0.0046,0.0002,0.0013,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +23690000,0.71,0.0082,0.0032,0.71,-0.058,-0.0046,-0.095,-0.015,0.0075,-3.7e+02,-0.0014,-0.0058,9.1e-05,0.012,0.0032,-0.13,0.21,-5.5e-06,0.43,-0.00034,0.00078,9e-05,0,0,-3.7e+02,7.9e-05,7.1e-05,0.036,0.013,0.015,0.0067,0.039,0.042,0.035,4.3e-07,5.9e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 23790000,0.71,0.0053,-0.00011,0.71,-0.083,-0.016,-0.15,-0.016,0.0069,-3.7e+02,-0.0013,-0.0058,9.3e-05,0.011,0.0028,-0.13,0.21,-4.7e-06,0.43,-0.00039,0.00078,0.00044,0,0,-3.7e+02,7.7e-05,7e-05,0.036,0.012,0.014,0.0066,0.036,0.038,0.035,4.2e-07,5.7e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 23890000,0.71,0.0026,-0.0062,0.71,-0.1,-0.025,-0.2,-0.026,0.0047,-3.7e+02,-0.0013,-0.0058,9.2e-05,0.012,0.0029,-0.13,0.21,-4.5e-06,0.43,-0.00042,0.00083,0.00035,0,0,-3.7e+02,7.8e-05,7e-05,0.036,0.013,0.016,0.0066,0.039,0.042,0.035,4.2e-07,5.7e-07,1.6e-06,0.0042,0.0046,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -23990000,0.71,0.0013,-0.011,0.71,-0.1,-0.029,-0.25,-0.031,0.00042,-3.7e+02,-0.0013,-0.0058,9.8e-05,0.012,0.0029,-0.13,0.21,-4.2e-06,0.43,-0.00039,0.00083,0.00032,0,0,-3.7e+02,7.7e-05,6.9e-05,0.036,0.012,0.015,0.0066,0.036,0.038,0.035,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0045,0.00019,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24090000,0.71,0.0025,-0.0095,0.71,-0.1,-0.028,-0.3,-0.041,-0.002,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0026,-0.13,0.21,-3.7e-06,0.43,-0.00042,0.0008,0.00036,0,0,-3.7e+02,7.7e-05,6.9e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.035,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24190000,0.71,0.0036,-0.0072,0.71,-0.11,-0.03,-0.35,-0.044,-0.0052,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0025,-0.13,0.21,-3e-06,0.43,-0.00042,0.00083,0.00036,0,0,-3.7e+02,7.6e-05,6.8e-05,0.036,0.012,0.015,0.0065,0.036,0.038,0.034,4e-07,5.3e-07,1.6e-06,0.0041,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +23990000,0.71,0.0013,-0.011,0.71,-0.1,-0.029,-0.26,-0.031,0.00042,-3.7e+02,-0.0013,-0.0058,9.8e-05,0.012,0.0029,-0.13,0.21,-4.2e-06,0.43,-0.00039,0.00083,0.00032,0,0,-3.7e+02,7.7e-05,6.9e-05,0.036,0.012,0.015,0.0065,0.036,0.038,0.035,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24090000,0.71,0.0025,-0.0095,0.71,-0.1,-0.028,-0.3,-0.041,-0.002,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0026,-0.13,0.21,-3.8e-06,0.43,-0.00042,0.0008,0.00036,0,0,-3.7e+02,7.7e-05,6.9e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.034,4.1e-07,5.5e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24190000,0.71,0.0036,-0.0072,0.71,-0.11,-0.03,-0.35,-0.044,-0.0052,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0025,-0.13,0.21,-3e-06,0.43,-0.00042,0.00083,0.00036,0,0,-3.7e+02,7.6e-05,6.8e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,4e-07,5.3e-07,1.6e-06,0.0042,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 24290000,0.71,0.0041,-0.0064,0.71,-0.12,-0.033,-0.41,-0.055,-0.0085,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0025,-0.13,0.21,-2.7e-06,0.43,-0.00046,0.00088,0.00042,0,0,-3.7e+02,7.6e-05,6.8e-05,0.036,0.013,0.016,0.0065,0.039,0.042,0.034,4e-07,5.3e-07,1.6e-06,0.0041,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 -24390000,0.71,0.0042,-0.0065,0.71,-0.13,-0.041,-0.46,-0.062,-0.021,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0031,-0.13,0.21,1.4e-07,0.43,-0.00034,0.00092,0.00042,0,0,-3.7e+02,7.5e-05,6.7e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0045,0.00018,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 +24390000,0.71,0.0042,-0.0065,0.71,-0.13,-0.041,-0.46,-0.062,-0.021,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0031,-0.13,0.21,1.4e-07,0.43,-0.00034,0.00092,0.00042,0,0,-3.7e+02,7.5e-05,6.7e-05,0.036,0.012,0.015,0.0064,0.036,0.038,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0045,0.00017,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 24490000,0.71,0.005,-0.0024,0.71,-0.14,-0.046,-0.51,-0.076,-0.025,-3.7e+02,-0.0013,-0.0058,0.00011,0.011,0.0031,-0.13,0.21,1.4e-07,0.43,-0.00034,0.00093,0.00041,0,0,-3.7e+02,7.5e-05,6.7e-05,0.036,0.013,0.016,0.0064,0.039,0.042,0.034,3.9e-07,5.2e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0016,0.0012,0.0012,1,1,0.01 24590000,0.71,0.0055,0.0013,0.71,-0.16,-0.057,-0.56,-0.081,-0.035,-3.7e+02,-0.0013,-0.0058,0.00013,0.01,0.0031,-0.13,0.21,1.2e-06,0.43,1.8e-05,0.00058,0.00036,0,0,-3.7e+02,7.4e-05,6.6e-05,0.036,0.012,0.015,0.0063,0.036,0.038,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24690000,0.71,0.0056,0.0022,0.71,-0.18,-0.07,-0.64,-0.097,-0.041,-3.7e+02,-0.0013,-0.0058,0.00013,0.01,0.003,-0.13,0.21,2.2e-06,0.43,-2.7e-05,0.00062,0.00054,0,0,-3.7e+02,7.4e-05,6.7e-05,0.036,0.013,0.016,0.0063,0.039,0.042,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24790000,0.71,0.0053,0.00098,0.71,-0.2,-0.083,-0.73,-0.11,-0.054,-3.7e+02,-0.0013,-0.0058,0.00013,0.01,0.003,-0.13,0.21,1.6e-06,0.43,5.6e-06,0.00059,0.0003,0,0,-3.7e+02,7.3e-05,6.5e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24690000,0.71,0.0056,0.0022,0.71,-0.18,-0.07,-0.64,-0.097,-0.041,-3.7e+02,-0.0013,-0.0058,0.00013,0.01,0.0029,-0.13,0.21,2.2e-06,0.43,-2.7e-05,0.00062,0.00054,0,0,-3.7e+02,7.4e-05,6.7e-05,0.036,0.013,0.016,0.0063,0.039,0.042,0.034,3.8e-07,5e-07,1.5e-06,0.0041,0.0044,0.00017,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24790000,0.71,0.0053,0.00098,0.71,-0.2,-0.083,-0.73,-0.11,-0.054,-3.7e+02,-0.0013,-0.0058,0.00013,0.01,0.003,-0.13,0.21,1.6e-06,0.43,5.7e-06,0.00059,0.0003,0,0,-3.7e+02,7.3e-05,6.5e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 24890000,0.71,0.0071,0.0027,0.71,-0.22,-0.094,-0.75,-0.13,-0.063,-3.7e+02,-0.0013,-0.0058,0.00013,0.01,0.0031,-0.13,0.21,2.4e-06,0.43,-0.0001,0.00075,0.00032,0,0,-3.7e+02,7.4e-05,6.6e-05,0.036,0.013,0.016,0.0062,0.039,0.042,0.034,3.7e-07,4.9e-07,1.5e-06,0.0041,0.0044,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -24990000,0.71,0.0089,0.0044,0.71,-0.24,-0.1,-0.81,-0.13,-0.073,-3.7e+02,-0.0013,-0.0058,0.00011,0.0098,0.0027,-0.13,0.21,2e-06,0.43,-0.00018,0.00085,-2e-05,0,0,-3.7e+02,7.2e-05,6.5e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.7e-07,1.5e-06,0.004,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25090000,0.71,0.0092,0.0038,0.71,-0.27,-0.11,-0.86,-0.16,-0.084,-3.7e+02,-0.0013,-0.0058,0.00011,0.0098,0.0028,-0.13,0.21,1.6e-06,0.43,-0.0002,0.00086,-5.6e-05,0,0,-3.7e+02,7.3e-05,6.5e-05,0.036,0.013,0.017,0.0062,0.039,0.042,0.034,3.7e-07,4.7e-07,1.5e-06,0.004,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +24990000,0.71,0.0089,0.0044,0.71,-0.24,-0.1,-0.81,-0.13,-0.073,-3.7e+02,-0.0013,-0.0058,0.00011,0.0098,0.0027,-0.13,0.21,2e-06,0.43,-0.00018,0.00085,-2e-05,0,0,-3.7e+02,7.2e-05,6.5e-05,0.036,0.012,0.015,0.0062,0.036,0.038,0.034,3.7e-07,4.7e-07,1.5e-06,0.0041,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25090000,0.71,0.0092,0.0038,0.71,-0.27,-0.11,-0.86,-0.16,-0.084,-3.7e+02,-0.0013,-0.0058,0.00011,0.0098,0.0028,-0.13,0.21,1.5e-06,0.43,-0.0002,0.00086,-5.6e-05,0,0,-3.7e+02,7.3e-05,6.5e-05,0.036,0.013,0.017,0.0062,0.039,0.042,0.033,3.7e-07,4.7e-07,1.5e-06,0.004,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 25190000,0.71,0.0087,0.0024,0.71,-0.3,-0.13,-0.91,-0.18,-0.11,-3.7e+02,-0.0013,-0.0058,0.00013,0.0092,0.0031,-0.13,0.21,6.9e-06,0.43,5.9e-05,0.00083,8e-05,0,0,-3.7e+02,7.1e-05,6.4e-05,0.035,0.012,0.016,0.0061,0.036,0.038,0.033,3.6e-07,4.6e-07,1.4e-06,0.004,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25290000,0.71,0.011,0.0093,0.71,-0.33,-0.14,-0.96,-0.21,-0.12,-3.7e+02,-0.0013,-0.0058,0.00013,0.0092,0.0031,-0.13,0.21,6.8e-06,0.43,8.4e-05,0.00077,8.7e-05,0,0,-3.7e+02,7.2e-05,6.4e-05,0.035,0.013,0.017,0.0061,0.039,0.042,0.033,3.6e-07,4.6e-07,1.4e-06,0.004,0.0043,0.00016,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25390000,0.71,0.012,0.016,0.71,-0.36,-0.16,-1,-0.22,-0.14,-3.7e+02,-0.0013,-0.0058,0.00014,0.0084,0.0029,-0.13,0.21,1.1e-05,0.43,0.00049,0.00046,0.00012,0,0,-3.7e+02,7.1e-05,6.3e-05,0.035,0.012,0.016,0.0061,0.036,0.038,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25490000,0.71,0.012,0.017,0.71,-0.41,-0.18,-1.1,-0.26,-0.16,-3.7e+02,-0.0013,-0.0058,0.00014,0.0083,0.0027,-0.13,0.21,9.5e-06,0.43,0.00066,0.00013,0.00031,0,0,-3.7e+02,7.2e-05,6.4e-05,0.035,0.013,0.018,0.0061,0.039,0.042,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 -25590000,0.71,0.012,0.015,0.71,-0.45,-0.21,-1.1,-0.29,-0.2,-3.7e+02,-0.0012,-0.0058,0.00016,0.0077,0.0032,-0.13,0.21,1.6e-05,0.43,0.00096,0.00014,0.00032,0,0,-3.7e+02,7e-05,6.3e-05,0.034,0.012,0.018,0.006,0.036,0.038,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0042,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25290000,0.71,0.011,0.0093,0.71,-0.33,-0.14,-0.96,-0.21,-0.12,-3.7e+02,-0.0013,-0.0058,0.00013,0.0092,0.0031,-0.13,0.21,6.8e-06,0.43,8.4e-05,0.00077,8.7e-05,0,0,-3.7e+02,7.2e-05,6.4e-05,0.035,0.013,0.017,0.0061,0.039,0.042,0.033,3.6e-07,4.6e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25390000,0.71,0.012,0.016,0.71,-0.36,-0.16,-1,-0.22,-0.14,-3.7e+02,-0.0013,-0.0058,0.00014,0.0084,0.0029,-0.13,0.21,1.1e-05,0.43,0.00049,0.00046,0.00012,0,0,-3.7e+02,7.1e-05,6.3e-05,0.035,0.012,0.016,0.006,0.036,0.038,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25490000,0.71,0.012,0.017,0.71,-0.41,-0.18,-1.1,-0.26,-0.16,-3.7e+02,-0.0013,-0.0058,0.00014,0.0084,0.0027,-0.13,0.21,9.5e-06,0.43,0.00066,0.00013,0.00031,0,0,-3.7e+02,7.2e-05,6.4e-05,0.035,0.013,0.018,0.006,0.039,0.042,0.033,3.5e-07,4.5e-07,1.4e-06,0.004,0.0043,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 +25590000,0.71,0.012,0.015,0.71,-0.45,-0.21,-1.1,-0.29,-0.2,-3.7e+02,-0.0012,-0.0058,0.00016,0.0077,0.0031,-0.13,0.21,1.6e-05,0.43,0.00096,0.00014,0.00032,0,0,-3.7e+02,7e-05,6.3e-05,0.034,0.012,0.018,0.006,0.036,0.038,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0042,0.00015,0.0012,3.9e-05,0.0012,0.0015,0.0012,0.0012,1,1,0.01 25690000,0.71,0.015,0.022,0.71,-0.5,-0.23,-1.2,-0.34,-0.22,-3.7e+02,-0.0012,-0.0058,0.00016,0.0077,0.0031,-0.13,0.21,1.6e-05,0.43,0.00095,0.00016,0.0004,0,0,-3.7e+02,7.1e-05,6.3e-05,0.034,0.013,0.02,0.006,0.039,0.042,0.033,3.5e-07,4.4e-07,1.4e-06,0.004,0.0042,0.00015,0.0012,3.9e-05,0.0012,0.0014,0.0012,0.0011,1,1,0.01 -25790000,0.71,0.018,0.028,0.71,-0.54,-0.26,-1.2,-0.36,-0.25,-3.7e+02,-0.0012,-0.0058,0.00016,0.007,0.0024,-0.13,0.21,1.9e-05,0.43,0.0013,-8.8e-05,-4.9e-05,0,0,-3.7e+02,7e-05,6.2e-05,0.033,0.013,0.019,0.006,0.036,0.038,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00015,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 -25890000,0.71,0.018,0.029,0.71,-0.62,-0.29,-1.3,-0.41,-0.28,-3.7e+02,-0.0012,-0.0058,0.00017,0.0072,0.0024,-0.13,0.21,2.1e-05,0.43,0.0014,-2e-05,-0.00011,0,0,-3.7e+02,7.1e-05,6.2e-05,0.033,0.014,0.022,0.006,0.039,0.042,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00015,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 +25790000,0.71,0.018,0.028,0.71,-0.54,-0.26,-1.2,-0.36,-0.25,-3.7e+02,-0.0012,-0.0058,0.00016,0.007,0.0024,-0.13,0.21,1.9e-05,0.43,0.0013,-8.9e-05,-4.9e-05,0,0,-3.7e+02,7e-05,6.2e-05,0.033,0.013,0.019,0.0059,0.036,0.038,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00015,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 +25890000,0.71,0.018,0.029,0.71,-0.62,-0.29,-1.3,-0.41,-0.28,-3.7e+02,-0.0012,-0.0058,0.00017,0.0072,0.0024,-0.13,0.21,2.1e-05,0.43,0.0014,-2.1e-05,-0.00011,0,0,-3.7e+02,7.1e-05,6.2e-05,0.033,0.014,0.022,0.006,0.039,0.042,0.033,3.4e-07,4.3e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0014,0.0011,0.0011,1,1,0.01 25990000,0.7,0.017,0.026,0.71,-0.67,-0.32,-1.3,-0.45,-0.33,-3.7e+02,-0.0012,-0.0058,0.00019,0.0063,0.0027,-0.13,0.21,2.9e-05,0.43,0.0023,-0.00058,-0.00057,0,0,-3.7e+02,7e-05,6.1e-05,0.032,0.013,0.021,0.0059,0.036,0.039,0.033,3.4e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0013,0.0011,0.0011,1,1,0.01 26090000,0.7,0.022,0.035,0.71,-0.74,-0.35,-1.3,-0.53,-0.37,-3.7e+02,-0.0012,-0.0059,0.00018,0.0064,0.0029,-0.13,0.21,2.5e-05,0.43,0.0024,-0.0005,-0.0012,0,0,-3.7e+02,7.1e-05,6.2e-05,0.032,0.014,0.024,0.0059,0.039,0.043,0.033,3.4e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.0011,3.9e-05,0.0011,0.0013,0.0011,0.0011,1,1,0.01 -26190000,0.7,0.024,0.045,0.71,-0.79,-0.39,-1.3,-0.55,-0.41,-3.7e+02,-0.0012,-0.0058,0.00018,0.0053,0.0017,-0.13,0.21,3.9e-05,0.43,0.0023,0.00039,-0.0014,0,0,-3.7e+02,7e-05,6.1e-05,0.03,0.014,0.024,0.0059,0.036,0.039,0.032,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.001,3.9e-05,0.001,0.0013,0.001,0.001,1,1,0.01 +26190000,0.7,0.024,0.045,0.71,-0.79,-0.39,-1.3,-0.55,-0.41,-3.7e+02,-0.0012,-0.0058,0.00018,0.0053,0.0017,-0.13,0.21,3.9e-05,0.43,0.0023,0.00039,-0.0014,0,0,-3.7e+02,7e-05,6.1e-05,0.03,0.014,0.024,0.0058,0.036,0.039,0.032,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.001,3.9e-05,0.001,0.0013,0.001,0.001,1,1,0.01 26290000,0.7,0.025,0.047,0.71,-0.89,-0.43,-1.3,-0.64,-0.45,-3.7e+02,-0.0012,-0.0058,0.00018,0.0052,0.0018,-0.13,0.21,3.8e-05,0.43,0.0023,0.00027,-0.0014,0,0,-3.7e+02,7.1e-05,6.1e-05,0.03,0.015,0.028,0.0059,0.039,0.043,0.033,3.3e-07,4.2e-07,1.4e-06,0.004,0.0042,0.00014,0.00099,3.9e-05,0.00099,0.0013,0.001,0.00099,1,1,0.01 -26390000,0.7,0.024,0.044,0.71,-0.96,-0.49,-1.3,-0.7,-0.54,-3.7e+02,-0.0011,-0.0059,0.00021,0.0043,0.0025,-0.13,0.21,4.6e-05,0.44,0.0036,-0.00019,-0.0024,0,0,-3.7e+02,7.1e-05,6e-05,0.028,0.014,0.027,0.0058,0.036,0.039,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00014,0.00096,3.9e-05,0.00095,0.0012,0.00096,0.00095,1,1,0.01 +26390000,0.7,0.024,0.044,0.71,-0.96,-0.49,-1.3,-0.7,-0.54,-3.7e+02,-0.0011,-0.0059,0.00021,0.0044,0.0025,-0.13,0.21,4.6e-05,0.44,0.0036,-0.00019,-0.0024,0,0,-3.7e+02,7.1e-05,6e-05,0.028,0.014,0.027,0.0058,0.036,0.039,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00014,0.00096,3.9e-05,0.00095,0.0012,0.00096,0.00095,1,1,0.01 26490000,0.7,0.031,0.06,0.71,-1.1,-0.53,-1.3,-0.8,-0.59,-3.7e+02,-0.0011,-0.0059,0.00021,0.0044,0.0025,-0.13,0.21,3.9e-05,0.44,0.004,-0.001,-0.0026,0,0,-3.7e+02,7.1e-05,6.1e-05,0.028,0.016,0.031,0.0058,0.039,0.044,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00014,0.00092,3.9e-05,0.00092,0.0012,0.00092,0.00091,1,1,0.01 -26590000,0.7,0.037,0.076,0.71,-1.2,-0.59,-1.3,-0.85,-0.66,-3.7e+02,-0.0011,-0.0059,0.00019,0.0028,0.0015,-0.13,0.21,3.9e-05,0.44,0.0041,-0.00065,-0.0048,0,0,-3.7e+02,7.1e-05,6e-05,0.025,0.015,0.031,0.0058,0.036,0.04,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00014,0.00087,3.9e-05,0.00086,0.001,0.00087,0.00086,1,1,0.01 +26590000,0.7,0.037,0.076,0.71,-1.2,-0.59,-1.3,-0.85,-0.66,-3.7e+02,-0.0011,-0.0059,0.00019,0.0028,0.0015,-0.13,0.21,3.9e-05,0.44,0.0041,-0.00065,-0.0048,0,0,-3.7e+02,7.1e-05,6e-05,0.025,0.015,0.031,0.0058,0.036,0.04,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00087,3.9e-05,0.00086,0.001,0.00087,0.00086,1,1,0.01 26690000,0.7,0.039,0.079,0.71,-1.3,-0.65,-1.3,-0.97,-0.72,-3.7e+02,-0.0011,-0.0059,0.00019,0.0028,0.0014,-0.13,0.21,4.5e-05,0.44,0.004,-0.00014,-0.004,0,0,-3.7e+02,7.2e-05,6.1e-05,0.025,0.017,0.038,0.0058,0.04,0.045,0.032,3.3e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00081,3.9e-05,0.0008,0.001,0.00081,0.00079,1,1,0.01 -26790000,0.7,0.036,0.074,0.71,-1.4,-0.74,-1.3,-1.1,-0.85,-3.7e+02,-0.0011,-0.0059,0.00022,0.0012,0.0023,-0.13,0.21,8.4e-05,0.44,0.0055,0.00061,-0.0037,0,0,-3.7e+02,7.2e-05,6e-05,0.022,0.016,0.036,0.0058,0.036,0.041,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00076,3.9e-05,0.00075,0.00092,0.00076,0.00074,1,1,0.01 +26790000,0.7,0.036,0.074,0.71,-1.4,-0.74,-1.3,-1.1,-0.85,-3.7e+02,-0.0011,-0.0059,0.00022,0.0012,0.0023,-0.13,0.21,8.4e-05,0.44,0.0055,0.00061,-0.0037,0,0,-3.7e+02,7.2e-05,6e-05,0.022,0.016,0.036,0.0057,0.036,0.041,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00076,3.9e-05,0.00075,0.00092,0.00076,0.00074,1,1,0.01 26890000,0.7,0.045,0.096,0.71,-1.6,-0.8,-1.3,-1.2,-0.93,-3.7e+02,-0.0011,-0.0059,0.00023,0.0013,0.0023,-0.13,0.21,8.9e-05,0.44,0.0054,0.0012,-0.0041,0,0,-3.7e+02,7.3e-05,6e-05,0.022,0.018,0.043,0.0058,0.04,0.046,0.032,3.2e-07,4.1e-07,1.3e-06,0.0039,0.0041,0.00013,0.00072,3.9e-05,0.0007,0.00092,0.00072,0.0007,1,1,0.01 -26990000,0.7,0.051,0.12,0.71,-1.7,-0.89,-1.3,-1.3,-1,-3.7e+02,-0.00099,-0.0059,0.00022,-0.00069,0.00038,-0.13,0.21,0.00013,0.44,0.0061,0.0034,-0.0056,0,0,-3.7e+02,7.3e-05,5.9e-05,0.019,0.017,0.042,0.0057,0.037,0.041,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00065,3.9e-05,0.00063,0.00079,0.00065,0.00062,1,1,0.01 -27090000,0.7,0.052,0.12,0.71,-1.9,-0.98,-1.3,-1.5,-1.1,-3.7e+02,-0.00099,-0.0059,0.00022,-0.00074,0.00039,-0.13,0.21,0.00013,0.44,0.006,0.0035,-0.0052,0,0,-3.7e+02,7.4e-05,6e-05,0.019,0.02,0.052,0.0058,0.04,0.048,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00059,3.9e-05,0.00056,0.00078,0.0006,0.00056,1,1,0.01 -27190000,0.7,0.05,0.11,0.7,-2.1,-1,-1.2,-1.7,-1.2,-3.7e+02,-0.00097,-0.0059,0.00022,-0.0018,0.00021,-0.13,0.21,4.8e-05,0.44,0.0021,0.0027,-0.0049,0,0,-3.7e+02,7.5e-05,6e-05,0.016,0.02,0.051,0.0057,0.043,0.05,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00055,3.9e-05,0.00051,0.00066,0.00055,0.00051,1,1,0.01 +26990000,0.7,0.051,0.12,0.71,-1.7,-0.89,-1.3,-1.3,-1,-3.7e+02,-0.00099,-0.0059,0.00022,-0.00068,0.00038,-0.13,0.21,0.00013,0.44,0.0061,0.0034,-0.0056,0,0,-3.7e+02,7.3e-05,5.9e-05,0.019,0.017,0.042,0.0057,0.037,0.041,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00065,3.9e-05,0.00063,0.00079,0.00065,0.00062,1,1,0.01 +27090000,0.7,0.052,0.12,0.71,-1.9,-0.98,-1.3,-1.5,-1.1,-3.7e+02,-0.00099,-0.0059,0.00022,-0.00072,0.00039,-0.13,0.21,0.00013,0.44,0.006,0.0035,-0.0052,0,0,-3.7e+02,7.4e-05,6e-05,0.019,0.02,0.052,0.0057,0.04,0.048,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00059,3.9e-05,0.00056,0.00078,0.0006,0.00056,1,1,0.01 +27190000,0.7,0.05,0.11,0.7,-2.1,-1,-1.2,-1.7,-1.2,-3.7e+02,-0.00097,-0.0059,0.00022,-0.0018,0.0002,-0.13,0.21,4.8e-05,0.44,0.0021,0.0027,-0.0049,0,0,-3.7e+02,7.5e-05,6e-05,0.016,0.02,0.051,0.0057,0.043,0.05,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00055,3.9e-05,0.00051,0.00066,0.00055,0.00051,1,1,0.01 27290000,0.71,0.044,0.095,0.7,-2.3,-1.1,-1.2,-1.9,-1.3,-3.7e+02,-0.00097,-0.0059,0.00023,-0.0018,0.00019,-0.13,0.21,5.6e-05,0.44,0.0019,0.0034,-0.0049,0,0,-3.7e+02,7.5e-05,6e-05,0.016,0.022,0.059,0.0057,0.047,0.057,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00052,3.9e-05,0.00048,0.00066,0.00052,0.00048,1,1,0.01 -27390000,0.71,0.038,0.079,0.7,-2.4,-1.1,-1.2,-2.1,-1.4,-3.7e+02,-0.00092,-0.0058,0.00022,-0.003,-0.0016,-0.13,0.21,1.3e-05,0.44,-0.0005,0.0031,-0.0063,0,0,-3.7e+02,7.6e-05,6e-05,0.013,0.021,0.052,0.0057,0.049,0.059,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00013,0.00049,3.9e-05,0.00046,0.00055,0.00049,0.00046,1,1,0.01 -27490000,0.71,0.032,0.064,0.7,-2.5,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.00092,-0.0058,0.00022,-0.003,-0.0015,-0.13,0.21,1.9e-05,0.44,-0.00058,0.0032,-0.0067,0,0,-3.7e+02,7.7e-05,6.1e-05,0.013,0.023,0.056,0.0057,0.054,0.067,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00048,3.9e-05,0.00045,0.00055,0.00048,0.00044,1,1,0.01 -27590000,0.72,0.028,0.051,0.69,-2.6,-1.1,-1.2,-2.6,-1.6,-3.7e+02,-0.00092,-0.0059,0.00023,-0.0037,-0.00088,-0.13,0.21,-3.7e-05,0.44,-0.0032,0.0027,-0.0065,0,0,-3.7e+02,7.7e-05,6e-05,0.011,0.021,0.047,0.0057,0.056,0.068,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00044,1,1,0.01 +27390000,0.71,0.038,0.079,0.7,-2.4,-1.1,-1.2,-2.1,-1.4,-3.7e+02,-0.00092,-0.0058,0.00022,-0.003,-0.0016,-0.13,0.21,1.3e-05,0.44,-0.0005,0.0031,-0.0063,0,0,-3.7e+02,7.6e-05,6e-05,0.013,0.021,0.052,0.0057,0.049,0.059,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00049,3.9e-05,0.00046,0.00055,0.00049,0.00046,1,1,0.01 +27490000,0.71,0.032,0.064,0.7,-2.5,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.00092,-0.0058,0.00022,-0.0029,-0.0015,-0.13,0.21,1.9e-05,0.44,-0.00058,0.0032,-0.0067,0,0,-3.7e+02,7.7e-05,6.1e-05,0.013,0.023,0.056,0.0057,0.054,0.067,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00048,3.9e-05,0.00045,0.00055,0.00048,0.00044,1,1,0.01 +27590000,0.72,0.028,0.051,0.69,-2.6,-1.1,-1.2,-2.6,-1.6,-3.7e+02,-0.00092,-0.0059,0.00023,-0.0036,-0.00088,-0.12,0.21,-3.7e-05,0.44,-0.0032,0.0027,-0.0065,0,0,-3.7e+02,7.7e-05,6e-05,0.011,0.021,0.047,0.0057,0.056,0.068,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00044,1,1,0.01 27690000,0.72,0.027,0.05,0.69,-2.6,-1.2,-1.2,-2.9,-1.7,-3.7e+02,-0.00092,-0.0059,0.00023,-0.0036,-0.00075,-0.12,0.21,-3.2e-05,0.44,-0.0033,0.0026,-0.0067,0,0,-3.7e+02,7.8e-05,6.1e-05,0.011,0.022,0.049,0.0057,0.062,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00046,3.9e-05,0.00044,0.00047,0.00046,0.00043,1,1,0.01 -27790000,0.72,0.027,0.051,0.69,-2.6,-1.2,-1.2,-3.1,-1.8,-3.7e+02,-0.00092,-0.0059,0.00022,-0.0042,-0.00056,-0.12,0.21,-6e-05,0.44,-0.005,0.0021,-0.0072,0,0,-3.7e+02,7.8e-05,6e-05,0.0097,0.02,0.042,0.0057,0.064,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00045,3.9e-05,0.00043,0.00041,0.00045,0.00043,1,1,0.01 +27790000,0.72,0.027,0.051,0.69,-2.6,-1.2,-1.2,-3.1,-1.8,-3.7e+02,-0.00092,-0.0059,0.00022,-0.0042,-0.00056,-0.12,0.21,-6e-05,0.44,-0.005,0.0021,-0.0072,0,0,-3.7e+02,7.8e-05,6e-05,0.0097,0.02,0.042,0.0056,0.064,0.077,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00045,3.9e-05,0.00043,0.00041,0.00045,0.00043,1,1,0.01 27890000,0.72,0.027,0.049,0.69,-2.7,-1.2,-1.2,-3.4,-1.9,-3.7e+02,-0.00091,-0.0059,0.00023,-0.0042,-0.00056,-0.12,0.21,-6.1e-05,0.44,-0.005,0.002,-0.0072,0,0,-3.7e+02,7.9e-05,6.1e-05,0.0097,0.021,0.043,0.0057,0.07,0.087,0.032,3.2e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00044,3.9e-05,0.00043,0.00041,0.00044,0.00042,1,1,0.01 -27990000,0.72,0.026,0.046,0.69,-2.7,-1.2,-1.2,-3.7,-2,-3.7e+02,-0.00093,-0.0059,0.00024,-0.004,0.00036,-0.12,0.21,-7.7e-05,0.44,-0.0063,0.0015,-0.0071,0,0,-3.7e+02,8e-05,6e-05,0.0086,0.02,0.038,0.0056,0.072,0.087,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00043,3.9e-05,0.00042,0.00037,0.00043,0.00042,1,1,0.01 -28090000,0.72,0.032,0.059,0.69,-2.8,-1.2,-1.2,-4,-2.1,-3.7e+02,-0.00093,-0.0059,0.00023,-0.0042,0.00057,-0.12,0.21,-7.6e-05,0.44,-0.0065,0.0014,-0.0072,0,0,-3.7e+02,8e-05,6.1e-05,0.0086,0.021,0.039,0.0057,0.078,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00042,3.9e-05,0.00042,0.00036,0.00042,0.00041,1,1,0.01 +27990000,0.72,0.026,0.046,0.69,-2.7,-1.2,-1.2,-3.7,-2,-3.7e+02,-0.00093,-0.0059,0.00024,-0.004,0.00035,-0.12,0.21,-7.7e-05,0.44,-0.0063,0.0015,-0.0071,0,0,-3.7e+02,8e-05,6e-05,0.0086,0.02,0.038,0.0056,0.072,0.087,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00043,3.9e-05,0.00042,0.00037,0.00043,0.00042,1,1,0.01 +28090000,0.72,0.032,0.059,0.69,-2.8,-1.2,-1.2,-4,-2.1,-3.7e+02,-0.00093,-0.0059,0.00023,-0.0041,0.00056,-0.12,0.21,-7.6e-05,0.44,-0.0065,0.0013,-0.0072,0,0,-3.7e+02,8e-05,6.1e-05,0.0086,0.021,0.039,0.0057,0.078,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00042,3.9e-05,0.00042,0.00036,0.00042,0.00041,1,1,0.01 28190000,0.72,0.037,0.072,0.69,-2.8,-1.2,-0.94,-4.3,-2.2,-3.7e+02,-0.00094,-0.0059,0.00024,-0.0042,0.001,-0.12,0.21,-9.4e-05,0.44,-0.0073,0.00091,-0.0071,0,0,-3.7e+02,8.1e-05,6.1e-05,0.0079,0.02,0.034,0.0056,0.08,0.097,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.00041,3.9e-05,0.00041,0.00033,0.00041,0.00041,1,1,0.01 -28290000,0.72,0.029,0.055,0.69,-2.8,-1.2,-0.077,-4.5,-2.4,-3.7e+02,-0.00094,-0.0059,0.00024,-0.0043,0.0011,-0.12,0.21,-9.7e-05,0.44,-0.0073,0.0013,-0.0069,0,0,-3.7e+02,8.2e-05,6.1e-05,0.0079,0.02,0.035,0.0057,0.087,0.11,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28390000,0.73,0.012,0.024,0.69,-2.8,-1.2,0.78,-4.8,-2.5,-3.7e+02,-0.00094,-0.0059,0.00023,-0.0042,0.0014,-0.12,0.21,-8.5e-05,0.44,-0.0075,0.0014,-0.007,0,0,-3.7e+02,8.3e-05,6.1e-05,0.0079,0.02,0.035,0.0057,0.094,0.12,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28490000,0.73,0.0028,0.0061,0.69,-2.8,-1.2,1.1,-5.1,-2.6,-3.7e+02,-0.00095,-0.0059,0.00023,-0.0039,0.0017,-0.12,0.21,-6.6e-05,0.44,-0.0076,0.0014,-0.0069,0,0,-3.7e+02,8.3e-05,6.2e-05,0.0079,0.021,0.035,0.0057,0.1,0.13,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28590000,0.73,0.00089,0.0025,0.69,-2.7,-1.2,0.97,-5.4,-2.7,-3.7e+02,-0.00095,-0.0059,0.00024,-0.004,0.0017,-0.12,0.21,-6.8e-05,0.44,-0.0075,0.0015,-0.0069,0,0,-3.7e+02,8.4e-05,6.2e-05,0.0079,0.021,0.033,0.0057,0.11,0.14,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 -28690000,0.73,0.00019,0.0016,0.69,-2.6,-1.2,0.98,-5.7,-2.8,-3.7e+02,-0.00095,-0.0059,0.00024,-0.0037,0.0021,-0.12,0.21,-5.2e-05,0.44,-0.0076,0.0014,-0.0068,0,0,-3.7e+02,8.5e-05,6.2e-05,0.0079,0.022,0.033,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.00039,0.0004,1,1,0.01 -28790000,0.73,-9.3e-06,0.0015,0.69,-2.6,-1.2,0.98,-6,-2.9,-3.7e+02,-0.00099,-0.0059,0.00024,-0.0032,0.0023,-0.12,0.21,-9.2e-05,0.44,-0.0091,0.00063,-0.006,0,0,-3.7e+02,8.5e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 -28890000,0.73,5.4e-07,0.0018,0.69,-2.5,-1.2,0.97,-6.2,-3,-3.7e+02,-0.00099,-0.0059,0.00024,-0.0029,0.0026,-0.12,0.21,-7.6e-05,0.44,-0.0091,0.00059,-0.0059,0,0,-3.7e+02,8.6e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.13,0.16,0.032,3.1e-07,4e-07,1.3e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 -28990000,0.73,0.00035,0.0024,0.68,-2.5,-1.1,0.97,-6.6,-3.1,-3.7e+02,-0.001,-0.0059,0.00025,-0.0016,0.0031,-0.12,0.21,-0.00011,0.44,-0.01,-0.00033,-0.0047,0,0,-3.7e+02,8.7e-05,6.1e-05,0.0073,0.02,0.025,0.0057,0.13,0.16,0.032,3e-07,4e-07,1.2e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.00039,0.0003,0.00039,0.00039,1,1,0.01 -29090000,0.73,0.00052,0.0028,0.68,-2.4,-1.1,0.96,-6.8,-3.3,-3.7e+02,-0.001,-0.0059,0.00025,-0.0014,0.0034,-0.12,0.21,-9.2e-05,0.44,-0.011,-0.00038,-0.0046,0,0,-3.7e+02,8.7e-05,6.2e-05,0.0073,0.021,0.025,0.0057,0.14,0.17,0.032,3e-07,4e-07,1.2e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 -29190000,0.73,0.00077,0.0032,0.68,-2.4,-1.1,0.95,-7.1,-3.4,-3.7e+02,-0.0011,-0.0059,0.00026,-0.001,0.0035,-0.12,0.21,-0.00013,0.44,-0.011,-0.00062,-0.0041,0,0,-3.7e+02,8.7e-05,6.1e-05,0.0072,0.02,0.023,0.0056,0.14,0.17,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 -29290000,0.73,0.0011,0.004,0.68,-2.3,-1.1,0.98,-7.3,-3.5,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00098,0.0039,-0.12,0.21,-0.00012,0.44,-0.011,-0.00069,-0.0041,0,0,-3.7e+02,8.8e-05,6.1e-05,0.0072,0.021,0.024,0.0057,0.14,0.18,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 -29390000,0.73,0.0017,0.0055,0.68,-2.3,-1.1,0.99,-7.6,-3.6,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00025,0.0044,-0.12,0.21,-0.00015,0.44,-0.012,-0.0014,-0.0033,0,0,-3.7e+02,8.8e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.18,0.031,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 -29490000,0.73,0.0023,0.0066,0.68,-2.3,-1.1,0.99,-7.9,-3.7,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00024,0.0046,-0.12,0.21,-0.00015,0.44,-0.012,-0.0013,-0.0033,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.15,0.19,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 -29590000,0.73,0.0027,0.0076,0.68,-2.2,-1.1,0.98,-8.1,-3.8,-3.7e+02,-0.0011,-0.0059,0.00026,0.00037,0.0047,-0.12,0.21,-0.00016,0.44,-0.012,-0.0016,-0.0029,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.19,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00038,1,1,0.01 -29690000,0.73,0.003,0.0082,0.68,-2.2,-1.1,0.98,-8.3,-3.9,-3.7e+02,-0.0011,-0.0059,0.00026,0.00031,0.005,-0.12,0.21,-0.00015,0.44,-0.012,-0.0016,-0.0029,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -29790000,0.73,0.0034,0.0087,0.68,-2.2,-1.1,0.96,-8.6,-4,-3.7e+02,-0.0012,-0.0059,0.00025,0.0013,0.0048,-0.12,0.21,-0.00017,0.44,-0.012,-0.0018,-0.0023,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +28290000,0.72,0.029,0.055,0.69,-2.8,-1.2,-0.078,-4.5,-2.4,-3.7e+02,-0.00094,-0.0059,0.00024,-0.0043,0.0011,-0.12,0.21,-9.7e-05,0.44,-0.0073,0.0013,-0.0069,0,0,-3.7e+02,8.2e-05,6.1e-05,0.0079,0.02,0.035,0.0057,0.087,0.11,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00012,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28390000,0.73,0.012,0.024,0.69,-2.8,-1.2,0.78,-4.8,-2.5,-3.7e+02,-0.00094,-0.0059,0.00023,-0.0042,0.0014,-0.12,0.21,-8.5e-05,0.44,-0.0075,0.0014,-0.007,0,0,-3.7e+02,8.3e-05,6.1e-05,0.0079,0.02,0.035,0.0057,0.094,0.12,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28490000,0.73,0.0028,0.0061,0.69,-2.8,-1.2,1.1,-5.1,-2.6,-3.7e+02,-0.00095,-0.0059,0.00023,-0.0038,0.0017,-0.12,0.21,-6.6e-05,0.44,-0.0076,0.0014,-0.0069,0,0,-3.7e+02,8.3e-05,6.2e-05,0.0079,0.021,0.035,0.0057,0.1,0.13,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28590000,0.73,0.00089,0.0025,0.69,-2.7,-1.2,0.97,-5.4,-2.7,-3.7e+02,-0.00095,-0.0059,0.00024,-0.0039,0.0017,-0.12,0.21,-6.9e-05,0.44,-0.0075,0.0015,-0.0069,0,0,-3.7e+02,8.4e-05,6.2e-05,0.0079,0.021,0.033,0.0057,0.11,0.14,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.0004,0.0004,1,1,0.01 +28690000,0.73,0.00019,0.0016,0.69,-2.6,-1.2,0.98,-5.7,-2.8,-3.7e+02,-0.00095,-0.0059,0.00024,-0.0036,0.0021,-0.12,0.21,-5.2e-05,0.44,-0.0076,0.0014,-0.0068,0,0,-3.7e+02,8.5e-05,6.2e-05,0.0079,0.022,0.033,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.0041,0.00011,0.0004,3.9e-05,0.0004,0.00033,0.00039,0.0004,1,1,0.01 +28790000,0.73,-8.8e-06,0.0015,0.69,-2.6,-1.2,0.98,-6,-2.9,-3.7e+02,-0.00099,-0.0059,0.00024,-0.0031,0.0023,-0.12,0.21,-9.2e-05,0.44,-0.009,0.00063,-0.006,0,0,-3.7e+02,8.5e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.12,0.15,0.032,3.1e-07,4e-07,1.3e-06,0.0039,0.004,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 +28890000,0.73,1.1e-06,0.0018,0.69,-2.5,-1.2,0.97,-6.2,-3,-3.7e+02,-0.00099,-0.0059,0.00024,-0.0029,0.0026,-0.12,0.21,-7.6e-05,0.44,-0.0091,0.00059,-0.0059,0,0,-3.7e+02,8.6e-05,6.2e-05,0.0075,0.021,0.028,0.0057,0.13,0.16,0.032,3.1e-07,4e-07,1.3e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.0004,0.00031,0.00039,0.00039,1,1,0.01 +28990000,0.73,0.00035,0.0024,0.68,-2.5,-1.1,0.97,-6.6,-3.1,-3.7e+02,-0.001,-0.0059,0.00025,-0.0016,0.003,-0.12,0.21,-0.00011,0.44,-0.01,-0.00033,-0.0047,0,0,-3.7e+02,8.7e-05,6.1e-05,0.0073,0.02,0.025,0.0056,0.13,0.16,0.032,3e-07,4e-07,1.2e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.00039,0.0003,0.00039,0.00039,1,1,0.01 +29090000,0.73,0.00052,0.0028,0.68,-2.4,-1.1,0.96,-6.8,-3.3,-3.7e+02,-0.001,-0.0059,0.00025,-0.0014,0.0034,-0.12,0.21,-9.3e-05,0.44,-0.011,-0.00039,-0.0046,0,0,-3.7e+02,8.7e-05,6.2e-05,0.0073,0.021,0.025,0.0057,0.14,0.17,0.032,3e-07,4e-07,1.2e-06,0.0038,0.004,0.00011,0.00039,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 +29190000,0.73,0.00077,0.0032,0.68,-2.4,-1.1,0.95,-7.1,-3.4,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00099,0.0034,-0.12,0.21,-0.00013,0.44,-0.011,-0.00062,-0.0041,0,0,-3.7e+02,8.8e-05,6.1e-05,0.0072,0.02,0.023,0.0056,0.14,0.17,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 +29290000,0.73,0.0011,0.004,0.68,-2.3,-1.1,0.98,-7.3,-3.5,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00096,0.0039,-0.12,0.21,-0.00012,0.44,-0.011,-0.00069,-0.0041,0,0,-3.7e+02,8.8e-05,6.1e-05,0.0072,0.021,0.024,0.0056,0.14,0.18,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.0003,0.00038,0.00039,1,1,0.01 +29390000,0.73,0.0017,0.0055,0.68,-2.3,-1.1,0.99,-7.6,-3.6,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00023,0.0044,-0.12,0.21,-0.00015,0.44,-0.012,-0.0014,-0.0033,0,0,-3.7e+02,8.8e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.18,0.031,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 +29490000,0.73,0.0023,0.0066,0.68,-2.3,-1.1,0.99,-7.9,-3.7,-3.7e+02,-0.0011,-0.0059,0.00026,-0.00022,0.0046,-0.12,0.21,-0.00015,0.44,-0.012,-0.0013,-0.0033,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.15,0.19,0.032,3e-07,3.9e-07,1.2e-06,0.0038,0.004,0.00011,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00039,1,1,0.01 +29590000,0.73,0.0027,0.0076,0.68,-2.2,-1.1,0.98,-8.1,-3.8,-3.7e+02,-0.0011,-0.0059,0.00026,0.0004,0.0046,-0.12,0.21,-0.00016,0.44,-0.012,-0.0016,-0.0029,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.15,0.19,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00038,0.00038,1,1,0.01 +29690000,0.73,0.003,0.0082,0.68,-2.2,-1.1,0.98,-8.3,-3.9,-3.7e+02,-0.0011,-0.0059,0.00026,0.00033,0.005,-0.12,0.21,-0.00015,0.44,-0.012,-0.0016,-0.0029,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.024,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00038,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +29790000,0.73,0.0034,0.0087,0.68,-2.2,-1.1,0.96,-8.6,-4,-3.7e+02,-0.0012,-0.0059,0.00025,0.0014,0.0048,-0.12,0.21,-0.00017,0.44,-0.012,-0.0019,-0.0023,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.02,0.023,0.0056,0.16,0.2,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 29890000,0.73,0.0034,0.0088,0.68,-2.1,-1.1,0.95,-8.8,-4.1,-3.7e+02,-0.0012,-0.0059,0.00025,0.0011,0.0053,-0.12,0.21,-0.00018,0.44,-0.013,-0.0019,-0.0023,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.17,0.21,0.031,2.9e-07,3.8e-07,1.2e-06,0.0038,0.004,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -29990000,0.73,0.0036,0.0089,0.68,-2.1,-1.1,0.94,-9.1,-4.2,-3.7e+02,-0.0012,-0.0059,0.00022,0.0015,0.005,-0.12,0.21,-0.00019,0.44,-0.013,-0.0021,-0.002,0,0,-3.7e+02,8.8e-05,6e-05,0.0071,0.02,0.024,0.0056,0.17,0.21,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -30090000,0.73,0.0035,0.0088,0.68,-2.1,-1.1,0.92,-9.3,-4.3,-3.7e+02,-0.0012,-0.0059,0.00022,0.0012,0.0054,-0.12,0.21,-0.0002,0.44,-0.013,-0.0022,-0.002,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.18,0.22,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 -30190000,0.73,0.0036,0.0085,0.68,-2.1,-1.1,0.91,-9.5,-4.4,-3.7e+02,-0.0012,-0.0059,0.00021,0.0021,0.0048,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-3.7e+02,8.8e-05,6e-05,0.007,0.02,0.025,0.0056,0.18,0.22,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00038,0.00028,0.00037,0.00038,1,1,0.01 -30290000,0.73,0.0035,0.0083,0.68,-2,-1.1,0.9,-9.7,-4.5,-3.7e+02,-0.0012,-0.0059,0.00021,0.0019,0.005,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-3.7e+02,8.8e-05,6e-05,0.007,0.021,0.026,0.0056,0.19,0.23,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30390000,0.73,0.0035,0.008,0.68,-2,-1.1,0.89,-10,-4.6,-3.7e+02,-0.0012,-0.0059,0.00019,0.0026,0.0049,-0.12,0.21,-0.00022,0.43,-0.012,-0.0025,-0.0014,0,0,-3.7e+02,8.7e-05,6e-05,0.007,0.021,0.025,0.0055,0.19,0.23,0.031,2.8e-07,3.5e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30490000,0.73,0.0034,0.0077,0.68,-2,-1.1,0.87,-10,-4.7,-3.7e+02,-0.0012,-0.0059,0.00019,0.0026,0.005,-0.12,0.21,-0.00022,0.43,-0.012,-0.0024,-0.0014,0,0,-3.7e+02,8.7e-05,6e-05,0.007,0.022,0.027,0.0056,0.2,0.24,0.031,2.8e-07,3.5e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30590000,0.73,0.0034,0.0073,0.68,-1.9,-1,0.83,-10,-4.8,-3.7e+02,-0.0012,-0.0059,0.00018,0.0034,0.0047,-0.12,0.21,-0.00024,0.43,-0.012,-0.0025,-0.001,0,0,-3.7e+02,8.6e-05,6e-05,0.0069,0.021,0.026,0.0055,0.2,0.24,0.031,2.8e-07,3.5e-07,1.1e-06,0.0037,0.0038,9.8e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30690000,0.73,0.0031,0.0069,0.68,-1.9,-1,0.83,-11,-4.9,-3.7e+02,-0.0012,-0.0059,0.00018,0.0031,0.005,-0.12,0.21,-0.00024,0.43,-0.012,-0.0024,-0.001,0,0,-3.7e+02,8.6e-05,6e-05,0.0069,0.022,0.028,0.0055,0.21,0.25,0.031,2.8e-07,3.5e-07,1.1e-06,0.0037,0.0038,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 -30790000,0.73,0.0031,0.0065,0.68,-1.9,-1,0.82,-11,-5,-3.7e+02,-0.0012,-0.0059,0.00015,0.0039,0.0044,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00079,0,0,-3.7e+02,8.4e-05,6e-05,0.0068,0.021,0.027,0.0055,0.21,0.25,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.7e-05,0.00036,3.8e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +29990000,0.73,0.0036,0.0089,0.68,-2.1,-1.1,0.94,-9.1,-4.2,-3.7e+02,-0.0012,-0.0059,0.00022,0.0016,0.005,-0.12,0.21,-0.00019,0.44,-0.013,-0.0021,-0.002,0,0,-3.7e+02,8.8e-05,6e-05,0.0071,0.02,0.024,0.0056,0.17,0.21,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +30090000,0.73,0.0035,0.0088,0.68,-2.1,-1.1,0.92,-9.3,-4.3,-3.7e+02,-0.0012,-0.0059,0.00022,0.0012,0.0053,-0.12,0.21,-0.0002,0.44,-0.013,-0.0022,-0.002,0,0,-3.7e+02,8.9e-05,6.1e-05,0.0071,0.021,0.025,0.0056,0.18,0.22,0.031,2.9e-07,3.7e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00039,0.00029,0.00037,0.00038,1,1,0.01 +30190000,0.73,0.0036,0.0085,0.68,-2.1,-1.1,0.91,-9.5,-4.4,-3.7e+02,-0.0012,-0.0059,0.00021,0.0021,0.0047,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-3.7e+02,8.8e-05,6e-05,0.007,0.02,0.025,0.0055,0.18,0.22,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,0.0001,0.00037,3.9e-05,0.00038,0.00028,0.00037,0.00038,1,1,0.01 +30290000,0.73,0.0035,0.0083,0.68,-2,-1.1,0.9,-9.7,-4.5,-3.7e+02,-0.0012,-0.0059,0.00021,0.0019,0.005,-0.12,0.21,-0.00022,0.44,-0.013,-0.0024,-0.0016,0,0,-3.7e+02,8.8e-05,6e-05,0.007,0.021,0.026,0.0056,0.19,0.23,0.031,2.8e-07,3.6e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30390000,0.73,0.0035,0.008,0.68,-2,-1.1,0.89,-10,-4.6,-3.7e+02,-0.0012,-0.0059,0.00019,0.0026,0.0048,-0.12,0.21,-0.00022,0.43,-0.012,-0.0025,-0.0014,0,0,-3.7e+02,8.7e-05,6e-05,0.007,0.021,0.025,0.0055,0.19,0.23,0.031,2.8e-07,3.5e-07,1.2e-06,0.0038,0.0039,9.9e-05,0.00037,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30490000,0.73,0.0034,0.0077,0.68,-2,-1.1,0.87,-10,-4.7,-3.7e+02,-0.0012,-0.0059,0.00019,0.0026,0.005,-0.12,0.21,-0.00022,0.43,-0.012,-0.0024,-0.0014,0,0,-3.7e+02,8.7e-05,6e-05,0.007,0.022,0.027,0.0056,0.2,0.24,0.031,2.8e-07,3.5e-07,1.2e-06,0.0038,0.0039,9.8e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30590000,0.73,0.0034,0.0073,0.68,-1.9,-1,0.83,-10,-4.8,-3.7e+02,-0.0012,-0.0059,0.00018,0.0034,0.0046,-0.12,0.21,-0.00024,0.43,-0.012,-0.0025,-0.001,0,0,-3.7e+02,8.6e-05,6e-05,0.0069,0.021,0.026,0.0055,0.2,0.24,0.031,2.8e-07,3.5e-07,1.1e-06,0.0037,0.0038,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30690000,0.73,0.0031,0.0069,0.68,-1.9,-1,0.83,-11,-4.9,-3.7e+02,-0.0012,-0.0059,0.00018,0.0032,0.0049,-0.12,0.21,-0.00024,0.43,-0.012,-0.0024,-0.001,0,0,-3.7e+02,8.6e-05,6e-05,0.0069,0.022,0.028,0.0055,0.21,0.25,0.031,2.8e-07,3.5e-07,1.1e-06,0.0037,0.0038,9.7e-05,0.00036,3.9e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 +30790000,0.73,0.0031,0.0065,0.68,-1.9,-1,0.82,-11,-5,-3.7e+02,-0.0012,-0.0059,0.00015,0.0039,0.0043,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00078,0,0,-3.7e+02,8.4e-05,6e-05,0.0068,0.021,0.027,0.0055,0.21,0.25,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.6e-05,0.00036,3.8e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 30890000,0.73,0.0029,0.006,0.68,-1.9,-1,0.81,-11,-5.1,-3.7e+02,-0.0013,-0.0059,0.00015,0.0039,0.0047,-0.12,0.21,-0.00024,0.43,-0.012,-0.0026,-0.00076,0,0,-3.7e+02,8.5e-05,6e-05,0.0068,0.022,0.029,0.0055,0.22,0.26,0.031,2.8e-07,3.4e-07,1.1e-06,0.0037,0.0038,9.6e-05,0.00036,3.8e-05,0.00038,0.00028,0.00036,0.00038,1,1,0.01 30990000,0.73,0.003,0.0054,0.68,-1.8,-1,0.8,-11,-5.2,-3.7e+02,-0.0013,-0.0058,0.00012,0.0048,0.0042,-0.12,0.21,-0.00025,0.43,-0.011,-0.0027,-0.00042,0,0,-3.7e+02,8.3e-05,5.9e-05,0.0067,0.021,0.028,0.0055,0.22,0.26,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.5e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 -31090000,0.73,0.0027,0.0049,0.68,-1.8,-1,0.79,-11,-5.3,-3.7e+02,-0.0013,-0.0058,0.00012,0.0045,0.0046,-0.12,0.21,-0.00026,0.43,-0.011,-0.0027,-0.00042,0,0,-3.7e+02,8.3e-05,6e-05,0.0067,0.022,0.03,0.0055,0.23,0.27,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.5e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 +31090000,0.73,0.0027,0.0049,0.68,-1.8,-1,0.79,-11,-5.3,-3.7e+02,-0.0013,-0.0058,0.00012,0.0046,0.0046,-0.12,0.21,-0.00026,0.43,-0.011,-0.0027,-0.00042,0,0,-3.7e+02,8.3e-05,6e-05,0.0067,0.022,0.03,0.0055,0.23,0.27,0.031,2.7e-07,3.3e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 31190000,0.73,0.0026,0.0044,0.68,-1.8,-1,0.78,-12,-5.3,-3.7e+02,-0.0013,-0.0058,9.7e-05,0.0049,0.0045,-0.12,0.21,-0.00027,0.43,-0.011,-0.0027,-0.00025,0,0,-3.7e+02,8.1e-05,5.9e-05,0.0066,0.021,0.028,0.0055,0.23,0.27,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 -31290000,0.73,0.0023,0.0039,0.68,-1.8,-1,0.78,-12,-5.4,-3.7e+02,-0.0013,-0.0058,0.0001,0.0046,0.0049,-0.11,0.21,-0.00027,0.43,-0.011,-0.0027,-0.00028,0,0,-3.7e+02,8.2e-05,5.9e-05,0.0066,0.022,0.03,0.0055,0.24,0.28,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.4e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 -31390000,0.73,0.0022,0.0032,0.68,-1.7,-0.99,0.78,-12,-5.5,-3.7e+02,-0.0013,-0.0058,7.8e-05,0.005,0.0047,-0.11,0.21,-0.0003,0.43,-0.011,-0.0028,-2.8e-05,0,0,-3.7e+02,7.9e-05,5.9e-05,0.0065,0.021,0.029,0.0054,0.24,0.28,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.3e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 -31490000,0.73,0.0019,0.0026,0.68,-1.7,-0.99,0.78,-12,-5.6,-3.7e+02,-0.0013,-0.0058,7.4e-05,0.0049,0.0052,-0.11,0.21,-0.0003,0.43,-0.011,-0.0029,8.8e-06,0,0,-3.7e+02,8e-05,5.9e-05,0.0065,0.022,0.031,0.0055,0.25,0.29,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 -31590000,0.73,0.002,0.0021,0.68,-1.7,-0.97,0.77,-12,-5.7,-3.7e+02,-0.0013,-0.0058,4.8e-05,0.0058,0.0049,-0.11,0.21,-0.00029,0.43,-0.01,-0.0029,0.00025,0,0,-3.7e+02,7.7e-05,5.9e-05,0.0063,0.021,0.029,0.0054,0.25,0.29,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31690000,0.73,0.0017,0.0014,0.68,-1.6,-0.97,0.78,-12,-5.8,-3.7e+02,-0.0013,-0.0058,5e-05,0.0055,0.0052,-0.11,0.21,-0.00029,0.43,-0.01,-0.0029,0.00021,0,0,-3.7e+02,7.8e-05,5.9e-05,0.0063,0.022,0.031,0.0054,0.26,0.3,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31790000,0.73,0.0015,0.00057,0.69,-1.6,-0.95,0.78,-13,-5.9,-3.7e+02,-0.0013,-0.0058,2.5e-05,0.0066,0.0051,-0.11,0.21,-0.0003,0.43,-0.0097,-0.0029,0.00055,0,0,-3.7e+02,7.6e-05,5.9e-05,0.0062,0.021,0.029,0.0054,0.26,0.3,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 +31290000,0.73,0.0023,0.0039,0.68,-1.8,-1,0.78,-12,-5.4,-3.7e+02,-0.0013,-0.0058,0.0001,0.0046,0.0049,-0.11,0.21,-0.00027,0.43,-0.011,-0.0027,-0.00028,0,0,-3.7e+02,8.2e-05,5.9e-05,0.0066,0.022,0.03,0.0055,0.24,0.28,0.031,2.7e-07,3.2e-07,1.1e-06,0.0037,0.0038,9.3e-05,0.00036,3.8e-05,0.00038,0.00027,0.00036,0.00037,1,1,0.01 +31390000,0.73,0.0022,0.0032,0.68,-1.7,-0.99,0.78,-12,-5.5,-3.7e+02,-0.0013,-0.0058,7.8e-05,0.0051,0.0047,-0.11,0.21,-0.0003,0.43,-0.011,-0.0028,-2.8e-05,0,0,-3.7e+02,7.9e-05,5.9e-05,0.0065,0.021,0.029,0.0054,0.24,0.28,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 +31490000,0.73,0.0019,0.0026,0.68,-1.7,-0.99,0.78,-12,-5.6,-3.7e+02,-0.0013,-0.0058,7.4e-05,0.005,0.0052,-0.11,0.21,-0.0003,0.43,-0.011,-0.0029,9.1e-06,0,0,-3.7e+02,8e-05,5.9e-05,0.0065,0.022,0.031,0.0055,0.25,0.29,0.031,2.7e-07,3.1e-07,1e-06,0.0037,0.0037,9.2e-05,0.00036,3.8e-05,0.00038,0.00026,0.00035,0.00037,1,1,0.01 +31590000,0.73,0.002,0.0021,0.68,-1.7,-0.97,0.77,-12,-5.7,-3.7e+02,-0.0013,-0.0058,4.7e-05,0.0059,0.0048,-0.11,0.21,-0.00029,0.43,-0.01,-0.0029,0.00025,0,0,-3.7e+02,7.7e-05,5.9e-05,0.0063,0.021,0.029,0.0054,0.25,0.29,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 +31690000,0.73,0.0016,0.0014,0.68,-1.6,-0.97,0.78,-12,-5.8,-3.7e+02,-0.0013,-0.0058,4.9e-05,0.0056,0.0052,-0.11,0.21,-0.00029,0.43,-0.01,-0.0029,0.00021,0,0,-3.7e+02,7.8e-05,5.9e-05,0.0063,0.022,0.031,0.0054,0.26,0.3,0.031,2.6e-07,3.1e-07,1e-06,0.0037,0.0037,9.1e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 +31790000,0.73,0.0015,0.00057,0.69,-1.6,-0.95,0.78,-13,-5.9,-3.7e+02,-0.0013,-0.0058,2.4e-05,0.0066,0.0051,-0.11,0.21,-0.0003,0.43,-0.0097,-0.0029,0.00055,0,0,-3.7e+02,7.6e-05,5.9e-05,0.0062,0.021,0.029,0.0054,0.26,0.3,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 31890000,0.73,0.0013,-0.00016,0.69,-1.6,-0.95,0.77,-13,-6,-3.7e+02,-0.0013,-0.0058,2.5e-05,0.0065,0.0056,-0.11,0.21,-0.00029,0.43,-0.0097,-0.0029,0.00058,0,0,-3.7e+02,7.6e-05,5.9e-05,0.0062,0.022,0.031,0.0054,0.27,0.31,0.031,2.6e-07,3e-07,1e-06,0.0037,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00026,0.00035,0.00037,1,1,0.01 -31990000,0.73,0.0012,-0.00077,0.69,-1.6,-0.93,0.77,-13,-6.1,-3.7e+02,-0.0013,-0.0058,-6.4e-06,0.007,0.0055,-0.11,0.21,-0.00029,0.43,-0.0092,-0.003,0.00075,0,0,-3.7e+02,7.4e-05,5.8e-05,0.006,0.021,0.03,0.0054,0.27,0.31,0.031,2.6e-07,2.9e-07,9.8e-07,0.0036,0.0037,9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32090000,0.73,0.00083,-0.0015,0.69,-1.5,-0.93,0.78,-13,-6.2,-3.7e+02,-0.0013,-0.0058,-7.3e-06,0.0068,0.006,-0.11,0.21,-0.00029,0.43,-0.0093,-0.003,0.00076,0,0,-3.7e+02,7.5e-05,5.9e-05,0.006,0.022,0.032,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.7e-07,0.0036,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32190000,0.73,0.00062,-0.0025,0.69,-1.5,-0.91,0.78,-13,-6.2,-3.7e+02,-0.0014,-0.0058,-4.2e-05,0.0073,0.006,-0.11,0.2,-0.0003,0.43,-0.0088,-0.0031,0.001,0,0,-3.7e+02,7.2e-05,5.8e-05,0.0059,0.021,0.03,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.5e-07,0.0036,0.0036,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32290000,0.73,0.00035,-0.0032,0.69,-1.5,-0.91,0.77,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-4.1e-05,0.0071,0.0066,-0.11,0.2,-0.0003,0.43,-0.0088,-0.0031,0.001,0,0,-3.7e+02,7.3e-05,5.8e-05,0.0059,0.022,0.032,0.0054,0.29,0.33,0.031,2.6e-07,2.9e-07,9.5e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 -32390000,0.73,0.00025,-0.004,0.69,-1.5,-0.89,0.77,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-5.9e-05,0.0076,0.0065,-0.11,0.2,-0.00029,0.43,-0.0084,-0.0031,0.0011,0,0,-3.7e+02,7.1e-05,5.8e-05,0.0057,0.021,0.03,0.0054,0.29,0.33,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 +31990000,0.73,0.0012,-0.00077,0.69,-1.6,-0.93,0.77,-13,-6.1,-3.7e+02,-0.0013,-0.0058,-6.6e-06,0.007,0.0054,-0.11,0.21,-0.00029,0.43,-0.0092,-0.003,0.00075,0,0,-3.7e+02,7.4e-05,5.8e-05,0.006,0.021,0.03,0.0054,0.27,0.31,0.031,2.6e-07,2.9e-07,9.8e-07,0.0036,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32090000,0.73,0.00083,-0.0015,0.69,-1.5,-0.93,0.78,-13,-6.2,-3.7e+02,-0.0013,-0.0058,-7.5e-06,0.0068,0.0059,-0.11,0.21,-0.00029,0.43,-0.0093,-0.003,0.00076,0,0,-3.7e+02,7.5e-05,5.9e-05,0.006,0.022,0.032,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.8e-07,0.0036,0.0037,8.9e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32190000,0.73,0.00062,-0.0025,0.69,-1.5,-0.91,0.78,-13,-6.2,-3.7e+02,-0.0014,-0.0058,-4.2e-05,0.0073,0.006,-0.11,0.2,-0.0003,0.43,-0.0088,-0.0031,0.001,0,0,-3.7e+02,7.2e-05,5.8e-05,0.0059,0.021,0.03,0.0054,0.28,0.32,0.031,2.6e-07,2.9e-07,9.5e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32290000,0.73,0.00035,-0.0032,0.69,-1.5,-0.91,0.77,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-4.1e-05,0.0071,0.0065,-0.11,0.2,-0.0003,0.43,-0.0088,-0.0031,0.001,0,0,-3.7e+02,7.3e-05,5.8e-05,0.0059,0.022,0.032,0.0054,0.29,0.33,0.031,2.6e-07,2.9e-07,9.5e-07,0.0036,0.0036,8.8e-05,0.00036,3.8e-05,0.00037,0.00025,0.00035,0.00037,1,1,0.01 +32390000,0.73,0.00025,-0.004,0.69,-1.5,-0.89,0.77,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-5.9e-05,0.0076,0.0064,-0.11,0.2,-0.00029,0.43,-0.0084,-0.0031,0.0011,0,0,-3.7e+02,7.1e-05,5.8e-05,0.0057,0.021,0.03,0.0054,0.29,0.33,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.7e-05,0.00036,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 32490000,0.72,0.0001,-0.0042,0.69,-1.4,-0.88,0.78,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-5.7e-05,0.0074,0.0069,-0.11,0.21,-0.00029,0.43,-0.0084,-0.0031,0.0011,0,0,-3.7e+02,7.1e-05,5.8e-05,0.0057,0.022,0.032,0.0054,0.3,0.34,0.031,2.5e-07,2.8e-07,9.3e-07,0.0036,0.0036,8.7e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 -32590000,0.72,0.00015,-0.0046,0.69,-1.4,-0.87,0.78,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-7.8e-05,0.0078,0.0069,-0.11,0.21,-0.0003,0.43,-0.008,-0.0031,0.0013,0,0,-3.7e+02,7e-05,5.8e-05,0.0056,0.021,0.03,0.0053,0.3,0.34,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.7e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 -32690000,0.72,0.00011,-0.0046,0.69,-1.4,-0.86,0.77,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-7.9e-05,0.0077,0.0073,-0.11,0.21,-0.0003,0.43,-0.008,-0.0031,0.0014,0,0,-3.7e+02,7e-05,5.8e-05,0.0056,0.022,0.032,0.0053,0.31,0.35,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00036,1,1,0.01 -32790000,0.72,0.00023,-0.0047,0.69,-1.3,-0.84,0.77,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-9.8e-05,0.0081,0.0073,-0.11,0.21,-0.0003,0.43,-0.0076,-0.0031,0.0015,0,0,-3.7e+02,6.8e-05,5.7e-05,0.0054,0.021,0.03,0.0053,0.3,0.35,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -32890000,0.72,0.00031,-0.0046,0.69,-1.3,-0.84,0.77,-14,-6.8,-3.7e+02,-0.0014,-0.0057,-0.00011,0.008,0.0079,-0.11,0.2,-0.0003,0.43,-0.0076,-0.0032,0.0016,0,0,-3.7e+02,6.9e-05,5.8e-05,0.0054,0.022,0.031,0.0053,0.32,0.36,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -32990000,0.72,0.00052,-0.0047,0.69,-1.3,-0.82,0.77,-15,-6.9,-3.7e+02,-0.0014,-0.0057,-0.00011,0.0085,0.008,-0.11,0.2,-0.0003,0.43,-0.0072,-0.0032,0.0017,0,0,-3.7e+02,6.7e-05,5.7e-05,0.0052,0.021,0.029,0.0053,0.31,0.36,0.03,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 -33090000,0.72,0.00049,-0.0047,0.69,-1.3,-0.82,0.76,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00011,0.0083,0.0083,-0.11,0.21,-0.0003,0.43,-0.0072,-0.0032,0.0017,0,0,-3.7e+02,6.7e-05,5.7e-05,0.0053,0.022,0.031,0.0053,0.33,0.37,0.031,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +32590000,0.72,0.00015,-0.0046,0.69,-1.4,-0.87,0.78,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-7.8e-05,0.0078,0.0068,-0.11,0.21,-0.0003,0.43,-0.008,-0.0031,0.0013,0,0,-3.7e+02,7e-05,5.8e-05,0.0056,0.021,0.03,0.0053,0.3,0.34,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00037,1,1,0.01 +32690000,0.72,0.00011,-0.0046,0.69,-1.4,-0.86,0.77,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-7.9e-05,0.0078,0.0072,-0.11,0.2,-0.0003,0.43,-0.008,-0.0031,0.0014,0,0,-3.7e+02,7e-05,5.8e-05,0.0056,0.022,0.032,0.0053,0.31,0.35,0.031,2.5e-07,2.8e-07,9.1e-07,0.0036,0.0036,8.6e-05,0.00035,3.8e-05,0.00037,0.00024,0.00035,0.00036,1,1,0.01 +32790000,0.72,0.00023,-0.0047,0.69,-1.3,-0.84,0.77,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-9.9e-05,0.0081,0.0072,-0.11,0.21,-0.0003,0.43,-0.0076,-0.0031,0.0015,0,0,-3.7e+02,6.8e-05,5.7e-05,0.0054,0.021,0.03,0.0053,0.3,0.35,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +32890000,0.72,0.00031,-0.0046,0.69,-1.3,-0.84,0.77,-14,-6.8,-3.7e+02,-0.0014,-0.0057,-0.00011,0.008,0.0078,-0.11,0.2,-0.0003,0.43,-0.0076,-0.0032,0.0016,0,0,-3.7e+02,6.9e-05,5.8e-05,0.0054,0.022,0.031,0.0053,0.32,0.36,0.031,2.5e-07,2.7e-07,8.9e-07,0.0036,0.0036,8.5e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +32990000,0.72,0.00052,-0.0047,0.69,-1.3,-0.82,0.77,-15,-6.9,-3.7e+02,-0.0014,-0.0057,-0.00011,0.0085,0.008,-0.11,0.2,-0.0003,0.43,-0.0072,-0.0032,0.0017,0,0,-3.7e+02,6.7e-05,5.7e-05,0.0052,0.021,0.029,0.0053,0.31,0.36,0.03,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 +33090000,0.72,0.00049,-0.0047,0.69,-1.3,-0.82,0.76,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00011,0.0084,0.0083,-0.11,0.21,-0.0003,0.43,-0.0072,-0.0032,0.0017,0,0,-3.7e+02,6.7e-05,5.7e-05,0.0053,0.022,0.031,0.0053,0.33,0.37,0.031,2.5e-07,2.7e-07,8.7e-07,0.0036,0.0036,8.4e-05,0.00035,3.8e-05,0.00037,0.00023,0.00035,0.00036,1,1,0.01 33190000,0.72,0.0039,-0.0039,0.7,-1.2,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00012,0.0085,0.0082,-0.11,0.21,-0.0003,0.43,-0.0068,-0.0031,0.0017,0,0,-3.7e+02,6.6e-05,5.7e-05,0.0051,0.022,0.029,0.0053,0.32,0.37,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0035,8.4e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 -33290000,0.67,0.016,-0.0033,0.74,-1.2,-0.78,0.68,-15,-7.1,-3.7e+02,-0.0014,-0.0057,-0.00011,0.0083,0.0085,-0.11,0.2,-0.00028,0.43,-0.007,-0.0032,0.0016,0,0,-3.7e+02,6.6e-05,5.7e-05,0.0051,0.022,0.031,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0035,8.4e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 -33390000,0.56,0.014,-0.0037,0.83,-1.2,-0.77,0.88,-15,-7.2,-3.7e+02,-0.0014,-0.0057,-0.00013,0.0085,0.0088,-0.11,0.21,-0.00034,0.43,-0.0063,-0.0032,0.0018,0,0,-3.7e+02,6.5e-05,5.6e-05,0.0047,0.021,0.028,0.0053,0.33,0.38,0.031,2.4e-07,2.6e-07,8.3e-07,0.0036,0.0035,8.3e-05,0.00032,3.8e-05,0.00036,0.00021,0.00032,0.00036,1,1,0.01 -33490000,0.43,0.007,-0.0011,0.9,-1.2,-0.76,0.89,-15,-7.3,-3.7e+02,-0.0014,-0.0057,-0.00014,0.0085,0.0089,-0.11,0.21,-0.00042,0.43,-0.0058,-0.002,0.0018,0,0,-3.7e+02,6.5e-05,5.6e-05,0.0041,0.022,0.029,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.1e-07,0.0036,0.0035,8.3e-05,0.00025,3.7e-05,0.00036,0.00017,0.00024,0.00036,1,1,0.01 -33590000,0.27,0.00094,-0.0036,0.96,-1.2,-0.75,0.86,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00018,0.0085,0.0089,-0.11,0.21,-0.00067,0.43,-0.0038,-0.0013,0.002,0,0,-3.7e+02,6.4e-05,5.5e-05,0.0031,0.02,0.027,0.0052,0.34,0.37,0.03,2.4e-07,2.6e-07,7.9e-07,0.0036,0.0035,8.3e-05,0.00016,3.6e-05,0.00036,0.00012,0.00015,0.00036,1,1,0.01 -33690000,0.098,-0.0027,-0.0066,1,-1.1,-0.74,0.87,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00018,0.0085,0.0089,-0.11,0.21,-0.00072,0.43,-0.0035,-0.001,0.002,0,0,-3.7e+02,6.4e-05,5.5e-05,0.0024,0.021,0.028,0.0053,0.35,0.37,0.031,2.4e-07,2.6e-07,7.8e-07,0.0036,0.0035,8.3e-05,0.0001,3.5e-05,0.00036,8.3e-05,9.8e-05,0.00036,1,1,0.01 -33790000,-0.074,-0.0045,-0.0084,1,-1.1,-0.72,0.85,-16,-7.5,-3.7e+02,-0.0014,-0.0057,-0.00021,0.0085,0.0089,-0.11,0.21,-0.00088,0.43,-0.0021,-0.001,0.0023,0,0,-3.7e+02,6.2e-05,5.4e-05,0.0019,0.02,0.026,0.0052,0.35,0.37,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,6.8e-05,3.5e-05,0.00036,5.5e-05,6.1e-05,0.00036,1,1,0.01 -33890000,-0.24,-0.0059,-0.009,0.97,-1,-0.69,0.83,-16,-7.6,-3.7e+02,-0.0014,-0.0057,-0.00021,0.0085,0.0089,-0.11,0.21,-0.001,0.43,-0.0012,-0.0011,0.0024,0,0,-3.7e+02,6.2e-05,5.4e-05,0.0016,0.022,0.028,0.0052,0.36,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.4e-05,4.8e-05,3.4e-05,0.00036,3.8e-05,4.1e-05,0.00036,1,1,0.01 -33990000,-0.39,-0.0046,-0.012,0.92,-0.94,-0.64,0.81,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00022,0.0085,0.009,-0.11,0.21,-0.00097,0.43,-0.0011,-0.00064,0.0025,0,0,-3.7e+02,6e-05,5.3e-05,0.0015,0.021,0.027,0.0052,0.36,0.37,0.03,2.4e-07,2.5e-07,7.7e-07,0.0036,0.0035,8.3e-05,3.6e-05,3.4e-05,0.00036,2.8e-05,2.9e-05,0.00036,1,1,0.01 -34090000,-0.5,-0.0037,-0.014,0.87,-0.88,-0.59,0.81,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00022,0.0084,0.0092,-0.11,0.21,-0.00095,0.43,-0.0012,-0.00052,0.0025,0,0,-3.7e+02,6e-05,5.3e-05,0.0014,0.023,0.03,0.0052,0.37,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,3e-05,3.4e-05,0.00036,2.2e-05,2.3e-05,0.00036,1,1,0.01 -34190000,-0.57,-0.0036,-0.012,0.82,-0.86,-0.54,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.0002,0.0063,0.012,-0.11,0.21,-0.00094,0.43,-0.001,-0.00031,0.0027,0,0,-3.7e+02,5.7e-05,5.1e-05,0.0013,0.023,0.029,0.0052,0.37,0.38,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.3e-05,2.5e-05,3.4e-05,0.00036,1.8e-05,1.8e-05,0.00036,1,1,0.01 +33290000,0.67,0.016,-0.0033,0.74,-1.2,-0.78,0.68,-15,-7.1,-3.7e+02,-0.0014,-0.0057,-0.00011,0.0083,0.0084,-0.11,0.2,-0.00028,0.43,-0.007,-0.0032,0.0016,0,0,-3.7e+02,6.6e-05,5.7e-05,0.0051,0.022,0.031,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.5e-07,0.0036,0.0035,8.3e-05,0.00035,3.8e-05,0.00037,0.00022,0.00035,0.00036,1,1,0.01 +33390000,0.56,0.014,-0.0037,0.83,-1.2,-0.77,0.88,-15,-7.2,-3.7e+02,-0.0014,-0.0057,-0.00013,0.0085,0.0087,-0.11,0.21,-0.00034,0.43,-0.0063,-0.0032,0.0018,0,0,-3.7e+02,6.5e-05,5.6e-05,0.0047,0.021,0.028,0.0053,0.33,0.38,0.031,2.4e-07,2.6e-07,8.3e-07,0.0036,0.0035,8.3e-05,0.00032,3.8e-05,0.00036,0.00021,0.00032,0.00036,1,1,0.01 +33490000,0.43,0.007,-0.0011,0.9,-1.2,-0.76,0.89,-15,-7.3,-3.7e+02,-0.0014,-0.0057,-0.00014,0.0085,0.0088,-0.11,0.21,-0.00042,0.43,-0.0058,-0.002,0.0018,0,0,-3.7e+02,6.5e-05,5.6e-05,0.0041,0.022,0.029,0.0053,0.34,0.38,0.031,2.4e-07,2.6e-07,8.1e-07,0.0036,0.0035,8.3e-05,0.00025,3.7e-05,0.00036,0.00017,0.00024,0.00036,1,1,0.01 +33590000,0.27,0.00094,-0.0036,0.96,-1.2,-0.75,0.86,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00018,0.0085,0.0088,-0.11,0.21,-0.00067,0.43,-0.0038,-0.0013,0.002,0,0,-3.7e+02,6.4e-05,5.5e-05,0.0031,0.02,0.027,0.0052,0.34,0.37,0.03,2.4e-07,2.6e-07,7.9e-07,0.0036,0.0035,8.3e-05,0.00016,3.6e-05,0.00036,0.00012,0.00015,0.00036,1,1,0.01 +33690000,0.098,-0.0027,-0.0066,1,-1.1,-0.74,0.87,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00019,0.0085,0.0088,-0.11,0.21,-0.00072,0.43,-0.0035,-0.001,0.002,0,0,-3.7e+02,6.4e-05,5.5e-05,0.0024,0.021,0.028,0.0053,0.35,0.37,0.031,2.4e-07,2.6e-07,7.8e-07,0.0036,0.0035,8.3e-05,0.0001,3.5e-05,0.00036,8.3e-05,9.8e-05,0.00036,1,1,0.01 +33790000,-0.074,-0.0045,-0.0084,1,-1.1,-0.72,0.85,-16,-7.5,-3.7e+02,-0.0014,-0.0057,-0.00021,0.0085,0.0088,-0.11,0.21,-0.00088,0.43,-0.0021,-0.001,0.0023,0,0,-3.7e+02,6.2e-05,5.4e-05,0.0019,0.02,0.026,0.0052,0.35,0.37,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,6.8e-05,3.5e-05,0.00036,5.5e-05,6.1e-05,0.00036,1,1,0.01 +33890000,-0.24,-0.0059,-0.009,0.97,-1,-0.69,0.83,-16,-7.6,-3.7e+02,-0.0014,-0.0057,-0.00021,0.0085,0.0088,-0.11,0.21,-0.001,0.43,-0.0012,-0.0011,0.0024,0,0,-3.7e+02,6.2e-05,5.4e-05,0.0016,0.022,0.028,0.0052,0.36,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,4.8e-05,3.4e-05,0.00036,3.8e-05,4.1e-05,0.00036,1,1,0.01 +33990000,-0.39,-0.0046,-0.012,0.92,-0.94,-0.64,0.8,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00022,0.0085,0.0089,-0.11,0.21,-0.00097,0.43,-0.0011,-0.00064,0.0025,0,0,-3.7e+02,6e-05,5.3e-05,0.0015,0.021,0.027,0.0052,0.36,0.37,0.03,2.4e-07,2.5e-07,7.7e-07,0.0036,0.0035,8.3e-05,3.6e-05,3.4e-05,0.00036,2.8e-05,2.9e-05,0.00036,1,1,0.01 +34090000,-0.5,-0.0037,-0.014,0.87,-0.88,-0.59,0.81,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00022,0.0085,0.0092,-0.11,0.21,-0.00095,0.43,-0.0012,-0.00052,0.0025,0,0,-3.7e+02,6e-05,5.3e-05,0.0014,0.023,0.03,0.0052,0.37,0.38,0.03,2.4e-07,2.6e-07,7.7e-07,0.0036,0.0035,8.3e-05,3e-05,3.4e-05,0.00036,2.2e-05,2.3e-05,0.00036,1,1,0.01 +34190000,-0.57,-0.0036,-0.012,0.82,-0.86,-0.54,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00021,0.0063,0.012,-0.11,0.21,-0.00094,0.43,-0.001,-0.00031,0.0027,0,0,-3.7e+02,5.7e-05,5.1e-05,0.0013,0.023,0.029,0.0052,0.37,0.38,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.2e-05,2.5e-05,3.4e-05,0.00036,1.8e-05,1.8e-05,0.00036,1,1,0.01 34290000,-0.61,-0.0046,-0.0091,0.79,-0.8,-0.48,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.0002,0.0061,0.012,-0.11,0.21,-0.00096,0.43,-0.00092,-0.00018,0.0027,0,0,-3.7e+02,5.7e-05,5.1e-05,0.0012,0.025,0.032,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.6e-07,0.0035,0.0035,8.2e-05,2.2e-05,3.4e-05,0.00036,1.5e-05,1.5e-05,0.00036,1,1,0.01 -34390000,-0.63,-0.0052,-0.0062,0.77,-0.78,-0.44,0.81,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00018,0.0033,0.016,-0.11,0.21,-0.00092,0.43,-0.00091,1.6e-05,0.0029,0,0,-3.7e+02,5.3e-05,4.9e-05,0.0012,0.025,0.031,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.5e-07,0.0034,0.0035,8.2e-05,2e-05,3.3e-05,0.00036,1.3e-05,1.3e-05,0.00036,1,1,0.01 -34490000,-0.65,-0.0062,-0.004,0.76,-0.72,-0.39,0.81,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00018,0.0031,0.017,-0.11,0.21,-0.00093,0.43,-0.00085,-2.5e-05,0.0029,0,0,-3.7e+02,5.3e-05,4.9e-05,0.0011,0.027,0.035,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.5e-07,0.0034,0.0035,8.2e-05,1.8e-05,3.3e-05,0.00036,1.2e-05,1.2e-05,0.00036,1,1,0.01 +34390000,-0.63,-0.0052,-0.0062,0.77,-0.77,-0.44,0.81,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00018,0.0033,0.016,-0.11,0.21,-0.00092,0.43,-0.00091,1.6e-05,0.0029,0,0,-3.7e+02,5.3e-05,4.9e-05,0.0012,0.025,0.031,0.0052,0.38,0.39,0.03,2.4e-07,2.5e-07,7.5e-07,0.0034,0.0035,8.2e-05,2e-05,3.3e-05,0.00036,1.3e-05,1.3e-05,0.00036,1,1,0.01 +34490000,-0.65,-0.0062,-0.004,0.76,-0.72,-0.39,0.81,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00018,0.0031,0.017,-0.11,0.21,-0.00093,0.43,-0.00085,-2.5e-05,0.0029,0,0,-3.7e+02,5.3e-05,4.9e-05,0.0011,0.027,0.035,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.5e-07,0.0034,0.0035,8.1e-05,1.8e-05,3.3e-05,0.00036,1.2e-05,1.2e-05,0.00036,1,1,0.01 34590000,-0.66,-0.0062,-0.0026,0.75,-0.7,-0.37,0.8,-16,-8,-3.7e+02,-0.0015,-0.0058,-0.00015,-0.0018,0.023,-0.11,0.21,-0.00088,0.43,-0.00092,3e-05,0.0032,0,0,-3.7e+02,5e-05,4.7e-05,0.0011,0.027,0.034,0.0052,0.39,0.4,0.03,2.4e-07,2.5e-07,7.5e-07,0.0033,0.0034,8.1e-05,1.6e-05,3.3e-05,0.00036,1.1e-05,1e-05,0.00036,1,1,0.01 34690000,-0.67,-0.0066,-0.0018,0.75,-0.64,-0.32,0.8,-17,-8.1,-3.7e+02,-0.0015,-0.0058,-0.00015,-0.0021,0.023,-0.11,0.21,-0.0009,0.43,-0.00078,0.00023,0.0031,0,0,-3.7e+02,5e-05,4.7e-05,0.0011,0.03,0.037,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.5e-07,0.0033,0.0034,8.1e-05,1.6e-05,3.3e-05,0.00036,9.9e-06,9.4e-06,0.00036,1,1,0.01 -34790000,-0.67,-0.006,-0.0013,0.74,-0.63,-0.3,0.79,-17,-8.1,-3.7e+02,-0.0015,-0.0058,-0.00011,-0.008,0.03,-0.11,0.21,-0.00089,0.43,-0.00062,0.00032,0.0032,0,0,-3.7e+02,4.6e-05,4.4e-05,0.001,0.029,0.036,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8.1e-05,1.4e-05,3.3e-05,0.00036,9.1e-06,8.6e-06,0.00036,1,1,0.01 -34890000,-0.67,-0.006,-0.0012,0.74,-0.57,-0.26,0.79,-17,-8.2,-3.7e+02,-0.0015,-0.0058,-0.00011,-0.0082,0.03,-0.11,0.21,-0.00089,0.43,-0.00063,0.00028,0.0033,0,0,-3.7e+02,4.6e-05,4.4e-05,0.001,0.032,0.04,0.0052,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,8.4e-06,7.9e-06,0.00036,1,1,0.01 +34790000,-0.67,-0.006,-0.0013,0.74,-0.63,-0.3,0.79,-17,-8.1,-3.7e+02,-0.0015,-0.0058,-0.00011,-0.008,0.03,-0.11,0.21,-0.00089,0.43,-0.00062,0.00032,0.0032,0,0,-3.7e+02,4.6e-05,4.4e-05,0.001,0.029,0.036,0.0052,0.4,0.41,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,9.1e-06,8.6e-06,0.00036,1,1,0.01 +34890000,-0.67,-0.006,-0.0012,0.74,-0.57,-0.26,0.79,-17,-8.2,-3.7e+02,-0.0015,-0.0058,-0.00011,-0.0081,0.03,-0.11,0.21,-0.00089,0.43,-0.00063,0.00028,0.0033,0,0,-3.7e+02,4.6e-05,4.4e-05,0.001,0.032,0.04,0.0052,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.0032,0.0033,8e-05,1.4e-05,3.3e-05,0.00036,8.4e-06,7.9e-06,0.00036,1,1,0.01 34990000,-0.67,-0.013,-0.0037,0.74,0.47,0.35,-0.043,-17,-8.2,-3.7e+02,-0.0016,-0.0058,-6.7e-05,-0.016,0.039,-0.11,0.21,-0.00087,0.43,-0.00051,0.00034,0.0035,0,0,-3.7e+02,4.2e-05,4.1e-05,0.001,0.034,0.046,0.0054,0.41,0.42,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.3e-05,3.3e-05,0.00036,8e-06,7.4e-06,0.00036,1,1,0.01 -35090000,-0.67,-0.013,-0.0037,0.74,0.6,0.39,-0.1,-17,-8.2,-3.7e+02,-0.0016,-0.0058,-6.8e-05,-0.016,0.039,-0.11,0.21,-0.00087,0.43,-0.00047,0.00028,0.0035,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00099,0.037,0.051,0.0055,0.42,0.43,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.2e-05,3.3e-05,0.00036,7.5e-06,6.9e-06,0.00036,1,1,0.01 +35090000,-0.67,-0.013,-0.0037,0.74,0.6,0.39,-0.1,-17,-8.2,-3.7e+02,-0.0016,-0.0058,-6.9e-05,-0.016,0.039,-0.11,0.21,-0.00087,0.43,-0.00047,0.00028,0.0035,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00099,0.037,0.051,0.0055,0.42,0.43,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.2e-05,3.3e-05,0.00036,7.5e-06,6.9e-06,0.00036,1,1,0.01 35190000,-0.67,-0.013,-0.0038,0.74,0.63,0.43,-0.1,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-6.9e-05,-0.016,0.039,-0.11,0.21,-0.00088,0.43,-0.00041,0.00032,0.0035,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00099,0.041,0.055,0.0055,0.43,0.44,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.2e-05,3.3e-05,0.00036,7.1e-06,6.4e-06,0.00036,1,1,0.01 -35290000,-0.67,-0.013,-0.0038,0.74,0.66,0.47,-0.099,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-7e-05,-0.016,0.039,-0.11,0.21,-0.00089,0.43,-0.00033,0.00032,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00098,0.044,0.06,0.0055,0.44,0.45,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.1e-05,3.3e-05,0.00036,6.8e-06,6.1e-06,0.00036,1,1,0.01 -35390000,-0.67,-0.013,-0.0038,0.74,0.69,0.51,-0.096,-17,-8,-3.7e+02,-0.0016,-0.0058,-7.3e-05,-0.016,0.039,-0.11,0.21,-0.00091,0.43,-0.00023,0.00029,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00098,0.048,0.064,0.0055,0.46,0.47,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8.1e-05,1.1e-05,3.3e-05,0.00036,6.5e-06,5.8e-06,0.00036,1,1,0.01 -35490000,-0.67,-0.013,-0.0038,0.74,0.72,0.56,-0.095,-17,-8,-3.7e+02,-0.0016,-0.0058,-7.6e-05,-0.016,0.039,-0.11,0.21,-0.00092,0.43,-0.00014,0.00024,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00097,0.053,0.069,0.0055,0.47,0.48,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8.1e-05,1.1e-05,3.3e-05,0.00036,6.2e-06,5.5e-06,0.00036,1,1,0.01 -35590000,-0.67,-0.013,-0.0038,0.74,0.76,0.6,-0.094,-16,-7.9,-3.7e+02,-0.0016,-0.0058,-7.5e-05,-0.016,0.039,-0.11,0.21,-0.00091,0.43,-0.00017,0.00025,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00097,0.057,0.075,0.0055,0.49,0.5,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8.1e-05,1.1e-05,3.3e-05,0.00036,6e-06,5.2e-06,0.00036,1,1,0.01 -35690000,-0.67,-0.013,-0.0038,0.74,0.79,0.64,-0.091,-16,-7.9,-3.7e+02,-0.0016,-0.0058,-7.6e-05,-0.016,0.04,-0.11,0.21,-0.00093,0.43,-9.2e-05,0.00024,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00097,0.062,0.08,0.0056,0.51,0.52,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8.1e-05,1e-05,3.3e-05,0.00036,5.8e-06,5e-06,0.00036,1,1,0.01 -35790000,-0.67,-0.013,-0.0038,0.74,0.82,0.68,-0.089,-16,-7.8,-3.7e+02,-0.0016,-0.0058,-7.7e-05,-0.016,0.04,-0.11,0.21,-0.00093,0.43,-6.7e-05,0.00023,0.0036,0,0,-3.7e+02,4.2e-05,4.2e-05,0.00097,0.067,0.086,0.0056,0.53,0.54,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.6e-06,4.8e-06,0.00036,1,1,0.023 -35890000,-0.67,-0.013,-0.0039,0.74,0.85,0.72,-0.085,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-7.8e-05,-0.016,0.04,-0.11,0.21,-0.00093,0.43,-5.2e-05,0.00022,0.0037,0,0,-3.7e+02,4.2e-05,4.2e-05,0.00097,0.072,0.092,0.0056,0.55,0.56,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.4e-06,4.6e-06,0.00036,1,1,0.048 -35990000,-0.67,-0.013,-0.0038,0.74,0.88,0.76,-0.082,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-7.7e-05,-0.016,0.04,-0.11,0.21,-0.00093,0.43,-7.7e-05,0.00021,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.078,0.098,0.0056,0.57,0.59,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,9.8e-06,3.3e-05,0.00036,5.3e-06,4.5e-06,0.00036,1,1,0.073 -36090000,-0.68,-0.013,-0.0038,0.74,0.91,0.81,-0.079,-16,-7.6,-3.7e+02,-0.0016,-0.0058,-7.9e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-4.2e-05,0.00019,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.083,0.11,0.0056,0.6,0.62,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,9.7e-06,3.3e-05,0.00036,5.2e-06,4.3e-06,0.00036,1,1,0.099 -36190000,-0.68,-0.013,-0.0038,0.74,0.94,0.85,-0.074,-16,-7.5,-3.7e+02,-0.0016,-0.0058,-8.3e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,5.5e-05,0.00018,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.089,0.11,0.0056,0.63,0.65,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.5e-06,3.3e-05,0.00036,5e-06,4.2e-06,0.00036,1,1,0.12 +35290000,-0.67,-0.013,-0.0038,0.74,0.66,0.47,-0.099,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-7.1e-05,-0.016,0.039,-0.11,0.21,-0.00089,0.43,-0.00033,0.00032,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00098,0.044,0.06,0.0055,0.44,0.45,0.03,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.1e-05,3.3e-05,0.00036,6.8e-06,6.1e-06,0.00036,1,1,0.01 +35390000,-0.67,-0.013,-0.0038,0.74,0.69,0.51,-0.096,-17,-8,-3.7e+02,-0.0016,-0.0058,-7.3e-05,-0.016,0.039,-0.11,0.21,-0.00091,0.43,-0.00023,0.00029,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00098,0.048,0.064,0.0055,0.46,0.47,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.1e-05,3.3e-05,0.00036,6.5e-06,5.8e-06,0.00036,1,1,0.01 +35490000,-0.67,-0.013,-0.0038,0.74,0.73,0.56,-0.095,-17,-8,-3.7e+02,-0.0016,-0.0058,-7.6e-05,-0.016,0.039,-0.11,0.21,-0.00092,0.43,-0.00014,0.00024,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00097,0.053,0.069,0.0055,0.47,0.48,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.1e-05,3.3e-05,0.00036,6.2e-06,5.5e-06,0.00036,1,1,0.01 +35590000,-0.67,-0.013,-0.0038,0.74,0.76,0.6,-0.094,-16,-7.9,-3.7e+02,-0.0016,-0.0058,-7.5e-05,-0.016,0.039,-0.11,0.21,-0.00091,0.43,-0.00017,0.00025,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00097,0.057,0.075,0.0055,0.49,0.5,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1.1e-05,3.3e-05,0.00036,6e-06,5.2e-06,0.00036,1,1,0.01 +35690000,-0.67,-0.013,-0.0038,0.74,0.79,0.64,-0.092,-16,-7.9,-3.7e+02,-0.0016,-0.0058,-7.6e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-9.2e-05,0.00024,0.0036,0,0,-3.7e+02,4.2e-05,4.1e-05,0.00097,0.062,0.08,0.0056,0.51,0.52,0.031,2.4e-07,2.5e-07,7.4e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.8e-06,5e-06,0.00036,1,1,0.01 +35790000,-0.67,-0.013,-0.0038,0.74,0.82,0.68,-0.089,-16,-7.8,-3.7e+02,-0.0016,-0.0058,-7.7e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-6.7e-05,0.00023,0.0036,0,0,-3.7e+02,4.2e-05,4.2e-05,0.00097,0.067,0.086,0.0056,0.53,0.54,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.6e-06,4.8e-06,0.00036,1,1,0.023 +35890000,-0.67,-0.013,-0.0038,0.74,0.85,0.72,-0.086,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-7.8e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-5.2e-05,0.00022,0.0037,0,0,-3.7e+02,4.2e-05,4.2e-05,0.00097,0.072,0.092,0.0056,0.55,0.56,0.031,2.4e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,1e-05,3.3e-05,0.00036,5.4e-06,4.6e-06,0.00036,1,1,0.048 +35990000,-0.67,-0.013,-0.0038,0.74,0.88,0.76,-0.083,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-7.7e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-7.7e-05,0.00021,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.078,0.098,0.0056,0.57,0.59,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,8e-05,9.8e-06,3.3e-05,0.00036,5.3e-06,4.5e-06,0.00036,1,1,0.073 +36090000,-0.68,-0.013,-0.0038,0.74,0.91,0.81,-0.079,-16,-7.6,-3.7e+02,-0.0016,-0.0058,-7.9e-05,-0.016,0.039,-0.11,0.21,-0.00093,0.43,-4.2e-05,0.00019,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.083,0.11,0.0056,0.6,0.62,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.7e-06,3.3e-05,0.00036,5.2e-06,4.3e-06,0.00036,1,1,0.099 +36190000,-0.68,-0.013,-0.0038,0.74,0.94,0.85,-0.075,-16,-7.5,-3.7e+02,-0.0016,-0.0058,-8.3e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,5.5e-05,0.00018,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.089,0.11,0.0056,0.63,0.65,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.5e-06,3.3e-05,0.00036,5e-06,4.2e-06,0.00036,1,1,0.12 36290000,-0.68,-0.013,-0.0038,0.74,0.97,0.89,-0.07,-16,-7.4,-3.7e+02,-0.0016,-0.0058,-8.4e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,7.5e-05,0.00018,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.095,0.12,0.0056,0.66,0.68,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.4e-06,3.3e-05,0.00036,4.9e-06,4.1e-06,0.00036,1,1,0.15 -36390000,-0.68,-0.013,-0.0038,0.74,1,0.93,-0.067,-16,-7.3,-3.7e+02,-0.0016,-0.0058,-8.4e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,7.3e-05,0.00022,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.1,0.13,0.0056,0.69,0.72,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.9e-05,9.3e-06,3.3e-05,0.00036,4.8e-06,3.9e-06,0.00036,1,1,0.17 -36490000,-0.68,-0.013,-0.0038,0.74,1,0.97,-0.063,-16,-7.2,-3.7e+02,-0.0016,-0.0058,-8.2e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,4.3e-05,0.00023,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.11,0.13,0.0056,0.72,0.76,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.2e-06,3.3e-05,0.00036,4.7e-06,3.8e-06,0.00036,1,1,0.2 +36390000,-0.68,-0.013,-0.0038,0.74,1,0.93,-0.067,-16,-7.3,-3.7e+02,-0.0016,-0.0058,-8.4e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,7.3e-05,0.00022,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.1,0.13,0.0056,0.69,0.72,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.3e-06,3.3e-05,0.00036,4.8e-06,3.9e-06,0.00036,1,1,0.17 +36490000,-0.68,-0.013,-0.0038,0.74,1,0.97,-0.063,-16,-7.2,-3.7e+02,-0.0016,-0.0058,-8.3e-05,-0.016,0.039,-0.11,0.21,-0.00095,0.43,4.3e-05,0.00023,0.0037,0,0,-3.7e+02,4.3e-05,4.2e-05,0.00096,0.11,0.13,0.0056,0.72,0.76,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.2e-06,3.3e-05,0.00036,4.7e-06,3.8e-06,0.00036,1,1,0.2 36590000,-0.68,-0.013,-0.0038,0.74,1.1,1,-0.057,-16,-7.1,-3.7e+02,-0.0016,-0.0058,-8.5e-05,-0.015,0.039,-0.11,0.21,-0.00096,0.43,9.1e-05,0.00025,0.0037,0,0,-3.7e+02,4.3e-05,4.3e-05,0.00096,0.12,0.14,0.0056,0.76,0.8,0.031,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9.1e-06,3.3e-05,0.00036,4.6e-06,3.7e-06,0.00036,1,1,0.23 -36690000,-0.68,-0.013,-0.0038,0.74,1.1,1.1,-0.052,-15,-7,-3.7e+02,-0.0016,-0.0058,-8.7e-05,-0.015,0.039,-0.11,0.21,-0.00096,0.43,0.00012,0.00026,0.0037,0,0,-3.7e+02,4.3e-05,4.3e-05,0.00096,0.12,0.15,0.0057,0.8,0.84,0.032,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9e-06,3.3e-05,0.00036,4.6e-06,3.6e-06,0.00036,1,1,0.25 -36790000,-0.68,-0.013,-0.0038,0.74,1.1,1.1,-0.046,-15,-6.9,-3.7e+02,-0.0016,-0.0058,-9.1e-05,-0.015,0.038,-0.11,0.21,-0.00097,0.43,0.00017,0.00022,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.13,0.16,0.0057,0.84,0.9,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.8e-05,8.9e-06,3.3e-05,0.00036,4.5e-06,3.5e-06,0.00036,1,1,0.28 -36890000,-0.68,-0.013,-0.0037,0.74,1.2,1.1,-0.042,-15,-6.8,-3.7e+02,-0.0016,-0.0058,-9.4e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00021,0.00022,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.14,0.17,0.0057,0.89,0.95,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.8e-06,3.3e-05,0.00036,4.4e-06,3.4e-06,0.00035,1,1,0.3 +36690000,-0.68,-0.013,-0.0038,0.74,1.1,1.1,-0.053,-15,-7,-3.7e+02,-0.0016,-0.0058,-8.7e-05,-0.015,0.039,-0.11,0.21,-0.00096,0.43,0.00012,0.00026,0.0037,0,0,-3.7e+02,4.3e-05,4.3e-05,0.00096,0.12,0.15,0.0057,0.8,0.84,0.032,2.5e-07,2.6e-07,7.5e-07,0.003,0.0031,7.8e-05,9e-06,3.3e-05,0.00036,4.6e-06,3.6e-06,0.00036,1,1,0.25 +36790000,-0.68,-0.013,-0.0037,0.74,1.1,1.1,-0.047,-15,-6.9,-3.7e+02,-0.0016,-0.0058,-9.1e-05,-0.015,0.038,-0.11,0.21,-0.00097,0.43,0.00017,0.00022,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.13,0.16,0.0057,0.84,0.9,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.9e-06,3.3e-05,0.00036,4.5e-06,3.5e-06,0.00036,1,1,0.28 +36890000,-0.68,-0.013,-0.0037,0.74,1.2,1.1,-0.042,-15,-6.8,-3.7e+02,-0.0016,-0.0058,-9.4e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00021,0.00022,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.14,0.17,0.0056,0.89,0.95,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.8e-06,3.3e-05,0.00036,4.4e-06,3.4e-06,0.00035,1,1,0.3 36990000,-0.68,-0.013,-0.0037,0.74,1.2,1.2,-0.037,-15,-6.7,-3.7e+02,-0.0016,-0.0058,-9.5e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00023,0.00023,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.15,0.18,0.0057,0.94,1,0.032,2.5e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.7e-06,3.3e-05,0.00036,4.3e-06,3.4e-06,0.00035,1,1,0.33 37090000,-0.68,-0.013,-0.0036,0.74,1.2,1.2,-0.031,-15,-6.6,-3.7e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00023,0.00026,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.15,0.18,0.0057,1,1.1,0.032,2.6e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.6e-06,3.3e-05,0.00036,4.3e-06,3.3e-06,0.00035,1,1,0.35 -37190000,-0.68,-0.013,-0.0036,0.74,1.3,1.3,-0.025,-15,-6.4,-3.7e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00023,0.00026,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.16,0.19,0.0057,1.1,1.1,0.032,2.6e-07,2.7e-07,7.5e-07,0.003,0.0031,7.7e-05,8.5e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00035,1,1,0.38 +37190000,-0.68,-0.013,-0.0036,0.74,1.3,1.3,-0.025,-15,-6.4,-3.7e+02,-0.0016,-0.0058,-9.6e-05,-0.015,0.038,-0.11,0.21,-0.00098,0.43,0.00023,0.00026,0.0037,0,0,-3.7e+02,4.4e-05,4.3e-05,0.00096,0.16,0.19,0.0057,1.1,1.1,0.032,2.6e-07,2.7e-07,7.5e-07,0.003,0.0031,7.6e-05,8.5e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00035,1,1,0.38 37290000,-0.68,-0.013,-0.0036,0.74,1.3,1.3,-0.02,-15,-6.3,-3.7e+02,-0.0016,-0.0058,-9.7e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00024,0.00026,0.0037,0,0,-3.7e+02,4.4e-05,4.4e-05,0.00096,0.17,0.2,0.0057,1.1,1.2,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.5e-06,3.3e-05,0.00036,4.2e-06,3.2e-06,0.00035,1,1,0.41 37390000,-0.68,-0.013,-0.0036,0.74,1.3,1.4,-0.015,-15,-6.2,-3.7e+02,-0.0016,-0.0058,-9.9e-05,-0.015,0.038,-0.11,0.21,-0.00099,0.43,0.00027,0.00027,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.18,0.21,0.0057,1.2,1.3,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.4e-06,3.3e-05,0.00036,4.1e-06,3.1e-06,0.00035,1,1,0.43 -37490000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0089,-14,-6,-3.7e+02,-0.0016,-0.0058,-0.0001,-0.015,0.038,-0.11,0.21,-0.001,0.43,0.0003,0.0003,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.19,0.22,0.0057,1.3,1.4,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.3e-06,3.3e-05,0.00036,4.1e-06,3e-06,0.00035,1,1,0.46 -37590000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0024,-14,-5.9,-3.7e+02,-0.0016,-0.0058,-0.0001,-0.015,0.038,-0.11,0.21,-0.001,0.43,0.00032,0.0003,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.2,0.23,0.0057,1.3,1.5,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.3e-06,3.3e-05,0.00036,4e-06,3e-06,0.00035,1,1,0.48 -37690000,-0.68,-0.013,-0.0035,0.74,1.4,1.5,0.0049,-14,-5.7,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00033,0.00029,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.21,0.24,0.0057,1.4,1.6,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00035,1,1,0.51 +37490000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0093,-14,-6,-3.7e+02,-0.0016,-0.0058,-0.0001,-0.015,0.038,-0.11,0.21,-0.001,0.43,0.0003,0.0003,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.19,0.22,0.0057,1.3,1.4,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.6e-05,8.3e-06,3.3e-05,0.00036,4.1e-06,3e-06,0.00035,1,1,0.46 +37590000,-0.68,-0.013,-0.0035,0.74,1.4,1.4,-0.0027,-14,-5.9,-3.7e+02,-0.0016,-0.0058,-0.0001,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00032,0.0003,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.2,0.23,0.0057,1.3,1.5,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.3e-06,3.3e-05,0.00036,4e-06,3e-06,0.00035,1,1,0.48 +37690000,-0.68,-0.013,-0.0035,0.74,1.4,1.5,0.0046,-14,-5.7,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00033,0.00029,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.21,0.24,0.0057,1.4,1.6,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00035,1,1,0.51 37790000,-0.68,-0.013,-0.0036,0.74,1.5,1.5,0.012,-14,-5.6,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00034,0.0003,0.0037,0,0,-3.7e+02,4.5e-05,4.4e-05,0.00096,0.22,0.25,0.0056,1.5,1.7,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.2e-06,3.3e-05,0.00036,4e-06,2.9e-06,0.00035,1,1,0.54 -37890000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.018,-14,-5.4,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00035,0.00028,0.0038,0,0,-3.7e+02,4.5e-05,4.5e-05,0.00096,0.23,0.27,0.0056,1.6,1.8,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.56 -37990000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.025,-14,-5.3,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00035,0.00028,0.0037,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.24,0.28,0.0057,1.7,1.9,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.5e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.59 +37890000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.017,-14,-5.4,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00035,0.00028,0.0038,0,0,-3.7e+02,4.5e-05,4.5e-05,0.00096,0.23,0.27,0.0056,1.6,1.8,0.032,2.6e-07,2.7e-07,7.6e-07,0.003,0.0031,7.5e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.56 +37990000,-0.68,-0.013,-0.0036,0.74,1.5,1.6,0.025,-14,-5.3,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.015,0.037,-0.11,0.21,-0.001,0.43,0.00035,0.00028,0.0037,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.24,0.28,0.0056,1.7,1.9,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8.1e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.59 38090000,-0.68,-0.013,-0.0036,0.74,1.5,1.7,0.034,-14,-5.1,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00037,0.00029,0.0037,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.25,0.29,0.0056,1.8,2,0.032,2.6e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.9e-06,2.8e-06,0.00035,1,1,0.61 38190000,-0.68,-0.013,-0.0035,0.74,1.6,1.7,0.04,-13,-4.9,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00029,0.0038,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.26,0.3,0.0056,1.9,2.2,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,8e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00035,1,1,0.64 -38290000,-0.68,-0.013,-0.0035,0.74,1.6,1.7,0.047,-13,-4.7,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00027,0.0038,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.27,0.31,0.0056,2.1,2.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00035,1,1,0.67 -38390000,-0.68,-0.013,-0.0035,0.74,1.6,1.8,0.052,-13,-4.6,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00029,0.0037,0,0,-3.7e+02,4.6e-05,4.6e-05,0.00096,0.28,0.32,0.0056,2.2,2.5,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00035,1,1,0.69 +38290000,-0.68,-0.013,-0.0035,0.74,1.6,1.7,0.046,-13,-4.7,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00027,0.0038,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.27,0.31,0.0056,2.1,2.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.4e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.7e-06,0.00035,1,1,0.67 +38390000,-0.68,-0.013,-0.0035,0.74,1.6,1.8,0.052,-13,-4.6,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00029,0.0037,0,0,-3.7e+02,4.6e-05,4.5e-05,0.00096,0.28,0.32,0.0056,2.2,2.5,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00035,1,1,0.69 38490000,-0.68,-0.013,-0.0035,0.74,1.7,1.8,0.058,-13,-4.4,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00031,0.0037,0,0,-3.7e+02,4.7e-05,4.6e-05,0.00096,0.29,0.34,0.0056,2.3,2.6,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.9e-06,3.3e-05,0.00036,3.8e-06,2.6e-06,0.00035,1,1,0.72 -38590000,-0.68,-0.013,-0.0034,0.74,1.7,1.9,0.064,-13,-4.2,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00032,0.0037,0,0,-3.7e+02,4.7e-05,4.6e-05,0.00097,0.3,0.35,0.0056,2.5,2.8,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.6e-06,0.00035,1,1,0.75 +38590000,-0.68,-0.013,-0.0034,0.74,1.7,1.9,0.063,-13,-4.2,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00038,0.00032,0.0037,0,0,-3.7e+02,4.7e-05,4.6e-05,0.00097,0.3,0.35,0.0056,2.5,2.8,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.6e-06,0.00035,1,1,0.75 38690000,-0.68,-0.013,-0.0034,0.74,1.7,1.9,0.069,-13,-4,-3.7e+02,-0.0016,-0.0058,-0.00011,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.00039,0.00034,0.0037,0,0,-3.7e+02,4.7e-05,4.6e-05,0.00097,0.31,0.36,0.0056,2.6,3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.77 -38790000,-0.68,-0.013,-0.0034,0.74,1.8,1.9,0.075,-12,-3.8,-3.7e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.0004,0.00033,0.0037,0,0,-3.7e+02,4.7e-05,4.6e-05,0.00097,0.33,0.38,0.0056,2.8,3.1,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.3e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.8 +38790000,-0.68,-0.013,-0.0034,0.74,1.8,1.9,0.075,-12,-3.8,-3.7e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.0004,0.00033,0.0037,0,0,-3.7e+02,4.7e-05,4.6e-05,0.00097,0.33,0.38,0.0056,2.8,3.1,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.2e-05,7.8e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.8 38890000,-0.68,-0.014,-0.0035,0.74,1.8,2,0.57,-12,-3.6,-3.7e+02,-0.0016,-0.0058,-0.00012,-0.014,0.037,-0.11,0.21,-0.001,0.43,0.0004,0.0003,0.0037,0,0,-3.7e+02,4.8e-05,4.7e-05,0.00097,0.33,0.39,0.0056,3,3.3,0.032,2.7e-07,2.8e-07,7.6e-07,0.003,0.0031,7.2e-05,7.7e-06,3.3e-05,0.00036,3.7e-06,2.5e-06,0.00035,1,1,0.83 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index 3c42e668968b..a63e88ee9de4 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -103,249 +103,249 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 10090000,0.98,-0.0067,-0.012,0.18,0.00073,0.019,0.00023,0.00018,0.03,-0.029,-0.0013,-0.0058,-0.00011,-0.00036,0.00036,-0.14,0.2,-4.9e-06,0.43,-9.7e-05,-0.00025,-0.00015,0,0,0.095,0.0022,0.0017,0.041,7.4,7.5,0.013,21,21,0.048,4e-05,3.1e-05,2.2e-06,0.04,0.04,0.00059,0.0013,4.2e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 10190000,0.98,-0.0072,-0.012,0.18,0.0053,0.0047,0.0011,0.0043,0.022,-0.03,-0.0011,-0.0058,-0.00012,-0.00036,0.00036,-0.14,0.2,-3.3e-06,0.43,-9.1e-05,-0.00012,-0.00015,0,0,0.095,0.0022,0.0016,0.041,7.4,7.6,0.012,23,23,0.048,3.9e-05,2.9e-05,2.2e-06,0.04,0.04,0.00057,0.0013,4.1e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 10290000,0.98,-0.0071,-0.012,0.18,0.012,0.0085,3e-05,0.008,0.023,-0.029,-0.0012,-0.0057,-0.00011,-0.00036,0.00036,-0.14,0.2,-3.7e-06,0.43,-0.00016,-0.00011,-0.00012,0,0,0.095,0.0022,0.0016,0.041,6.4,6.5,0.012,20,20,0.048,3.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 -10390000,0.98,-0.0071,-0.012,0.18,0.0076,0.0026,-0.0025,0.00078,3e-05,-0.028,-0.0012,-0.0056,-0.00011,-0.0003,0.00041,-0.14,0.2,-3.9e-06,0.43,-0.0002,-0.00011,-6.5e-05,0,0,0.095,0.0022,0.0016,0.041,0.25,0.25,0.56,0.25,0.25,0.048,3.6e-05,2.7e-05,2.2e-06,0.04,0.04,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 -10490000,0.98,-0.0073,-0.012,0.18,0.0096,0.00083,0.0071,0.0016,0.00011,-0.023,-0.0011,-0.0057,-0.00011,-0.00035,0.00028,-0.14,0.2,-3e-06,0.43,-0.00016,-6e-05,-8.7e-05,0,0,0.095,0.0021,0.0016,0.041,0.25,0.26,0.55,0.26,0.26,0.057,3.5e-05,2.5e-05,2.2e-06,0.04,0.04,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10590000,0.98,-0.007,-0.012,0.18,0.00028,-0.00035,0.013,-0.0011,-0.0055,-0.021,-0.0012,-0.0056,-0.00011,-0.00031,0.00026,-0.14,0.2,-3.6e-06,0.43,-0.00018,-9.8e-05,-7.3e-05,0,0,0.095,0.0021,0.0015,0.041,0.13,0.13,0.27,0.13,0.13,0.055,3.3e-05,2.4e-05,2.2e-06,0.04,0.04,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10690000,0.98,-0.0071,-0.013,0.18,0.0031,-0.0029,0.016,-0.0009,-0.0057,-0.018,-0.0011,-0.0056,-0.00011,-0.00028,0.00019,-0.14,0.2,-3.3e-06,0.43,-0.00021,-4.9e-05,-7e-05,0,0,0.095,0.0021,0.0015,0.041,0.13,0.14,0.26,0.14,0.14,0.065,3.2e-05,2.3e-05,2.2e-06,0.04,0.04,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10790000,0.98,-0.0073,-0.013,0.18,0.0057,-0.0061,0.014,-0.00055,-0.005,-0.015,-0.0011,-0.0056,-0.00011,-0.00017,8.6e-05,-0.14,0.2,-3.2e-06,0.43,-0.00026,1.2e-05,-9e-05,0,0,0.095,0.002,0.0014,0.041,0.09,0.094,0.17,0.09,0.09,0.062,3e-05,2.1e-05,2.2e-06,0.04,0.04,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 -10890000,0.98,-0.0069,-0.013,0.18,0.008,-0.003,0.01,0.00021,-0.0052,-0.018,-0.0012,-0.0055,-0.00011,-6.9e-05,0.00021,-0.14,0.2,-4.1e-06,0.43,-0.00033,-3.1e-05,-7.2e-05,0,0,0.095,0.002,0.0014,0.041,0.096,0.1,0.16,0.096,0.096,0.068,2.9e-05,2e-05,2.2e-06,0.04,0.04,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -10990000,0.98,-0.0069,-0.013,0.18,0.0054,0.0031,0.016,-0.00022,-0.0036,-0.012,-0.0012,-0.0056,-0.00011,-0.00022,0.00016,-0.14,0.2,-4.1e-06,0.43,-0.00026,-6e-05,-0.00012,0,0,0.095,0.0019,0.0014,0.041,0.074,0.081,0.12,0.072,0.072,0.065,2.6e-05,1.9e-05,2.2e-06,0.04,0.04,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -11090000,0.98,-0.0075,-0.013,0.18,0.0093,0.0016,0.02,0.00071,-0.0039,-0.0075,-0.0011,-0.0056,-0.00011,-0.00031,-4.4e-05,-0.14,0.2,-2.9e-06,0.43,-0.00024,2.4e-05,-0.0001,0,0,0.095,0.0019,0.0013,0.041,0.081,0.092,0.11,0.078,0.078,0.069,2.6e-05,1.8e-05,2.2e-06,0.04,0.04,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -11190000,0.98,-0.0077,-0.013,0.18,0.0082,0.0022,0.026,0.0013,-0.0032,-0.00043,-0.001,-0.0056,-0.00012,-0.00044,2e-06,-0.14,0.2,-2.4e-06,0.43,-0.00017,-2e-06,-0.00012,0,0,0.095,0.0017,0.0013,0.04,0.066,0.075,0.083,0.062,0.062,0.066,2.2e-05,1.6e-05,2.2e-06,0.04,0.04,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 -11290000,0.98,-0.0077,-0.012,0.18,0.0065,-0.00033,0.026,0.0016,-0.0032,-0.00019,-0.001,-0.0057,-0.00012,-0.00054,0.00012,-0.14,0.2,-2.2e-06,0.43,-0.0001,-4.1e-05,-0.00015,0,0,0.095,0.0017,0.0012,0.04,0.074,0.088,0.077,0.067,0.068,0.069,2.2e-05,1.5e-05,2.2e-06,0.04,0.04,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11390000,0.98,-0.0076,-0.012,0.18,0.0045,0.00078,0.016,0.0009,-0.0025,-0.0086,-0.001,-0.0057,-0.00012,-0.00056,3e-05,-0.14,0.2,-2.3e-06,0.43,-7.8e-05,-5.1e-05,-0.00018,0,0,0.095,0.0015,0.0012,0.04,0.062,0.073,0.062,0.056,0.056,0.066,1.9e-05,1.3e-05,2.2e-06,0.04,0.04,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11490000,0.98,-0.0075,-0.012,0.18,0.0052,-0.00073,0.02,0.0016,-0.0025,-0.0025,-0.001,-0.0057,-0.00012,-0.00054,-5.2e-05,-0.14,0.2,-2.3e-06,0.43,-0.0001,-3e-05,-0.00017,0,0,0.095,0.0015,0.0011,0.04,0.07,0.086,0.057,0.061,0.062,0.067,1.8e-05,1.3e-05,2.2e-06,0.04,0.039,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11590000,0.98,-0.0076,-0.012,0.18,0.0047,-0.00064,0.018,0.00077,-0.002,-0.0036,-0.001,-0.0058,-0.00012,-0.00063,4.1e-05,-0.14,0.2,-2.3e-06,0.43,-5.1e-05,-7e-05,-0.00019,0,0,0.095,0.0014,0.0011,0.04,0.06,0.072,0.048,0.052,0.052,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 -11690000,0.98,-0.0075,-0.012,0.18,0.0041,0.0018,0.018,0.00093,-0.0018,-0.005,-0.0011,-0.0058,-0.00012,-0.00059,0.00016,-0.14,0.2,-2.5e-06,0.43,-4.5e-05,-8.6e-05,-0.00022,0,0,0.095,0.0014,0.001,0.04,0.068,0.084,0.044,0.058,0.059,0.066,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -11790000,0.98,-0.0075,-0.012,0.18,0.0028,0.0026,0.019,0.00044,-0.0024,-0.002,-0.0011,-0.0058,-0.00012,-6.6e-05,0.00012,-0.14,0.2,-2.6e-06,0.43,-5.7e-05,-9.1e-05,-0.00022,0,0,0.095,0.0012,0.00096,0.039,0.058,0.07,0.037,0.049,0.05,0.063,1.2e-05,9.4e-06,2.2e-06,0.039,0.039,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -11890000,0.98,-0.0077,-0.012,0.18,0.0039,0.0013,0.017,0.0003,-0.0026,-0.0013,-0.0011,-0.0058,-0.00012,-0.00027,0.00028,-0.14,0.2,-2.4e-06,0.43,-2.7e-05,-9.2e-05,-0.00026,0,0,0.095,0.0012,0.00095,0.039,0.066,0.082,0.034,0.056,0.057,0.063,1.2e-05,9.1e-06,2.2e-06,0.039,0.039,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -11990000,0.98,-0.0077,-0.012,0.18,0.0067,0.0035,0.015,0.0014,-0.0027,-0.005,-0.0011,-0.0058,-0.00012,-0.00034,0.00044,-0.14,0.2,-2.7e-06,0.43,-4.5e-05,-9.9e-05,-0.00026,0,0,0.095,0.0011,0.00088,0.039,0.056,0.068,0.03,0.048,0.049,0.061,1e-05,7.9e-06,2.2e-06,0.039,0.039,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 -12090000,0.98,-0.0077,-0.012,0.18,0.0099,0.001,0.018,0.0028,-0.0029,0.0011,-0.001,-0.0058,-0.00012,-0.00053,0.00019,-0.14,0.2,-2.4e-06,0.43,-4.4e-05,-6.6e-05,-0.00025,0,0,0.095,0.0011,0.00088,0.039,0.064,0.079,0.027,0.054,0.056,0.06,9.9e-06,7.6e-06,2.2e-06,0.039,0.039,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12190000,0.98,-0.0077,-0.012,0.18,0.011,-0.00015,0.017,0.0025,-0.0017,0.0029,-0.001,-0.0058,-0.00012,-0.0012,-0.00046,-0.14,0.2,-2.3e-06,0.43,-7.3e-06,-3.1e-05,-0.00028,0,0,0.095,0.00094,0.00081,0.039,0.055,0.065,0.024,0.047,0.048,0.058,8.3e-06,6.6e-06,2.2e-06,0.039,0.039,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12290000,0.98,-0.0078,-0.012,0.18,0.0081,-0.0036,0.016,0.0032,-0.0024,0.0039,-0.001,-0.0058,-0.00013,-0.0015,-0.00029,-0.14,0.2,-2.1e-06,0.43,2e-05,-3.9e-05,-0.00028,0,0,0.095,0.00094,0.00081,0.039,0.062,0.075,0.022,0.053,0.055,0.058,8.2e-06,6.4e-06,2.2e-06,0.039,0.038,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12390000,0.98,-0.0079,-0.012,0.18,0.008,-0.0049,0.014,0.0027,-0.0021,-0.0021,-0.001,-0.0058,-0.00013,-0.0018,-0.00077,-0.14,0.2,-2e-06,0.43,4.7e-05,-1.8e-05,-0.0003,0,0,0.095,0.00084,0.00075,0.039,0.053,0.062,0.02,0.046,0.047,0.056,6.8e-06,5.5e-06,2.2e-06,0.039,0.038,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 -12490000,0.98,-0.008,-0.012,0.18,0.0097,-0.0064,0.018,0.0041,-0.0031,-6.2e-05,-0.00099,-0.0058,-0.00013,-0.0021,-0.001,-0.14,0.2,-1.9e-06,0.43,5.5e-05,1.2e-05,-0.00031,0,0,0.095,0.00085,0.00074,0.039,0.06,0.071,0.018,0.053,0.055,0.055,6.7e-06,5.4e-06,2.1e-06,0.039,0.038,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12590000,0.98,-0.008,-0.012,0.18,0.012,-0.01,0.02,0.0043,-0.0042,0.0017,-0.00098,-0.0058,-0.00013,-0.0023,-0.00089,-0.14,0.2,-1.8e-06,0.43,6.9e-05,1.2e-05,-0.00032,0,0,0.095,0.00077,0.00069,0.039,0.051,0.059,0.017,0.046,0.047,0.054,5.7e-06,4.7e-06,2.1e-06,0.039,0.038,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12690000,0.98,-0.008,-0.012,0.18,0.012,-0.014,0.019,0.0054,-0.0056,0.0033,-0.00097,-0.0058,-0.00013,-0.0025,-0.00083,-0.14,0.2,-1.8e-06,0.43,7.8e-05,1.6e-05,-0.00033,0,0,0.095,0.00077,0.00069,0.039,0.057,0.067,0.015,0.053,0.054,0.053,5.6e-06,4.6e-06,2.1e-06,0.039,0.038,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12790000,0.98,-0.0081,-0.012,0.18,0.014,-0.012,0.021,0.0054,-0.0062,0.0054,-0.00098,-0.0058,-0.00013,-0.0018,-0.0013,-0.14,0.2,-1.8e-06,0.43,4.4e-05,4e-05,-0.00031,0,0,0.095,0.0007,0.00065,0.039,0.049,0.056,0.014,0.046,0.047,0.051,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 -12890000,0.98,-0.008,-0.012,0.18,0.016,-0.013,0.022,0.0071,-0.007,0.0085,-0.00099,-0.0058,-0.00012,-0.0014,-0.0015,-0.14,0.2,-1.9e-06,0.43,2.4e-05,4.4e-05,-0.00029,0,0,0.095,0.0007,0.00065,0.039,0.055,0.063,0.013,0.052,0.054,0.051,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -12990000,0.98,-0.0079,-0.012,0.18,0.013,-0.0088,0.022,0.005,-0.0047,0.0096,-0.001,-0.0058,-0.00012,-0.0013,-0.0016,-0.14,0.2,-2.4e-06,0.43,3.8e-05,2e-05,-0.00032,0,0,0.095,0.00065,0.00061,0.038,0.047,0.053,0.012,0.046,0.047,0.05,4.1e-06,3.5e-06,2.1e-06,0.038,0.037,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -13090000,0.98,-0.0079,-0.012,0.18,0.015,-0.0077,0.02,0.0067,-0.0048,0.0085,-0.001,-0.0058,-0.00012,-0.00078,-0.0018,-0.14,0.2,-2.5e-06,0.43,1.5e-05,2.5e-05,-0.0003,0,0,0.095,0.00065,0.00061,0.038,0.052,0.059,0.011,0.052,0.054,0.049,4.1e-06,3.4e-06,2.1e-06,0.038,0.037,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -13190000,0.98,-0.0079,-0.012,0.18,0.0097,-0.0078,0.019,0.003,-0.0048,0.0091,-0.0011,-0.0058,-0.00012,-0.00056,-0.0023,-0.14,0.2,-2.6e-06,0.43,3.9e-05,2.3e-05,-0.00031,0,0,0.095,0.00061,0.00058,0.038,0.044,0.05,0.011,0.045,0.047,0.047,3.6e-06,3.1e-06,2.1e-06,0.038,0.037,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 -13290000,0.98,-0.0079,-0.012,0.18,0.011,-0.0095,0.016,0.0046,-0.0059,0.0085,-0.001,-0.0058,-0.00012,-0.00078,-0.0028,-0.14,0.2,-2.4e-06,0.43,4.8e-05,4.4e-05,-0.00031,0,0,0.095,0.00061,0.00058,0.038,0.049,0.055,0.01,0.052,0.054,0.047,3.5e-06,3e-06,2.1e-06,0.038,0.037,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13390000,0.98,-0.0079,-0.012,0.18,0.0091,-0.0081,0.016,0.0032,-0.0049,0.0091,-0.0011,-0.0058,-0.00012,-0.0015,-0.0028,-0.14,0.2,-2.7e-06,0.43,8.6e-05,4.1e-05,-0.00035,0,0,0.095,0.00057,0.00055,0.038,0.042,0.047,0.0094,0.045,0.046,0.046,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13490000,0.98,-0.0079,-0.012,0.18,0.011,-0.0068,0.015,0.0048,-0.0056,0.0053,-0.001,-0.0058,-0.00012,-0.0015,-0.0033,-0.14,0.2,-2.6e-06,0.43,8.9e-05,6.4e-05,-0.00035,0,0,0.095,0.00057,0.00055,0.038,0.047,0.052,0.009,0.052,0.053,0.045,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13590000,0.98,-0.0079,-0.012,0.18,0.014,-0.0071,0.017,0.0065,-0.0048,0.0038,-0.001,-0.0058,-0.00013,-0.002,-0.0034,-0.14,0.2,-2.6e-06,0.43,9.8e-05,5.7e-05,-0.00035,0,0,0.095,0.00054,0.00053,0.038,0.04,0.044,0.0085,0.045,0.046,0.044,2.8e-06,2.4e-06,2.1e-06,0.038,0.037,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 -13690000,0.98,-0.0078,-0.012,0.18,0.014,-0.0082,0.017,0.0077,-0.0052,0.0064,-0.0011,-0.0058,-0.00012,-0.0017,-0.0031,-0.14,0.2,-2.6e-06,0.43,8.5e-05,3.7e-05,-0.00033,0,0,0.095,0.00054,0.00053,0.038,0.044,0.049,0.0082,0.052,0.053,0.044,2.8e-06,2.4e-06,2.1e-06,0.038,0.036,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -13790000,0.98,-0.0077,-0.012,0.18,0.019,-0.0043,0.017,0.0098,-0.0027,0.0059,-0.0011,-0.0058,-0.00013,-0.0022,-0.0025,-0.14,0.2,-2.8e-06,0.43,8.3e-05,1.5e-05,-0.00034,0,0,0.095,0.00052,0.00051,0.038,0.038,0.042,0.0078,0.045,0.046,0.042,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -13890000,0.98,-0.0076,-0.012,0.18,0.019,-0.0029,0.018,0.011,-0.0025,0.0082,-0.0011,-0.0058,-0.00012,-0.0016,-0.002,-0.14,0.2,-3e-06,0.43,6.2e-05,-2.3e-08,-0.00034,0,0,0.095,0.00052,0.00051,0.038,0.042,0.046,0.0076,0.051,0.053,0.042,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -13990000,0.98,-0.0076,-0.012,0.18,0.019,-0.00099,0.017,0.0088,-0.003,0.0071,-0.0011,-0.0058,-0.00012,-0.001,-0.0024,-0.14,0.2,-2.9e-06,0.43,7e-05,-1.3e-06,-0.00031,0,0,0.095,0.0005,0.0005,0.038,0.036,0.039,0.0073,0.045,0.046,0.041,2.3e-06,2e-06,2.1e-06,0.037,0.036,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 -14090000,0.98,-0.0077,-0.011,0.18,0.017,-0.0082,0.018,0.011,-0.0049,0.0035,-0.0011,-0.0058,-0.00013,-0.0028,-0.0022,-0.14,0.2,-2.8e-06,0.43,0.00012,6.8e-06,-0.00035,0,0,0.095,0.0005,0.0005,0.038,0.04,0.043,0.0072,0.051,0.053,0.041,2.2e-06,2e-06,2.1e-06,0.037,0.036,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14190000,0.98,-0.0078,-0.011,0.18,0.016,-0.0075,0.018,0.01,-0.0045,0.0037,-0.001,-0.0058,-0.00014,-0.004,-0.0034,-0.14,0.2,-2.6e-06,0.43,0.00018,3.2e-05,-0.00037,0,0,0.095,0.00048,0.00048,0.038,0.034,0.037,0.007,0.045,0.046,0.04,2.1e-06,1.8e-06,2.1e-06,0.037,0.036,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14290000,0.98,-0.0077,-0.011,0.18,0.018,-0.0081,0.016,0.012,-0.0054,0.008,-0.001,-0.0058,-0.00014,-0.0041,-0.0036,-0.14,0.2,-2.6e-06,0.43,0.00018,3.6e-05,-0.00036,0,0,0.095,0.00048,0.00048,0.038,0.038,0.041,0.0069,0.051,0.052,0.039,2e-06,1.8e-06,2.1e-06,0.037,0.036,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14390000,0.98,-0.0078,-0.011,0.18,0.018,-0.0095,0.018,0.011,-0.0054,0.012,-0.001,-0.0058,-0.00014,-0.0039,-0.0044,-0.14,0.2,-2.4e-06,0.43,0.00019,4.1e-05,-0.00035,0,0,0.095,0.00047,0.00047,0.038,0.033,0.035,0.0067,0.045,0.046,0.039,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 -14490000,0.98,-0.008,-0.011,0.18,0.018,-0.011,0.021,0.013,-0.0073,0.015,-0.001,-0.0058,-0.00014,-0.0049,-0.0045,-0.14,0.2,-2.3e-06,0.43,0.00022,4.9e-05,-0.00037,0,0,0.095,0.00047,0.00047,0.038,0.036,0.038,0.0066,0.051,0.052,0.038,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14590000,0.98,-0.0081,-0.011,0.18,0.017,-0.01,0.019,0.0099,-0.0073,0.011,-0.001,-0.0058,-0.00015,-0.0055,-0.0058,-0.14,0.2,-2.1e-06,0.43,0.00027,6.8e-05,-0.00037,0,0,0.095,0.00045,0.00046,0.038,0.031,0.033,0.0065,0.045,0.045,0.038,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14690000,0.98,-0.0081,-0.011,0.18,0.017,-0.01,0.019,0.012,-0.0083,0.011,-0.001,-0.0058,-0.00014,-0.0054,-0.0062,-0.14,0.2,-2e-06,0.43,0.00027,7.5e-05,-0.00037,0,0,0.095,0.00045,0.00046,0.038,0.034,0.036,0.0065,0.05,0.051,0.037,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14790000,0.98,-0.0082,-0.011,0.18,0.019,-0.0033,0.019,0.01,-0.0022,0.014,-0.0011,-0.0058,-0.00014,-0.0047,-0.0076,-0.14,0.2,-2.2e-06,0.43,0.00027,7.3e-05,-0.00035,0,0,0.095,0.00044,0.00045,0.038,0.03,0.031,0.0064,0.044,0.045,0.036,1.7e-06,1.5e-06,2.1e-06,0.037,0.035,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 -14890000,0.98,-0.0082,-0.011,0.18,0.021,-0.0054,0.023,0.013,-0.0023,0.015,-0.0011,-0.0058,-0.00013,-0.0043,-0.0092,-0.14,0.2,-1.8e-06,0.43,0.00027,9.5e-05,-0.00031,0,0,0.095,0.00044,0.00045,0.038,0.032,0.034,0.0064,0.05,0.051,0.036,1.6e-06,1.5e-06,2.1e-06,0.037,0.035,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -14990000,0.98,-0.0083,-0.011,0.18,0.02,-0.0057,0.026,0.012,-0.0029,0.017,-0.0011,-0.0058,-0.00013,-0.0042,-0.011,-0.14,0.2,-1.5e-06,0.43,0.0003,0.00012,-0.00029,0,0,0.095,0.00043,0.00045,0.038,0.028,0.03,0.0064,0.044,0.045,0.036,1.6e-06,1.4e-06,2.1e-06,0.037,0.035,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -15090000,0.98,-0.0083,-0.011,0.18,0.021,-0.0049,0.03,0.014,-0.0036,0.019,-0.0011,-0.0058,-0.00013,-0.0043,-0.011,-0.14,0.2,-1.5e-06,0.43,0.0003,0.00013,-0.00029,0,0,0.095,0.00043,0.00045,0.038,0.03,0.032,0.0064,0.05,0.051,0.035,1.5e-06,1.4e-06,2.1e-06,0.037,0.035,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -15190000,0.98,-0.0085,-0.011,0.18,0.019,-0.0058,0.03,0.012,-0.0032,0.021,-0.0011,-0.0058,-0.00014,-0.0048,-0.012,-0.14,0.2,-1.4e-06,0.43,0.00034,0.00014,-0.00029,0,0,0.095,0.00043,0.00044,0.038,0.027,0.028,0.0064,0.044,0.045,0.035,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 -15290000,0.98,-0.0086,-0.012,0.18,0.022,-0.0065,0.03,0.015,-0.0034,0.018,-0.0011,-0.0058,-0.00013,-0.0043,-0.014,-0.14,0.2,-1.2e-06,0.43,0.00034,0.00017,-0.00027,0,0,0.095,0.00043,0.00044,0.038,0.029,0.031,0.0065,0.049,0.05,0.035,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15390000,0.98,-0.0088,-0.011,0.18,0.021,-0.0039,0.03,0.012,-0.0028,0.018,-0.0011,-0.0058,-0.00013,-0.0046,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00037,0.00019,-0.00029,0,0,0.095,0.00042,0.00043,0.038,0.025,0.027,0.0064,0.044,0.044,0.034,1.4e-06,1.3e-06,2.1e-06,0.036,0.034,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15490000,0.98,-0.0088,-0.011,0.18,0.022,-0.0067,0.03,0.014,-0.0034,0.019,-0.0011,-0.0058,-0.00013,-0.0046,-0.014,-0.14,0.2,-1.4e-06,0.43,0.00037,0.00019,-0.00029,0,0,0.095,0.00042,0.00043,0.038,0.028,0.029,0.0065,0.049,0.05,0.034,1.4e-06,1.2e-06,2.1e-06,0.036,0.034,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15590000,0.98,-0.0088,-0.011,0.18,0.023,-0.0081,0.029,0.014,-0.0059,0.018,-0.0011,-0.0058,-0.00013,-0.0043,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00037,0.00019,-0.00028,0,0,0.095,0.00041,0.00043,0.038,0.024,0.026,0.0065,0.043,0.044,0.034,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 -15690000,0.98,-0.0086,-0.011,0.18,0.024,-0.01,0.03,0.015,-0.0063,0.019,-0.0011,-0.0058,-0.00012,-0.0033,-0.012,-0.14,0.2,-1.8e-06,0.43,0.00032,0.00013,-0.00026,0,0,0.095,0.00041,0.00043,0.038,0.026,0.028,0.0066,0.049,0.049,0.034,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -15790000,0.98,-0.0086,-0.011,0.18,0.019,-0.0094,0.03,0.012,-0.0047,0.021,-0.0011,-0.0058,-0.00012,-0.0021,-0.011,-0.14,0.2,-2.2e-06,0.43,0.0003,0.00012,-0.00026,0,0,0.095,0.00041,0.00042,0.038,0.023,0.025,0.0066,0.043,0.044,0.033,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -15890000,0.98,-0.0087,-0.011,0.18,0.02,-0.0085,0.03,0.015,-0.0061,0.02,-0.0011,-0.0058,-0.00012,-0.0032,-0.012,-0.14,0.2,-1.9e-06,0.43,0.00034,0.00014,-0.00027,0,0,0.095,0.00041,0.00042,0.038,0.025,0.026,0.0067,0.048,0.049,0.034,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -15990000,0.98,-0.0086,-0.011,0.18,0.018,-0.0074,0.027,0.013,-0.0051,0.02,-0.0011,-0.0058,-0.00012,-0.0035,-0.014,-0.14,0.2,-2.1e-06,0.43,0.00038,0.00019,-0.00029,0,0,0.095,0.0004,0.00042,0.038,0.022,0.023,0.0068,0.043,0.043,0.033,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 -16090000,0.98,-0.0087,-0.011,0.18,0.019,-0.0092,0.025,0.015,-0.0062,0.02,-0.0011,-0.0058,-0.00013,-0.0041,-0.014,-0.14,0.2,-2e-06,0.43,0.00041,0.00021,-0.00031,0,0,0.095,0.0004,0.00042,0.038,0.024,0.025,0.0069,0.048,0.049,0.033,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16190000,0.98,-0.0086,-0.011,0.18,0.015,-0.0076,0.024,0.011,-0.0054,0.016,-0.0011,-0.0058,-0.00013,-0.0048,-0.015,-0.14,0.2,-2e-06,0.43,0.00044,0.00021,-0.00033,0,0,0.095,0.0004,0.00041,0.038,0.021,0.022,0.0069,0.043,0.043,0.033,1.2e-06,1e-06,2e-06,0.036,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16290000,0.98,-0.0086,-0.011,0.18,0.017,-0.009,0.024,0.013,-0.0061,0.018,-0.0011,-0.0058,-0.00013,-0.0045,-0.014,-0.14,0.2,-2e-06,0.43,0.00043,0.0002,-0.00032,0,0,0.095,0.0004,0.00041,0.038,0.023,0.024,0.007,0.047,0.048,0.033,1.2e-06,1e-06,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16390000,0.98,-0.0087,-0.011,0.18,0.019,-0.0081,0.024,0.013,-0.0047,0.018,-0.0011,-0.0058,-0.00013,-0.0041,-0.017,-0.14,0.2,-1.8e-06,0.43,0.00045,0.00024,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.021,0.022,0.007,0.042,0.043,0.033,1.1e-06,1e-06,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 -16490000,0.98,-0.0089,-0.011,0.18,0.022,-0.01,0.027,0.015,-0.0059,0.022,-0.0011,-0.0058,-0.00013,-0.0045,-0.017,-0.14,0.2,-1.5e-06,0.43,0.00046,0.00025,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.022,0.023,0.0072,0.047,0.048,0.033,1.1e-06,1e-06,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16590000,0.98,-0.0089,-0.011,0.18,0.026,-0.01,0.03,0.013,-0.0049,0.022,-0.0011,-0.0058,-0.00013,-0.0044,-0.018,-0.14,0.2,-1.7e-06,0.43,0.00048,0.00025,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.02,0.021,0.0072,0.042,0.042,0.033,1.1e-06,9.7e-07,2e-06,0.035,0.033,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16690000,0.98,-0.0089,-0.011,0.18,0.028,-0.015,0.03,0.016,-0.0059,0.023,-0.0011,-0.0058,-0.00013,-0.0038,-0.017,-0.14,0.2,-1.9e-06,0.43,0.00046,0.00024,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.021,0.022,0.0073,0.047,0.047,0.033,1.1e-06,9.6e-07,2e-06,0.035,0.033,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16790000,0.98,-0.0087,-0.011,0.18,0.028,-0.014,0.029,0.013,-0.0047,0.023,-0.0011,-0.0058,-0.00012,-0.0033,-0.017,-0.14,0.2,-2.2e-06,0.43,0.00046,0.00024,-0.00029,0,0,0.095,0.00038,0.0004,0.038,0.019,0.02,0.0073,0.042,0.042,0.033,1e-06,9.3e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 -16890000,0.98,-0.0087,-0.011,0.18,0.028,-0.014,0.03,0.016,-0.0055,0.022,-0.0011,-0.0058,-0.00012,-0.0022,-0.017,-0.14,0.2,-2.3e-06,0.43,0.00043,0.00023,-0.00028,0,0,0.095,0.00038,0.0004,0.038,0.02,0.022,0.0074,0.046,0.047,0.033,1e-06,9.2e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -16990000,0.98,-0.0088,-0.011,0.18,0.026,-0.014,0.03,0.014,-0.0046,0.02,-0.0011,-0.0058,-0.00011,-0.0019,-0.017,-0.14,0.2,-2.3e-06,0.43,0.00045,0.00025,-0.00028,0,0,0.095,0.00038,0.0004,0.038,0.018,0.019,0.0074,0.041,0.042,0.033,1e-06,9e-07,2e-06,0.035,0.032,0.00042,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -17090000,0.98,-0.0089,-0.011,0.18,0.03,-0.017,0.03,0.018,-0.0063,0.02,-0.0011,-0.0058,-0.00012,-0.0023,-0.019,-0.14,0.2,-2.4e-06,0.43,0.00048,0.00032,-0.00029,0,0,0.095,0.00038,0.0004,0.038,0.02,0.021,0.0075,0.046,0.046,0.033,9.9e-07,8.9e-07,2e-06,0.035,0.032,0.00042,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -17190000,0.98,-0.009,-0.011,0.18,0.028,-0.021,0.031,0.014,-0.0095,0.023,-0.0011,-0.0058,-0.00012,-0.0033,-0.019,-0.14,0.2,-2.9e-06,0.43,0.00053,0.00033,-0.00033,0,0,0.095,0.00038,0.0004,0.038,0.018,0.019,0.0076,0.041,0.042,0.033,9.6e-07,8.7e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 -17290000,0.98,-0.009,-0.011,0.18,0.031,-0.023,0.031,0.017,-0.012,0.023,-0.0011,-0.0058,-0.00013,-0.004,-0.019,-0.14,0.2,-2.9e-06,0.43,0.00055,0.00034,-0.00035,0,0,0.095,0.00038,0.0004,0.038,0.019,0.02,0.0077,0.045,0.046,0.033,9.6e-07,8.6e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17390000,0.98,-0.0089,-0.011,0.18,0.025,-0.023,0.03,0.016,-0.009,0.023,-0.0011,-0.0058,-0.00012,-0.0027,-0.018,-0.14,0.2,-3.2e-06,0.43,0.00053,0.00034,-0.00034,0,0,0.095,0.00037,0.00039,0.038,0.017,0.018,0.0076,0.041,0.041,0.033,9.3e-07,8.4e-07,2e-06,0.034,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17490000,0.98,-0.009,-0.011,0.18,0.024,-0.025,0.03,0.019,-0.012,0.025,-0.0011,-0.0058,-0.00013,-0.003,-0.019,-0.14,0.2,-3.2e-06,0.43,0.00054,0.00034,-0.00035,0,0,0.095,0.00037,0.00039,0.038,0.018,0.019,0.0078,0.045,0.046,0.033,9.3e-07,8.3e-07,2e-06,0.034,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17590000,0.98,-0.0089,-0.011,0.18,0.021,-0.022,0.029,0.014,-0.0098,0.022,-0.0011,-0.0058,-0.00013,-0.0025,-0.019,-0.14,0.2,-3.8e-06,0.43,0.00055,0.00034,-0.00035,0,0,0.095,0.00037,0.00039,0.038,0.017,0.018,0.0077,0.04,0.041,0.033,9e-07,8.1e-07,2e-06,0.034,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 -17690000,0.98,-0.009,-0.011,0.18,0.022,-0.023,0.03,0.016,-0.012,0.025,-0.0011,-0.0058,-0.00013,-0.0023,-0.019,-0.14,0.2,-3.6e-06,0.43,0.00053,0.00031,-0.00033,0,0,0.095,0.00037,0.00039,0.038,0.018,0.019,0.0078,0.045,0.045,0.033,9e-07,8e-07,2e-06,0.034,0.031,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -17790000,0.98,-0.0091,-0.011,0.18,0.023,-0.022,0.031,0.015,-0.011,0.03,-0.0011,-0.0058,-0.00013,-0.0015,-0.019,-0.14,0.2,-3.5e-06,0.43,0.00051,0.00029,-0.00031,0,0,0.095,0.00037,0.00039,0.038,0.016,0.017,0.0078,0.04,0.041,0.033,8.8e-07,7.8e-07,2e-06,0.034,0.031,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -17890000,0.98,-0.0089,-0.011,0.18,0.026,-0.024,0.031,0.017,-0.013,0.034,-0.0011,-0.0058,-0.00012,-0.00093,-0.018,-0.14,0.2,-3.5e-06,0.43,0.00048,0.00027,-0.0003,0,0,0.095,0.00037,0.00039,0.038,0.017,0.018,0.0079,0.044,0.045,0.033,8.7e-07,7.8e-07,2e-06,0.034,0.031,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -17990000,0.98,-0.0089,-0.011,0.18,0.025,-0.02,0.03,0.016,-0.0083,0.035,-0.0012,-0.0058,-0.00012,-0.00013,-0.02,-0.14,0.2,-3.6e-06,0.43,0.00048,0.00027,-0.00029,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.0079,0.04,0.04,0.033,8.5e-07,7.6e-07,2e-06,0.034,0.031,0.00038,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 -18090000,0.98,-0.009,-0.011,0.18,0.026,-0.021,0.03,0.018,-0.01,0.033,-0.0012,-0.0058,-0.00012,-9.3e-05,-0.02,-0.14,0.2,-3.4e-06,0.43,0.00048,0.00026,-0.00028,0,0,0.095,0.00036,0.00038,0.038,0.017,0.018,0.008,0.044,0.045,0.034,8.5e-07,7.5e-07,1.9e-06,0.034,0.031,0.00038,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18190000,0.98,-0.0091,-0.011,0.18,0.025,-0.019,0.03,0.017,-0.0083,0.031,-0.0012,-0.0058,-0.00011,0.0015,-0.021,-0.13,0.2,-3.6e-06,0.43,0.00045,0.00028,-0.00025,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0079,0.04,0.04,0.034,8.2e-07,7.4e-07,1.9e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18290000,0.98,-0.0092,-0.011,0.18,0.028,-0.02,0.029,0.02,-0.01,0.03,-0.0012,-0.0058,-0.00011,0.0016,-0.022,-0.13,0.2,-3.4e-06,0.43,0.00045,0.0003,-0.00024,0,0,0.095,0.00036,0.00038,0.038,0.016,0.018,0.008,0.044,0.044,0.034,8.2e-07,7.3e-07,1.9e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18390000,0.98,-0.0091,-0.011,0.18,0.027,-0.019,0.029,0.019,-0.0089,0.029,-0.0012,-0.0058,-0.00011,0.0018,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00046,0.0003,-0.00025,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0079,0.039,0.04,0.034,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 -18490000,0.98,-0.0091,-0.011,0.18,0.031,-0.019,0.028,0.022,-0.01,0.031,-0.0012,-0.0058,-0.00011,0.0025,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00045,0.00031,-0.00024,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.008,0.043,0.044,0.034,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18590000,0.98,-0.0089,-0.011,0.18,0.028,-0.019,0.028,0.019,-0.0093,0.033,-0.0012,-0.0058,-0.00011,0.0027,-0.021,-0.13,0.2,-4.2e-06,0.43,0.00044,0.00028,-0.00024,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0079,0.039,0.04,0.034,7.8e-07,6.9e-07,1.9e-06,0.033,0.03,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18690000,0.98,-0.0088,-0.011,0.18,0.028,-0.018,0.026,0.021,-0.011,0.032,-0.0012,-0.0058,-0.00011,0.0037,-0.02,-0.13,0.2,-4.3e-06,0.43,0.00041,0.00025,-0.00022,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.008,0.043,0.044,0.034,7.7e-07,6.9e-07,1.9e-06,0.033,0.03,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18790000,0.98,-0.0087,-0.011,0.18,0.026,-0.017,0.026,0.019,-0.0093,0.03,-0.0012,-0.0058,-0.00011,0.0041,-0.02,-0.13,0.2,-4.7e-06,0.43,0.00041,0.00026,-0.00023,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0079,0.039,0.04,0.034,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 -18890000,0.98,-0.0087,-0.011,0.18,0.027,-0.018,0.024,0.022,-0.011,0.026,-0.0012,-0.0058,-0.00011,0.0039,-0.02,-0.13,0.2,-4.7e-06,0.43,0.00043,0.00027,-0.00024,0,0,0.095,0.00035,0.00037,0.038,0.015,0.017,0.008,0.043,0.043,0.034,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -18990000,0.98,-0.0087,-0.011,0.18,0.024,-0.018,0.025,0.019,-0.0097,0.03,-0.0012,-0.0058,-0.00011,0.0046,-0.019,-0.13,0.2,-5.4e-06,0.43,0.00042,0.00026,-0.00024,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0079,0.039,0.039,0.034,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -19090000,0.98,-0.0087,-0.011,0.18,0.023,-0.018,0.025,0.021,-0.011,0.026,-0.0012,-0.0058,-0.0001,0.0052,-0.019,-0.13,0.2,-5.3e-06,0.43,0.00041,0.00027,-0.00024,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.0079,0.042,0.043,0.035,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -19190000,0.98,-0.0086,-0.011,0.18,0.02,-0.018,0.025,0.019,-0.01,0.025,-0.0012,-0.0058,-0.00011,0.005,-0.019,-0.13,0.2,-6.1e-06,0.43,0.00043,0.00028,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0079,0.038,0.039,0.034,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.00032,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 -19290000,0.98,-0.0086,-0.011,0.18,0.021,-0.019,0.025,0.021,-0.012,0.024,-0.0012,-0.0058,-0.00011,0.005,-0.019,-0.13,0.2,-6e-06,0.43,0.00044,0.00029,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.0079,0.042,0.043,0.034,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.00032,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19390000,0.98,-0.0087,-0.011,0.18,0.019,-0.016,0.026,0.018,-0.0097,0.023,-0.0012,-0.0058,-0.00011,0.0055,-0.019,-0.13,0.2,-6.5e-06,0.43,0.00043,0.00028,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,6.9e-07,6.2e-07,1.9e-06,0.032,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19490000,0.98,-0.0088,-0.011,0.18,0.021,-0.017,0.026,0.021,-0.012,0.023,-0.0012,-0.0058,-0.00012,0.0049,-0.02,-0.13,0.2,-6.1e-06,0.43,0.00043,0.00026,-0.00025,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,6.9e-07,6.1e-07,1.9e-06,0.032,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19590000,0.98,-0.0087,-0.011,0.18,0.018,-0.019,0.028,0.019,-0.011,0.023,-0.0012,-0.0058,-0.00012,0.0051,-0.02,-0.13,0.2,-6.3e-06,0.43,0.00043,0.00025,-0.00025,0,0,0.095,0.00034,0.00036,0.038,0.013,0.015,0.0077,0.038,0.039,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 -19690000,0.98,-0.0088,-0.011,0.18,0.018,-0.018,0.026,0.022,-0.013,0.022,-0.0012,-0.0058,-0.00011,0.0056,-0.021,-0.13,0.2,-6e-06,0.43,0.00043,0.00025,-0.00024,0,0,0.095,0.00034,0.00036,0.038,0.014,0.016,0.0078,0.042,0.042,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -19790000,0.98,-0.0089,-0.011,0.18,0.016,-0.016,0.025,0.021,-0.011,0.019,-0.0012,-0.0058,-0.00012,0.0057,-0.021,-0.13,0.2,-6.5e-06,0.43,0.00043,0.00026,-0.00026,0,0,0.095,0.00034,0.00036,0.038,0.013,0.014,0.0077,0.038,0.039,0.035,6.6e-07,5.8e-07,1.8e-06,0.032,0.029,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -19890000,0.98,-0.0089,-0.011,0.18,0.017,-0.016,0.025,0.023,-0.013,0.017,-0.0012,-0.0058,-0.00012,0.0056,-0.021,-0.13,0.2,-6.5e-06,0.43,0.00043,0.00026,-0.00026,0,0,0.095,0.00034,0.00036,0.038,0.014,0.015,0.0077,0.041,0.042,0.035,6.5e-07,5.8e-07,1.8e-06,0.032,0.029,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -19990000,0.98,-0.0089,-0.011,0.18,0.015,-0.016,0.022,0.02,-0.01,0.014,-0.0012,-0.0058,-0.00012,0.0066,-0.02,-0.13,0.2,-7e-06,0.43,0.00042,0.00027,-0.00026,0,0,0.095,0.00034,0.00036,0.038,0.013,0.014,0.0076,0.038,0.038,0.035,6.4e-07,5.7e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 -20090000,0.98,-0.0089,-0.012,0.18,0.017,-0.019,0.022,0.022,-0.012,0.017,-0.0012,-0.0058,-0.00012,0.0067,-0.021,-0.13,0.2,-7e-06,0.43,0.00043,0.00027,-0.00026,0,0,0.095,0.00034,0.00036,0.038,0.014,0.015,0.0076,0.041,0.042,0.035,6.4e-07,5.6e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5.1 -20190000,0.98,-0.0089,-0.012,0.18,0.017,-0.016,0.023,0.022,-0.011,0.017,-0.0012,-0.0058,-0.00012,0.0067,-0.022,-0.13,0.2,-7.5e-06,0.43,0.00043,0.00029,-0.00027,0,0,0.12,0.00034,0.00036,0.038,0.013,0.014,0.0075,0.037,0.038,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20290000,0.98,-0.009,-0.012,0.18,0.015,-0.018,0.023,0.023,-0.012,0.018,-0.0012,-0.0058,-0.00012,0.0067,-0.022,-0.13,0.2,-7.5e-06,0.43,0.00043,0.00029,-0.00028,0,0,0.12,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20390000,0.98,-0.0089,-0.012,0.18,0.013,-0.016,0.024,0.022,-0.011,0.019,-0.0012,-0.0058,-0.00012,0.0077,-0.022,-0.13,0.2,-7.6e-06,0.43,0.00042,0.00027,-0.00026,0,0,0.12,0.00034,0.00035,0.038,0.013,0.014,0.0075,0.037,0.038,0.035,6.1e-07,5.4e-07,1.8e-06,0.031,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20490000,0.98,-0.0089,-0.012,0.18,0.0096,-0.017,0.023,0.023,-0.012,0.017,-0.0012,-0.0058,-0.00012,0.0078,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00041,0.00026,-0.00026,0,0,0.12,0.00034,0.00035,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6e-07,5.3e-07,1.8e-06,0.031,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20590000,0.98,-0.0088,-0.012,0.18,0.0088,-0.017,0.023,0.022,-0.01,0.015,-0.0013,-0.0058,-0.00011,0.009,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00039,0.00024,-0.00025,0,0,0.12,0.00033,0.00035,0.038,0.013,0.014,0.0074,0.037,0.038,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20690000,0.98,-0.0087,-0.012,0.18,0.0077,-0.017,0.024,0.022,-0.012,0.016,-0.0013,-0.0058,-0.00012,0.0088,-0.022,-0.13,0.2,-7.6e-06,0.43,0.0004,0.00024,-0.00025,0,0,0.12,0.00033,0.00035,0.038,0.013,0.015,0.0074,0.04,0.042,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20790000,0.98,-0.0081,-0.012,0.18,0.0038,-0.013,0.0089,0.019,-0.01,0.015,-0.0013,-0.0058,-0.00011,0.0096,-0.022,-0.13,0.2,-8e-06,0.43,0.00038,0.00024,-0.00025,0,0,0.11,0.00033,0.00035,0.038,0.013,0.014,0.0073,0.037,0.038,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20890000,0.98,0.00097,-0.0077,0.18,-3.9e-05,-0.0021,-0.11,0.02,-0.011,0.0084,-0.0013,-0.0058,-0.00011,0.0097,-0.023,-0.13,0.2,-8.8e-06,0.43,0.00038,0.00037,-0.00019,0,0,0.11,0.00033,0.00035,0.038,0.013,0.015,0.0073,0.04,0.041,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 -20990000,0.98,0.0044,-0.0043,0.18,-0.012,0.017,-0.25,0.017,-0.0086,-0.0066,-0.0013,-0.0058,-0.00011,0.0099,-0.023,-0.13,0.2,-8.8e-06,0.43,0.00038,0.00035,-0.00015,0,0,0.093,0.00033,0.00035,0.038,0.013,0.014,0.0072,0.037,0.038,0.034,5.6e-07,5e-07,1.7e-06,0.031,0.028,0.00024,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21090000,0.98,0.0027,-0.0047,0.18,-0.024,0.032,-0.37,0.016,-0.006,-0.037,-0.0013,-0.0058,-0.00011,0.0099,-0.023,-0.13,0.2,-7e-06,0.43,0.00043,0.00016,-0.00019,0,0,0.063,0.00033,0.00035,0.038,0.014,0.015,0.0072,0.04,0.041,0.035,5.6e-07,4.9e-07,1.7e-06,0.031,0.028,0.00024,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21190000,0.98,-6.4e-05,-0.0063,0.18,-0.029,0.039,-0.49,0.013,-0.0039,-0.074,-0.0013,-0.0058,-0.0001,0.0097,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00044,0.00018,-0.00018,0,0,0.026,0.00033,0.00034,0.038,0.013,0.014,0.0071,0.037,0.038,0.035,5.5e-07,4.8e-07,1.7e-06,0.031,0.028,0.00024,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21290000,0.98,-0.0023,-0.0076,0.18,-0.029,0.041,-0.62,0.0099,-0.00035,-0.13,-0.0013,-0.0058,-0.00011,0.0092,-0.024,-0.13,0.2,-7e-06,0.43,0.00043,0.00022,-0.00011,0,0,-0.032,0.00033,0.00034,0.037,0.014,0.015,0.0071,0.04,0.041,0.035,5.4e-07,4.8e-07,1.7e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21390000,0.98,-0.0037,-0.0082,0.18,-0.026,0.038,-0.75,0.0082,0.0037,-0.2,-0.0013,-0.0058,-0.00011,0.0093,-0.024,-0.13,0.2,-6.5e-06,0.43,0.00045,0.00015,-0.00012,0,0,-0.097,0.00032,0.00034,0.037,0.013,0.014,0.007,0.037,0.038,0.035,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00023,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21490000,0.98,-0.0045,-0.0086,0.18,-0.021,0.035,-0.89,0.0054,0.0077,-0.28,-0.0013,-0.0058,-0.0001,0.0097,-0.024,-0.13,0.2,-6.5e-06,0.43,0.00044,0.00017,-0.00017,0,0,-0.18,0.00032,0.00034,0.037,0.014,0.016,0.007,0.04,0.041,0.035,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00023,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21590000,0.98,-0.0049,-0.0086,0.18,-0.015,0.031,-1,0.0044,0.0098,-0.37,-0.0013,-0.0058,-9.4e-05,0.01,-0.023,-0.13,0.2,-6.5e-06,0.43,0.00042,0.00022,-0.00018,0,0,-0.27,0.00032,0.00034,0.037,0.013,0.015,0.0069,0.037,0.038,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21690000,0.98,-0.0052,-0.0085,0.18,-0.012,0.027,-1.1,0.0032,0.013,-0.49,-0.0013,-0.0058,-8.7e-05,0.011,-0.024,-0.13,0.2,-6.5e-06,0.43,0.0004,0.00026,-0.00017,0,0,-0.39,0.00032,0.00034,0.037,0.014,0.016,0.0069,0.04,0.041,0.035,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21790000,0.98,-0.0055,-0.0086,0.18,-0.0066,0.022,-1.3,0.007,0.012,-0.61,-0.0013,-0.0058,-7.8e-05,0.011,-0.023,-0.13,0.2,-6.5e-06,0.43,0.0004,0.00026,-0.00022,0,0,-0.51,0.00032,0.00033,0.037,0.013,0.015,0.0069,0.037,0.038,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21890000,0.98,-0.0058,-0.0088,0.18,-0.0029,0.017,-1.4,0.0062,0.014,-0.75,-0.0013,-0.0058,-8e-05,0.011,-0.023,-0.13,0.2,-6.9e-06,0.43,0.00037,0.00028,-0.00021,0,0,-0.65,0.00032,0.00033,0.037,0.014,0.016,0.0068,0.04,0.041,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.027,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -21990000,0.98,-0.0064,-0.009,0.18,-0.00084,0.013,-1.4,0.01,0.011,-0.88,-0.0013,-0.0058,-7.4e-05,0.011,-0.022,-0.13,0.2,-6.5e-06,0.43,0.0004,0.00029,-0.00023,0,0,-0.78,0.00031,0.00033,0.037,0.013,0.015,0.0068,0.037,0.038,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22090000,0.98,-0.0071,-0.0098,0.18,0.0012,0.0094,-1.4,0.0095,0.012,-1,-0.0013,-0.0058,-6.6e-05,0.012,-0.022,-0.13,0.2,-6.5e-06,0.43,0.0004,0.00031,-0.00024,0,0,-0.93,0.00031,0.00033,0.037,0.014,0.016,0.0068,0.04,0.041,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22190000,0.98,-0.0075,-0.01,0.18,0.007,0.005,-1.4,0.015,0.0079,-1.2,-0.0013,-0.0058,-5.7e-05,0.013,-0.02,-0.13,0.2,-6.7e-06,0.43,0.0004,0.00032,-0.00024,0,0,-1.1,0.00031,0.00032,0.037,0.013,0.014,0.0067,0.037,0.038,0.034,4.8e-07,4.3e-07,1.6e-06,0.029,0.027,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22290000,0.98,-0.0082,-0.01,0.18,0.013,-0.00065,-1.4,0.016,0.008,-1.3,-0.0013,-0.0058,-5.9e-05,0.012,-0.02,-0.13,0.2,-6.6e-06,0.43,0.00039,0.00032,-0.00024,0,0,-1.2,0.00031,0.00032,0.037,0.014,0.015,0.0067,0.04,0.041,0.034,4.8e-07,4.2e-07,1.6e-06,0.029,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22390000,0.98,-0.0085,-0.01,0.18,0.017,-0.0092,-1.4,0.022,-0.00079,-1.5,-0.0013,-0.0058,-6.2e-05,0.011,-0.02,-0.13,0.2,-6.7e-06,0.43,0.00041,0.00032,-0.00026,0,0,-1.4,0.0003,0.00032,0.037,0.013,0.014,0.0066,0.037,0.038,0.034,4.7e-07,4.2e-07,1.6e-06,0.029,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22490000,0.98,-0.0087,-0.011,0.18,0.021,-0.016,-1.4,0.024,-0.0023,-1.6,-0.0013,-0.0058,-6.6e-05,0.011,-0.02,-0.13,0.2,-7e-06,0.43,0.00042,0.00034,-0.00028,0,0,-1.5,0.00031,0.00032,0.037,0.013,0.015,0.0066,0.04,0.041,0.034,4.7e-07,4.1e-07,1.6e-06,0.029,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22590000,0.98,-0.0086,-0.011,0.18,0.029,-0.024,-1.4,0.034,-0.01,-1.7,-0.0013,-0.0058,-5.8e-05,0.011,-0.02,-0.13,0.2,-6.6e-06,0.43,0.00042,0.00036,-0.00027,0,0,-1.6,0.0003,0.00032,0.037,0.012,0.014,0.0065,0.036,0.038,0.034,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22690000,0.98,-0.0085,-0.012,0.18,0.032,-0.029,-1.4,0.038,-0.013,-1.9,-0.0013,-0.0058,-6e-05,0.011,-0.021,-0.13,0.2,-6.5e-06,0.43,0.00042,0.00036,-0.00029,0,0,-1.8,0.0003,0.00032,0.037,0.013,0.015,0.0065,0.04,0.041,0.034,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22790000,0.98,-0.0085,-0.012,0.18,0.038,-0.036,-1.4,0.048,-0.023,-2,-0.0013,-0.0058,-6.3e-05,0.011,-0.02,-0.13,0.2,-6.7e-06,0.43,0.00041,0.00033,-0.00031,0,0,-1.9,0.0003,0.00031,0.037,0.012,0.014,0.0065,0.036,0.038,0.034,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22890000,0.98,-0.0087,-0.012,0.18,0.042,-0.041,-1.4,0.052,-0.026,-2.2,-0.0013,-0.0058,-5.5e-05,0.011,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00041,0.00034,-0.00029,0,0,-2.1,0.0003,0.00031,0.037,0.013,0.015,0.0065,0.04,0.041,0.034,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -22990000,0.98,-0.0086,-0.013,0.18,0.046,-0.046,-1.4,0.061,-0.035,-2.3,-0.0013,-0.0058,-4.6e-05,0.011,-0.02,-0.13,0.2,-6.8e-06,0.43,0.00041,0.00031,-0.00027,0,0,-2.2,0.0003,0.00031,0.037,0.012,0.014,0.0064,0.036,0.038,0.034,4.3e-07,3.9e-07,1.6e-06,0.028,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23090000,0.98,-0.0086,-0.013,0.18,0.051,-0.05,-1.4,0.065,-0.04,-2.5,-0.0013,-0.0058,-4.5e-05,0.011,-0.02,-0.13,0.2,-6.8e-06,0.43,0.00039,0.00032,-0.00025,0,0,-2.4,0.0003,0.00031,0.037,0.013,0.014,0.0064,0.04,0.041,0.034,4.3e-07,3.9e-07,1.5e-06,0.028,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23190000,0.98,-0.0086,-0.013,0.18,0.057,-0.052,-1.4,0.076,-0.05,-2.6,-0.0013,-0.0058,-4.8e-05,0.011,-0.019,-0.13,0.2,-7.6e-06,0.43,0.00038,0.00029,-0.00025,0,0,-2.5,0.00029,0.00031,0.037,0.012,0.013,0.0063,0.036,0.037,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23290000,0.98,-0.0091,-0.014,0.18,0.062,-0.057,-1.4,0.082,-0.055,-2.8,-0.0013,-0.0058,-4.5e-05,0.011,-0.02,-0.13,0.2,-7.6e-06,0.43,0.00034,0.00033,-0.00025,0,0,-2.7,0.00029,0.00031,0.037,0.013,0.014,0.0063,0.039,0.041,0.034,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23390000,0.98,-0.009,-0.014,0.18,0.067,-0.06,-1.4,0.092,-0.061,-2.9,-0.0013,-0.0058,-5.8e-05,0.012,-0.019,-0.13,0.2,-7.9e-06,0.43,0.00035,0.0003,-0.00024,0,0,-2.8,0.00029,0.0003,0.037,0.012,0.013,0.0063,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23490000,0.98,-0.0091,-0.014,0.18,0.072,-0.062,-1.4,0.1,-0.067,-3,-0.0013,-0.0058,-5.1e-05,0.012,-0.02,-0.13,0.2,-7.6e-06,0.43,0.00034,0.00036,-0.00028,0,0,-2.9,0.00029,0.0003,0.037,0.013,0.014,0.0063,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23590000,0.98,-0.0093,-0.014,0.18,0.075,-0.064,-1.4,0.11,-0.076,-3.2,-0.0013,-0.0058,-4.7e-05,0.012,-0.019,-0.13,0.2,-8.6e-06,0.43,0.00029,0.00032,-0.00024,0,0,-3.1,0.00029,0.0003,0.037,0.012,0.013,0.0062,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23690000,0.98,-0.01,-0.014,0.18,0.074,-0.066,-1.3,0.11,-0.082,-3.3,-0.0013,-0.0058,-3.9e-05,0.013,-0.019,-0.13,0.2,-8.4e-06,0.43,0.00028,0.00035,-0.00024,0,0,-3.2,0.00029,0.0003,0.037,0.012,0.014,0.0062,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23790000,0.98,-0.012,-0.017,0.18,0.068,-0.062,-0.95,0.12,-0.086,-3.4,-0.0013,-0.0058,-3.7e-05,0.014,-0.019,-0.13,0.2,-8.1e-06,0.43,0.00026,0.00038,-0.00022,0,0,-3.3,0.00029,0.0003,0.037,0.011,0.013,0.0061,0.036,0.037,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23890000,0.98,-0.015,-0.021,0.18,0.064,-0.062,-0.52,0.13,-0.092,-3.5,-0.0013,-0.0058,-3.5e-05,0.014,-0.02,-0.13,0.2,-8.1e-06,0.43,0.00025,0.0004,-0.00025,0,0,-3.4,0.00029,0.0003,0.037,0.012,0.013,0.0061,0.039,0.041,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -23990000,0.98,-0.017,-0.024,0.18,0.064,-0.061,-0.13,0.14,-0.095,-3.6,-0.0013,-0.0058,-4.1e-05,0.015,-0.019,-0.13,0.2,-8.2e-06,0.43,0.00021,0.00042,1.6e-06,0,0,-3.5,0.00028,0.0003,0.037,0.011,0.012,0.0061,0.036,0.037,0.033,3.9e-07,3.5e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24090000,0.98,-0.017,-0.023,0.18,0.07,-0.069,0.099,0.14,-0.1,-3.6,-0.0013,-0.0058,-4.4e-05,0.015,-0.019,-0.13,0.2,-8.2e-06,0.43,0.00023,0.00039,1.7e-06,0,0,-3.5,0.00028,0.0003,0.037,0.012,0.013,0.0061,0.039,0.04,0.033,3.9e-07,3.5e-07,1.4e-06,0.028,0.026,0.00016,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24190000,0.98,-0.014,-0.019,0.18,0.08,-0.075,0.089,0.15,-0.11,-3.6,-0.0013,-0.0058,-4.4e-05,0.016,-0.019,-0.13,0.2,-7.8e-06,0.43,0.00022,0.00036,0.0001,0,0,-3.5,0.00028,0.0003,0.037,0.011,0.012,0.006,0.036,0.037,0.033,3.8e-07,3.5e-07,1.4e-06,0.027,0.026,0.00016,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24290000,0.98,-0.012,-0.016,0.18,0.084,-0.078,0.067,0.16,-0.11,-3.6,-0.0013,-0.0058,-4.2e-05,0.016,-0.019,-0.13,0.2,-7.4e-06,0.43,0.00026,0.00031,9.6e-05,0,0,-3.5,0.00028,0.0003,0.037,0.012,0.013,0.006,0.039,0.04,0.033,3.8e-07,3.5e-07,1.4e-06,0.027,0.026,0.00016,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24390000,0.98,-0.011,-0.015,0.18,0.077,-0.073,0.083,0.16,-0.11,-3.6,-0.0013,-0.0058,-4.1e-05,0.018,-0.02,-0.13,0.2,-6.1e-06,0.43,0.00025,0.00035,0.00016,0,0,-3.5,0.00028,0.00029,0.037,0.011,0.012,0.006,0.035,0.037,0.033,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00016,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24490000,0.98,-0.011,-0.015,0.18,0.073,-0.069,0.081,0.17,-0.12,-3.6,-0.0013,-0.0058,-2.7e-05,0.018,-0.02,-0.13,0.2,-6.1e-06,0.43,0.00017,0.00046,0.00021,0,0,-3.5,0.00028,0.00029,0.037,0.012,0.013,0.006,0.038,0.04,0.033,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00016,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24590000,0.98,-0.012,-0.015,0.18,0.069,-0.066,0.077,0.17,-0.12,-3.6,-0.0013,-0.0058,-3.8e-05,0.02,-0.021,-0.13,0.2,-4.8e-06,0.43,0.00021,0.00043,0.00022,0,0,-3.5,0.00028,0.00029,0.037,0.011,0.012,0.0059,0.035,0.037,0.033,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24690000,0.98,-0.012,-0.015,0.18,0.068,-0.065,0.076,0.18,-0.12,-3.5,-0.0013,-0.0058,-3.7e-05,0.02,-0.021,-0.13,0.2,-5e-06,0.43,0.0002,0.00046,0.00022,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0059,0.038,0.04,0.033,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24790000,0.98,-0.012,-0.014,0.18,0.065,-0.063,0.068,0.18,-0.12,-3.5,-0.0014,-0.0058,-4.5e-05,0.021,-0.022,-0.13,0.2,-4.4e-06,0.43,0.00019,0.00046,0.00021,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0059,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24890000,0.98,-0.012,-0.014,0.18,0.063,-0.067,0.057,0.19,-0.13,-3.5,-0.0014,-0.0058,-3.9e-05,0.021,-0.022,-0.13,0.2,-4.2e-06,0.43,0.00019,0.00047,0.00024,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0059,0.038,0.04,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -24990000,0.98,-0.012,-0.014,0.18,0.055,-0.063,0.05,0.19,-0.12,-3.5,-0.0014,-0.0058,-5.3e-05,0.023,-0.023,-0.13,0.2,-4.4e-06,0.43,0.00016,0.00058,0.00025,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25090000,0.98,-0.012,-0.014,0.18,0.051,-0.063,0.048,0.19,-0.12,-3.5,-0.0014,-0.0058,-5.4e-05,0.023,-0.023,-0.13,0.2,-5.1e-06,0.43,0.00014,0.00065,0.00028,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.6e-07,3.3e-07,1.3e-06,0.027,0.025,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25190000,0.98,-0.012,-0.014,0.18,0.046,-0.057,0.048,0.19,-0.12,-3.5,-0.0014,-0.0058,-7.1e-05,0.025,-0.023,-0.13,0.2,-5e-06,0.43,0.00012,0.00068,0.00027,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25290000,0.98,-0.012,-0.013,0.18,0.041,-0.059,0.042,0.2,-0.12,-3.5,-0.0014,-0.0058,-7.8e-05,0.024,-0.023,-0.13,0.2,-5.6e-06,0.43,0.00011,0.00071,0.00024,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25390000,0.98,-0.012,-0.013,0.18,0.033,-0.052,0.041,0.19,-0.11,-3.5,-0.0014,-0.0058,-9.4e-05,0.026,-0.024,-0.13,0.2,-6.4e-06,0.43,7.3e-05,0.00076,0.00026,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25490000,0.98,-0.013,-0.013,0.18,0.028,-0.053,0.04,0.19,-0.12,-3.5,-0.0014,-0.0058,-9.6e-05,0.026,-0.025,-0.13,0.2,-6.2e-06,0.43,6.7e-05,0.00072,0.00023,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25590000,0.98,-0.013,-0.012,0.18,0.023,-0.049,0.042,0.19,-0.11,-3.5,-0.0014,-0.0058,-0.00011,0.027,-0.025,-0.13,0.2,-7e-06,0.43,3.6e-05,0.00075,0.0002,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25690000,0.98,-0.012,-0.012,0.18,0.023,-0.048,0.031,0.19,-0.11,-3.5,-0.0014,-0.0058,-0.00011,0.027,-0.025,-0.13,0.2,-7.1e-06,0.43,4.2e-05,0.00077,0.00022,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25790000,0.98,-0.012,-0.011,0.18,0.012,-0.04,0.031,0.18,-0.1,-3.5,-0.0014,-0.0058,-0.00012,0.029,-0.026,-0.13,0.2,-7.6e-06,0.43,-1.8e-05,0.0007,0.0002,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25890000,0.98,-0.012,-0.012,0.18,0.0061,-0.039,0.033,0.18,-0.11,-3.5,-0.0014,-0.0058,-0.00013,0.029,-0.026,-0.13,0.2,-7.7e-06,0.43,-3.8e-05,0.00068,0.00016,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -25990000,0.98,-0.012,-0.012,0.18,-0.003,-0.032,0.027,0.17,-0.097,-3.5,-0.0014,-0.0058,-0.00015,0.03,-0.026,-0.13,0.2,-9.1e-06,0.43,-9.3e-05,0.00066,0.00014,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.3e-07,3.1e-07,1.3e-06,0.026,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26090000,0.98,-0.012,-0.012,0.18,-0.0076,-0.032,0.025,0.17,-0.1,-3.5,-0.0014,-0.0058,-0.00014,0.03,-0.026,-0.13,0.2,-8.6e-06,0.43,-9e-05,0.00064,0.00017,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.013,0.0057,0.038,0.039,0.032,3.3e-07,3.1e-07,1.3e-06,0.026,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26190000,0.98,-0.012,-0.012,0.18,-0.015,-0.025,0.021,0.16,-0.092,-3.5,-0.0015,-0.0058,-0.00014,0.032,-0.026,-0.13,0.2,-9e-06,0.43,-0.00011,0.00064,0.00019,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26290000,0.98,-0.012,-0.013,0.18,-0.015,-0.025,0.015,0.16,-0.095,-3.5,-0.0015,-0.0058,-0.00015,0.031,-0.027,-0.13,0.2,-9.6e-06,0.43,-0.00012,0.00066,0.00016,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26390000,0.98,-0.011,-0.013,0.18,-0.021,-0.017,0.019,0.15,-0.086,-3.5,-0.0015,-0.0058,-0.00016,0.033,-0.027,-0.13,0.2,-1.1e-05,0.43,-0.00016,0.00063,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26490000,0.98,-0.011,-0.012,0.18,-0.023,-0.015,0.028,0.14,-0.087,-3.5,-0.0015,-0.0058,-0.00016,0.032,-0.027,-0.13,0.2,-1.1e-05,0.43,-0.00016,0.00066,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26590000,0.98,-0.01,-0.013,0.18,-0.026,-0.0064,0.028,0.13,-0.079,-3.5,-0.0015,-0.0058,-0.00017,0.033,-0.027,-0.13,0.2,-1.2e-05,0.43,-0.00019,0.00069,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26690000,0.98,-0.01,-0.012,0.18,-0.026,-0.0024,0.027,0.13,-0.08,-3.5,-0.0015,-0.0058,-0.00018,0.033,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00021,0.00069,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26790000,0.98,-0.0099,-0.012,0.18,-0.035,0.0018,0.026,0.12,-0.073,-3.5,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00023,0.00067,0.00011,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26890000,0.98,-0.0092,-0.012,0.18,-0.04,0.0047,0.022,0.11,-0.073,-3.5,-0.0015,-0.0058,-0.00018,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00023,0.00066,0.00011,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -26990000,0.98,-0.0087,-0.013,0.18,-0.048,0.012,0.021,0.099,-0.065,-3.5,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00025,0.00064,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27090000,0.98,-0.0085,-0.013,0.18,-0.05,0.018,0.024,0.094,-0.064,-3.5,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00025,0.00063,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27190000,0.98,-0.0086,-0.013,0.18,-0.056,0.025,0.027,0.081,-0.056,-3.5,-0.0015,-0.0058,-0.0002,0.035,-0.027,-0.13,0.2,-1.4e-05,0.43,-0.00026,0.00062,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27290000,0.98,-0.0088,-0.014,0.18,-0.063,0.03,0.14,0.076,-0.054,-3.5,-0.0015,-0.0058,-0.0002,0.035,-0.027,-0.13,0.2,-1.4e-05,0.43,-0.00027,0.00063,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27390000,0.98,-0.01,-0.016,0.18,-0.07,0.037,0.46,0.064,-0.045,-3.5,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.6e-05,0.43,-0.00033,0.00055,0.00018,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27490000,0.98,-0.012,-0.018,0.18,-0.074,0.042,0.78,0.057,-0.041,-3.5,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.13,0.2,-1.6e-05,0.43,-0.0003,0.00052,0.00018,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.013,0.0055,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27590000,0.98,-0.011,-0.017,0.18,-0.07,0.046,0.87,0.046,-0.036,-3.4,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00046,0.00021,0,0,-3.3,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27690000,0.98,-0.01,-0.014,0.18,-0.065,0.042,0.78,0.04,-0.031,-3.3,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00045,0.00019,0,0,-3.2,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27790000,0.98,-0.0088,-0.012,0.18,-0.065,0.04,0.77,0.032,-0.027,-3.2,-0.0015,-0.0058,-0.0002,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00042,0.0002,0,0,-3.1,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27890000,0.98,-0.0085,-0.013,0.18,-0.071,0.047,0.81,0.026,-0.023,-3.2,-0.0015,-0.0058,-0.0002,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00041,0.0002,0,0,-3.1,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -27990000,0.98,-0.0089,-0.013,0.18,-0.072,0.049,0.8,0.019,-0.019,-3.1,-0.0015,-0.0058,-0.0002,0.034,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00027,0.00035,0.00022,0,0,-3,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28090000,0.98,-0.0092,-0.013,0.18,-0.076,0.05,0.8,0.012,-0.014,-3,-0.0015,-0.0058,-0.00019,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00038,0.00021,0,0,-2.9,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28190000,0.98,-0.0086,-0.013,0.18,-0.077,0.047,0.81,0.004,-0.012,-2.9,-0.0014,-0.0058,-0.00019,0.033,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00025,0.00036,0.00022,0,0,-2.8,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28290000,0.98,-0.0081,-0.013,0.18,-0.081,0.051,0.81,-0.0031,-0.0068,-2.9,-0.0015,-0.0058,-0.00018,0.033,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00026,0.00038,0.00019,0,0,-2.8,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28390000,0.98,-0.0081,-0.014,0.18,-0.082,0.054,0.81,-0.0096,-0.0024,-2.8,-0.0014,-0.0058,-0.00017,0.033,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00031,0.00029,0.0002,0,0,-2.7,0.00028,0.00029,0.036,0.011,0.012,0.0054,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28490000,0.98,-0.0084,-0.014,0.18,-0.085,0.058,0.81,-0.019,0.0031,-2.7,-0.0014,-0.0058,-0.00017,0.033,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00028,0.00028,0.00023,0,0,-2.6,0.00029,0.00029,0.036,0.011,0.012,0.0054,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 -28590000,0.98,-0.0085,-0.014,0.18,-0.079,0.054,0.81,-0.023,0.0026,-2.6,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00025,0.00026,0.00022,0,0,-2.5,0.00028,0.00029,0.036,0.011,0.012,0.0054,0.035,0.036,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28690000,0.98,-0.0082,-0.014,0.18,-0.078,0.055,0.81,-0.031,0.0079,-2.6,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00022,0.00026,0.00022,0,0,-2.5,0.00029,0.00029,0.036,0.011,0.012,0.0054,0.038,0.039,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28790000,0.98,-0.0076,-0.014,0.18,-0.076,0.056,0.81,-0.035,0.011,-2.5,-0.0014,-0.0058,-0.00015,0.031,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00025,0.00016,0.00022,0,0,-2.4,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28890000,0.98,-0.0074,-0.013,0.18,-0.08,0.058,0.81,-0.043,0.017,-2.4,-0.0014,-0.0058,-0.00014,0.032,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00025,0.0002,0.00019,0,0,-2.3,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -28990000,0.98,-0.0072,-0.013,0.18,-0.077,0.055,0.81,-0.044,0.017,-2.3,-0.0014,-0.0058,-0.00014,0.031,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00028,5e-05,0.00023,0,0,-2.2,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29090000,0.98,-0.007,-0.013,0.18,-0.08,0.057,0.81,-0.052,0.023,-2.3,-0.0014,-0.0058,-0.00014,0.031,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.0003,3.1e-05,0.00023,0,0,-2.2,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29190000,0.98,-0.0069,-0.014,0.18,-0.078,0.056,0.8,-0.052,0.023,-2.2,-0.0014,-0.0058,-0.00012,0.03,-0.028,-0.12,0.2,-2e-05,0.43,-0.00033,-9.9e-05,0.00024,0,0,-2.1,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29290000,0.98,-0.0072,-0.014,0.18,-0.081,0.062,0.81,-0.061,0.029,-2.1,-0.0014,-0.0058,-0.00012,0.03,-0.028,-0.12,0.2,-2e-05,0.43,-0.00033,-0.00012,0.00024,0,0,-2,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29390000,0.98,-0.0076,-0.013,0.18,-0.078,0.061,0.81,-0.06,0.031,-2,-0.0014,-0.0058,-0.00011,0.029,-0.028,-0.12,0.2,-2.2e-05,0.43,-0.00036,-0.00025,0.00025,0,0,-1.9,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,9.9e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29490000,0.98,-0.0076,-0.013,0.18,-0.081,0.062,0.81,-0.068,0.038,-2,-0.0014,-0.0058,-0.0001,0.029,-0.028,-0.12,0.2,-2.2e-05,0.43,-0.00038,-0.00022,0.00023,0,0,-1.9,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,9.8e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29590000,0.98,-0.0075,-0.013,0.18,-0.077,0.061,0.81,-0.067,0.038,-1.9,-0.0014,-0.0058,-8.6e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00043,-0.00032,0.00022,0,0,-1.8,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.7e-07,2.6e-07,9.7e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29690000,0.98,-0.0075,-0.013,0.18,-0.082,0.06,0.81,-0.076,0.044,-1.8,-0.0014,-0.0058,-7.9e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00045,-0.00029,0.0002,0,0,-1.7,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.7e-07,2.6e-07,9.7e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29790000,0.98,-0.0073,-0.013,0.18,-0.079,0.054,0.81,-0.072,0.042,-1.7,-0.0014,-0.0058,-6.3e-05,0.027,-0.028,-0.12,0.2,-2.5e-05,0.43,-0.0005,-0.00041,0.00021,0,0,-1.6,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29890000,0.98,-0.0068,-0.013,0.18,-0.08,0.056,0.8,-0.08,0.048,-1.7,-0.0014,-0.0058,-5.6e-05,0.027,-0.028,-0.12,0.2,-2.5e-05,0.43,-0.00052,-0.00038,0.00019,0,0,-1.6,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -29990000,0.98,-0.007,-0.013,0.18,-0.075,0.051,0.8,-0.076,0.044,-1.6,-0.0014,-0.0058,-4.5e-05,0.026,-0.028,-0.12,0.2,-2.6e-05,0.43,-0.00051,-0.00043,0.0002,0,0,-1.5,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.5e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30090000,0.98,-0.0071,-0.013,0.18,-0.077,0.051,0.8,-0.084,0.049,-1.5,-0.0014,-0.0058,-5.6e-05,0.026,-0.028,-0.12,0.2,-2.7e-05,0.43,-0.00046,-0.00049,0.00025,0,0,-1.4,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.4e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30190000,0.98,-0.0071,-0.013,0.18,-0.071,0.048,0.8,-0.078,0.047,-1.5,-0.0014,-0.0058,-5.8e-05,0.025,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00047,-0.00071,0.00031,0,0,-1.4,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.031,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30290000,0.98,-0.0071,-0.013,0.18,-0.071,0.048,0.8,-0.085,0.052,-1.4,-0.0014,-0.0058,-5.6e-05,0.025,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00051,-0.00076,0.00031,0,0,-1.3,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30390000,0.98,-0.0071,-0.013,0.18,-0.065,0.043,0.8,-0.078,0.049,-1.3,-0.0014,-0.0058,-3.9e-05,0.025,-0.029,-0.12,0.2,-3e-05,0.43,-0.00064,-0.00097,0.00031,0,0,-1.2,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.2e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30490000,0.98,-0.0071,-0.013,0.18,-0.069,0.043,0.8,-0.085,0.054,-1.2,-0.0014,-0.0058,-3.3e-05,0.025,-0.029,-0.12,0.2,-3e-05,0.43,-0.00069,-0.00096,0.00029,0,0,-1.1,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.031,2.7e-07,2.5e-07,9.2e-07,0.025,0.023,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30590000,0.98,-0.0074,-0.013,0.18,-0.064,0.041,0.8,-0.077,0.051,-1.2,-0.0014,-0.0058,-1.7e-05,0.024,-0.03,-0.12,0.2,-3e-05,0.43,-0.00079,-0.0011,0.00029,0,0,-1.1,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.1e-07,0.025,0.023,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30690000,0.98,-0.0078,-0.014,0.18,-0.063,0.04,0.8,-0.084,0.055,-1.1,-0.0014,-0.0058,-1.7e-05,0.024,-0.03,-0.12,0.2,-3.1e-05,0.43,-0.00077,-0.001,0.00029,0,0,-1,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.5e-07,9e-07,0.025,0.023,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30790000,0.98,-0.0075,-0.013,0.17,-0.056,0.034,0.8,-0.076,0.053,-1,-0.0014,-0.0058,-1.3e-05,0.024,-0.03,-0.12,0.2,-3.2e-05,0.43,-0.00084,-0.0012,0.00032,0,0,-0.92,0.00028,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.4e-07,8.9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30890000,0.98,-0.0069,-0.013,0.17,-0.056,0.031,0.79,-0.081,0.056,-0.95,-0.0014,-0.0058,-2e-05,0.024,-0.031,-0.12,0.2,-3.3e-05,0.43,-0.00075,-0.0011,0.00034,0,0,-0.85,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -30990000,0.98,-0.0071,-0.013,0.17,-0.049,0.025,0.79,-0.071,0.049,-0.88,-0.0014,-0.0057,-1.3e-05,0.023,-0.032,-0.12,0.2,-3.3e-05,0.43,-0.00078,-0.0013,0.00037,0,0,-0.78,0.00028,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31090000,0.98,-0.0073,-0.013,0.17,-0.048,0.024,0.79,-0.075,0.052,-0.81,-0.0014,-0.0057,-1.7e-05,0.023,-0.032,-0.12,0.2,-3.4e-05,0.43,-0.00074,-0.0012,0.00039,0,0,-0.71,0.00028,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31190000,0.98,-0.0075,-0.013,0.17,-0.043,0.02,0.8,-0.066,0.047,-0.74,-0.0013,-0.0057,-1.1e-06,0.023,-0.033,-0.12,0.2,-3.4e-05,0.43,-0.00083,-0.0013,0.00038,0,0,-0.64,0.00028,0.00028,0.035,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31290000,0.98,-0.0077,-0.014,0.17,-0.04,0.018,0.8,-0.07,0.049,-0.67,-0.0013,-0.0057,4e-06,0.023,-0.033,-0.12,0.2,-3.3e-05,0.43,-0.00087,-0.0012,0.00036,0,0,-0.57,0.00028,0.00028,0.035,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31390000,0.98,-0.0075,-0.013,0.17,-0.035,0.011,0.8,-0.061,0.043,-0.59,-0.0013,-0.0057,3.3e-06,0.023,-0.033,-0.12,0.2,-3.3e-05,0.43,-0.00095,-0.0015,0.00041,0,0,-0.49,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.6e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31490000,0.98,-0.0073,-0.014,0.17,-0.036,0.0081,0.8,-0.065,0.044,-0.52,-0.0013,-0.0057,1.7e-06,0.023,-0.033,-0.12,0.2,-3.2e-05,0.43,-0.001,-0.0017,0.00042,0,0,-0.42,0.00028,0.00028,0.035,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.5e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31590000,0.98,-0.0071,-0.014,0.17,-0.033,0.0062,0.8,-0.054,0.04,-0.45,-0.0013,-0.0057,1.1e-05,0.023,-0.033,-0.12,0.2,-3.2e-05,0.43,-0.0011,-0.0018,0.00044,0,0,-0.35,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.5e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31690000,0.98,-0.0071,-0.014,0.17,-0.036,0.0056,0.8,-0.058,0.041,-0.38,-0.0013,-0.0057,2e-05,0.023,-0.033,-0.12,0.2,-3.1e-05,0.43,-0.0012,-0.0018,0.00042,0,0,-0.28,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.4e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31790000,0.98,-0.0074,-0.015,0.17,-0.027,0.003,0.8,-0.045,0.039,-0.3,-0.0013,-0.0057,2.5e-05,0.023,-0.034,-0.12,0.2,-3.1e-05,0.43,-0.0013,-0.0019,0.00045,0,0,-0.2,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.3e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31890000,0.99,-0.0071,-0.015,0.17,-0.025,0.00078,0.8,-0.049,0.039,-0.23,-0.0013,-0.0057,2.9e-05,0.023,-0.033,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0021,0.00046,0,0,-0.13,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.3e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -31990000,0.99,-0.0074,-0.014,0.17,-0.017,-0.00031,0.79,-0.036,0.036,-0.17,-0.0013,-0.0057,2.6e-05,0.023,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0022,0.00052,0,0,-0.068,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8.2e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32090000,0.99,-0.0077,-0.014,0.17,-0.019,-0.0037,0.8,-0.038,0.036,-0.096,-0.0013,-0.0057,2.6e-05,0.023,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0023,0.00053,0,0,0.0043,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.2e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32190000,0.99,-0.0079,-0.014,0.17,-0.013,-0.0073,0.8,-0.026,0.034,-0.027,-0.0013,-0.0057,2.2e-05,0.024,-0.034,-0.12,0.2,-2.9e-05,0.43,-0.0014,-0.0024,0.00057,0,0,0.073,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32290000,0.99,-0.0078,-0.014,0.17,-0.013,-0.0099,0.8,-0.027,0.033,0.042,-0.0013,-0.0057,2.6e-05,0.024,-0.034,-0.12,0.2,-2.8e-05,0.43,-0.0015,-0.0025,0.00058,0,0,0.14,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32390000,0.99,-0.008,-0.015,0.17,-0.0063,-0.012,0.8,-0.015,0.03,0.12,-0.0013,-0.0057,2.3e-05,0.024,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0016,-0.0027,0.00064,0,0,0.22,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32490000,0.99,-0.011,-0.012,0.17,0.018,-0.077,-0.077,-0.014,0.024,0.12,-0.0013,-0.0057,2e-05,0.024,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0015,-0.0027,0.00063,0,0,0.22,0.00028,0.00028,0.035,0.012,0.014,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32590000,0.99,-0.011,-0.013,0.17,0.021,-0.079,-0.08,0.0014,0.02,0.1,-0.0013,-0.0057,1.9e-05,0.024,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.0007,0,0,0.2,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32690000,0.99,-0.011,-0.012,0.17,0.016,-0.085,-0.081,0.0033,0.012,0.088,-0.0013,-0.0057,1.8e-05,0.024,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.0007,0,0,0.19,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32790000,0.99,-0.011,-0.013,0.17,0.017,-0.084,-0.082,0.015,0.0092,0.073,-0.0013,-0.0057,1.6e-05,0.024,-0.034,-0.12,0.2,-2.5e-05,0.43,-0.0015,-0.0022,0.00077,0,0,0.17,0.00028,0.00027,0.035,0.011,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32890000,0.99,-0.011,-0.013,0.17,0.017,-0.09,-0.084,0.017,0.00073,0.058,-0.0013,-0.0057,2e-05,0.024,-0.034,-0.12,0.2,-2.6e-05,0.43,-0.0015,-0.0021,0.00078,0,0,0.16,0.00028,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -32990000,0.98,-0.011,-0.013,0.17,0.017,-0.089,-0.083,0.028,-0.0031,0.044,-0.0014,-0.0057,2.2e-05,0.024,-0.034,-0.12,0.2,-2.4e-05,0.43,-0.0015,-0.002,0.00084,0,0,0.14,0.00027,0.00027,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -33090000,0.98,-0.011,-0.013,0.17,0.013,-0.093,-0.08,0.029,-0.012,0.037,-0.0014,-0.0057,2.2e-05,0.024,-0.034,-0.12,0.2,-2.4e-05,0.43,-0.0015,-0.002,0.00084,0,0,0.14,0.00027,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 -33190000,0.98,-0.01,-0.013,0.17,0.011,-0.094,-0.079,0.037,-0.016,0.029,-0.0014,-0.0057,1.3e-05,0.025,-0.034,-0.12,0.2,-2.2e-05,0.43,-0.0015,-0.002,0.00087,0,0,0.13,0.00027,0.00027,0.034,0.011,0.012,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.6e-07,0.024,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 -33290000,0.98,-0.01,-0.013,0.17,0.0073,-0.096,-0.079,0.037,-0.024,0.021,-0.0014,-0.0057,2.4e-05,0.025,-0.033,-0.12,0.2,-2.1e-05,0.43,-0.0016,-0.0021,0.0009,0,0,0.12,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 -33390000,0.98,-0.01,-0.013,0.17,0.0051,-0.09,-0.077,0.043,-0.022,0.012,-0.0014,-0.0057,1.6e-05,0.027,-0.032,-0.12,0.2,-1.8e-05,0.43,-0.0016,-0.002,0.00095,0,0,0.12,0.00027,0.00027,0.034,0.011,0.012,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.033 -33490000,0.98,-0.01,-0.013,0.17,-0.00022,-0.093,-0.076,0.042,-0.031,0.0027,-0.0014,-0.0057,2.1e-05,0.027,-0.032,-0.12,0.2,-1.7e-05,0.43,-0.0017,-0.0022,0.00097,0,0,0.12,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.4e-07,0.024,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.058 -33590000,0.98,-0.01,-0.013,0.17,-0.003,-0.092,-0.073,0.046,-0.029,-0.0052,-0.0014,-0.0057,2e-05,0.029,-0.031,-0.12,0.2,-1.3e-05,0.43,-0.0018,-0.0022,0.001,0,0,0.12,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.2e-07,7.4e-07,0.024,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.083 -33690000,0.98,-0.01,-0.013,0.17,-0.0063,-0.095,-0.074,0.046,-0.038,-0.013,-0.0014,-0.0057,2.5e-05,0.029,-0.032,-0.12,0.2,-1.4e-05,0.43,-0.0018,-0.002,0.001,0,0,0.12,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.2e-07,7.3e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.11 -33790000,0.98,-0.01,-0.013,0.17,-0.0082,-0.092,-0.068,0.052,-0.036,-0.02,-0.0014,-0.0057,1.5e-05,0.031,-0.031,-0.12,0.2,-1.2e-05,0.43,-0.0017,-0.0019,0.0011,0,0,0.12,0.00027,0.00026,0.034,0.011,0.012,0.0051,0.035,0.036,0.03,2.3e-07,2.2e-07,7.3e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.13 -33890000,0.98,-0.01,-0.013,0.17,-0.012,-0.093,-0.068,0.051,-0.045,-0.027,-0.0014,-0.0057,2.5e-05,0.031,-0.031,-0.12,0.2,-1.2e-05,0.43,-0.0018,-0.0019,0.0011,0,0,0.12,0.00027,0.00026,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.16 -33990000,0.98,-0.0099,-0.013,0.17,-0.013,-0.089,-0.064,0.055,-0.04,-0.031,-0.0014,-0.0057,1.2e-05,0.033,-0.031,-0.12,0.2,-8.8e-06,0.43,-0.0017,-0.0018,0.0011,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.18 -34090000,0.98,-0.0098,-0.013,0.17,-0.017,-0.093,-0.063,0.054,-0.049,-0.035,-0.0014,-0.0057,1.5e-05,0.032,-0.031,-0.12,0.2,-9.3e-06,0.43,-0.0017,-0.0017,0.0011,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.21 -34190000,0.98,-0.0098,-0.013,0.17,-0.018,-0.088,-0.06,0.058,-0.044,-0.038,-0.0014,-0.0057,1.1e-05,0.034,-0.03,-0.12,0.2,-6.9e-06,0.43,-0.0017,-0.0016,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.23 -34290000,0.98,-0.0096,-0.013,0.17,-0.019,-0.092,-0.059,0.056,-0.052,-0.044,-0.0014,-0.0057,1.7e-05,0.034,-0.03,-0.12,0.2,-6.2e-06,0.43,-0.0017,-0.0016,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.26 -34390000,0.98,-0.0095,-0.013,0.17,-0.021,-0.086,-0.054,0.058,-0.047,-0.048,-0.0014,-0.0056,1e-05,0.036,-0.03,-0.12,0.2,-4.1e-06,0.43,-0.0016,-0.0015,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.28 -34490000,0.98,-0.0095,-0.013,0.17,-0.024,-0.089,-0.052,0.057,-0.055,-0.051,-0.0014,-0.0056,1.9e-05,0.036,-0.03,-0.12,0.2,-3.7e-06,0.43,-0.0017,-0.0015,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.31 -34590000,0.98,-0.0094,-0.013,0.17,-0.026,-0.081,0.74,0.059,-0.05,-0.023,-0.0014,-0.0056,1.1e-05,0.037,-0.03,-0.12,0.2,-1.2e-06,0.43,-0.0017,-0.0014,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.33 -34690000,0.98,-0.0093,-0.013,0.17,-0.03,-0.079,1.7,0.056,-0.058,0.097,-0.0014,-0.0056,1.5e-05,0.037,-0.03,-0.12,0.2,-9.4e-07,0.43,-0.0017,-0.0014,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.0051,0.038,0.039,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.36 -34790000,0.98,-0.0093,-0.013,0.17,-0.033,-0.071,2.7,0.058,-0.052,0.28,-0.0015,-0.0056,8.3e-06,0.039,-0.03,-0.12,0.2,1.7e-06,0.43,-0.0017,-0.0014,0.0013,0,0,0.12,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.38 -34890000,0.98,-0.0092,-0.012,0.17,-0.038,-0.069,3.7,0.055,-0.058,0.57,-0.0015,-0.0056,1.2e-05,0.04,-0.03,-0.12,0.2,1.8e-06,0.43,-0.0017,-0.0013,0.0013,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.41 +10390000,0.98,-0.0071,-0.012,0.18,0.0076,0.0026,-0.0025,0.00078,3e-05,-0.028,-0.0012,-0.0056,-0.00011,-0.0003,0.00041,-0.14,0.2,-3.9e-06,0.43,-0.0002,-0.00011,-6.5e-05,0,0,0.095,0.0022,0.0016,0.041,0.25,0.25,0.56,0.25,0.25,0.048,3.6e-05,2.7e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.6 +10490000,0.98,-0.0073,-0.012,0.18,0.0096,0.00082,0.007,0.0016,0.00011,-0.023,-0.0011,-0.0057,-0.00011,-0.00033,0.00027,-0.14,0.2,-3e-06,0.43,-0.00016,-5.9e-05,-8.7e-05,0,0,0.095,0.0021,0.0016,0.041,0.25,0.26,0.55,0.26,0.26,0.057,3.5e-05,2.5e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10590000,0.98,-0.007,-0.012,0.18,0.00028,-0.00036,0.013,-0.0011,-0.0055,-0.021,-0.0012,-0.0056,-0.00011,-0.0003,0.00025,-0.14,0.2,-3.6e-06,0.43,-0.00018,-9.8e-05,-7.3e-05,0,0,0.095,0.0021,0.0015,0.041,0.13,0.13,0.27,0.13,0.13,0.055,3.3e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10690000,0.98,-0.0071,-0.013,0.18,0.0031,-0.0029,0.016,-0.0009,-0.0057,-0.018,-0.0011,-0.0056,-0.00011,-0.00027,0.00018,-0.14,0.2,-3.3e-06,0.43,-0.00021,-4.9e-05,-7e-05,0,0,0.095,0.0021,0.0015,0.041,0.13,0.14,0.26,0.14,0.14,0.065,3.2e-05,2.3e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10790000,0.98,-0.0073,-0.013,0.18,0.0057,-0.0061,0.014,-0.00055,-0.005,-0.015,-0.0011,-0.0056,-0.00011,-0.00016,7.3e-05,-0.14,0.2,-3.1e-06,0.43,-0.00026,1.3e-05,-9e-05,0,0,0.095,0.002,0.0014,0.041,0.09,0.094,0.17,0.09,0.09,0.061,3e-05,2.1e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.7 +10890000,0.98,-0.0069,-0.013,0.18,0.008,-0.003,0.0099,0.00021,-0.0052,-0.018,-0.0012,-0.0055,-0.00011,-5.5e-05,0.0002,-0.14,0.2,-4.1e-06,0.43,-0.00033,-3e-05,-7.2e-05,0,0,0.095,0.002,0.0014,0.041,0.096,0.1,0.16,0.096,0.096,0.068,2.9e-05,2e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +10990000,0.98,-0.0069,-0.013,0.18,0.0054,0.0031,0.016,-0.00022,-0.0036,-0.012,-0.0012,-0.0056,-0.00011,-0.00021,0.00015,-0.14,0.2,-4.1e-06,0.43,-0.00026,-5.9e-05,-0.00012,0,0,0.095,0.0019,0.0014,0.041,0.074,0.081,0.12,0.072,0.072,0.065,2.6e-05,1.9e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +11090000,0.98,-0.0075,-0.013,0.18,0.0093,0.0016,0.019,0.00071,-0.0039,-0.0075,-0.0011,-0.0056,-0.00011,-0.0003,-5.7e-05,-0.14,0.2,-2.9e-06,0.43,-0.00024,2.4e-05,-0.0001,0,0,0.095,0.0019,0.0013,0.041,0.081,0.092,0.11,0.078,0.078,0.069,2.6e-05,1.8e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +11190000,0.98,-0.0077,-0.013,0.18,0.0082,0.0022,0.026,0.0013,-0.0032,-0.00047,-0.001,-0.0056,-0.00012,-0.00042,-1.2e-05,-0.14,0.2,-2.4e-06,0.43,-0.00017,-1.3e-06,-0.00012,0,0,0.095,0.0017,0.0013,0.04,0.066,0.075,0.084,0.062,0.062,0.066,2.2e-05,1.6e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.8 +11290000,0.98,-0.0077,-0.012,0.18,0.0065,-0.00037,0.025,0.0016,-0.0032,-0.00025,-0.001,-0.0057,-0.00012,-0.00052,0.00011,-0.14,0.2,-2.2e-06,0.43,-0.0001,-4e-05,-0.00015,0,0,0.095,0.0017,0.0012,0.04,0.074,0.088,0.078,0.067,0.068,0.069,2.2e-05,1.5e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11390000,0.98,-0.0076,-0.012,0.18,0.0045,0.00076,0.016,0.0009,-0.0025,-0.0086,-0.001,-0.0057,-0.00012,-0.00055,1.9e-05,-0.14,0.2,-2.3e-06,0.43,-7.8e-05,-5.1e-05,-0.00018,0,0,0.095,0.0015,0.0012,0.04,0.062,0.073,0.064,0.056,0.056,0.066,1.9e-05,1.3e-05,2.2e-06,0.04,0.04,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11490000,0.98,-0.0075,-0.012,0.18,0.0052,-0.00076,0.02,0.0016,-0.0025,-0.0026,-0.001,-0.0057,-0.00012,-0.00053,-6.4e-05,-0.14,0.2,-2.3e-06,0.43,-0.0001,-3e-05,-0.00017,0,0,0.095,0.0015,0.0011,0.04,0.07,0.086,0.058,0.061,0.062,0.067,1.8e-05,1.3e-05,2.2e-06,0.04,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11590000,0.98,-0.0076,-0.012,0.18,0.0047,-0.00067,0.018,0.00077,-0.002,-0.0037,-0.001,-0.0058,-0.00012,-0.00061,2.7e-05,-0.14,0.2,-2.3e-06,0.43,-5e-05,-7e-05,-0.00019,0,0,0.095,0.0014,0.0011,0.04,0.06,0.072,0.049,0.052,0.052,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.9 +11690000,0.98,-0.0075,-0.012,0.18,0.0041,0.0017,0.018,0.00093,-0.0018,-0.0051,-0.0011,-0.0058,-0.00012,-0.00057,0.00015,-0.14,0.2,-2.5e-06,0.43,-4.4e-05,-8.6e-05,-0.00022,0,0,0.095,0.0014,0.001,0.04,0.068,0.084,0.046,0.058,0.059,0.065,1.5e-05,1.1e-05,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +11790000,0.98,-0.0075,-0.012,0.18,0.0028,0.0026,0.019,0.00044,-0.0024,-0.0021,-0.0011,-0.0058,-0.00012,-4.6e-05,0.00011,-0.14,0.2,-2.6e-06,0.43,-5.7e-05,-9.1e-05,-0.00022,0,0,0.095,0.0012,0.00096,0.039,0.058,0.07,0.039,0.049,0.05,0.062,1.2e-05,9.4e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +11890000,0.98,-0.0077,-0.012,0.18,0.0039,0.0012,0.017,0.0003,-0.0026,-0.0015,-0.0011,-0.0058,-0.00012,-0.00025,0.00027,-0.14,0.2,-2.4e-06,0.43,-2.6e-05,-9.1e-05,-0.00026,0,0,0.095,0.0012,0.00095,0.039,0.066,0.082,0.036,0.056,0.057,0.063,1.2e-05,9.1e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +11990000,0.98,-0.0077,-0.012,0.18,0.0067,0.0034,0.014,0.0014,-0.0027,-0.0051,-0.0011,-0.0058,-0.00012,-0.00032,0.00043,-0.14,0.2,-2.7e-06,0.43,-4.4e-05,-9.8e-05,-0.00026,0,0,0.095,0.0011,0.00088,0.039,0.056,0.068,0.032,0.048,0.049,0.061,1e-05,7.9e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3 +12090000,0.98,-0.0077,-0.012,0.18,0.0098,0.00099,0.017,0.0028,-0.0029,0.00085,-0.001,-0.0058,-0.00012,-0.00051,0.00017,-0.14,0.2,-2.4e-06,0.43,-4.3e-05,-6.6e-05,-0.00025,0,0,0.095,0.0011,0.00088,0.039,0.064,0.079,0.029,0.054,0.056,0.06,9.9e-06,7.6e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12190000,0.98,-0.0077,-0.012,0.18,0.011,-0.00018,0.016,0.0025,-0.0017,0.0027,-0.001,-0.0058,-0.00012,-0.0012,-0.00048,-0.14,0.2,-2.3e-06,0.43,-7.1e-06,-3.1e-05,-0.00028,0,0,0.095,0.00094,0.00081,0.039,0.055,0.065,0.026,0.047,0.048,0.058,8.3e-06,6.6e-06,2.2e-06,0.039,0.039,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12290000,0.98,-0.0078,-0.012,0.18,0.0081,-0.0037,0.015,0.0032,-0.0024,0.0036,-0.001,-0.0058,-0.00013,-0.0015,-0.0003,-0.14,0.2,-2.1e-06,0.43,2e-05,-3.9e-05,-0.00028,0,0,0.095,0.00094,0.00081,0.039,0.062,0.075,0.024,0.053,0.055,0.058,8.2e-06,6.4e-06,2.2e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12390000,0.98,-0.0079,-0.012,0.18,0.008,-0.0049,0.013,0.0027,-0.0021,-0.0024,-0.001,-0.0058,-0.00013,-0.0018,-0.00078,-0.14,0.2,-2e-06,0.43,4.7e-05,-1.8e-05,-0.0003,0,0,0.095,0.00084,0.00075,0.039,0.053,0.062,0.022,0.046,0.047,0.056,6.8e-06,5.5e-06,2.2e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.1 +12490000,0.98,-0.008,-0.012,0.18,0.0096,-0.0064,0.017,0.0041,-0.0032,-0.00046,-0.00099,-0.0058,-0.00013,-0.0021,-0.001,-0.14,0.2,-1.9e-06,0.43,5.5e-05,1.2e-05,-0.00031,0,0,0.095,0.00085,0.00074,0.039,0.06,0.071,0.021,0.053,0.055,0.056,6.7e-06,5.4e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12590000,0.98,-0.008,-0.012,0.18,0.012,-0.01,0.018,0.0043,-0.0042,0.0013,-0.00098,-0.0058,-0.00013,-0.0023,-0.0009,-0.14,0.2,-1.8e-06,0.43,6.9e-05,1.2e-05,-0.00032,0,0,0.095,0.00077,0.00069,0.039,0.051,0.059,0.019,0.046,0.047,0.054,5.7e-06,4.7e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12690000,0.98,-0.008,-0.012,0.18,0.012,-0.014,0.018,0.0054,-0.0056,0.0028,-0.00097,-0.0058,-0.00013,-0.0024,-0.00085,-0.14,0.2,-1.8e-06,0.43,7.9e-05,1.7e-05,-0.00033,0,0,0.095,0.00077,0.00069,0.039,0.057,0.067,0.018,0.053,0.054,0.054,5.6e-06,4.6e-06,2.1e-06,0.039,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12790000,0.98,-0.0081,-0.012,0.18,0.014,-0.012,0.019,0.0054,-0.0062,0.005,-0.00098,-0.0058,-0.00013,-0.0018,-0.0013,-0.14,0.2,-1.8e-06,0.43,4.4e-05,4e-05,-0.00031,0,0,0.095,0.0007,0.00065,0.039,0.049,0.056,0.016,0.046,0.047,0.052,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.2 +12890000,0.98,-0.008,-0.012,0.18,0.016,-0.013,0.021,0.0071,-0.007,0.0079,-0.00099,-0.0058,-0.00012,-0.0014,-0.0015,-0.14,0.2,-1.9e-06,0.43,2.4e-05,4.5e-05,-0.00029,0,0,0.095,0.0007,0.00065,0.039,0.055,0.063,0.016,0.052,0.054,0.052,4.8e-06,4e-06,2.1e-06,0.038,0.038,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +12990000,0.98,-0.0079,-0.012,0.18,0.013,-0.0088,0.021,0.005,-0.0047,0.0091,-0.001,-0.0058,-0.00012,-0.0013,-0.0016,-0.14,0.2,-2.4e-06,0.43,3.8e-05,2e-05,-0.00032,0,0,0.095,0.00065,0.00061,0.038,0.047,0.053,0.014,0.046,0.047,0.05,4.1e-06,3.5e-06,2.1e-06,0.038,0.037,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +13090000,0.98,-0.0079,-0.012,0.18,0.015,-0.0077,0.018,0.0067,-0.0048,0.0078,-0.001,-0.0058,-0.00012,-0.00076,-0.0018,-0.14,0.2,-2.4e-06,0.43,1.5e-05,2.5e-05,-0.0003,0,0,0.095,0.00065,0.00061,0.038,0.052,0.059,0.014,0.052,0.054,0.05,4.1e-06,3.4e-06,2.1e-06,0.038,0.037,0.00055,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +13190000,0.98,-0.0079,-0.012,0.18,0.0097,-0.0078,0.017,0.003,-0.0048,0.0084,-0.0011,-0.0058,-0.00012,-0.00054,-0.0023,-0.14,0.2,-2.6e-06,0.43,3.9e-05,2.3e-05,-0.00031,0,0,0.095,0.00061,0.00058,0.038,0.044,0.05,0.013,0.046,0.047,0.048,3.6e-06,3.1e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.3 +13290000,0.98,-0.008,-0.012,0.18,0.011,-0.0095,0.015,0.0046,-0.0059,0.0076,-0.001,-0.0058,-0.00012,-0.00076,-0.0028,-0.14,0.2,-2.4e-06,0.43,4.8e-05,4.4e-05,-0.00031,0,0,0.095,0.00061,0.00058,0.038,0.049,0.056,0.013,0.052,0.054,0.048,3.5e-06,3e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13390000,0.98,-0.0079,-0.012,0.18,0.0091,-0.0081,0.014,0.0032,-0.0049,0.0081,-0.0011,-0.0058,-0.00012,-0.0014,-0.0028,-0.14,0.2,-2.7e-06,0.43,8.6e-05,4.1e-05,-0.00035,0,0,0.095,0.00057,0.00055,0.038,0.042,0.047,0.012,0.045,0.046,0.047,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13490000,0.98,-0.0079,-0.012,0.18,0.011,-0.0068,0.014,0.0048,-0.0056,0.0041,-0.001,-0.0058,-0.00012,-0.0015,-0.0033,-0.14,0.2,-2.6e-06,0.43,8.9e-05,6.4e-05,-0.00035,0,0,0.095,0.00057,0.00055,0.038,0.047,0.052,0.011,0.052,0.053,0.046,3.1e-06,2.7e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13590000,0.98,-0.0079,-0.012,0.18,0.014,-0.0071,0.015,0.0065,-0.0048,0.0025,-0.001,-0.0058,-0.00013,-0.002,-0.0034,-0.14,0.2,-2.6e-06,0.43,9.8e-05,5.7e-05,-0.00035,0,0,0.095,0.00054,0.00053,0.038,0.04,0.044,0.011,0.045,0.046,0.045,2.8e-06,2.4e-06,2.1e-06,0.038,0.037,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.4 +13690000,0.98,-0.0078,-0.012,0.18,0.014,-0.0082,0.015,0.0077,-0.0052,0.0051,-0.0011,-0.0058,-0.00012,-0.0017,-0.0031,-0.14,0.2,-2.6e-06,0.43,8.5e-05,3.7e-05,-0.00033,0,0,0.095,0.00054,0.00053,0.038,0.044,0.049,0.011,0.052,0.053,0.045,2.8e-06,2.4e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +13790000,0.98,-0.0077,-0.012,0.18,0.019,-0.0044,0.015,0.0098,-0.0027,0.0044,-0.0011,-0.0058,-0.00013,-0.0022,-0.0026,-0.14,0.2,-2.8e-06,0.43,8.3e-05,1.5e-05,-0.00034,0,0,0.095,0.00052,0.00051,0.038,0.038,0.042,0.01,0.045,0.046,0.044,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +13890000,0.98,-0.0076,-0.012,0.18,0.019,-0.0029,0.016,0.011,-0.0025,0.0066,-0.0011,-0.0058,-0.00012,-0.0015,-0.002,-0.14,0.2,-3e-06,0.43,6.2e-05,1.1e-07,-0.00034,0,0,0.095,0.00052,0.00051,0.038,0.042,0.046,0.01,0.051,0.053,0.044,2.5e-06,2.2e-06,2.1e-06,0.038,0.036,0.00054,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +13990000,0.98,-0.0076,-0.012,0.18,0.019,-0.001,0.014,0.0088,-0.003,0.0053,-0.0011,-0.0058,-0.00012,-0.001,-0.0025,-0.14,0.2,-2.9e-06,0.43,7e-05,-1.1e-06,-0.00031,0,0,0.095,0.0005,0.0005,0.038,0.036,0.039,0.0097,0.045,0.046,0.043,2.3e-06,2e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.5 +14090000,0.98,-0.0077,-0.011,0.18,0.017,-0.0082,0.015,0.011,-0.0049,0.0015,-0.0011,-0.0058,-0.00013,-0.0028,-0.0023,-0.14,0.2,-2.8e-06,0.43,0.00012,6.9e-06,-0.00035,0,0,0.095,0.0005,0.0005,0.038,0.04,0.043,0.0096,0.051,0.053,0.042,2.2e-06,2e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14190000,0.98,-0.0078,-0.011,0.18,0.016,-0.0075,0.015,0.01,-0.0045,0.0015,-0.001,-0.0058,-0.00014,-0.0039,-0.0034,-0.14,0.2,-2.6e-06,0.43,0.00018,3.2e-05,-0.00037,0,0,0.095,0.00048,0.00048,0.038,0.034,0.037,0.0094,0.045,0.046,0.042,2.1e-06,1.8e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14290000,0.98,-0.0077,-0.011,0.18,0.018,-0.0081,0.013,0.012,-0.0054,0.0057,-0.001,-0.0058,-0.00014,-0.004,-0.0036,-0.14,0.2,-2.6e-06,0.43,0.00018,3.6e-05,-0.00036,0,0,0.095,0.00048,0.00048,0.038,0.038,0.041,0.0092,0.051,0.052,0.041,2e-06,1.8e-06,2.1e-06,0.037,0.036,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14390000,0.98,-0.0078,-0.011,0.18,0.018,-0.0095,0.015,0.011,-0.0055,0.01,-0.001,-0.0058,-0.00014,-0.0038,-0.0044,-0.14,0.2,-2.4e-06,0.43,0.00019,4.1e-05,-0.00035,0,0,0.095,0.00047,0.00047,0.038,0.033,0.035,0.009,0.045,0.046,0.04,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00053,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.6 +14490000,0.98,-0.008,-0.011,0.18,0.018,-0.011,0.019,0.013,-0.0073,0.012,-0.001,-0.0058,-0.00014,-0.0049,-0.0045,-0.14,0.2,-2.3e-06,0.43,0.00022,5e-05,-0.00037,0,0,0.095,0.00047,0.00047,0.038,0.036,0.038,0.009,0.051,0.052,0.04,1.9e-06,1.7e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14590000,0.98,-0.0081,-0.011,0.18,0.017,-0.01,0.016,0.0099,-0.0073,0.008,-0.001,-0.0058,-0.00015,-0.0054,-0.0058,-0.14,0.2,-2.1e-06,0.43,0.00027,6.9e-05,-0.00037,0,0,0.095,0.00045,0.00046,0.038,0.031,0.033,0.0088,0.045,0.045,0.04,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14690000,0.98,-0.0081,-0.011,0.18,0.017,-0.01,0.016,0.012,-0.0083,0.0081,-0.001,-0.0058,-0.00014,-0.0053,-0.0062,-0.14,0.2,-2e-06,0.43,0.00027,7.5e-05,-0.00037,0,0,0.095,0.00045,0.00046,0.038,0.034,0.036,0.0088,0.05,0.051,0.039,1.8e-06,1.6e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14790000,0.98,-0.0082,-0.011,0.18,0.019,-0.0034,0.016,0.01,-0.0022,0.011,-0.0011,-0.0058,-0.00014,-0.0047,-0.0076,-0.14,0.2,-2.2e-06,0.43,0.00027,7.3e-05,-0.00035,0,0,0.095,0.00044,0.00045,0.038,0.03,0.031,0.0086,0.044,0.045,0.039,1.7e-06,1.5e-06,2.1e-06,0.037,0.035,0.00052,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.7 +14890000,0.98,-0.0082,-0.011,0.18,0.021,-0.0055,0.02,0.013,-0.0023,0.012,-0.0011,-0.0058,-0.00013,-0.0042,-0.0093,-0.14,0.2,-1.8e-06,0.43,0.00027,9.5e-05,-0.00031,0,0,0.095,0.00044,0.00045,0.038,0.032,0.034,0.0087,0.05,0.051,0.039,1.6e-06,1.5e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +14990000,0.98,-0.0083,-0.011,0.18,0.02,-0.0057,0.023,0.012,-0.0029,0.014,-0.0011,-0.0058,-0.00013,-0.0041,-0.011,-0.14,0.2,-1.5e-06,0.43,0.0003,0.00012,-0.00029,0,0,0.095,0.00043,0.00045,0.038,0.028,0.03,0.0085,0.044,0.045,0.038,1.6e-06,1.4e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +15090000,0.98,-0.0083,-0.011,0.18,0.021,-0.0049,0.026,0.014,-0.0036,0.016,-0.0011,-0.0058,-0.00013,-0.0042,-0.011,-0.14,0.2,-1.5e-06,0.43,0.0003,0.00013,-0.00029,0,0,0.095,0.00043,0.00045,0.038,0.03,0.032,0.0085,0.05,0.051,0.038,1.5e-06,1.4e-06,2.1e-06,0.037,0.035,0.00051,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +15190000,0.98,-0.0085,-0.011,0.18,0.019,-0.0059,0.027,0.012,-0.0032,0.017,-0.0011,-0.0058,-0.00014,-0.0048,-0.012,-0.14,0.2,-1.4e-06,0.43,0.00034,0.00014,-0.00029,0,0,0.095,0.00043,0.00044,0.038,0.027,0.028,0.0085,0.044,0.045,0.038,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.8 +15290000,0.98,-0.0086,-0.012,0.18,0.022,-0.0065,0.026,0.015,-0.0034,0.014,-0.0011,-0.0058,-0.00013,-0.0042,-0.014,-0.14,0.2,-1.2e-06,0.43,0.00033,0.00017,-0.00027,0,0,0.095,0.00043,0.00044,0.038,0.029,0.031,0.0085,0.049,0.05,0.037,1.5e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15390000,0.98,-0.0088,-0.011,0.18,0.021,-0.0039,0.025,0.012,-0.0028,0.014,-0.0011,-0.0058,-0.00013,-0.0045,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00037,0.00019,-0.00029,0,0,0.095,0.00042,0.00043,0.038,0.025,0.027,0.0084,0.044,0.044,0.037,1.4e-06,1.3e-06,2.1e-06,0.036,0.034,0.0005,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15490000,0.98,-0.0088,-0.011,0.18,0.022,-0.0067,0.025,0.014,-0.0034,0.015,-0.0011,-0.0058,-0.00013,-0.0046,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00037,0.00019,-0.00029,0,0,0.095,0.00042,0.00043,0.038,0.028,0.029,0.0085,0.049,0.05,0.037,1.4e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15590000,0.98,-0.0088,-0.011,0.18,0.023,-0.0081,0.025,0.014,-0.0059,0.013,-0.0011,-0.0058,-0.00013,-0.0042,-0.014,-0.14,0.2,-1.3e-06,0.43,0.00036,0.00019,-0.00028,0,0,0.095,0.00041,0.00043,0.038,0.024,0.026,0.0084,0.043,0.044,0.037,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,3.9 +15690000,0.98,-0.0086,-0.011,0.18,0.024,-0.01,0.025,0.015,-0.0063,0.014,-0.0011,-0.0058,-0.00012,-0.0032,-0.012,-0.14,0.2,-1.8e-06,0.43,0.00031,0.00013,-0.00026,0,0,0.095,0.00041,0.00043,0.038,0.026,0.028,0.0085,0.049,0.049,0.037,1.3e-06,1.2e-06,2.1e-06,0.036,0.034,0.00049,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +15790000,0.98,-0.0086,-0.011,0.18,0.019,-0.0094,0.025,0.012,-0.0047,0.015,-0.0011,-0.0058,-0.00012,-0.0021,-0.012,-0.14,0.2,-2.2e-06,0.43,0.0003,0.00012,-0.00026,0,0,0.095,0.00041,0.00042,0.038,0.023,0.025,0.0084,0.043,0.044,0.036,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +15890000,0.98,-0.0087,-0.011,0.18,0.02,-0.0085,0.025,0.015,-0.0061,0.014,-0.0011,-0.0058,-0.00012,-0.0031,-0.012,-0.14,0.2,-1.9e-06,0.43,0.00034,0.00014,-0.00027,0,0,0.095,0.00041,0.00042,0.038,0.025,0.026,0.0085,0.048,0.049,0.036,1.3e-06,1.1e-06,2.1e-06,0.036,0.034,0.00048,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +15990000,0.98,-0.0086,-0.011,0.18,0.018,-0.0074,0.022,0.013,-0.0051,0.013,-0.0011,-0.0058,-0.00012,-0.0034,-0.014,-0.14,0.2,-2.1e-06,0.43,0.00038,0.00019,-0.00029,0,0,0.095,0.0004,0.00042,0.038,0.022,0.023,0.0084,0.043,0.043,0.036,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4 +16090000,0.98,-0.0087,-0.011,0.18,0.019,-0.0092,0.02,0.015,-0.0063,0.013,-0.0011,-0.0058,-0.00013,-0.004,-0.014,-0.14,0.2,-2e-06,0.43,0.00041,0.00021,-0.00031,0,0,0.095,0.0004,0.00042,0.038,0.024,0.025,0.0085,0.048,0.049,0.036,1.2e-06,1.1e-06,2e-06,0.036,0.033,0.00047,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16190000,0.98,-0.0086,-0.011,0.18,0.015,-0.0076,0.018,0.011,-0.0054,0.0094,-0.0011,-0.0058,-0.00013,-0.0047,-0.015,-0.13,0.2,-2e-06,0.43,0.00044,0.00021,-0.00033,0,0,0.095,0.0004,0.00041,0.038,0.021,0.022,0.0084,0.043,0.043,0.036,1.2e-06,1e-06,2e-06,0.036,0.033,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16290000,0.98,-0.0086,-0.011,0.18,0.017,-0.009,0.018,0.013,-0.0061,0.011,-0.0011,-0.0058,-0.00013,-0.0044,-0.014,-0.13,0.2,-2e-06,0.43,0.00043,0.0002,-0.00032,0,0,0.095,0.0004,0.00041,0.038,0.023,0.024,0.0085,0.047,0.048,0.036,1.2e-06,1e-06,2e-06,0.035,0.033,0.00046,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16390000,0.98,-0.0087,-0.011,0.18,0.019,-0.0081,0.018,0.013,-0.0048,0.011,-0.0011,-0.0058,-0.00013,-0.004,-0.017,-0.13,0.2,-1.7e-06,0.43,0.00045,0.00024,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.021,0.022,0.0084,0.042,0.043,0.036,1.1e-06,1e-06,2e-06,0.035,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.1 +16490000,0.98,-0.0089,-0.011,0.18,0.022,-0.01,0.021,0.015,-0.0059,0.015,-0.0011,-0.0058,-0.00013,-0.0044,-0.017,-0.13,0.2,-1.5e-06,0.43,0.00046,0.00025,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.022,0.023,0.0085,0.047,0.048,0.036,1.1e-06,1e-06,2e-06,0.035,0.033,0.00045,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16590000,0.98,-0.0089,-0.011,0.18,0.026,-0.01,0.024,0.013,-0.0049,0.015,-0.0011,-0.0058,-0.00013,-0.0043,-0.018,-0.13,0.2,-1.7e-06,0.43,0.00048,0.00025,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.02,0.021,0.0084,0.042,0.042,0.036,1.1e-06,9.7e-07,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16690000,0.98,-0.0089,-0.011,0.18,0.028,-0.015,0.024,0.016,-0.0059,0.015,-0.0011,-0.0058,-0.00013,-0.0037,-0.017,-0.13,0.2,-1.9e-06,0.43,0.00046,0.00024,-0.0003,0,0,0.095,0.00039,0.00041,0.038,0.021,0.022,0.0085,0.047,0.047,0.036,1.1e-06,9.6e-07,2e-06,0.035,0.033,0.00044,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16790000,0.98,-0.0087,-0.011,0.18,0.028,-0.014,0.023,0.013,-0.0048,0.015,-0.0011,-0.0058,-0.00012,-0.0031,-0.017,-0.13,0.2,-2.2e-06,0.43,0.00046,0.00024,-0.00029,0,0,0.095,0.00038,0.0004,0.038,0.019,0.02,0.0085,0.042,0.042,0.036,1e-06,9.3e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.2 +16890000,0.98,-0.0087,-0.011,0.18,0.028,-0.014,0.024,0.016,-0.0056,0.013,-0.0011,-0.0058,-0.00012,-0.0021,-0.017,-0.13,0.2,-2.3e-06,0.43,0.00043,0.00023,-0.00028,0,0,0.095,0.00038,0.0004,0.038,0.02,0.022,0.0085,0.046,0.047,0.036,1e-06,9.2e-07,2e-06,0.035,0.032,0.00043,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +16990000,0.98,-0.0087,-0.011,0.18,0.026,-0.014,0.024,0.014,-0.0046,0.012,-0.0011,-0.0058,-0.00011,-0.0017,-0.017,-0.13,0.2,-2.3e-06,0.43,0.00044,0.00025,-0.00028,0,0,0.095,0.00038,0.0004,0.038,0.018,0.019,0.0084,0.041,0.042,0.035,1e-06,9e-07,2e-06,0.035,0.032,0.00042,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +17090000,0.98,-0.0089,-0.011,0.18,0.03,-0.017,0.023,0.018,-0.0063,0.011,-0.0011,-0.0058,-0.00012,-0.0022,-0.019,-0.13,0.2,-2.4e-06,0.43,0.00048,0.00032,-0.00029,0,0,0.095,0.00038,0.0004,0.038,0.02,0.021,0.0085,0.046,0.046,0.035,9.9e-07,8.9e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +17190000,0.98,-0.009,-0.011,0.18,0.028,-0.021,0.025,0.014,-0.0096,0.014,-0.0011,-0.0058,-0.00012,-0.0031,-0.019,-0.13,0.2,-2.9e-06,0.43,0.00052,0.00033,-0.00033,0,0,0.095,0.00038,0.0004,0.038,0.018,0.019,0.0084,0.041,0.042,0.035,9.6e-07,8.7e-07,2e-06,0.035,0.032,0.00041,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.3 +17290000,0.98,-0.009,-0.011,0.18,0.031,-0.023,0.025,0.017,-0.012,0.014,-0.0011,-0.0058,-0.00013,-0.0038,-0.019,-0.13,0.2,-2.9e-06,0.43,0.00055,0.00034,-0.00035,0,0,0.095,0.00038,0.0004,0.038,0.019,0.02,0.0085,0.045,0.046,0.036,9.6e-07,8.6e-07,2e-06,0.035,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17390000,0.98,-0.0089,-0.011,0.18,0.025,-0.023,0.024,0.016,-0.009,0.013,-0.0011,-0.0058,-0.00012,-0.0025,-0.018,-0.13,0.2,-3.2e-06,0.43,0.00053,0.00034,-0.00034,0,0,0.095,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.041,0.041,0.035,9.3e-07,8.4e-07,2e-06,0.034,0.032,0.0004,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17490000,0.98,-0.009,-0.011,0.18,0.024,-0.025,0.024,0.019,-0.012,0.015,-0.0011,-0.0058,-0.00013,-0.0028,-0.019,-0.13,0.2,-3.2e-06,0.43,0.00054,0.00034,-0.00035,0,0,0.095,0.00037,0.00039,0.038,0.018,0.019,0.0085,0.045,0.046,0.036,9.3e-07,8.3e-07,2e-06,0.034,0.032,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17590000,0.98,-0.0089,-0.011,0.18,0.021,-0.022,0.023,0.014,-0.0098,0.013,-0.0011,-0.0058,-0.00013,-0.0023,-0.019,-0.13,0.2,-3.8e-06,0.43,0.00055,0.00034,-0.00035,0,0,0.095,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.04,0.041,0.035,9e-07,8.1e-07,2e-06,0.034,0.032,0.00039,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.4 +17690000,0.98,-0.009,-0.011,0.18,0.022,-0.023,0.024,0.016,-0.012,0.015,-0.0011,-0.0058,-0.00013,-0.002,-0.019,-0.13,0.2,-3.5e-06,0.43,0.00053,0.00032,-0.00033,0,0,0.095,0.00037,0.00039,0.038,0.018,0.019,0.0084,0.045,0.045,0.035,9e-07,8e-07,2e-06,0.034,0.031,0.00038,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +17790000,0.98,-0.0091,-0.011,0.18,0.023,-0.022,0.025,0.015,-0.011,0.02,-0.0011,-0.0058,-0.00013,-0.0013,-0.019,-0.13,0.2,-3.5e-06,0.43,0.0005,0.00029,-0.00031,0,0,0.095,0.00037,0.00039,0.038,0.016,0.017,0.0084,0.04,0.041,0.036,8.8e-07,7.8e-07,2e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +17890000,0.98,-0.0089,-0.011,0.18,0.026,-0.024,0.025,0.017,-0.013,0.025,-0.0011,-0.0058,-0.00012,-0.00072,-0.018,-0.13,0.2,-3.5e-06,0.43,0.00048,0.00027,-0.0003,0,0,0.095,0.00037,0.00039,0.038,0.017,0.018,0.0084,0.044,0.045,0.036,8.7e-07,7.8e-07,2e-06,0.034,0.031,0.00037,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +17990000,0.98,-0.0089,-0.011,0.18,0.025,-0.02,0.024,0.016,-0.0083,0.026,-0.0012,-0.0058,-0.00012,9.1e-05,-0.02,-0.13,0.2,-3.5e-06,0.43,0.00048,0.00027,-0.00029,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.0083,0.04,0.04,0.035,8.5e-07,7.6e-07,2e-06,0.034,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.5 +18090000,0.98,-0.009,-0.011,0.18,0.026,-0.021,0.024,0.018,-0.01,0.024,-0.0012,-0.0058,-0.00012,0.00014,-0.02,-0.13,0.2,-3.3e-06,0.43,0.00047,0.00027,-0.00028,0,0,0.095,0.00036,0.00038,0.038,0.017,0.018,0.0083,0.044,0.045,0.036,8.5e-07,7.5e-07,1.9e-06,0.034,0.031,0.00036,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18190000,0.98,-0.0091,-0.011,0.18,0.025,-0.019,0.024,0.017,-0.0083,0.022,-0.0012,-0.0058,-0.00011,0.0017,-0.021,-0.13,0.2,-3.6e-06,0.43,0.00045,0.00029,-0.00025,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0082,0.04,0.04,0.035,8.2e-07,7.4e-07,1.9e-06,0.034,0.031,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18290000,0.98,-0.0092,-0.011,0.18,0.028,-0.02,0.023,0.02,-0.01,0.02,-0.0012,-0.0058,-0.00011,0.0019,-0.022,-0.13,0.2,-3.4e-06,0.43,0.00045,0.0003,-0.00024,0,0,0.095,0.00036,0.00038,0.038,0.016,0.018,0.0082,0.044,0.044,0.036,8.2e-07,7.3e-07,1.9e-06,0.034,0.031,0.00035,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18390000,0.98,-0.0091,-0.011,0.18,0.027,-0.019,0.023,0.019,-0.0089,0.019,-0.0012,-0.0058,-0.00011,0.0021,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00046,0.00031,-0.00025,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0081,0.039,0.04,0.035,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.6 +18490000,0.98,-0.0091,-0.011,0.18,0.031,-0.019,0.022,0.022,-0.01,0.021,-0.0012,-0.0058,-0.00011,0.0027,-0.022,-0.13,0.2,-3.7e-06,0.43,0.00044,0.00031,-0.00024,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.0082,0.043,0.044,0.036,8e-07,7.1e-07,1.9e-06,0.033,0.031,0.00034,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18590000,0.98,-0.0089,-0.011,0.18,0.028,-0.019,0.022,0.019,-0.0093,0.024,-0.0012,-0.0058,-0.00011,0.003,-0.021,-0.13,0.2,-4.2e-06,0.43,0.00044,0.00028,-0.00024,0,0,0.095,0.00036,0.00038,0.038,0.015,0.016,0.0081,0.039,0.04,0.035,7.8e-07,6.9e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18690000,0.98,-0.0088,-0.011,0.18,0.028,-0.018,0.021,0.021,-0.011,0.022,-0.0012,-0.0058,-0.00011,0.0039,-0.02,-0.13,0.2,-4.2e-06,0.43,0.0004,0.00025,-0.00022,0,0,0.095,0.00036,0.00038,0.038,0.016,0.017,0.0081,0.043,0.044,0.035,7.7e-07,6.9e-07,1.9e-06,0.033,0.03,0.00033,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18790000,0.98,-0.0087,-0.011,0.18,0.026,-0.017,0.02,0.019,-0.0093,0.02,-0.0012,-0.0058,-0.00011,0.0044,-0.02,-0.13,0.2,-4.7e-06,0.43,0.00041,0.00026,-0.00023,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.008,0.039,0.04,0.036,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00032,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.7 +18890000,0.98,-0.0087,-0.011,0.18,0.027,-0.018,0.018,0.022,-0.011,0.016,-0.0012,-0.0058,-0.00011,0.0042,-0.02,-0.13,0.2,-4.7e-06,0.43,0.00042,0.00028,-0.00024,0,0,0.095,0.00035,0.00037,0.038,0.015,0.017,0.008,0.043,0.043,0.036,7.5e-07,6.7e-07,1.9e-06,0.033,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +18990000,0.98,-0.0087,-0.011,0.18,0.024,-0.018,0.019,0.019,-0.0097,0.02,-0.0012,-0.0058,-0.00011,0.005,-0.019,-0.13,0.2,-5.3e-06,0.43,0.00042,0.00027,-0.00024,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0079,0.039,0.039,0.035,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.00031,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +19090000,0.98,-0.0087,-0.011,0.18,0.023,-0.018,0.02,0.022,-0.011,0.016,-0.0012,-0.0058,-0.0001,0.0055,-0.019,-0.13,0.2,-5.2e-06,0.43,0.00041,0.00027,-0.00023,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.008,0.042,0.043,0.036,7.3e-07,6.5e-07,1.9e-06,0.033,0.03,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +19190000,0.98,-0.0086,-0.011,0.18,0.02,-0.018,0.02,0.019,-0.01,0.016,-0.0012,-0.0058,-0.00011,0.0053,-0.019,-0.13,0.2,-6e-06,0.43,0.00043,0.00028,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.0003,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.8 +19290000,0.98,-0.0086,-0.011,0.18,0.021,-0.019,0.02,0.021,-0.012,0.015,-0.0012,-0.0058,-0.00011,0.0053,-0.019,-0.13,0.2,-6e-06,0.43,0.00043,0.00029,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,7.1e-07,6.3e-07,1.9e-06,0.033,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19390000,0.98,-0.0087,-0.011,0.18,0.019,-0.016,0.022,0.018,-0.0097,0.014,-0.0012,-0.0058,-0.00011,0.0059,-0.019,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00028,-0.00026,0,0,0.095,0.00035,0.00037,0.038,0.014,0.015,0.0078,0.038,0.039,0.035,6.9e-07,6.2e-07,1.9e-06,0.032,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19490000,0.98,-0.0088,-0.011,0.18,0.021,-0.017,0.021,0.021,-0.012,0.014,-0.0012,-0.0058,-0.00012,0.0053,-0.02,-0.13,0.2,-6e-06,0.43,0.00043,0.00026,-0.00025,0,0,0.095,0.00035,0.00037,0.038,0.015,0.016,0.0078,0.042,0.043,0.035,6.9e-07,6.1e-07,1.9e-06,0.032,0.03,0.00029,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19590000,0.98,-0.0087,-0.011,0.18,0.018,-0.019,0.023,0.019,-0.011,0.014,-0.0012,-0.0058,-0.00012,0.0055,-0.02,-0.13,0.2,-6.3e-06,0.43,0.00043,0.00026,-0.00025,0,0,0.095,0.00034,0.00036,0.038,0.013,0.015,0.0076,0.038,0.039,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,4.9 +19690000,0.98,-0.0088,-0.011,0.18,0.018,-0.017,0.022,0.022,-0.013,0.014,-0.0012,-0.0058,-0.00011,0.006,-0.021,-0.13,0.2,-6e-06,0.43,0.00042,0.00026,-0.00024,0,0,0.095,0.00034,0.00036,0.038,0.014,0.016,0.0076,0.042,0.042,0.035,6.7e-07,6e-07,1.8e-06,0.032,0.029,0.00028,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +19790000,0.98,-0.0089,-0.011,0.18,0.016,-0.016,0.02,0.021,-0.011,0.01,-0.0012,-0.0058,-0.00012,0.0061,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00027,-0.00025,0,0,0.095,0.00034,0.00036,0.038,0.013,0.014,0.0076,0.038,0.039,0.035,6.6e-07,5.8e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +19890000,0.98,-0.0089,-0.011,0.18,0.017,-0.016,0.021,0.023,-0.013,0.0089,-0.0012,-0.0058,-0.00012,0.006,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00027,-0.00026,0,0,0.095,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.5e-07,5.8e-07,1.8e-06,0.032,0.029,0.00027,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +19990000,0.98,-0.0089,-0.012,0.18,0.015,-0.016,0.018,0.02,-0.01,0.006,-0.0012,-0.0058,-0.00012,0.007,-0.021,-0.13,0.2,-7e-06,0.43,0.00042,0.00027,-0.00025,0,0,0.095,0.00034,0.00036,0.038,0.013,0.014,0.0074,0.038,0.038,0.035,6.4e-07,5.7e-07,1.8e-06,0.032,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5 +20090000,0.98,-0.0089,-0.012,0.18,0.017,-0.019,0.019,0.022,-0.012,0.0095,-0.0012,-0.0058,-0.00012,0.0071,-0.021,-0.13,0.2,-6.9e-06,0.43,0.00042,0.00028,-0.00025,0,0,0.095,0.00034,0.00036,0.038,0.014,0.015,0.0075,0.041,0.042,0.035,6.4e-07,5.6e-07,1.8e-06,0.032,0.029,0.00026,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,5.1 +20190000,0.98,-0.0089,-0.012,0.18,0.017,-0.016,0.02,0.022,-0.011,0.0094,-0.0012,-0.0058,-0.00013,0.0071,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00042,0.00029,-0.00027,0,0,0.11,0.00034,0.00036,0.038,0.013,0.014,0.0074,0.037,0.038,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20290000,0.98,-0.009,-0.012,0.18,0.015,-0.018,0.02,0.023,-0.012,0.01,-0.0012,-0.0058,-0.00012,0.0071,-0.022,-0.13,0.2,-7.5e-06,0.43,0.00042,0.0003,-0.00027,0,0,0.11,0.00034,0.00036,0.038,0.014,0.015,0.0073,0.041,0.042,0.035,6.2e-07,5.5e-07,1.8e-06,0.032,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20390000,0.98,-0.0089,-0.012,0.18,0.013,-0.016,0.02,0.022,-0.011,0.012,-0.0012,-0.0058,-0.00012,0.0081,-0.022,-0.13,0.2,-7.6e-06,0.43,0.00041,0.00028,-0.00026,0,0,0.11,0.00033,0.00035,0.038,0.013,0.014,0.0073,0.037,0.038,0.035,6.1e-07,5.4e-07,1.8e-06,0.031,0.029,0.00025,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20490000,0.98,-0.0089,-0.012,0.18,0.0096,-0.017,0.02,0.023,-0.012,0.0099,-0.0012,-0.0058,-0.00012,0.0082,-0.022,-0.13,0.2,-7.4e-06,0.43,0.00041,0.00027,-0.00026,0,0,0.11,0.00034,0.00035,0.038,0.014,0.015,0.0073,0.041,0.042,0.035,6e-07,5.3e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20590000,0.98,-0.0088,-0.012,0.18,0.0088,-0.017,0.02,0.022,-0.01,0.0085,-0.0013,-0.0058,-0.00011,0.0094,-0.022,-0.13,0.2,-7.3e-06,0.43,0.00039,0.00025,-0.00025,0,0,0.11,0.00033,0.00035,0.038,0.013,0.014,0.0072,0.037,0.038,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20690000,0.98,-0.0087,-0.012,0.18,0.0077,-0.017,0.021,0.022,-0.012,0.0092,-0.0013,-0.0058,-0.00012,0.0092,-0.022,-0.13,0.2,-7.5e-06,0.43,0.00039,0.00025,-0.00025,0,0,0.11,0.00033,0.00035,0.038,0.013,0.015,0.0072,0.04,0.042,0.035,5.9e-07,5.2e-07,1.8e-06,0.031,0.029,0.00024,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20790000,0.98,-0.0081,-0.012,0.18,0.0038,-0.013,0.0061,0.019,-0.01,0.008,-0.0013,-0.0058,-0.00011,0.01,-0.022,-0.13,0.2,-7.9e-06,0.43,0.00038,0.00025,-0.00025,0,0,0.11,0.00033,0.00035,0.038,0.013,0.014,0.0071,0.037,0.038,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20890000,0.98,0.00098,-0.0077,0.18,-4.9e-05,-0.002,-0.11,0.02,-0.011,0.002,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-8.7e-06,0.43,0.00037,0.00037,-0.00019,0,0,0.1,0.00033,0.00035,0.038,0.013,0.015,0.0071,0.04,0.041,0.035,5.7e-07,5.1e-07,1.8e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0013,0.0013,0.0015,0.0013,1,1,0.01 +20990000,0.98,0.0044,-0.0043,0.18,-0.012,0.017,-0.25,0.017,-0.0086,-0.013,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-8.7e-06,0.43,0.00037,0.00036,-0.00015,0,0,0.087,0.00033,0.00035,0.038,0.013,0.014,0.007,0.037,0.038,0.034,5.6e-07,5e-07,1.7e-06,0.031,0.028,0.00023,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21090000,0.98,0.0027,-0.0047,0.18,-0.024,0.032,-0.37,0.016,-0.006,-0.043,-0.0013,-0.0058,-0.00011,0.01,-0.023,-0.13,0.2,-7e-06,0.43,0.00042,0.00016,-0.00019,0,0,0.057,0.00033,0.00035,0.038,0.014,0.015,0.007,0.04,0.041,0.035,5.6e-07,4.9e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21190000,0.98,-6.1e-05,-0.0063,0.18,-0.029,0.039,-0.5,0.013,-0.0039,-0.08,-0.0013,-0.0058,-0.0001,0.01,-0.024,-0.13,0.2,-6.3e-06,0.43,0.00043,0.00019,-0.00018,0,0,0.02,0.00033,0.00034,0.038,0.013,0.014,0.0069,0.037,0.038,0.034,5.5e-07,4.8e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21290000,0.98,-0.0023,-0.0076,0.18,-0.029,0.041,-0.63,0.0099,-0.0003,-0.14,-0.0013,-0.0058,-0.00011,0.0096,-0.024,-0.13,0.2,-6.9e-06,0.43,0.00042,0.00023,-0.00011,0,0,-0.038,0.00033,0.00034,0.037,0.014,0.015,0.0069,0.04,0.041,0.034,5.4e-07,4.8e-07,1.7e-06,0.031,0.028,0.00022,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21390000,0.98,-0.0037,-0.0082,0.18,-0.026,0.038,-0.75,0.0082,0.0037,-0.2,-0.0013,-0.0058,-0.00011,0.0097,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00044,0.00015,-0.00012,0,0,-0.1,0.00032,0.00034,0.037,0.013,0.014,0.0068,0.037,0.038,0.034,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21490000,0.98,-0.0045,-0.0086,0.18,-0.021,0.035,-0.89,0.0054,0.0077,-0.29,-0.0013,-0.0058,-0.0001,0.01,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00043,0.00018,-0.00017,0,0,-0.19,0.00032,0.00034,0.037,0.014,0.016,0.0068,0.04,0.041,0.034,5.3e-07,4.7e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21590000,0.98,-0.0049,-0.0086,0.18,-0.015,0.032,-1,0.0044,0.0099,-0.38,-0.0013,-0.0058,-9.5e-05,0.011,-0.024,-0.13,0.2,-6.5e-06,0.43,0.00042,0.00023,-0.00018,0,0,-0.28,0.00032,0.00034,0.037,0.013,0.015,0.0067,0.037,0.038,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.00021,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21690000,0.98,-0.0052,-0.0085,0.18,-0.012,0.027,-1.1,0.0032,0.013,-0.49,-0.0013,-0.0058,-8.8e-05,0.011,-0.024,-0.13,0.2,-6.4e-06,0.43,0.00039,0.00027,-0.00016,0,0,-0.39,0.00032,0.00034,0.037,0.014,0.016,0.0067,0.04,0.041,0.034,5.2e-07,4.6e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21790000,0.98,-0.0055,-0.0086,0.18,-0.0065,0.022,-1.3,0.007,0.012,-0.61,-0.0013,-0.0058,-7.8e-05,0.012,-0.023,-0.13,0.2,-6.4e-06,0.43,0.00039,0.00027,-0.00022,0,0,-0.51,0.00032,0.00033,0.037,0.013,0.015,0.0066,0.037,0.038,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.028,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21890000,0.98,-0.0058,-0.0088,0.18,-0.0029,0.017,-1.4,0.0062,0.014,-0.75,-0.0013,-0.0058,-8.1e-05,0.012,-0.023,-0.13,0.2,-6.8e-06,0.43,0.00036,0.00029,-0.00021,0,0,-0.65,0.00032,0.00033,0.037,0.014,0.016,0.0066,0.04,0.041,0.034,5e-07,4.5e-07,1.7e-06,0.03,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +21990000,0.98,-0.0064,-0.009,0.18,-0.00083,0.013,-1.4,0.01,0.011,-0.89,-0.0013,-0.0058,-7.5e-05,0.012,-0.022,-0.13,0.2,-6.5e-06,0.43,0.00039,0.0003,-0.00023,0,0,-0.79,0.00031,0.00033,0.037,0.013,0.015,0.0066,0.037,0.038,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.0002,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22090000,0.98,-0.0071,-0.0099,0.18,0.0012,0.0095,-1.4,0.0095,0.013,-1,-0.0013,-0.0058,-6.6e-05,0.012,-0.022,-0.13,0.2,-6.4e-06,0.43,0.00039,0.00031,-0.00024,0,0,-0.93,0.00031,0.00033,0.037,0.014,0.016,0.0066,0.04,0.041,0.034,4.9e-07,4.4e-07,1.6e-06,0.03,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22190000,0.98,-0.0075,-0.01,0.18,0.007,0.0051,-1.4,0.015,0.008,-1.2,-0.0013,-0.0058,-5.8e-05,0.013,-0.02,-0.13,0.2,-6.6e-06,0.43,0.00039,0.00033,-0.00024,0,0,-1.1,0.00031,0.00032,0.037,0.013,0.014,0.0065,0.037,0.038,0.034,4.8e-07,4.3e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22290000,0.98,-0.0082,-0.01,0.18,0.013,-0.00054,-1.4,0.016,0.0081,-1.3,-0.0013,-0.0058,-6e-05,0.013,-0.021,-0.13,0.2,-6.5e-06,0.43,0.00039,0.00033,-0.00023,0,0,-1.2,0.00031,0.00032,0.037,0.014,0.015,0.0065,0.04,0.041,0.034,4.8e-07,4.2e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22390000,0.98,-0.0085,-0.01,0.18,0.017,-0.0091,-1.4,0.022,-0.00072,-1.5,-0.0013,-0.0058,-6.3e-05,0.012,-0.02,-0.13,0.2,-6.6e-06,0.43,0.0004,0.00033,-0.00026,0,0,-1.4,0.0003,0.00032,0.037,0.013,0.014,0.0064,0.037,0.038,0.034,4.7e-07,4.2e-07,1.6e-06,0.029,0.027,0.00019,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22490000,0.98,-0.0087,-0.011,0.18,0.021,-0.016,-1.4,0.024,-0.0023,-1.6,-0.0013,-0.0058,-6.7e-05,0.011,-0.02,-0.13,0.2,-6.9e-06,0.43,0.00041,0.00035,-0.00028,0,0,-1.5,0.00031,0.00032,0.037,0.013,0.015,0.0064,0.04,0.041,0.034,4.7e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22590000,0.98,-0.0086,-0.012,0.18,0.029,-0.024,-1.4,0.034,-0.01,-1.7,-0.0013,-0.0058,-5.8e-05,0.012,-0.02,-0.13,0.2,-6.5e-06,0.43,0.00042,0.00037,-0.00027,0,0,-1.6,0.0003,0.00032,0.037,0.012,0.014,0.0063,0.036,0.038,0.033,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22690000,0.98,-0.0085,-0.012,0.18,0.032,-0.028,-1.4,0.038,-0.013,-1.9,-0.0013,-0.0058,-6.1e-05,0.012,-0.021,-0.13,0.2,-6.4e-06,0.43,0.00041,0.00037,-0.00028,0,0,-1.8,0.0003,0.00032,0.037,0.013,0.015,0.0064,0.04,0.041,0.034,4.5e-07,4.1e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22790000,0.98,-0.0085,-0.012,0.18,0.038,-0.036,-1.4,0.048,-0.022,-2,-0.0013,-0.0058,-6.4e-05,0.011,-0.021,-0.13,0.2,-6.6e-06,0.43,0.0004,0.00034,-0.00031,0,0,-1.9,0.0003,0.00031,0.037,0.012,0.014,0.0063,0.036,0.038,0.033,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22890000,0.98,-0.0087,-0.012,0.18,0.042,-0.041,-1.4,0.052,-0.026,-2.2,-0.0013,-0.0058,-5.6e-05,0.011,-0.021,-0.13,0.2,-6.3e-06,0.43,0.00041,0.00035,-0.00029,0,0,-2.1,0.0003,0.00031,0.037,0.013,0.015,0.0063,0.04,0.041,0.033,4.4e-07,4e-07,1.6e-06,0.029,0.027,0.00018,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +22990000,0.98,-0.0086,-0.013,0.18,0.046,-0.045,-1.4,0.061,-0.035,-2.3,-0.0013,-0.0058,-4.7e-05,0.012,-0.02,-0.13,0.2,-6.7e-06,0.43,0.0004,0.00032,-0.00026,0,0,-2.2,0.0003,0.00031,0.037,0.012,0.014,0.0062,0.036,0.038,0.033,4.3e-07,3.9e-07,1.6e-06,0.029,0.027,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23090000,0.98,-0.0086,-0.013,0.18,0.051,-0.05,-1.4,0.065,-0.04,-2.5,-0.0013,-0.0058,-4.6e-05,0.012,-0.02,-0.13,0.2,-6.7e-06,0.43,0.00039,0.00033,-0.00025,0,0,-2.4,0.0003,0.00031,0.037,0.013,0.014,0.0062,0.04,0.041,0.033,4.3e-07,3.9e-07,1.5e-06,0.028,0.027,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23190000,0.98,-0.0086,-0.013,0.18,0.057,-0.052,-1.4,0.076,-0.05,-2.6,-0.0013,-0.0058,-4.9e-05,0.012,-0.02,-0.13,0.2,-7.5e-06,0.43,0.00037,0.0003,-0.00025,0,0,-2.5,0.00029,0.00031,0.037,0.012,0.013,0.0061,0.036,0.037,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23290000,0.98,-0.0091,-0.014,0.18,0.062,-0.057,-1.4,0.082,-0.055,-2.8,-0.0013,-0.0058,-4.6e-05,0.012,-0.02,-0.13,0.2,-7.5e-06,0.43,0.00034,0.00034,-0.00025,0,0,-2.7,0.00029,0.00031,0.037,0.013,0.014,0.0062,0.039,0.041,0.033,4.2e-07,3.8e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23390000,0.98,-0.009,-0.014,0.18,0.067,-0.06,-1.4,0.092,-0.061,-2.9,-0.0013,-0.0058,-5.9e-05,0.012,-0.019,-0.13,0.2,-7.7e-06,0.43,0.00035,0.00031,-0.00023,0,0,-2.8,0.00029,0.0003,0.037,0.012,0.013,0.0061,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00017,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23490000,0.98,-0.0091,-0.014,0.18,0.072,-0.062,-1.4,0.1,-0.067,-3,-0.0013,-0.0058,-5.1e-05,0.012,-0.02,-0.13,0.2,-7.5e-06,0.43,0.00033,0.00037,-0.00028,0,0,-2.9,0.00029,0.0003,0.037,0.013,0.014,0.0061,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23590000,0.98,-0.0093,-0.014,0.18,0.075,-0.064,-1.4,0.11,-0.076,-3.2,-0.0013,-0.0058,-4.8e-05,0.013,-0.019,-0.13,0.2,-8.4e-06,0.43,0.00029,0.00033,-0.00024,0,0,-3.1,0.00029,0.0003,0.037,0.012,0.013,0.006,0.036,0.037,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23690000,0.98,-0.01,-0.015,0.18,0.074,-0.066,-1.3,0.11,-0.082,-3.3,-0.0013,-0.0058,-4e-05,0.013,-0.02,-0.13,0.2,-8.3e-06,0.43,0.00027,0.00036,-0.00024,0,0,-3.2,0.00029,0.0003,0.037,0.012,0.014,0.006,0.039,0.041,0.033,4.1e-07,3.7e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23790000,0.98,-0.012,-0.017,0.18,0.068,-0.062,-0.95,0.12,-0.086,-3.4,-0.0013,-0.0058,-3.8e-05,0.014,-0.02,-0.13,0.2,-8e-06,0.43,0.00025,0.00039,-0.00022,0,0,-3.3,0.00029,0.0003,0.037,0.011,0.013,0.006,0.036,0.037,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23890000,0.98,-0.015,-0.021,0.18,0.064,-0.062,-0.52,0.13,-0.092,-3.5,-0.0013,-0.0058,-3.6e-05,0.014,-0.02,-0.13,0.2,-8e-06,0.43,0.00024,0.00041,-0.00024,0,0,-3.4,0.00029,0.0003,0.037,0.012,0.013,0.006,0.039,0.041,0.033,4e-07,3.6e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +23990000,0.98,-0.017,-0.024,0.18,0.064,-0.061,-0.13,0.14,-0.095,-3.6,-0.0013,-0.0058,-4.2e-05,0.015,-0.019,-0.13,0.2,-8.1e-06,0.43,0.0002,0.00043,3.8e-06,0,0,-3.5,0.00028,0.0003,0.037,0.011,0.012,0.0059,0.036,0.037,0.033,3.9e-07,3.5e-07,1.5e-06,0.028,0.026,0.00016,0.0013,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24090000,0.98,-0.017,-0.023,0.18,0.07,-0.069,0.099,0.14,-0.1,-3.6,-0.0013,-0.0058,-4.5e-05,0.015,-0.019,-0.13,0.2,-8.1e-06,0.43,0.00022,0.0004,3.7e-06,0,0,-3.5,0.00028,0.0003,0.037,0.012,0.013,0.0059,0.039,0.04,0.033,3.9e-07,3.5e-07,1.4e-06,0.028,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24190000,0.98,-0.014,-0.019,0.18,0.08,-0.074,0.089,0.15,-0.1,-3.6,-0.0013,-0.0058,-4.5e-05,0.017,-0.019,-0.13,0.2,-7.7e-06,0.43,0.00022,0.00037,0.0001,0,0,-3.5,0.00028,0.0003,0.037,0.011,0.012,0.0059,0.036,0.037,0.032,3.8e-07,3.5e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24290000,0.98,-0.012,-0.016,0.18,0.084,-0.078,0.067,0.16,-0.11,-3.6,-0.0013,-0.0058,-4.3e-05,0.017,-0.019,-0.13,0.2,-7.3e-06,0.43,0.00025,0.00032,9.8e-05,0,0,-3.5,0.00028,0.0003,0.037,0.012,0.013,0.0059,0.039,0.04,0.033,3.8e-07,3.5e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24390000,0.98,-0.011,-0.015,0.18,0.077,-0.073,0.083,0.16,-0.11,-3.6,-0.0013,-0.0058,-4.2e-05,0.018,-0.02,-0.13,0.2,-6e-06,0.43,0.00024,0.00036,0.00016,0,0,-3.5,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.037,0.032,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24490000,0.98,-0.011,-0.015,0.18,0.073,-0.069,0.081,0.17,-0.12,-3.6,-0.0013,-0.0058,-2.8e-05,0.019,-0.021,-0.13,0.2,-6e-06,0.43,0.00017,0.00047,0.00021,0,0,-3.5,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.8e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24590000,0.98,-0.012,-0.015,0.18,0.069,-0.066,0.077,0.17,-0.12,-3.6,-0.0013,-0.0058,-3.9e-05,0.02,-0.021,-0.13,0.2,-4.7e-06,0.43,0.0002,0.00044,0.00023,0,0,-3.5,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.037,0.032,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24690000,0.98,-0.012,-0.015,0.18,0.068,-0.065,0.076,0.18,-0.12,-3.5,-0.0013,-0.0058,-3.8e-05,0.02,-0.021,-0.13,0.2,-4.9e-06,0.43,0.00019,0.00047,0.00022,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.7e-07,3.4e-07,1.4e-06,0.027,0.026,0.00015,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24790000,0.98,-0.012,-0.014,0.18,0.065,-0.063,0.068,0.18,-0.12,-3.5,-0.0014,-0.0058,-4.6e-05,0.022,-0.022,-0.13,0.2,-4.3e-06,0.43,0.00019,0.00047,0.00021,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0058,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.026,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24890000,0.98,-0.012,-0.014,0.18,0.063,-0.067,0.057,0.19,-0.13,-3.5,-0.0014,-0.0058,-4e-05,0.022,-0.022,-0.13,0.2,-4.1e-06,0.43,0.00018,0.00048,0.00024,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0058,0.038,0.04,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +24990000,0.98,-0.012,-0.014,0.18,0.055,-0.063,0.05,0.19,-0.12,-3.5,-0.0014,-0.0058,-5.4e-05,0.024,-0.023,-0.13,0.2,-4.3e-06,0.43,0.00015,0.00059,0.00025,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25090000,0.98,-0.012,-0.014,0.18,0.051,-0.063,0.048,0.19,-0.12,-3.5,-0.0014,-0.0058,-5.4e-05,0.024,-0.023,-0.13,0.2,-4.9e-06,0.43,0.00013,0.00066,0.00029,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.6e-07,3.3e-07,1.4e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25190000,0.98,-0.012,-0.014,0.18,0.046,-0.057,0.048,0.19,-0.12,-3.5,-0.0014,-0.0058,-7.2e-05,0.025,-0.024,-0.13,0.2,-4.9e-06,0.43,0.00011,0.00069,0.00028,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25290000,0.98,-0.012,-0.013,0.18,0.041,-0.059,0.043,0.2,-0.12,-3.5,-0.0014,-0.0058,-7.9e-05,0.025,-0.023,-0.13,0.2,-5.5e-06,0.43,0.0001,0.00072,0.00025,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25390000,0.98,-0.012,-0.013,0.18,0.033,-0.052,0.041,0.19,-0.11,-3.5,-0.0014,-0.0058,-9.4e-05,0.027,-0.024,-0.13,0.2,-6.3e-06,0.43,6.6e-05,0.00077,0.00026,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0057,0.035,0.036,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25490000,0.98,-0.013,-0.013,0.18,0.028,-0.052,0.041,0.19,-0.12,-3.5,-0.0014,-0.0058,-9.6e-05,0.027,-0.025,-0.13,0.2,-6.1e-06,0.43,6e-05,0.00073,0.00024,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0057,0.038,0.04,0.032,3.5e-07,3.2e-07,1.3e-06,0.027,0.025,0.00014,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25590000,0.98,-0.013,-0.012,0.18,0.023,-0.049,0.042,0.19,-0.11,-3.5,-0.0014,-0.0058,-0.00011,0.028,-0.026,-0.13,0.2,-6.9e-06,0.43,2.9e-05,0.00076,0.00021,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25690000,0.98,-0.012,-0.012,0.18,0.023,-0.048,0.031,0.19,-0.11,-3.5,-0.0014,-0.0058,-0.00011,0.028,-0.026,-0.13,0.2,-7e-06,0.43,3.4e-05,0.00078,0.00022,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25790000,0.98,-0.012,-0.012,0.18,0.012,-0.04,0.031,0.18,-0.1,-3.5,-0.0014,-0.0058,-0.00012,0.029,-0.026,-0.13,0.2,-7.5e-06,0.43,-2.6e-05,0.00071,0.00021,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25890000,0.98,-0.012,-0.012,0.18,0.006,-0.039,0.033,0.18,-0.11,-3.5,-0.0014,-0.0058,-0.00013,0.029,-0.026,-0.13,0.2,-7.6e-06,0.43,-4.6e-05,0.00068,0.00016,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.4e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +25990000,0.98,-0.012,-0.012,0.18,-0.003,-0.032,0.027,0.17,-0.097,-3.5,-0.0014,-0.0058,-0.00015,0.031,-0.026,-0.13,0.2,-9e-06,0.43,-0.0001,0.00066,0.00014,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0056,0.035,0.036,0.032,3.3e-07,3.1e-07,1.3e-06,0.027,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26090000,0.98,-0.012,-0.012,0.18,-0.0076,-0.032,0.026,0.17,-0.1,-3.5,-0.0014,-0.0058,-0.00014,0.031,-0.026,-0.13,0.2,-8.5e-06,0.43,-9.8e-05,0.00065,0.00017,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3.1e-07,1.3e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26190000,0.98,-0.012,-0.012,0.18,-0.015,-0.025,0.021,0.16,-0.092,-3.5,-0.0015,-0.0058,-0.00014,0.032,-0.026,-0.13,0.2,-8.9e-06,0.43,-0.00012,0.00065,0.00019,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26290000,0.98,-0.012,-0.013,0.18,-0.015,-0.024,0.015,0.16,-0.095,-3.5,-0.0015,-0.0058,-0.00015,0.032,-0.027,-0.13,0.2,-9.5e-06,0.43,-0.00013,0.00066,0.00016,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0056,0.038,0.039,0.032,3.3e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26390000,0.98,-0.011,-0.013,0.18,-0.021,-0.017,0.019,0.15,-0.086,-3.5,-0.0015,-0.0058,-0.00016,0.033,-0.027,-0.13,0.2,-1.1e-05,0.43,-0.00017,0.00064,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26490000,0.98,-0.011,-0.013,0.18,-0.023,-0.015,0.028,0.14,-0.087,-3.5,-0.0015,-0.0058,-0.00016,0.033,-0.027,-0.13,0.2,-1.1e-05,0.43,-0.00017,0.00067,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,3e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26590000,0.98,-0.01,-0.013,0.18,-0.026,-0.0064,0.029,0.13,-0.079,-3.5,-0.0015,-0.0058,-0.00017,0.034,-0.028,-0.13,0.2,-1.2e-05,0.43,-0.0002,0.00069,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00013,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26690000,0.98,-0.01,-0.012,0.18,-0.027,-0.0024,0.027,0.13,-0.08,-3.5,-0.0015,-0.0058,-0.00018,0.033,-0.028,-0.13,0.2,-1.3e-05,0.43,-0.00021,0.0007,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26790000,0.98,-0.0099,-0.012,0.18,-0.035,0.0019,0.027,0.12,-0.073,-3.5,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00024,0.00068,0.00011,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0055,0.035,0.036,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26890000,0.98,-0.0092,-0.012,0.18,-0.04,0.0048,0.022,0.11,-0.073,-3.5,-0.0015,-0.0058,-0.00019,0.034,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00024,0.00066,0.00011,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.2e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +26990000,0.98,-0.0087,-0.013,0.18,-0.048,0.012,0.022,0.098,-0.065,-3.5,-0.0015,-0.0058,-0.00019,0.035,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00026,0.00065,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27090000,0.98,-0.0085,-0.013,0.18,-0.05,0.018,0.025,0.093,-0.064,-3.5,-0.0015,-0.0058,-0.00019,0.035,-0.027,-0.13,0.2,-1.3e-05,0.43,-0.00025,0.00064,0.00012,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0055,0.038,0.039,0.031,3.1e-07,2.9e-07,1.2e-06,0.026,0.025,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27190000,0.98,-0.0086,-0.013,0.18,-0.056,0.025,0.027,0.081,-0.056,-3.5,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.4e-05,0.43,-0.00027,0.00063,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27290000,0.98,-0.0088,-0.014,0.18,-0.063,0.03,0.14,0.076,-0.054,-3.5,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.4e-05,0.43,-0.00027,0.00063,0.00013,0,0,-3.4,0.00028,0.00029,0.037,0.012,0.013,0.0054,0.038,0.039,0.031,3.1e-07,2.8e-07,1.2e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27390000,0.98,-0.01,-0.016,0.18,-0.071,0.037,0.46,0.064,-0.045,-3.5,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.13,0.2,-1.5e-05,0.43,-0.00033,0.00056,0.00018,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27490000,0.98,-0.012,-0.018,0.18,-0.074,0.042,0.78,0.057,-0.041,-3.5,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.13,0.2,-1.6e-05,0.43,-0.00031,0.00052,0.00018,0,0,-3.4,0.00028,0.00029,0.037,0.011,0.013,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27590000,0.98,-0.011,-0.017,0.18,-0.07,0.046,0.87,0.046,-0.036,-3.4,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00029,0.00047,0.00021,0,0,-3.3,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27690000,0.98,-0.01,-0.014,0.18,-0.065,0.042,0.78,0.04,-0.031,-3.3,-0.0015,-0.0058,-0.00021,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00046,0.00019,0,0,-3.2,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27790000,0.98,-0.0088,-0.012,0.18,-0.065,0.04,0.77,0.032,-0.027,-3.2,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00042,0.0002,0,0,-3.1,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.035,0.036,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27890000,0.98,-0.0085,-0.013,0.18,-0.071,0.047,0.81,0.026,-0.023,-3.2,-0.0015,-0.0058,-0.0002,0.035,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00042,0.0002,0,0,-3.1,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,3e-07,2.8e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +27990000,0.98,-0.0089,-0.013,0.18,-0.072,0.049,0.8,0.019,-0.019,-3.1,-0.0015,-0.0058,-0.0002,0.034,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00027,0.00036,0.00022,0,0,-3,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28090000,0.98,-0.0092,-0.013,0.18,-0.076,0.05,0.8,0.011,-0.014,-3,-0.0015,-0.0058,-0.00019,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00028,0.00038,0.00021,0,0,-2.9,0.00028,0.00029,0.037,0.011,0.012,0.0054,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00012,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28190000,0.98,-0.0086,-0.013,0.18,-0.077,0.047,0.81,0.004,-0.012,-2.9,-0.0015,-0.0058,-0.00019,0.034,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00026,0.00037,0.00022,0,0,-2.8,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28290000,0.98,-0.0081,-0.013,0.18,-0.081,0.051,0.81,-0.0032,-0.0067,-2.9,-0.0015,-0.0058,-0.00018,0.034,-0.029,-0.12,0.2,-1.6e-05,0.43,-0.00027,0.00039,0.00019,0,0,-2.8,0.00028,0.00029,0.037,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28390000,0.98,-0.0081,-0.014,0.18,-0.082,0.055,0.81,-0.0097,-0.0023,-2.8,-0.0014,-0.0058,-0.00017,0.033,-0.029,-0.12,0.2,-1.6e-05,0.43,-0.00032,0.0003,0.0002,0,0,-2.7,0.00028,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28490000,0.98,-0.0084,-0.015,0.18,-0.085,0.058,0.81,-0.019,0.0032,-2.7,-0.0014,-0.0058,-0.00017,0.033,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00029,0.00029,0.00023,0,0,-2.6,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1.1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0015,0.0012,1,1,0.01 +28590000,0.98,-0.0085,-0.014,0.18,-0.079,0.054,0.81,-0.023,0.0026,-2.6,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.6e-05,0.43,-0.00026,0.00027,0.00022,0,0,-2.5,0.00028,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28690000,0.98,-0.0082,-0.014,0.18,-0.078,0.055,0.81,-0.031,0.008,-2.6,-0.0014,-0.0058,-0.00016,0.032,-0.028,-0.12,0.2,-1.7e-05,0.43,-0.00023,0.00027,0.00022,0,0,-2.5,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.9e-07,2.7e-07,1e-06,0.026,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28790000,0.98,-0.0076,-0.014,0.18,-0.076,0.056,0.81,-0.035,0.011,-2.5,-0.0014,-0.0058,-0.00015,0.032,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00025,0.00017,0.00022,0,0,-2.4,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28890000,0.98,-0.0074,-0.013,0.18,-0.08,0.058,0.81,-0.043,0.017,-2.4,-0.0014,-0.0058,-0.00014,0.032,-0.029,-0.12,0.2,-1.7e-05,0.43,-0.00025,0.0002,0.00019,0,0,-2.3,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +28990000,0.98,-0.0072,-0.013,0.18,-0.077,0.055,0.81,-0.044,0.017,-2.3,-0.0014,-0.0058,-0.00014,0.031,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00029,5.9e-05,0.00023,0,0,-2.2,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29090000,0.98,-0.007,-0.013,0.18,-0.08,0.057,0.81,-0.052,0.023,-2.3,-0.0014,-0.0058,-0.00014,0.031,-0.028,-0.12,0.2,-1.8e-05,0.43,-0.00031,4.1e-05,0.00023,0,0,-2.2,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29190000,0.98,-0.0069,-0.014,0.18,-0.078,0.056,0.81,-0.052,0.023,-2.2,-0.0014,-0.0058,-0.00012,0.03,-0.028,-0.12,0.2,-2e-05,0.43,-0.00033,-8.9e-05,0.00024,0,0,-2.1,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.035,0.036,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29290000,0.98,-0.0072,-0.014,0.18,-0.081,0.062,0.81,-0.061,0.029,-2.1,-0.0014,-0.0058,-0.00012,0.03,-0.028,-0.12,0.2,-2e-05,0.43,-0.00033,-0.00011,0.00024,0,0,-2,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,1e-06,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29390000,0.98,-0.0076,-0.013,0.18,-0.078,0.061,0.81,-0.06,0.031,-2,-0.0014,-0.0058,-0.00011,0.029,-0.028,-0.12,0.2,-2.2e-05,0.43,-0.00036,-0.00024,0.00025,0,0,-1.9,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.8e-07,2.6e-07,9.9e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29490000,0.98,-0.0076,-0.013,0.18,-0.081,0.062,0.81,-0.069,0.038,-2,-0.0014,-0.0058,-0.0001,0.029,-0.028,-0.12,0.2,-2.2e-05,0.43,-0.00039,-0.00021,0.00023,0,0,-1.9,0.00029,0.00029,0.036,0.011,0.012,0.0053,0.038,0.039,0.031,2.8e-07,2.6e-07,9.8e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29590000,0.98,-0.0075,-0.013,0.18,-0.077,0.061,0.81,-0.067,0.038,-1.9,-0.0014,-0.0058,-8.7e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00043,-0.00031,0.00023,0,0,-1.8,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.6e-07,9.7e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29690000,0.98,-0.0075,-0.013,0.18,-0.082,0.06,0.81,-0.076,0.044,-1.8,-0.0014,-0.0058,-8e-05,0.028,-0.028,-0.12,0.2,-2.3e-05,0.43,-0.00045,-0.00028,0.00021,0,0,-1.7,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.6e-07,9.7e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29790000,0.98,-0.0073,-0.013,0.18,-0.079,0.054,0.81,-0.072,0.043,-1.7,-0.0014,-0.0058,-6.4e-05,0.027,-0.028,-0.12,0.2,-2.5e-05,0.43,-0.00051,-0.0004,0.00021,0,0,-1.6,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29890000,0.98,-0.0068,-0.013,0.18,-0.08,0.056,0.8,-0.08,0.048,-1.7,-0.0014,-0.0058,-5.7e-05,0.028,-0.028,-0.12,0.2,-2.4e-05,0.43,-0.00053,-0.00037,0.00019,0,0,-1.6,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.031,2.7e-07,2.5e-07,9.6e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +29990000,0.98,-0.007,-0.013,0.18,-0.075,0.051,0.8,-0.076,0.044,-1.6,-0.0014,-0.0058,-4.6e-05,0.027,-0.029,-0.12,0.2,-2.6e-05,0.43,-0.00051,-0.00042,0.00021,0,0,-1.5,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.5e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30090000,0.98,-0.0071,-0.013,0.18,-0.077,0.051,0.8,-0.084,0.049,-1.5,-0.0014,-0.0058,-5.6e-05,0.026,-0.028,-0.12,0.2,-2.7e-05,0.43,-0.00046,-0.00048,0.00026,0,0,-1.4,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.4e-07,0.025,0.024,0.00011,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30190000,0.98,-0.0071,-0.013,0.18,-0.071,0.048,0.8,-0.078,0.047,-1.5,-0.0014,-0.0058,-5.9e-05,0.026,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00047,-0.0007,0.00032,0,0,-1.4,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30290000,0.98,-0.0071,-0.013,0.18,-0.071,0.048,0.8,-0.085,0.052,-1.4,-0.0014,-0.0058,-5.7e-05,0.026,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00051,-0.00075,0.00032,0,0,-1.3,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.3e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30390000,0.98,-0.0071,-0.013,0.18,-0.065,0.043,0.8,-0.078,0.049,-1.3,-0.0014,-0.0058,-4e-05,0.025,-0.029,-0.12,0.2,-3e-05,0.43,-0.00065,-0.00096,0.00032,0,0,-1.2,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.2e-07,0.025,0.024,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30490000,0.98,-0.0071,-0.013,0.18,-0.069,0.043,0.8,-0.085,0.054,-1.2,-0.0014,-0.0058,-3.4e-05,0.025,-0.029,-0.12,0.2,-2.9e-05,0.43,-0.00069,-0.00095,0.0003,0,0,-1.1,0.00029,0.00029,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.7e-07,2.5e-07,9.2e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30590000,0.98,-0.0074,-0.014,0.18,-0.064,0.041,0.8,-0.077,0.051,-1.2,-0.0014,-0.0058,-1.8e-05,0.025,-0.03,-0.12,0.2,-3e-05,0.43,-0.00079,-0.0011,0.0003,0,0,-1.1,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.5e-07,9.1e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30690000,0.98,-0.0078,-0.014,0.18,-0.063,0.04,0.8,-0.084,0.055,-1.1,-0.0014,-0.0058,-1.8e-05,0.025,-0.03,-0.12,0.2,-3e-05,0.43,-0.00077,-0.001,0.00029,0,0,-0.99,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.5e-07,9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30790000,0.98,-0.0075,-0.013,0.17,-0.056,0.034,0.8,-0.076,0.053,-1,-0.0014,-0.0058,-1.4e-05,0.024,-0.031,-0.12,0.2,-3.2e-05,0.43,-0.00085,-0.0012,0.00033,0,0,-0.92,0.00028,0.00028,0.036,0.011,0.012,0.0052,0.035,0.036,0.03,2.6e-07,2.4e-07,8.9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30890000,0.98,-0.0069,-0.013,0.17,-0.056,0.031,0.79,-0.081,0.056,-0.95,-0.0014,-0.0058,-2.1e-05,0.024,-0.031,-0.12,0.2,-3.2e-05,0.43,-0.00075,-0.0011,0.00035,0,0,-0.85,0.00029,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.9e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +30990000,0.98,-0.0071,-0.013,0.17,-0.049,0.025,0.8,-0.071,0.049,-0.88,-0.0014,-0.0057,-1.3e-05,0.024,-0.032,-0.12,0.2,-3.3e-05,0.43,-0.00079,-0.0013,0.00038,0,0,-0.78,0.00028,0.00028,0.036,0.011,0.012,0.0051,0.035,0.036,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31090000,0.98,-0.0073,-0.013,0.17,-0.048,0.024,0.79,-0.075,0.052,-0.81,-0.0014,-0.0057,-1.8e-05,0.024,-0.032,-0.12,0.2,-3.3e-05,0.43,-0.00074,-0.0012,0.00039,0,0,-0.71,0.00028,0.00028,0.036,0.011,0.012,0.0052,0.038,0.039,0.03,2.6e-07,2.4e-07,8.8e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31190000,0.98,-0.0075,-0.013,0.17,-0.043,0.02,0.8,-0.066,0.047,-0.74,-0.0013,-0.0057,-1.7e-06,0.024,-0.033,-0.12,0.2,-3.4e-05,0.43,-0.00084,-0.0012,0.00038,0,0,-0.64,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31290000,0.98,-0.0077,-0.014,0.17,-0.04,0.018,0.8,-0.07,0.049,-0.67,-0.0013,-0.0057,3.4e-06,0.024,-0.033,-0.12,0.2,-3.3e-05,0.43,-0.00087,-0.0012,0.00037,0,0,-0.57,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.6e-07,2.4e-07,8.7e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31390000,0.98,-0.0075,-0.013,0.17,-0.035,0.011,0.8,-0.061,0.043,-0.59,-0.0013,-0.0057,2.7e-06,0.023,-0.033,-0.12,0.2,-3.3e-05,0.43,-0.00096,-0.0015,0.00042,0,0,-0.49,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.6e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31490000,0.98,-0.0073,-0.014,0.17,-0.036,0.0081,0.8,-0.065,0.044,-0.52,-0.0013,-0.0057,1e-06,0.023,-0.033,-0.12,0.2,-3.2e-05,0.43,-0.001,-0.0017,0.00043,0,0,-0.42,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.6e-07,2.4e-07,8.5e-07,0.025,0.023,0.0001,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31590000,0.98,-0.0071,-0.014,0.17,-0.033,0.0062,0.8,-0.054,0.04,-0.45,-0.0013,-0.0057,1.1e-05,0.023,-0.033,-0.12,0.2,-3.2e-05,0.43,-0.0011,-0.0018,0.00045,0,0,-0.35,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.5e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31690000,0.98,-0.0071,-0.014,0.17,-0.036,0.0056,0.8,-0.058,0.041,-0.38,-0.0013,-0.0057,1.9e-05,0.023,-0.033,-0.12,0.2,-3.1e-05,0.43,-0.0012,-0.0018,0.00043,0,0,-0.28,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.4e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31790000,0.98,-0.0074,-0.015,0.17,-0.027,0.003,0.8,-0.045,0.039,-0.3,-0.0013,-0.0057,2.4e-05,0.024,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0019,0.00045,0,0,-0.2,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.4e-07,8.3e-07,0.025,0.023,9.9e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31890000,0.99,-0.0071,-0.015,0.17,-0.025,0.00083,0.8,-0.049,0.039,-0.23,-0.0013,-0.0057,2.8e-05,0.024,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.002,0.00047,0,0,-0.13,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.3e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +31990000,0.99,-0.0074,-0.014,0.17,-0.017,-0.00026,0.79,-0.036,0.036,-0.17,-0.0013,-0.0057,2.5e-05,0.024,-0.034,-0.12,0.2,-3e-05,0.43,-0.0014,-0.0022,0.00052,0,0,-0.066,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8.2e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32090000,0.99,-0.0077,-0.014,0.17,-0.019,-0.0037,0.8,-0.038,0.036,-0.094,-0.0013,-0.0057,2.5e-05,0.024,-0.034,-0.12,0.2,-2.9e-05,0.43,-0.0014,-0.0023,0.00054,0,0,0.0058,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.4e-07,8.2e-07,0.025,0.023,9.8e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32190000,0.99,-0.008,-0.014,0.17,-0.013,-0.0073,0.8,-0.026,0.034,-0.026,-0.0013,-0.0057,2.1e-05,0.024,-0.034,-0.12,0.2,-2.9e-05,0.43,-0.0014,-0.0024,0.00058,0,0,0.074,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32290000,0.99,-0.0079,-0.015,0.17,-0.013,-0.0098,0.8,-0.027,0.033,0.044,-0.0013,-0.0057,2.6e-05,0.025,-0.034,-0.12,0.2,-2.8e-05,0.43,-0.0015,-0.0025,0.00059,0,0,0.14,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8.1e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32390000,0.99,-0.008,-0.015,0.17,-0.0063,-0.011,0.8,-0.015,0.03,0.12,-0.0013,-0.0057,2.3e-05,0.025,-0.034,-0.12,0.2,-2.6e-05,0.43,-0.0016,-0.0027,0.00065,0,0,0.22,0.00028,0.00028,0.035,0.011,0.012,0.0051,0.035,0.036,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32490000,0.99,-0.011,-0.012,0.17,0.018,-0.077,-0.076,-0.014,0.024,0.12,-0.0013,-0.0057,1.9e-05,0.025,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0015,-0.0027,0.00064,0,0,0.22,0.00028,0.00028,0.035,0.012,0.014,0.0051,0.038,0.039,0.03,2.5e-07,2.3e-07,8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32590000,0.99,-0.011,-0.013,0.17,0.021,-0.079,-0.079,0.0015,0.02,0.1,-0.0013,-0.0057,1.8e-05,0.025,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.00071,0,0,0.2,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32690000,0.99,-0.011,-0.012,0.17,0.016,-0.085,-0.08,0.0033,0.012,0.09,-0.0013,-0.0057,1.7e-05,0.025,-0.034,-0.12,0.2,-2.7e-05,0.43,-0.0014,-0.0023,0.00071,0,0,0.19,0.00028,0.00028,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.9e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32790000,0.99,-0.011,-0.013,0.17,0.017,-0.084,-0.081,0.015,0.0093,0.074,-0.0013,-0.0057,1.6e-05,0.025,-0.034,-0.12,0.2,-2.5e-05,0.43,-0.0015,-0.0022,0.00078,0,0,0.17,0.00028,0.00027,0.035,0.011,0.013,0.0051,0.035,0.036,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32890000,0.99,-0.011,-0.013,0.17,0.017,-0.09,-0.083,0.017,0.00078,0.059,-0.0013,-0.0057,1.9e-05,0.025,-0.034,-0.12,0.2,-2.5e-05,0.43,-0.0015,-0.0021,0.00079,0,0,0.16,0.00028,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.8e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +32990000,0.98,-0.011,-0.013,0.17,0.017,-0.089,-0.082,0.028,-0.0031,0.046,-0.0014,-0.0057,2.1e-05,0.025,-0.034,-0.12,0.2,-2.4e-05,0.43,-0.0015,-0.002,0.00085,0,0,0.15,0.00027,0.00027,0.035,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +33090000,0.98,-0.011,-0.013,0.17,0.013,-0.093,-0.079,0.029,-0.012,0.038,-0.0014,-0.0057,2.1e-05,0.025,-0.034,-0.12,0.2,-2.4e-05,0.43,-0.0015,-0.002,0.00085,0,0,0.14,0.00027,0.00027,0.035,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.7e-07,0.025,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0013,0.0014,0.0012,1,1,0.01 +33190000,0.98,-0.01,-0.013,0.17,0.011,-0.094,-0.078,0.037,-0.015,0.031,-0.0014,-0.0057,1.2e-05,0.026,-0.034,-0.12,0.2,-2.2e-05,0.43,-0.0015,-0.002,0.00088,0,0,0.13,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.6e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 +33290000,0.98,-0.01,-0.013,0.17,0.0073,-0.096,-0.078,0.037,-0.024,0.023,-0.0014,-0.0057,2.3e-05,0.026,-0.034,-0.12,0.2,-2.1e-05,0.43,-0.0016,-0.0021,0.00092,0,0,0.12,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.7e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.01 +33390000,0.98,-0.01,-0.013,0.17,0.0052,-0.09,-0.076,0.043,-0.022,0.014,-0.0014,-0.0057,1.6e-05,0.028,-0.033,-0.12,0.2,-1.8e-05,0.43,-0.0016,-0.002,0.00096,0,0,0.12,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.3e-07,7.5e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.033 +33490000,0.98,-0.01,-0.013,0.17,-0.00014,-0.093,-0.075,0.042,-0.031,0.0042,-0.0014,-0.0057,2.1e-05,0.028,-0.032,-0.12,0.2,-1.7e-05,0.43,-0.0017,-0.0021,0.00098,0,0,0.12,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.3e-07,7.4e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.058 +33590000,0.98,-0.01,-0.013,0.17,-0.0029,-0.092,-0.072,0.046,-0.029,-0.0037,-0.0014,-0.0057,2e-05,0.029,-0.031,-0.12,0.2,-1.3e-05,0.43,-0.0018,-0.0022,0.001,0,0,0.12,0.00027,0.00027,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.4e-07,2.2e-07,7.4e-07,0.024,0.023,9.6e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.083 +33690000,0.98,-0.01,-0.013,0.17,-0.0062,-0.095,-0.073,0.046,-0.038,-0.012,-0.0014,-0.0057,2.4e-05,0.029,-0.032,-0.12,0.2,-1.4e-05,0.43,-0.0018,-0.002,0.001,0,0,0.12,0.00027,0.00027,0.034,0.012,0.013,0.0051,0.038,0.039,0.03,2.4e-07,2.2e-07,7.3e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.11 +33790000,0.98,-0.01,-0.013,0.17,-0.0081,-0.092,-0.068,0.052,-0.036,-0.019,-0.0014,-0.0057,1.4e-05,0.031,-0.031,-0.12,0.2,-1.2e-05,0.43,-0.0017,-0.0019,0.0011,0,0,0.12,0.00027,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.3e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.13 +33890000,0.98,-0.01,-0.013,0.17,-0.012,-0.093,-0.067,0.051,-0.045,-0.025,-0.0014,-0.0057,2.4e-05,0.031,-0.031,-0.12,0.2,-1.2e-05,0.43,-0.0018,-0.0018,0.0011,0,0,0.12,0.00027,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.5e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.16 +33990000,0.98,-0.0099,-0.013,0.17,-0.013,-0.088,-0.064,0.055,-0.04,-0.029,-0.0014,-0.0057,1.1e-05,0.033,-0.031,-0.12,0.2,-8.6e-06,0.43,-0.0017,-0.0018,0.0011,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.18 +34090000,0.98,-0.0098,-0.013,0.17,-0.017,-0.093,-0.062,0.054,-0.049,-0.033,-0.0014,-0.0057,1.4e-05,0.033,-0.031,-0.12,0.2,-9e-06,0.43,-0.0017,-0.0017,0.0011,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.2e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.21 +34190000,0.98,-0.0098,-0.013,0.17,-0.018,-0.088,-0.06,0.058,-0.044,-0.037,-0.0014,-0.0057,1e-05,0.035,-0.031,-0.12,0.2,-6.6e-06,0.43,-0.0017,-0.0016,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.23 +34290000,0.98,-0.0096,-0.013,0.17,-0.019,-0.092,-0.058,0.056,-0.052,-0.043,-0.0014,-0.0057,1.7e-05,0.035,-0.031,-0.12,0.2,-5.9e-06,0.43,-0.0017,-0.0016,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7.1e-07,0.024,0.023,9.4e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.26 +34390000,0.98,-0.0095,-0.013,0.17,-0.021,-0.085,-0.054,0.058,-0.047,-0.047,-0.0014,-0.0056,9.7e-06,0.036,-0.03,-0.12,0.2,-3.8e-06,0.43,-0.0016,-0.0015,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0014,0.0012,1,1,0.28 +34490000,0.98,-0.0095,-0.013,0.17,-0.024,-0.089,-0.052,0.057,-0.055,-0.05,-0.0014,-0.0056,1.8e-05,0.036,-0.03,-0.12,0.2,-3.5e-06,0.43,-0.0017,-0.0015,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,7e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.31 +34590000,0.98,-0.0094,-0.013,0.17,-0.026,-0.081,0.74,0.059,-0.05,-0.021,-0.0014,-0.0056,1.1e-05,0.038,-0.03,-0.12,0.2,-1e-06,0.43,-0.0017,-0.0014,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.33 +34690000,0.98,-0.0094,-0.013,0.17,-0.03,-0.079,1.7,0.056,-0.058,0.098,-0.0014,-0.0056,1.4e-05,0.038,-0.03,-0.12,0.2,-7.2e-07,0.43,-0.0017,-0.0014,0.0012,0,0,0.12,0.00026,0.00026,0.034,0.011,0.012,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.9e-07,0.024,0.023,9.3e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.36 +34790000,0.98,-0.0093,-0.013,0.17,-0.033,-0.07,2.7,0.058,-0.052,0.28,-0.0015,-0.0056,7.7e-06,0.04,-0.031,-0.12,0.2,1.9e-06,0.43,-0.0017,-0.0013,0.0013,0,0,0.12,0.00026,0.00026,0.034,0.011,0.011,0.005,0.035,0.036,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.2e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.38 +34890000,0.98,-0.0092,-0.013,0.17,-0.038,-0.069,3.7,0.055,-0.058,0.57,-0.0015,-0.0056,1.1e-05,0.04,-0.031,-0.12,0.2,2e-06,0.43,-0.0017,-0.0013,0.0013,0,0,0.12,0.00026,0.00026,0.034,0.012,0.013,0.005,0.038,0.039,0.03,2.3e-07,2.2e-07,6.8e-07,0.024,0.023,9.2e-05,0.0012,4e-05,0.0012,0.0012,0.0013,0.0012,1,1,0.41 From c2bd3900be72c8ad071a98be5171e56614643dfd Mon Sep 17 00:00:00 2001 From: Hubert <1701213518@sz.pku.edu.cn> Date: Fri, 6 Sep 2024 16:47:31 +0800 Subject: [PATCH 14/40] Jenkins: compile add micoair h743 --- .ci/Jenkinsfile-compile | 1 + 1 file changed, 1 insertion(+) diff --git a/.ci/Jenkinsfile-compile b/.ci/Jenkinsfile-compile index fcf70a5a2fdc..469898417f67 100644 --- a/.ci/Jenkinsfile-compile +++ b/.ci/Jenkinsfile-compile @@ -77,6 +77,7 @@ pipeline { "matek_h743-mini_default", "matek_h743-slim_default", "matek_h743_default", + "micoair_h743_default", "modalai_fc-v1_default", "modalai_fc-v2_default", "mro_ctrl-zero-classic_default", From 232f699a7f8e6b6e6654d4e164ce57880f6867b2 Mon Sep 17 00:00:00 2001 From: Hubert <1701213518@sz.pku.edu.cn> Date: Fri, 6 Sep 2024 16:54:29 +0800 Subject: [PATCH 15/40] cmake-variants.yaml add micoair h743 --- .vscode/cmake-variants.yaml | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/.vscode/cmake-variants.yaml b/.vscode/cmake-variants.yaml index d55b170485e2..4d1f7924087b 100644 --- a/.vscode/cmake-variants.yaml +++ b/.vscode/cmake-variants.yaml @@ -286,6 +286,11 @@ CONFIG: buildType: MiniSizeRel settings: CONFIG: matek_gnss-m9n-f4_default + micoair_h743_default: + short: micoair_h743 + buildType: MinSizeRel + settings: + CONFIG: micoair_h743_default modalai_fc-v1_default: short: modalai_fc-v1 buildType: MinSizeRel From 67ee4817ae474f085d920a8ff7d9eed3121382c2 Mon Sep 17 00:00:00 2001 From: Hubert <1701213518@sz.pku.edu.cn> Date: Fri, 6 Sep 2024 17:01:37 +0800 Subject: [PATCH 16/40] Makefile add micoair h743 bootloader --- Makefile | 1 + 1 file changed, 1 insertion(+) diff --git a/Makefile b/Makefile index 5de475d79074..1cf17524f81d 100644 --- a/Makefile +++ b/Makefile @@ -340,6 +340,7 @@ bootloaders_update: \ matek_h743_bootloader \ matek_h743-mini_bootloader \ matek_h743-slim_bootloader \ + micoair_h743_bootloader \ modalai_fc-v2_bootloader \ mro_ctrl-zero-classic_bootloader \ mro_ctrl-zero-h7_bootloader \ From bb0210ecd7028a14e7aaed850f4091fb5b9487da Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Fri, 6 Sep 2024 17:21:49 +0200 Subject: [PATCH 17/40] rover: add rtl as a landed condition for rovers (#23646) The RTL sequence from the navigator requires the vehicle to land. This is now handled for rovers by setting its state to landed if it is within the acceptance radius of the home position when in return mode. --- .../land_detector/RoverLandDetector.cpp | 28 +++++++++++++++++++ src/modules/land_detector/RoverLandDetector.h | 18 +++++++++++- 2 files changed, 45 insertions(+), 1 deletion(-) diff --git a/src/modules/land_detector/RoverLandDetector.cpp b/src/modules/land_detector/RoverLandDetector.cpp index e9942c4eae01..2011419db8c3 100644 --- a/src/modules/land_detector/RoverLandDetector.cpp +++ b/src/modules/land_detector/RoverLandDetector.cpp @@ -51,12 +51,40 @@ bool RoverLandDetector::_get_ground_contact_state() bool RoverLandDetector::_get_landed_state() { + _update_topics(); + const float distance_to_home = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _home_position(0), _home_position(1)); + if (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND) { return true; // If Landing has been requested then say we have landed. + } else if (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL + && distance_to_home < _param_nav_acc_rad.get() && _param_rtl_land_delay.get() > -FLT_EPSILON) { + return true; // If the rover reaches the home position during RTL we say we have landed + } else { return !_armed; // If we are armed we are not landed. } } +void RoverLandDetector::_update_topics() +{ + if (_vehicle_global_position_sub.updated()) { + vehicle_global_position_s vehicle_global_position{}; + _vehicle_global_position_sub.copy(&vehicle_global_position); + _curr_pos = matrix::Vector2d(vehicle_global_position.lat, vehicle_global_position.lon); + } + + if (_home_position_sub.updated()) { + home_position_s home_position{}; + _home_position_sub.copy(&home_position); + _home_position = matrix::Vector2d(home_position.lat, home_position.lon); + } +} + +void RoverLandDetector::_set_hysteresis_factor(const int factor) +{ + _landed_hysteresis.set_hysteresis_time_from(true, 0_ms); +} + } // namespace land_detector diff --git a/src/modules/land_detector/RoverLandDetector.h b/src/modules/land_detector/RoverLandDetector.h index 5ebc5b6677df..c90ac8d1408e 100644 --- a/src/modules/land_detector/RoverLandDetector.h +++ b/src/modules/land_detector/RoverLandDetector.h @@ -42,6 +42,9 @@ #pragma once #include "LandDetector.h" +#include +#include +#include namespace land_detector { @@ -55,7 +58,20 @@ class RoverLandDetector : public LandDetector protected: bool _get_ground_contact_state() override; bool _get_landed_state() override; - void _set_hysteresis_factor(const int factor) override {}; + void _set_hysteresis_factor(const int factor) override; + void _update_topics() override; + +private: + uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)}; + uORB::Subscription _home_position_sub{ORB_ID(home_position)}; + matrix::Vector2d _curr_pos{}; + matrix::Vector2d _home_position{}; + + DEFINE_PARAMETERS( + (ParamFloat) _param_nav_acc_rad, + (ParamFloat) _param_rtl_land_delay + ) + }; } // namespace land_detector From 8bca467c1530cfdffa9bb35fa6d938ed29f2dee4 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 9 Sep 2024 14:53:20 +0200 Subject: [PATCH 18/40] dist-sensor: use enum instead of integer --- src/lib/drivers/rangefinder/PX4Rangefinder.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/lib/drivers/rangefinder/PX4Rangefinder.cpp b/src/lib/drivers/rangefinder/PX4Rangefinder.cpp index b3297a75fad8..e26f3215fcf3 100644 --- a/src/lib/drivers/rangefinder/PX4Rangefinder.cpp +++ b/src/lib/drivers/rangefinder/PX4Rangefinder.cpp @@ -39,8 +39,8 @@ PX4Rangefinder::PX4Rangefinder(const uint32_t device_id, const uint8_t device_or { set_device_id(device_id); set_orientation(device_orientation); - set_rangefinder_type(distance_sensor_s::MAV_DISTANCE_SENSOR_LASER); // Default to type LASER - set_mode(UINT8_C(0)); + set_rangefinder_type(distance_sensor_s::MAV_DISTANCE_SENSOR_LASER); + set_mode(distance_sensor_s::DISTANCE_SENSOR_MODE_UNKNOWN); } PX4Rangefinder::~PX4Rangefinder() From 15e9c65a8fac921873de58169f88dd8070d9024f Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 9 Sep 2024 15:22:09 +0200 Subject: [PATCH 19/40] dist-sensor: reduce enum names --- msg/DistanceSensor.msg | 8 ++++---- .../lightware_laser_i2c/lightware_laser_i2c.cpp | 4 ++-- src/lib/drivers/rangefinder/PX4Rangefinder.cpp | 2 +- src/lib/drivers/rangefinder/PX4Rangefinder.hpp | 2 +- .../HealthAndArmingChecks/checks/distanceSensorChecks.cpp | 2 +- 5 files changed, 9 insertions(+), 9 deletions(-) diff --git a/msg/DistanceSensor.msg b/msg/DistanceSensor.msg index 88bd8ca81906..4b7cffefd0ac 100644 --- a/msg/DistanceSensor.msg +++ b/msg/DistanceSensor.msg @@ -41,7 +41,7 @@ uint8 ROTATION_DOWNWARD_FACING = 25 # MAV_SENSOR_ROTATION_PITCH_270 uint8 ROTATION_CUSTOM = 100 # MAV_SENSOR_ROTATION_CUSTOM -uint8 mode # mode of operation -uint8 DISTANCE_SENSOR_MODE_UNKNOWN = 0 # Unknown mode -uint8 DISTANCE_SENSOR_MODE_RUN = 1 # sensor is running continuosly -uint8 DISTANCE_SENSOR_MODE_DISABLED = 2 # sensor is disabled per request +uint8 mode +uint8 MODE_UNKNOWN = 0 +uint8 MODE_ENABLED = 1 +uint8 MODE_DISABLED = 2 diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp index 0bc0f55a772a..6c1dfbcea068 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp +++ b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp @@ -499,7 +499,7 @@ void LightwareLaser::RunImpl() case State::Running: if (!_restriction) { - _px4_rangefinder.set_mode(distance_sensor_s::DISTANCE_SENSOR_MODE_RUN); + _px4_rangefinder.set_mode(distance_sensor_s::MODE_ENABLED); if (PX4_OK != collect()) { PX4_DEBUG("collection error"); @@ -511,7 +511,7 @@ void LightwareLaser::RunImpl() } } else { - _px4_rangefinder.set_mode(distance_sensor_s::DISTANCE_SENSOR_MODE_DISABLED); + _px4_rangefinder.set_mode(distance_sensor_s::MODE_DISABLED); if (!_prev_restriction) { // Publish disabled status once _px4_rangefinder.update(hrt_absolute_time(), -1.f, 0); diff --git a/src/lib/drivers/rangefinder/PX4Rangefinder.cpp b/src/lib/drivers/rangefinder/PX4Rangefinder.cpp index e26f3215fcf3..98c479efb18f 100644 --- a/src/lib/drivers/rangefinder/PX4Rangefinder.cpp +++ b/src/lib/drivers/rangefinder/PX4Rangefinder.cpp @@ -40,7 +40,7 @@ PX4Rangefinder::PX4Rangefinder(const uint32_t device_id, const uint8_t device_or set_device_id(device_id); set_orientation(device_orientation); set_rangefinder_type(distance_sensor_s::MAV_DISTANCE_SENSOR_LASER); - set_mode(distance_sensor_s::DISTANCE_SENSOR_MODE_UNKNOWN); + set_mode(distance_sensor_s::MODE_UNKNOWN); } PX4Rangefinder::~PX4Rangefinder() diff --git a/src/lib/drivers/rangefinder/PX4Rangefinder.hpp b/src/lib/drivers/rangefinder/PX4Rangefinder.hpp index 1005242abaa8..725f03d3216c 100644 --- a/src/lib/drivers/rangefinder/PX4Rangefinder.hpp +++ b/src/lib/drivers/rangefinder/PX4Rangefinder.hpp @@ -60,7 +60,7 @@ class PX4Rangefinder void set_orientation(const uint8_t device_orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING); - void set_mode(const uint8_t mode) {_distance_sensor_pub.get().mode = mode; } + void set_mode(const uint8_t mode) { _distance_sensor_pub.get().mode = mode; } void update(const hrt_abstime ×tamp_sample, const float distance, const int8_t quality = -1); diff --git a/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp b/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp index 02b0a390fd22..fceb5e740b55 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/distanceSensorChecks.cpp @@ -49,7 +49,7 @@ void DistanceSensorChecks::checkAndReport(const Context &context, Report &report if (exists) { distance_sensor_s dist_sens; valid = _distance_sensor_sub[instance].copy(&dist_sens) && ((hrt_elapsed_time(&dist_sens.timestamp) < 1_s) - || (dist_sens.mode == distance_sensor_s::DISTANCE_SENSOR_MODE_DISABLED)); + || (dist_sens.mode == distance_sensor_s::MODE_DISABLED)); reporter.setIsPresent(health_component_t::distance_sensor); } From a5729da4e988f0769e0cdf54ce034ca0ff8a8481 Mon Sep 17 00:00:00 2001 From: jmackay2 <1.732mackay@gmail.com> Date: Tue, 10 Sep 2024 05:53:00 -0400 Subject: [PATCH 20/40] Simplify gz bridge CMakeLists and add GZ Ionic (#23657) Co-authored-by: jmackay2 --- src/modules/simulation/gz_bridge/CMakeLists.txt | 9 ++------- 1 file changed, 2 insertions(+), 7 deletions(-) diff --git a/src/modules/simulation/gz_bridge/CMakeLists.txt b/src/modules/simulation/gz_bridge/CMakeLists.txt index 0d1e8eed66fd..2af0a069b34c 100644 --- a/src/modules/simulation/gz_bridge/CMakeLists.txt +++ b/src/modules/simulation/gz_bridge/CMakeLists.txt @@ -32,13 +32,8 @@ ############################################################################ # Find the gz_Transport library -# First look for GZ Harmonic libraries -find_package(gz-transport NAMES gz-transport13) - -# If Harmonic not found, look for GZ Garden libraries -if(NOT gz-transport_FOUND) - find_package(gz-transport NAMES gz-transport12) -endif() +# Look for GZ Ionic, Harmonic, and Garden library options in that order +find_package(gz-transport NAMES gz-transport14 gz-transport13 gz-transport12) if(gz-transport_FOUND) From 03aec2e18882e9e0d931923bdcce2f25b8884015 Mon Sep 17 00:00:00 2001 From: Mathieu Bresciani Date: Tue, 10 Sep 2024 15:06:19 +0200 Subject: [PATCH 21/40] HeadingSmoothing: fix angle wrapping and add unit tests Co-authored-by: Matthias Grob --- src/lib/motion_planning/CMakeLists.txt | 1 + src/lib/motion_planning/HeadingSmoothing.cpp | 2 +- .../motion_planning/HeadingSmoothingTest.cpp | 147 ++++++++++++++++++ 3 files changed, 149 insertions(+), 1 deletion(-) create mode 100644 src/lib/motion_planning/HeadingSmoothingTest.cpp diff --git a/src/lib/motion_planning/CMakeLists.txt b/src/lib/motion_planning/CMakeLists.txt index 6b04cded05fe..fc6674dc2a2b 100644 --- a/src/lib/motion_planning/CMakeLists.txt +++ b/src/lib/motion_planning/CMakeLists.txt @@ -43,3 +43,4 @@ target_include_directories(motion_planning PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) px4_add_unit_gtest(SRC VelocitySmoothingTest.cpp LINKLIBS motion_planning) px4_add_unit_gtest(SRC PositionSmoothingTest.cpp LINKLIBS motion_planning) +px4_add_unit_gtest(SRC HeadingSmoothingTest.cpp LINKLIBS motion_planning) diff --git a/src/lib/motion_planning/HeadingSmoothing.cpp b/src/lib/motion_planning/HeadingSmoothing.cpp index 037eeb701b99..b8094dff0831 100644 --- a/src/lib/motion_planning/HeadingSmoothing.cpp +++ b/src/lib/motion_planning/HeadingSmoothing.cpp @@ -35,7 +35,7 @@ HeadingSmoothing::HeadingSmoothing() { - _velocity_smoothing.setMaxVel(M_PI_F); // smoothed "velocity" is heading [-pi, pi] + _velocity_smoothing.setMaxVel(M_TWOPI_F); // "velocity" is heading. 2Pi limit is needed for correct angle wrapping } void HeadingSmoothing::reset(const float heading, const float heading_rate) diff --git a/src/lib/motion_planning/HeadingSmoothingTest.cpp b/src/lib/motion_planning/HeadingSmoothingTest.cpp new file mode 100644 index 000000000000..fd9d3c916fc7 --- /dev/null +++ b/src/lib/motion_planning/HeadingSmoothingTest.cpp @@ -0,0 +1,147 @@ +/**************************************************************************** + * + * Copyright (C) 2024 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * are met: + * + * 1. Redistributions of source code must retain the above copyright + * notice, this list of conditions and the following disclaimer. + * 2. Redistributions in binary form must reproduce the above copyright + * notice, this list of conditions and the following disclaimer in + * the documentation and/or other materials provided with the + * distribution. + * 3. Neither the name PX4 nor the names of its contributors may be + * used to endorse or promote products derived from this software + * without specific prior written permission. + * + * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS + * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT + * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS + * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE + * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, + * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, + * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS + * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED + * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT + * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN + * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE + * POSSIBILITY OF SUCH DAMAGE. + * + ****************************************************************************/ + +/** + * Test code for the Heading Smoothing library + * Run exclusively this test with the command "make tests TESTFILTER=HeadingSmoothing" + */ + +#include "mathlib/math/Limits.hpp" +#include + +#include + +using namespace matrix; + +class HeadingSmoothingTest : public ::testing::Test +{ +public: + HeadingSmoothingTest() + { + _smoothing.setMaxHeadingRate(15.f); + _smoothing.setMaxHeadingAccel(1.f); + } + + HeadingSmoothing _smoothing; + float _dt{.1f}; +}; + +TEST_F(HeadingSmoothingTest, convergence) +{ + const float heading_current = math::radians(0.f); + const float heading_target = math::radians(5.f); + _smoothing.reset(heading_current, 0.f); + + const int nb_steps = ceilf(1.f / _dt); + + for (int i = 0; i < nb_steps; i++) { + _smoothing.update(heading_target, _dt); + } + + const float heading = _smoothing.getSmoothedHeading(); + const float heading_rate = _smoothing.getSmoothedHeadingRate(); + EXPECT_EQ(heading, heading_target) << "heading (deg): " << math::degrees(heading); + EXPECT_EQ(heading_rate, 0.f); +} + +TEST_F(HeadingSmoothingTest, zero_crossing) +{ + const float heading_current = math::radians(-95.f); + const float heading_target = math::radians(5.f); + _smoothing.reset(heading_current, 0.f); + + const int nb_steps = ceilf(4.f / _dt); + + for (int i = 0; i < nb_steps; i++) { + _smoothing.update(heading_target, _dt); + } + + const float heading = _smoothing.getSmoothedHeading(); + const float heading_rate = _smoothing.getSmoothedHeadingRate(); + EXPECT_EQ(heading, heading_target) << "heading (deg): " << math::degrees(heading); + EXPECT_EQ(heading_rate, 0.f); +} + +TEST_F(HeadingSmoothingTest, wrap_pi) +{ + const float heading_current = math::radians(-170.f); + const float heading_target = math::radians(170.f); + _smoothing.reset(heading_current, 0.f); + + const int nb_steps = ceilf(2.f / _dt); + + for (int i = 0; i < nb_steps; i++) { + _smoothing.update(heading_target, _dt); + } + + const float heading = _smoothing.getSmoothedHeading(); + const float heading_rate = _smoothing.getSmoothedHeadingRate(); + EXPECT_EQ(heading, heading_target) << "heading (deg): " << math::degrees(heading); + EXPECT_EQ(heading_rate, 0.f); +} + +TEST_F(HeadingSmoothingTest, positive_rate) +{ + const float max_heading_rate = .15f; + _smoothing.setMaxHeadingRate(max_heading_rate); + const float heading_current = math::radians(-170.f); + const float heading_target = math::radians(-20.f); + _smoothing.reset(heading_current, 0.f); + + const int nb_steps = ceilf(2.f / _dt); + + for (int i = 0; i < nb_steps; i++) { + _smoothing.update(heading_target, _dt); + } + + const float heading_rate = _smoothing.getSmoothedHeadingRate(); + EXPECT_EQ(heading_rate, max_heading_rate); +} + +TEST_F(HeadingSmoothingTest, negative_rate) +{ + const float max_heading_rate = 0.15; + _smoothing.setMaxHeadingRate(max_heading_rate); + const float heading_current = math::radians(-20.f); + const float heading_target = math::radians(-140.f); + _smoothing.reset(heading_current, 0.f); + + const int nb_steps = ceilf(2.f / _dt); + + for (int i = 0; i < nb_steps; i++) { + _smoothing.update(heading_target, _dt); + } + + const float heading_rate = _smoothing.getSmoothedHeadingRate(); + EXPECT_EQ(heading_rate, -max_heading_rate); +} From c94c1ce4d2712fa8af892eaeeae3a6aa2f859961 Mon Sep 17 00:00:00 2001 From: Roman Bapst Date: Tue, 10 Sep 2024 18:44:24 +0300 Subject: [PATCH 22/40] Navigator: Support straight line mission landings (#23576) * introduced altitude acceptance radius in position setpoint for fixed wing guidance - allows navigator to explicitly set the altitude acceptance radius - needed for staright line landing support * added ignore_alt_acceptance to position setpoint message to allow guidance logic to ignore altitude error on waypoint - can be useful to prevent loitering at a waypoint within a mission landing sequence * only set altitude acceptance radius to infinity for a waypoint inside a mission landing for fixed wing vehicles * navigator: return altitude acceptance radius from triplet if it's valid * FixedWingPositionControl: check if alt acceptance radius provided in position setpoint is larger 0 --------- Signed-off-by: RomanBapst Co-authored-by: Alvaro Fernandez --- msg/PositionSetpoint.msg | 3 +- .../FixedwingPositionControl.cpp | 6 ++- src/modules/navigator/mission.cpp | 42 ++++--------------- src/modules/navigator/mission.h | 1 - src/modules/navigator/mission_base.cpp | 36 ++++++++++++++++ src/modules/navigator/mission_base.h | 3 ++ src/modules/navigator/mission_block.cpp | 4 ++ src/modules/navigator/navigator_main.cpp | 7 +++- .../navigator/rtl_direct_mission_land.cpp | 7 ++++ src/modules/navigator/rtl_mission_fast.cpp | 5 +++ 10 files changed, 75 insertions(+), 39 deletions(-) diff --git a/msg/PositionSetpoint.msg b/msg/PositionSetpoint.msg index 035d35205ee2..51bfaa3da0b9 100644 --- a/msg/PositionSetpoint.msg +++ b/msg/PositionSetpoint.msg @@ -30,7 +30,8 @@ bool loiter_direction_counter_clockwise # loiter direction is clockwise by defau float32 loiter_orientation # Orientation of the major axis with respect to true north in rad [-pi,pi) uint8 loiter_pattern # loitern pattern to follow -float32 acceptance_radius # navigation acceptance_radius if we're doing waypoint navigation +float32 acceptance_radius # horizontal acceptance_radius (meters) +float32 alt_acceptance_radius # vertical acceptance radius, only used for fixed wing guidance, NAN = let guidance choose (meters) float32 cruising_speed # the generally desired cruising speed (not a hard constraint) bool gliding_enabled # commands the vehicle to glide if the capability is available (fixed wing only) diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 7858fe2c1c5f..00e7869c6949 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -1029,11 +1029,15 @@ FixedwingPositionControl::handle_setpoint_type(const position_setpoint_s &pos_sp _current_latitude, _current_longitude, _current_altitude, &dist_xy, &dist_z); + const float acc_rad_z = (PX4_ISFINITE(pos_sp_curr.alt_acceptance_radius) + && pos_sp_curr.alt_acceptance_radius > FLT_EPSILON) ? pos_sp_curr.alt_acceptance_radius : + _param_nav_fw_alt_rad.get(); + // Achieve position setpoint altitude via loiter when laterally close to WP. // Detect if system has switchted into a Loiter before (check _position_sp_type), and in that // case remove the dist_xy check (not switch out of Loiter until altitude is reached). if ((!_vehicle_status.in_transition_mode) && (dist >= 0.f) - && (dist_z > _param_nav_fw_alt_rad.get()) + && (dist_z > acc_rad_z) && (dist_xy < acc_rad || _position_sp_type == position_setpoint_s::SETPOINT_TYPE_LOITER)) { // SETPOINT_TYPE_POSITION -> SETPOINT_TYPE_LOITER diff --git a/src/modules/navigator/mission.cpp b/src/modules/navigator/mission.cpp index ea7dae675217..cb8f07fa0e4f 100644 --- a/src/modules/navigator/mission.cpp +++ b/src/modules/navigator/mission.cpp @@ -91,41 +91,6 @@ Mission::on_activation() MissionBase::on_activation(); } -bool -Mission::isLanding() -{ - if (get_land_start_available()) { - static constexpr size_t max_num_next_items{1u}; - int32_t next_mission_items_index[max_num_next_items]; - size_t num_found_items; - - getNextPositionItems(_mission.land_start_index + 1, next_mission_items_index, num_found_items, max_num_next_items); - - // vehicle is currently landing if - // mission valid, still flying, and in the landing portion of mission (past land start marker) - bool on_landing_stage = (num_found_items > 0U) && _mission.current_seq > next_mission_items_index[0U]; - - // special case: if the land start index is at a LOITER_TO_ALT WP, then we're in the landing sequence already when the - // distance to the WP is below the loiter radius + acceptance. - if ((num_found_items > 0U) && _mission.current_seq == next_mission_items_index[0U] - && _mission_item.nav_cmd == NAV_CMD_LOITER_TO_ALT) { - const float d_current = get_distance_to_next_waypoint(_mission_item.lat, _mission_item.lon, - _navigator->get_global_position()->lat, _navigator->get_global_position()->lon); - - // consider mission_item.loiter_radius invalid if NAN or 0, use default value in this case. - const float mission_item_loiter_radius_abs = (PX4_ISFINITE(_mission_item.loiter_radius) - && fabsf(_mission_item.loiter_radius) > FLT_EPSILON) ? fabsf(_mission_item.loiter_radius) : - _navigator->get_loiter_radius(); - - on_landing_stage = d_current <= (_navigator->get_acceptance_radius() + mission_item_loiter_radius_abs); - } - - return _navigator->get_mission_result()->valid && on_landing_stage; - - } else { - return false; - } -} bool Mission::set_current_mission_index(uint16_t index) @@ -244,6 +209,13 @@ void Mission::setActiveMissionItems() mission_item_to_position_setpoint(_mission_item, &pos_sp_triplet->current); } + // prevent fixed wing lateral guidance from loitering at a waypoint as part of a mission landing if the altitude + // is not achieved. + if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && isLanding() && + _mission_item.nav_cmd == NAV_CMD_WAYPOINT) { + pos_sp_triplet->current.alt_acceptance_radius = FLT_MAX; + } + // Allow a rotary wing vehicle to decelerate before reaching a wp with a hold time or a timeout // This is done by setting the position triplet's next position's valid flag to false, // which makes the FlightTask disregard the next position diff --git a/src/modules/navigator/mission.h b/src/modules/navigator/mission.h index 7299e065e584..8a24ac4dc0d3 100644 --- a/src/modules/navigator/mission.h +++ b/src/modules/navigator/mission.h @@ -67,7 +67,6 @@ class Mission : public MissionBase uint16_t get_land_start_index() const { return _mission.land_start_index; } bool get_land_start_available() const { return hasMissionLandStart(); } - bool isLanding(); private: diff --git a/src/modules/navigator/mission_base.cpp b/src/modules/navigator/mission_base.cpp index cee250095be1..37f104dea2b7 100644 --- a/src/modules/navigator/mission_base.cpp +++ b/src/modules/navigator/mission_base.cpp @@ -367,6 +367,42 @@ MissionBase::on_active() updateAltToAvoidTerrainCollisionAndRepublishTriplet(_mission_item); } +bool +MissionBase::isLanding() +{ + if (hasMissionLandStart() && (_mission.current_seq > _mission.land_start_index)) { + static constexpr size_t max_num_next_items{1u}; + int32_t next_mission_items_index[max_num_next_items]; + size_t num_found_items; + + getNextPositionItems(_mission.land_start_index + 1, next_mission_items_index, num_found_items, max_num_next_items); + + // vehicle is currently landing if + // mission valid, still flying, and in the landing portion of mission (past land start marker) + bool on_landing_stage = (num_found_items > 0U) && _mission.current_seq > next_mission_items_index[0U]; + + // special case: if the land start index is at a LOITER_TO_ALT WP, then we're in the landing sequence already when the + // distance to the WP is below the loiter radius + acceptance. + if ((num_found_items > 0U) && _mission.current_seq == next_mission_items_index[0U] + && _mission_item.nav_cmd == NAV_CMD_LOITER_TO_ALT) { + const float d_current = get_distance_to_next_waypoint(_mission_item.lat, _mission_item.lon, + _navigator->get_global_position()->lat, _navigator->get_global_position()->lon); + + // consider mission_item.loiter_radius invalid if NAN or 0, use default value in this case. + const float mission_item_loiter_radius_abs = (PX4_ISFINITE(_mission_item.loiter_radius) + && fabsf(_mission_item.loiter_radius) > FLT_EPSILON) ? fabsf(_mission_item.loiter_radius) : + _navigator->get_loiter_radius(); + + on_landing_stage = d_current <= (_navigator->get_acceptance_radius() + mission_item_loiter_radius_abs); + } + + return _navigator->get_mission_result()->valid && on_landing_stage; + + } else { + return false; + } +} + void MissionBase::update_mission() { if (_mission.count == 0u || !_is_current_planned_mission_item_valid || !isMissionValid()) { diff --git a/src/modules/navigator/mission_base.h b/src/modules/navigator/mission_base.h index f819b5c0e51a..1a6cbf977534 100644 --- a/src/modules/navigator/mission_base.h +++ b/src/modules/navigator/mission_base.h @@ -73,6 +73,8 @@ class MissionBase : public MissionBlock, public ModuleParams virtual void on_activation() override; virtual void on_active() override; + bool isLanding(); + protected: /** @@ -321,6 +323,7 @@ class MissionBase : public MissionBlock, public ModuleParams */ void setMissionIndex(int32_t index); + bool _is_current_planned_mission_item_valid{false}; /**< Flag indicating if the currently loaded mission item is valid*/ bool _mission_has_been_activated{false}; /**< Flag indicating if the mission has been activated*/ bool _mission_checked{false}; /**< Flag indicating if the mission has been checked by the mission validator*/ diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index 2659ad95cc57..84d95ae5a310 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -673,6 +673,10 @@ MissionBlock::mission_item_to_position_setpoint(const mission_item_s &item, posi sp->acceptance_radius = _navigator->get_default_acceptance_radius(); } + // by default, FW guidance logic will take alt acceptance from NAV_FW_ALT_RAD, in some special cases + // we override it after this + sp->alt_acceptance_radius = NAN; + sp->cruising_speed = _navigator->get_cruising_speed(); sp->cruising_throttle = _navigator->get_cruising_throttle(); diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index dbf3324b867e..9a9f46e96282 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -1116,9 +1116,14 @@ float Navigator::get_default_acceptance_radius() float Navigator::get_altitude_acceptance_radius() { if (get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) { + + const position_setpoint_s &curr_sp = get_position_setpoint_triplet()->current; const position_setpoint_s &next_sp = get_position_setpoint_triplet()->next; - if (!force_vtol() && next_sp.type == position_setpoint_s::SETPOINT_TYPE_LAND && next_sp.valid) { + if ((PX4_ISFINITE(curr_sp.alt_acceptance_radius) && curr_sp.alt_acceptance_radius > FLT_EPSILON)) { + return curr_sp.alt_acceptance_radius; + + } else if (!force_vtol() && next_sp.type == position_setpoint_s::SETPOINT_TYPE_LAND && next_sp.valid) { // Use separate (tighter) altitude acceptance for clean altitude starting point before FW landing return _param_nav_fw_altl_rad.get(); diff --git a/src/modules/navigator/rtl_direct_mission_land.cpp b/src/modules/navigator/rtl_direct_mission_land.cpp index 5f55b92affd8..bc6df21a49c3 100644 --- a/src/modules/navigator/rtl_direct_mission_land.cpp +++ b/src/modules/navigator/rtl_direct_mission_land.cpp @@ -212,6 +212,13 @@ void RtlDirectMissionLand::setActiveMissionItems() } mission_item_to_position_setpoint(_mission_item, &pos_sp_triplet->current); + + // prevent lateral guidance from loitering at a waypoint as part of a mission landing if the altitude + // is not achieved. + if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && MissionBase::isLanding() + && _mission_item.nav_cmd == NAV_CMD_WAYPOINT) { + pos_sp_triplet->current.alt_acceptance_radius = FLT_MAX; + } } issue_command(_mission_item); diff --git a/src/modules/navigator/rtl_mission_fast.cpp b/src/modules/navigator/rtl_mission_fast.cpp index 0bcafd94e8fb..d3e07a36ddc3 100644 --- a/src/modules/navigator/rtl_mission_fast.cpp +++ b/src/modules/navigator/rtl_mission_fast.cpp @@ -168,6 +168,11 @@ void RtlMissionFast::setActiveMissionItems() } mission_item_to_position_setpoint(_mission_item, &pos_sp_triplet->current); + + if (_vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && isLanding() && + _mission_item.nav_cmd == NAV_CMD_WAYPOINT) { + pos_sp_triplet->current.alt_acceptance_radius = FLT_MAX; + } } issue_command(_mission_item); From 5d8a107925edf7e6670922f1f3d9bc9ea5de4d8c Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Thu, 5 Sep 2024 13:50:00 +0200 Subject: [PATCH 23/40] differential: fix closed loop control removed thresholds for closed loop setpoints and added minimum thresholds for yaw rate and speed measurements instead to avoid moving due to measurement noise --- .../rover_differential/RoverDifferential.cpp | 4 +- .../rover_differential/RoverDifferential.hpp | 6 +++ .../RoverDifferentialControl.cpp | 47 ++++++------------- 3 files changed, 23 insertions(+), 34 deletions(-) diff --git a/src/modules/rover_differential/RoverDifferential.cpp b/src/modules/rover_differential/RoverDifferential.cpp index 502c38de2a44..411c5c4b5559 100644 --- a/src/modules/rover_differential/RoverDifferential.cpp +++ b/src/modules/rover_differential/RoverDifferential.cpp @@ -142,7 +142,7 @@ void RoverDifferential::updateSubscriptions() if (_vehicle_angular_velocity_sub.updated()) { vehicle_angular_velocity_s vehicle_angular_velocity{}; _vehicle_angular_velocity_sub.copy(&vehicle_angular_velocity); - _vehicle_yaw_rate = vehicle_angular_velocity.xyz[2]; + _vehicle_yaw_rate = fabsf(vehicle_angular_velocity.xyz[2]) > YAW_RATE_THRESHOLD ? vehicle_angular_velocity.xyz[2] : 0.f; } if (_vehicle_attitude_sub.updated()) { @@ -157,7 +157,7 @@ void RoverDifferential::updateSubscriptions() _vehicle_local_position_sub.copy(&vehicle_local_position); Vector3f velocity_in_local_frame(vehicle_local_position.vx, vehicle_local_position.vy, vehicle_local_position.vz); Vector3f velocity_in_body_frame = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_in_local_frame); - _vehicle_forward_speed = velocity_in_body_frame(0); + _vehicle_forward_speed = fabsf(velocity_in_body_frame(0)) > SPEED_THRESHOLD ? velocity_in_body_frame(0) : 0.f; } } diff --git a/src/modules/rover_differential/RoverDifferential.hpp b/src/modules/rover_differential/RoverDifferential.hpp index 8dfd4f7affff..eee464ede127 100644 --- a/src/modules/rover_differential/RoverDifferential.hpp +++ b/src/modules/rover_differential/RoverDifferential.hpp @@ -113,6 +113,12 @@ class RoverDifferential : public ModuleBase, public ModulePar int _nav_state{0}; bool _armed{false}; + // Thresholds to avoid moving at rest due to measurement noise + static constexpr float YAW_RATE_THRESHOLD = + 0.02f; // [rad/s] The minimum threshold for the yaw rate measurement not to be interpreted as zero + static constexpr float SPEED_THRESHOLD = + 0.1f; // [m/s] The minimum threshold for the speed measurement not to be interpreted as zero + DEFINE_PARAMETERS( (ParamFloat) _param_rd_man_yaw_scale, (ParamFloat) _param_rd_max_yaw_rate diff --git a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp index 8b16020a0a05..a7019e3a8470 100644 --- a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp +++ b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp @@ -84,32 +84,20 @@ void RoverDifferentialControl::computeMotorCommands(const float vehicle_yaw, con // Closed loop yaw control (Overrides yaw rate setpoint) if (PX4_ISFINITE(_rover_differential_setpoint.yaw_setpoint)) { - if (fabsf(_rover_differential_setpoint.yaw_setpoint - vehicle_yaw) < FLT_EPSILON) { - _rover_differential_setpoint.yaw_rate_setpoint = 0.f; - pid_reset_integral(&_pid_yaw); - - } else { - const float heading_error = matrix::wrap_pi(_rover_differential_setpoint.yaw_setpoint - vehicle_yaw); - _rover_differential_setpoint.yaw_rate_setpoint = pid_calculate(&_pid_yaw, heading_error, 0, 0, dt); - } + float heading_error = matrix::wrap_pi(_rover_differential_setpoint.yaw_setpoint - vehicle_yaw); + _rover_differential_setpoint.yaw_rate_setpoint = pid_calculate(&_pid_yaw, heading_error, 0, 0, dt); } // Yaw rate control float speed_diff_normalized{0.f}; if (PX4_ISFINITE(_rover_differential_setpoint.yaw_rate_setpoint)) { // Closed loop yaw rate control - if (fabsf(_rover_differential_setpoint.yaw_rate_setpoint) < FLT_EPSILON) { - speed_diff_normalized = 0.f; - pid_reset_integral(&_pid_yaw_rate); - - } else { - const float speed_diff = _rover_differential_setpoint.yaw_rate_setpoint * _param_rd_wheel_track.get(); // Feedforward - speed_diff_normalized = math::interpolate(speed_diff, -_param_rd_max_speed.get(), - _param_rd_max_speed.get(), -1.f, 1.f); - speed_diff_normalized = math::constrain(speed_diff_normalized + - pid_calculate(&_pid_yaw_rate, _rover_differential_setpoint.yaw_rate_setpoint, vehicle_yaw_rate, 0, dt), - -1.f, 1.f); // Feedback - } + const float speed_diff = _rover_differential_setpoint.yaw_rate_setpoint * _param_rd_wheel_track.get(); // Feedforward + speed_diff_normalized = math::interpolate(speed_diff, -_param_rd_max_speed.get(), + _param_rd_max_speed.get(), -1.f, 1.f); + speed_diff_normalized = math::constrain(speed_diff_normalized + + pid_calculate(&_pid_yaw_rate, _rover_differential_setpoint.yaw_rate_setpoint, vehicle_yaw_rate, 0, dt), + -1.f, 1.f); // Feedback } else { // Use normalized setpoint speed_diff_normalized = PX4_ISFINITE(_rover_differential_setpoint.yaw_rate_setpoint_normalized) ? @@ -120,20 +108,15 @@ void RoverDifferentialControl::computeMotorCommands(const float vehicle_yaw, con float throttle{0.f}; if (PX4_ISFINITE(_rover_differential_setpoint.forward_speed_setpoint)) { // Closed loop speed control - if (fabsf(_rover_differential_setpoint.forward_speed_setpoint) < FLT_EPSILON) { - pid_reset_integral(&_pid_throttle); - - } else { - throttle = pid_calculate(&_pid_throttle, _rover_differential_setpoint.forward_speed_setpoint, vehicle_forward_speed, 0, - dt); - - if (_param_rd_max_speed.get() > FLT_EPSILON) { // Feed-forward term - throttle += math::interpolate(_rover_differential_setpoint.forward_speed_setpoint, - 0.f, _param_rd_max_speed.get(), - 0.f, 1.f); - } + if (_param_rd_max_speed.get() > FLT_EPSILON) { // Feedforward + throttle += math::interpolate(_rover_differential_setpoint.forward_speed_setpoint, + 0.f, _param_rd_max_speed.get(), + 0.f, 1.f); } + throttle = pid_calculate(&_pid_throttle, _rover_differential_setpoint.forward_speed_setpoint, vehicle_forward_speed, 0, + dt); // Feedback + } else { // Use normalized setpoint throttle = PX4_ISFINITE(_rover_differential_setpoint.forward_speed_setpoint_normalized) ? math::constrain(_rover_differential_setpoint.forward_speed_setpoint_normalized, -1.f, 1.f) : 0.f; From 741ea6b707378771846c0e97f5bc6160c97bbac2 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Thu, 5 Sep 2024 15:11:10 +0200 Subject: [PATCH 24/40] differential: add individual parameters for speed and yaw rate feedforward --- .../init.d-posix/airframes/4009_gz_r1_rover | 5 ++- .../airframes/50001_aion_robotics_r1_rover | 5 ++- msg/RoverDifferentialStatus.msg | 16 ++++---- .../RoverDifferentialControl.cpp | 40 +++++++++++-------- .../RoverDifferentialControl.hpp | 3 +- .../RoverDifferentialGuidance.cpp | 2 +- .../RoverDifferentialGuidance.hpp | 1 - src/modules/rover_differential/module.yaml | 27 +++++++++++-- 8 files changed, 66 insertions(+), 33 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover index 26429add58e5..4bf8815520af 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover @@ -16,11 +16,12 @@ param set-default RD_WHEEL_TRACK 0.3 param set-default RD_MAN_YAW_SCALE 0.1 param set-default RD_MAX_ACCEL 6 param set-default RD_MAX_JERK 30 -param set-default RD_MAX_SPEED 7 -param set-default RD_YAW_RATE_P 5 +param set-default RD_MAX_THR_YAW_R 5 +param set-default RD_YAW_RATE_P 0.1 param set-default RD_YAW_RATE_I 0 param set-default RD_YAW_P 5 param set-default RD_YAW_I 0 +param set-default RD_MAX_THR_SPD 7 param set-default RD_SPEED_P 1 param set-default RD_SPEED_I 0 param set-default RD_MAX_YAW_RATE 180 diff --git a/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover b/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover index 1ea26ad6bff0..d00063c573c3 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover +++ b/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover @@ -25,12 +25,13 @@ param set-default RBCLW_REV 1 # reverse right wheels param set-default RD_WHEEL_TRACK 0.3 param set-default RD_MAN_YAW_SCALE 1 param set-default RD_MAX_ACCEL 5 -param set-default RD_MAX_JERK 50 -param set-default RD_MAX_SPEED 2 +param set-default RD_MAX_JERK 10 +param set-default RD_MAX_THR_YAW_R 4 param set-default RD_YAW_RATE_P 0.1 param set-default RD_YAW_RATE_I 0 param set-default RD_YAW_P 5 param set-default RD_YAW_I 0 +param set-default RD_MAX_THR_SPD 2 param set-default RD_SPEED_P 0.5 param set-default RD_SPEED_I 0.1 param set-default RD_MAX_YAW_RATE 300 diff --git a/msg/RoverDifferentialStatus.msg b/msg/RoverDifferentialStatus.msg index 4d3d54eb9909..808da3dc0d4f 100644 --- a/msg/RoverDifferentialStatus.msg +++ b/msg/RoverDifferentialStatus.msg @@ -1,11 +1,13 @@ uint64 timestamp # time since system start (microseconds) -float32 actual_speed # [m/s] Actual forward speed of the rover -float32 actual_yaw_deg # [deg] Actual yaw of the rover -float32 actual_yaw_rate_deg_s # [deg/s] Actual yaw rate of the rover -float32 desired_yaw_rate_deg_s # [deg/s] Yaw rate setpoint for the closed loop yaw rate controller -float32 pid_yaw_integral # Integral of the PID for the closed loop yaw controller -float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller -float32 pid_throttle_integral # Integral of the PID for the closed loop speed controller +float32 actual_speed # [m/s] Actual forward speed of the rover +float32 actual_yaw # [rad] Actual yaw of the rover +float32 actual_yaw_rate # [rad/s] Actual yaw rate of the rover +float32 desired_yaw_rate # [rad/s] Yaw rate setpoint for the closed loop yaw rate controller +float32 forward_speed_normalized # [-1, 1] Normalized forward speed setpoint +float32 speed_diff_normalized # [-1, 1] Normalized speed difference setpoint between the left and right motor +float32 pid_yaw_integral # Integral of the PID for the closed loop yaw controller +float32 pid_yaw_rate_integral # Integral of the PID for the closed loop yaw rate controller +float32 pid_throttle_integral # Integral of the PID for the closed loop speed controller # TOPICS rover_differential_status diff --git a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp index a7019e3a8470..7ec57fb176bc 100644 --- a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp +++ b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp @@ -92,9 +92,13 @@ void RoverDifferentialControl::computeMotorCommands(const float vehicle_yaw, con float speed_diff_normalized{0.f}; if (PX4_ISFINITE(_rover_differential_setpoint.yaw_rate_setpoint)) { // Closed loop yaw rate control - const float speed_diff = _rover_differential_setpoint.yaw_rate_setpoint * _param_rd_wheel_track.get(); // Feedforward - speed_diff_normalized = math::interpolate(speed_diff, -_param_rd_max_speed.get(), - _param_rd_max_speed.get(), -1.f, 1.f); + if (_param_rd_wheel_track.get() > FLT_EPSILON && _param_rd_max_thr_yaw_r.get() > FLT_EPSILON) { // Feedforward + const float speed_diff = _rover_differential_setpoint.yaw_rate_setpoint * _param_rd_wheel_track.get() / + 2.f; + speed_diff_normalized = math::interpolate(speed_diff, -_param_rd_max_thr_yaw_r.get(), + _param_rd_max_thr_yaw_r.get(), -1.f, 1.f); + } + speed_diff_normalized = math::constrain(speed_diff_normalized + pid_calculate(&_pid_yaw_rate, _rover_differential_setpoint.yaw_rate_setpoint, vehicle_yaw_rate, 0, dt), -1.f, 1.f); // Feedback @@ -105,30 +109,34 @@ void RoverDifferentialControl::computeMotorCommands(const float vehicle_yaw, con } // Speed control - float throttle{0.f}; + float forward_speed_normalized{0.f}; if (PX4_ISFINITE(_rover_differential_setpoint.forward_speed_setpoint)) { // Closed loop speed control - if (_param_rd_max_speed.get() > FLT_EPSILON) { // Feedforward - throttle += math::interpolate(_rover_differential_setpoint.forward_speed_setpoint, - 0.f, _param_rd_max_speed.get(), - 0.f, 1.f); + if (_param_rd_max_thr_spd.get() > FLT_EPSILON) { // Feedforward + forward_speed_normalized = math::interpolate(_rover_differential_setpoint.forward_speed_setpoint, + -_param_rd_max_thr_spd.get(), _param_rd_max_thr_spd.get(), + -1.f, 1.f); } - throttle = pid_calculate(&_pid_throttle, _rover_differential_setpoint.forward_speed_setpoint, vehicle_forward_speed, 0, - dt); // Feedback + forward_speed_normalized = math::constrain(forward_speed_normalized + pid_calculate(&_pid_throttle, + _rover_differential_setpoint.forward_speed_setpoint, + vehicle_forward_speed, 0, + dt), -1.f, 1.f); // Feedback } else { // Use normalized setpoint - throttle = PX4_ISFINITE(_rover_differential_setpoint.forward_speed_setpoint_normalized) ? - math::constrain(_rover_differential_setpoint.forward_speed_setpoint_normalized, -1.f, 1.f) : 0.f; + forward_speed_normalized = PX4_ISFINITE(_rover_differential_setpoint.forward_speed_setpoint_normalized) ? + math::constrain(_rover_differential_setpoint.forward_speed_setpoint_normalized, -1.f, 1.f) : 0.f; } // Publish rover differential status (logging) rover_differential_status_s rover_differential_status{}; rover_differential_status.timestamp = _timestamp; rover_differential_status.actual_speed = vehicle_forward_speed; - rover_differential_status.actual_yaw_deg = M_RAD_TO_DEG_F * vehicle_yaw; - rover_differential_status.desired_yaw_rate_deg_s = M_RAD_TO_DEG_F * _rover_differential_setpoint.yaw_rate_setpoint; - rover_differential_status.actual_yaw_rate_deg_s = M_RAD_TO_DEG_F * vehicle_yaw_rate; + rover_differential_status.actual_yaw = vehicle_yaw; + rover_differential_status.desired_yaw_rate = _rover_differential_setpoint.yaw_rate_setpoint; + rover_differential_status.actual_yaw_rate = vehicle_yaw_rate; + rover_differential_status.forward_speed_normalized = forward_speed_normalized; + rover_differential_status.speed_diff_normalized = speed_diff_normalized; rover_differential_status.pid_yaw_rate_integral = _pid_yaw_rate.integral; rover_differential_status.pid_throttle_integral = _pid_throttle.integral; rover_differential_status.pid_yaw_integral = _pid_yaw.integral; @@ -137,7 +145,7 @@ void RoverDifferentialControl::computeMotorCommands(const float vehicle_yaw, con // Publish to motors actuator_motors_s actuator_motors{}; actuator_motors.reversible_flags = _param_r_rev.get(); - computeInverseKinematics(throttle, speed_diff_normalized).copyTo(actuator_motors.control); + computeInverseKinematics(forward_speed_normalized, speed_diff_normalized).copyTo(actuator_motors.control); actuator_motors.timestamp = _timestamp; _actuator_motors_pub.publish(actuator_motors); diff --git a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp index 9f49186ad8b6..a5eb08135f50 100644 --- a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp +++ b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp @@ -113,7 +113,8 @@ class RoverDifferentialControl : public ModuleParams // Parameters DEFINE_PARAMETERS( (ParamFloat) _param_rd_wheel_track, - (ParamFloat) _param_rd_max_speed, + (ParamFloat) _param_rd_max_thr_spd, + (ParamFloat) _param_rd_max_thr_yaw_r, (ParamFloat) _param_rd_max_yaw_rate, (ParamFloat) _param_rd_yaw_rate_p, (ParamFloat) _param_rd_yaw_rate_i, diff --git a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp index 848a7f513acf..c56830ad08a2 100644 --- a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp +++ b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp @@ -216,7 +216,7 @@ void RoverDifferentialGuidance::updateWaypoints() // Waypoint cruising speed if (position_setpoint_triplet.current.cruising_speed > 0.f) { - _max_forward_speed = math::constrain(position_setpoint_triplet.current.cruising_speed, 0.f, _param_rd_max_speed.get()); + _max_forward_speed = position_setpoint_triplet.current.cruising_speed; } else { _max_forward_speed = _param_rd_miss_spd_def.get(); diff --git a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp index fd3a9485a04e..d2b9862b2cc0 100644 --- a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp +++ b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp @@ -140,7 +140,6 @@ class RoverDifferentialGuidance : public ModuleParams // Parameters DEFINE_PARAMETERS( - (ParamFloat) _param_rd_max_speed, (ParamFloat) _param_nav_acc_rad, (ParamFloat) _param_rd_max_jerk, (ParamFloat) _param_rd_max_accel, diff --git a/src/modules/rover_differential/module.yaml b/src/modules/rover_differential/module.yaml index 6602497685db..8ef9f62f5e30 100644 --- a/src/modules/rover_differential/module.yaml +++ b/src/modules/rover_differential/module.yaml @@ -113,10 +113,14 @@ parameters: decimal: 2 default: 0.5 - RD_MAX_SPEED: + RD_MAX_THR_SPD: description: - short: Maximum speed the rover can drive - long: This parameter is used to map desired speeds to normalized motor commands. + short: Speed the rover drives at maximum throttle + long: | + This parameter is used to calculate the feedforward term of the closed loop speed control which linearly + maps desired speeds to normalized motor commands [-1. 1]. + A good starting point is the observed ground speed when the rover drives at maximum throttle in manual mode. + Increase this parameter if the rover is faster than the setpoint, and decrease if the rover is slower. type: float unit: m/s min: 0 @@ -138,6 +142,23 @@ parameters: decimal: 2 default: 90 + RD_MAX_THR_YAW_R: + description: + short: Yaw rate turning left/right wheels at max speed in opposite directions + long: | + This parameter is used to calculate the feedforward term of the closed loop yaw rate control. + The controller first calculates the required speed difference between the left and right motor to achieve the desired yaw rate. + This desired speed difference is then linearly mapped to normalized motor commands. + A good starting point is twice the speed the rover drives at maximum throttle (RD_MAX_THR_SPD)). + Increase this parameter if the rover turns faster than the setpoint, and decrease if the rover turns slower. + type: float + unit: m/s + min: 0 + max: 100 + increment: 0.01 + decimal: 2 + default: 2 + RD_MISS_SPD_DEF: description: short: Default forward speed for the rover during auto modes From 22c2878cf8dd3a0f183b2a6db573aef643619359 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth Date: Wed, 11 Sep 2024 11:16:07 +0200 Subject: [PATCH 25/40] send acknowledgement after receiving vehicle wind cmd --- src/modules/ekf2/EKF2.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 38e5660e4ff4..46a28e469f99 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -571,7 +571,12 @@ void EKF2::Run() const float wind_direction_accuracy_rad = math::radians(vehicle_command.param4); _ekf.resetWindToExternalObservation(vehicle_command.param1, wind_direction_rad, vehicle_command.param2, wind_direction_accuracy_rad); + command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED; +#else + command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_UNSUPPORTED; #endif // CONFIG_EKF2_WIND + command_ack.timestamp = hrt_absolute_time(); + _vehicle_command_ack_pub.publish(command_ack); } } } From 4ba4b340cc146d65b3f97abb70a22a826137d099 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Tue, 10 Sep 2024 11:03:18 +0200 Subject: [PATCH 26/40] Reduce the orbit jerk by using a slew rate --- .../tasks/Orbit/FlightTaskOrbit.cpp | 11 +++++++++-- .../tasks/Orbit/FlightTaskOrbit.hpp | 2 ++ 2 files changed, 11 insertions(+), 2 deletions(-) diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp index 144c6c7ba158..3136c9805176 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.cpp @@ -181,6 +181,7 @@ bool FlightTaskOrbit::activate(const trajectory_setpoint_s &last_setpoint) _initial_heading = _yaw; _slew_rate_yaw.setForcedValue(_yaw); _slew_rate_yaw.setSlewRate(math::radians(_param_mpc_yawrauto_max.get())); + _slew_rate_velocity.setSlewRate(_param_mpc_acc_hor.get()); // need a valid position and velocity ret = ret && _position.isAllFinite() && _velocity.isAllFinite(); @@ -216,6 +217,7 @@ bool FlightTaskOrbit::update() if (_is_position_on_circle()) { if (_in_circle_approach) { _in_circle_approach = false; + _slew_rate_velocity.setForcedValue(0.f); // reset the slew rate when moving between orbits. FlightTaskManualAltitudeSmoothVel::_smoothing.reset( PX4_ISFINITE(_acceleration_setpoint(2)) ? _acceleration_setpoint(2) : 0.f, PX4_ISFINITE(_velocity_setpoint(2)) ? _velocity_setpoint(2) : _velocity(2), @@ -329,15 +331,20 @@ void FlightTaskOrbit::_generate_circle_setpoints() Vector3f center_to_position = _position - _center; // xy velocity to go around in a circle Vector2f velocity_xy(-center_to_position(1), center_to_position(0)); + + // slew rate is used to reduce the jerk when starting an orbit. + _slew_rate_velocity.update(_orbit_velocity, _deltatime); + velocity_xy = velocity_xy.unit_or_zero(); - velocity_xy *= _orbit_velocity; + velocity_xy *= _slew_rate_velocity.getState(); // xy velocity adjustment to stay on the radius distance velocity_xy += (_orbit_radius - center_to_position.xy().norm()) * Vector2f(center_to_position).unit_or_zero(); _position_setpoint(0) = _position_setpoint(1) = NAN; _velocity_setpoint.xy() = velocity_xy; - _acceleration_setpoint.xy() = -Vector2f(center_to_position.unit_or_zero()) * _orbit_velocity * _orbit_velocity / + _acceleration_setpoint.xy() = -Vector2f(center_to_position.unit_or_zero()) * _slew_rate_velocity.getState() * + _slew_rate_velocity.getState() / _orbit_radius; } diff --git a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp index 2c55bbc15ba7..13e53bf83fe9 100644 --- a/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp +++ b/src/modules/flight_mode_manager/tasks/Orbit/FlightTaskOrbit.hpp @@ -47,6 +47,7 @@ #include #include #include +#include class FlightTaskOrbit : public FlightTaskManualAltitudeSmoothVel @@ -127,6 +128,7 @@ class FlightTaskOrbit : public FlightTaskManualAltitudeSmoothVel bool _currently_orbiting{false}; float _initial_heading = 0.f; /**< the heading of the drone when the orbit command was issued */ SlewRateYaw _slew_rate_yaw; + SlewRate _slew_rate_velocity; orb_advert_t _mavlink_log_pub{nullptr}; uORB::PublicationMulti _orbit_status_pub{ORB_ID(orbit_status)}; From 585c92796d30058845b8e62ea13adb25f0b2181c Mon Sep 17 00:00:00 2001 From: Konrad Date: Fri, 13 Sep 2024 12:35:50 +0200 Subject: [PATCH 27/40] mission_base: do not make terrain avoidance check when mission is not run anymore --- src/modules/navigator/mission_block.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/src/modules/navigator/mission_block.cpp b/src/modules/navigator/mission_block.cpp index 84d95ae5a310..c2b17bbedbab 100644 --- a/src/modules/navigator/mission_block.cpp +++ b/src/modules/navigator/mission_block.cpp @@ -1030,6 +1030,7 @@ void MissionBlock::updateAltToAvoidTerrainCollisionAndRepublishTriplet(mission_i if (_navigator->get_nav_min_gnd_dist_param() > FLT_EPSILON && _mission_item.nav_cmd != NAV_CMD_LAND && _mission_item.nav_cmd != NAV_CMD_VTOL_LAND && _mission_item.nav_cmd != NAV_CMD_DO_VTOL_TRANSITION + && _mission_item.nav_cmd != NAV_CMD_IDLE && _navigator->get_local_position()->dist_bottom_valid && _navigator->get_local_position()->dist_bottom < _navigator->get_nav_min_gnd_dist_param() && _navigator->get_local_position()->vz > FLT_EPSILON From 4713a6737ee660af113bd412671a62a2fb8a755a Mon Sep 17 00:00:00 2001 From: Konrad Date: Thu, 5 Sep 2024 17:08:53 +0200 Subject: [PATCH 28/40] TECS: ramp up fast descend over 2_s to ramp down the throttle command --- msg/TecsStatus.msg | 1 + src/lib/tecs/TECS.cpp | 36 +++++++++++++------ src/lib/tecs/TECS.hpp | 27 +++++++++++--- .../FixedwingPositionControl.cpp | 3 +- 4 files changed, 50 insertions(+), 17 deletions(-) diff --git a/msg/TecsStatus.msg b/msg/TecsStatus.msg index ae6835dc5249..af3826b1555d 100644 --- a/msg/TecsStatus.msg +++ b/msg/TecsStatus.msg @@ -27,3 +27,4 @@ float32 pitch_sp_rad # Current pitch setpoint [rad] float32 throttle_trim # estimated throttle value [0,1] required to fly level at equivalent_airspeed_sp in the current atmospheric conditions float32 underspeed_ratio # 0: no underspeed, 1: maximal underspeed. Controller takes measures to avoid stall proportional to ratio if >0. +float32 fast_descend_ratio # value indicating if fast descend mode is enabled with ramp up and ramp down [0-1] diff --git a/src/lib/tecs/TECS.cpp b/src/lib/tecs/TECS.cpp index 4a6d3593e894..6a09b8775913 100644 --- a/src/lib/tecs/TECS.cpp +++ b/src/lib/tecs/TECS.cpp @@ -44,11 +44,11 @@ #include "matrix/Matrix.hpp" #include "matrix/Vector2.hpp" +#include using math::constrain; using math::max; using math::min; -using namespace time_literals; static inline constexpr bool TIMESTAMP_VALID(float dt) { return (PX4_ISFINITE(dt) && dt > FLT_EPSILON);} @@ -525,16 +525,12 @@ void TECSControl::_calcThrottleControl(float dt, const SpecificEnergyRates &spec if (1.f - param.fast_descend < FLT_EPSILON) { // During fast descend, we control airspeed over the pitch control loop. Give minimal thrust as soon as we are descending - if (specific_energy_rates.spe_rate.estimate > 0) { // We have a positive altitude rate and are stil climbing - throttle_setpoint = param.throttle_trim; // Do not cut off throttle yet - - } else { - throttle_setpoint = param.throttle_min; - } + throttle_setpoint = param.throttle_min; } else { _calcThrottleControlUpdate(dt, limit, ste_rate, param, flag); - throttle_setpoint = _calcThrottleControlOutput(limit, ste_rate, param, flag); + throttle_setpoint = (1.f - param.fast_descend) * _calcThrottleControlOutput(limit, ste_rate, param, + flag) + param.fast_descend * param.throttle_min; } // Rate limit the throttle demand @@ -677,6 +673,11 @@ void TECS::initControlParams(float target_climbrate, float target_sinkrate, floa _control_param.throttle_min = throttle_min; } +float TECS::calcTrueAirspeedSetpoint(float eas_to_tas, float eas_setpoint) +{ + return lerp(eas_to_tas * eas_setpoint, _control_param.tas_max, _fast_descend); +} + void TECS::initialize(const float altitude, const float altitude_rate, const float equivalent_airspeed, float eas_to_tas) { @@ -699,6 +700,9 @@ void TECS::initialize(const float altitude, const float altitude_rate, const flo .tas_rate = 0.0f}; _control.initialize(control_setpoint, control_input, _control_param, _control_flag); + + _fast_descend = 0.f; + _enabled_fast_descend_timestamp = 0U; } void TECS::update(float pitch, float altitude, float hgt_setpoint, float EAS_setpoint, float equivalent_airspeed, @@ -753,8 +757,7 @@ void TECS::update(float pitch, float altitude, float hgt_setpoint, float EAS_set TECSControl::Setpoint control_setpoint; control_setpoint.altitude_reference = _altitude_reference_model.getAltitudeReference(); control_setpoint.altitude_rate_setpoint_direct = _altitude_reference_model.getHeightRateSetpointDirect(); - control_setpoint.tas_setpoint = _control_param.tas_max * _fast_descend + (1 - _fast_descend) * eas_to_tas * - EAS_setpoint; + control_setpoint.tas_setpoint = calcTrueAirspeedSetpoint(eas_to_tas, EAS_setpoint); const TECSControl::Input control_input{ .altitude = altitude, .altitude_rate = hgt_rate, @@ -765,11 +768,13 @@ void TECS::update(float pitch, float altitude, float hgt_setpoint, float EAS_set } _debug_status.control = _control.getDebugOutput(); + _debug_status.true_airspeed_sp = calcTrueAirspeedSetpoint(eas_to_tas, EAS_setpoint); _debug_status.true_airspeed_filtered = eas_to_tas * _airspeed_filter.getState().speed; _debug_status.true_airspeed_derivative = eas_to_tas * _airspeed_filter.getState().speed_rate; _debug_status.altitude_reference = _altitude_reference_model.getAltitudeReference().alt; _debug_status.height_rate_reference = _altitude_reference_model.getAltitudeReference().alt_rate; _debug_status.height_rate_direct = _altitude_reference_model.getHeightRateSetpointDirect(); + _debug_status.fast_descend = _fast_descend; _update_timestamp = now; } @@ -778,13 +783,22 @@ void TECS::_setFastDescend(const float alt_setpoint, const float alt) { if (_control_flag.airspeed_enabled && (_fast_descend_alt_err > FLT_EPSILON) && ((alt_setpoint + _fast_descend_alt_err) < alt)) { - _fast_descend = 1.f; + auto now = hrt_absolute_time(); + + if (_enabled_fast_descend_timestamp == 0U) { + _enabled_fast_descend_timestamp = now; + } + + _fast_descend = constrain(max(_fast_descend, static_cast(now - _enabled_fast_descend_timestamp) / + static_cast(FAST_DESCEND_RAMP_UP_TIME)), 0.f, 1.f); } else if ((_fast_descend > FLT_EPSILON) && (_fast_descend_alt_err > FLT_EPSILON)) { // Were in fast descend, scale it down. up until 5m above target altitude _fast_descend = constrain((alt - alt_setpoint - 5.f) / _fast_descend_alt_err, 0.f, 1.f); + _enabled_fast_descend_timestamp = 0U; } else { _fast_descend = 0.f; + _enabled_fast_descend_timestamp = 0U; } } diff --git a/src/lib/tecs/TECS.hpp b/src/lib/tecs/TECS.hpp index f033bf72dabf..57cc12690b14 100644 --- a/src/lib/tecs/TECS.hpp +++ b/src/lib/tecs/TECS.hpp @@ -50,6 +50,8 @@ #include #include +using namespace time_literals; + class TECSAirspeedFilter { public: @@ -203,8 +205,8 @@ class TECSControl float equivalent_airspeed_trim; ///< Equivalent cruise airspeed for airspeed less mode [m/s]. float tas_min; ///< True airspeed demand lower limit [m/s]. float tas_max; ///< True airspeed demand upper limit [m/s]. - float pitch_max; ///< Maximum pitch angle allowed in [rad]. - float pitch_min; ///< Minimal pitch angle allowed in [rad]. + float pitch_max; ///< Maximum pitch angle above trim allowed in [rad]. + float pitch_min; ///< Minimal pitch angle below trim allowed in [rad]. float throttle_trim; ///< Normalized throttle required to fly level at calibrated airspeed setpoint [0,1] float throttle_max; ///< Normalized throttle upper limit. float throttle_min; ///< Normalized throttle lower limit. @@ -320,7 +322,7 @@ class TECSControl /** * @brief Get the pitch setpoint. * - * @return THe commanded pitch angle in [rad]. + * @return The commanded pitch angle above trim in [rad]. */ float getPitchSetpoint() const {return _pitch_setpoint;}; /** @@ -478,7 +480,7 @@ class TECSControl * @param seb_rate is the specific energy balance rate in [m²/s³]. * @param param is the control parameters. * @param flag is the control flags. - * @return pitch setpoint angle [rad]. + * @return pitch setpoint angle above trim [rad]. */ float _calcPitchControlOutput(const Input &input, const ControlValues &seb_rate, const Param ¶m, const Flag &flag) const; @@ -537,7 +539,7 @@ class TECSControl // Output DebugOutput _debug_output; ///< Debug output. - float _pitch_setpoint{0.0f}; ///< Controlled pitch setpoint [rad]. + float _pitch_setpoint{0.0f}; ///< Controlled pitch setpoint above trim [rad]. float _throttle_setpoint{0.0f}; ///< Controlled throttle setpoint [0,1]. float _ratio_undersped{0.0f}; ///< A continuous representation of how "undersped" the TAS is [0,1] }; @@ -547,11 +549,13 @@ class TECS public: struct DebugOutput { TECSControl::DebugOutput control; + float true_airspeed_sp; float true_airspeed_filtered; float true_airspeed_derivative; float altitude_reference; float height_rate_reference; float height_rate_direct; + float fast_descend; }; public: TECS() = default; @@ -658,6 +662,17 @@ class TECS void initControlParams(float target_climbrate, float target_sinkrate, float eas_to_tas, float pitch_limit_max, float pitch_limit_min, float throttle_min, float throttle_setpoint_max, float throttle_trim); + /** + * @brief calculate true airspeed setpoint + * + * Calculate true airspeed setpoint based on input and fast descend ratio + * + * @param eas_to_tas is the eas to tas conversion factor + * @param eas_setpoint is the desired equivalent airspeed setpoint [m/s] + * @return true airspeed setpoint[m/s] + */ + float calcTrueAirspeedSetpoint(float eas_to_tas, float eas_setpoint); + /** * @brief Initialize the control loop * @@ -675,9 +690,11 @@ class TECS float _equivalent_airspeed_max{20.0f}; ///< equivalent airspeed demand upper limit (m/sec) float _fast_descend_alt_err{-1.f}; ///< Altitude difference between current altitude to altitude setpoint needed to descend with higher airspeed [m]. float _fast_descend{0.f}; ///< Value for fast descend in [0,1]. continuous value used to flatten the high speed value out when close to target altitude. + hrt_abstime _enabled_fast_descend_timestamp{0U}; ///< timestamp at activation of fast descend mode static constexpr float DT_MIN = 0.001f; ///< minimum allowed value of _dt (sec) static constexpr float DT_MAX = 1.0f; ///< max value of _dt allowed before a filter state reset is performed (sec) + static constexpr hrt_abstime FAST_DESCEND_RAMP_UP_TIME = 2_s; ///< Ramp up time until fast descend is fully engaged DebugOutput _debug_status{}; diff --git a/src/modules/fw_pos_control/FixedwingPositionControl.cpp b/src/modules/fw_pos_control/FixedwingPositionControl.cpp index 00e7869c6949..fcd5ce553903 100644 --- a/src/modules/fw_pos_control/FixedwingPositionControl.cpp +++ b/src/modules/fw_pos_control/FixedwingPositionControl.cpp @@ -424,7 +424,7 @@ FixedwingPositionControl::tecs_status_publish(float alt_sp, float equivalent_air tecs_status.height_rate_setpoint = debug_output.control.altitude_rate_control; tecs_status.height_rate = -_local_pos.vz; tecs_status.equivalent_airspeed_sp = equivalent_airspeed_sp; - tecs_status.true_airspeed_sp = _eas2tas * equivalent_airspeed_sp; + tecs_status.true_airspeed_sp = debug_output.true_airspeed_sp; tecs_status.true_airspeed_filtered = debug_output.true_airspeed_filtered; tecs_status.true_airspeed_derivative_sp = debug_output.control.true_airspeed_derivative_control; tecs_status.true_airspeed_derivative = debug_output.true_airspeed_derivative; @@ -439,6 +439,7 @@ FixedwingPositionControl::tecs_status_publish(float alt_sp, float equivalent_air tecs_status.pitch_sp_rad = _tecs.get_pitch_setpoint(); tecs_status.throttle_trim = throttle_trim; tecs_status.underspeed_ratio = _tecs.get_underspeed_ratio(); + tecs_status.fast_descend_ratio = debug_output.fast_descend; tecs_status.timestamp = hrt_absolute_time(); From 878c8bfcce19d4d3e8c5f4cbe1ec44da41b0dd34 Mon Sep 17 00:00:00 2001 From: RomanBapst Date: Tue, 10 Sep 2024 17:50:03 +0300 Subject: [PATCH 29/40] SIH: fix airspeed for tailsitter Signed-off-by: RomanBapst --- src/modules/simulation/simulator_sih/sih.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/modules/simulation/simulator_sih/sih.cpp b/src/modules/simulation/simulator_sih/sih.cpp index 399a4ecc938d..2ca4987338e8 100644 --- a/src/modules/simulation/simulator_sih/sih.cpp +++ b/src/modules/simulation/simulator_sih/sih.cpp @@ -450,7 +450,8 @@ void Sih::send_airspeed(const hrt_abstime &time_now_us) // TODO: send differential pressure instead? airspeed_s airspeed{}; airspeed.timestamp_sample = time_now_us; - airspeed.true_airspeed_m_s = fmaxf(0.1f, _v_B(0) + generate_wgn() * 0.2f); + // airspeed sensor is mounted along the negative Z axis since the vehicle is a tailsitter + airspeed.true_airspeed_m_s = fmaxf(0.1f, -_v_B(2) + generate_wgn() * 0.2f); airspeed.indicated_airspeed_m_s = airspeed.true_airspeed_m_s * sqrtf(_wing_l.get_rho() / RHO); airspeed.air_temperature_celsius = NAN; airspeed.confidence = 0.7f; From 11440cfb454871db8276d4c3a1a3fcd33b7534df Mon Sep 17 00:00:00 2001 From: RomanBapst Date: Fri, 13 Sep 2024 12:13:11 +0300 Subject: [PATCH 30/40] added some default parameteter that allow the transition to complete Signed-off-by: RomanBapst --- .../init.d/airframes/1102_tailsitter_duo_sih.hil | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil b/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil index a9b2f7f03b1b..6ac2671d0730 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil @@ -43,6 +43,10 @@ param set-default CA_SV_CS1_TRQ_P 0.3 param set-default CA_SV_CS1_TRQ_Y -0.3 param set-default CA_SV_CS1_TYPE 6 +param set-default FW_AIRSPD_MAX 12 +param set-default FW_AIRSPD_MIN 7 +param set-default FW_AIRSPD_TRIM 10 + param set-default HIL_ACT_FUNC1 101 param set-default HIL_ACT_FUNC2 102 param set-default HIL_ACT_FUNC5 202 @@ -75,3 +79,5 @@ param set SIH_L_ROLL 0.145 # sih as tailsitter param set SIH_VEHICLE_TYPE 2 + +param set-default VT_ARSP_TRANS 6 From 9ca0630376fca98396943c065034d3cacae34746 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 13 Sep 2024 13:51:18 +0200 Subject: [PATCH 31/40] airframes: SIH_tailsitter: add SENS_DPRES_OFF to bypass airspeed cal Signed-off-by: Silvan Fuhrer --- .../px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil | 2 ++ 1 file changed, 2 insertions(+) diff --git a/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil b/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil index 6ac2671d0730..d9e8611cdb0d 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil +++ b/ROMFS/px4fmu_common/init.d/airframes/1102_tailsitter_duo_sih.hil @@ -66,6 +66,8 @@ param set-default CBRK_SUPPLY_CHK 894281 # - without safety switch param set-default CBRK_IO_SAFETY 22027 +param set-default SENS_DPRES_OFF 0.001 + param set SIH_T_MAX 2.0 param set SIH_Q_MAX 0.0165 param set SIH_MASS 0.2 From e6f07bde2aa1daef45ea6336d892efb4ef89b1fa Mon Sep 17 00:00:00 2001 From: Konrad Date: Mon, 9 Sep 2024 10:35:35 +0200 Subject: [PATCH 32/40] lightware_laser: add option to listen to system to enable/disable distance sensor --- msg/CMakeLists.txt | 1 + msg/DistanceSensorModeChangeRequest.msg | 5 +++++ .../lightware_laser_i2c/lightware_laser_i2c.cpp | 16 +++++++++++++++- .../lightware_laser_i2c/parameters.c | 2 +- 4 files changed, 22 insertions(+), 2 deletions(-) create mode 100644 msg/DistanceSensorModeChangeRequest.msg diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 91c38488f5aa..596ca30fcdf7 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -73,6 +73,7 @@ set(msg_files DebugVect.msg DifferentialPressure.msg DistanceSensor.msg + DistanceSensorModeChangeRequest.msg Ekf2Timestamps.msg EscReport.msg EscStatus.msg diff --git a/msg/DistanceSensorModeChangeRequest.msg b/msg/DistanceSensorModeChangeRequest.msg new file mode 100644 index 000000000000..294e225e354f --- /dev/null +++ b/msg/DistanceSensorModeChangeRequest.msg @@ -0,0 +1,5 @@ +uint64 timestamp # time since system start (microseconds) + +uint8 req_mode # requested mode of operation +uint8 MODE_DISABLED = 0 +uint8 MODE_ENABLED = 1 diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp index 6c1dfbcea068..152073f2ac5c 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp +++ b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp @@ -55,6 +55,7 @@ #include #include #include +#include using namespace time_literals; @@ -143,6 +144,8 @@ class LightwareLaser : public device::I2C, public I2CSPIDriver, uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; typeof(px4::msg::VehicleStatus::vehicle_type) _vehicle_type{px4::msg::VehicleStatus::VEHICLE_TYPE_UNKNOWN}; + uORB::Subscription _dist_sense_mode_change_sub{ORB_ID(distance_sensor_mode_change_request)}; + typeof(px4::msg::DistanceSensorModeChangeRequest::req_mode) _req_mode{px4::msg::DistanceSensorModeChangeRequest::MODE_DISABLED}; bool _restriction{false}; bool _auto_restriction{false}; bool _prev_restriction{false}; @@ -412,6 +415,17 @@ void LightwareLaser::start() int LightwareLaser::updateRestriction() { + if (_dist_sense_mode_change_sub.updated()) { + distance_sensor_mode_change_request_s dist_sense_mode_change; + + if (_dist_sense_mode_change_sub.copy(&dist_sense_mode_change)) { + _req_mode = dist_sense_mode_change.req_mode; + + } else { + _req_mode = distance_sensor_mode_change_request_s::MODE_DISABLED; + } + } + px4::msg::VehicleStatus vehicle_status; if (_vehicle_status_sub.update(&vehicle_status)) { @@ -452,7 +466,7 @@ int LightwareLaser::updateRestriction() break; case 2: - _restriction = _auto_restriction; + _restriction = _auto_restriction && _req_mode != distance_sensor_mode_change_request_s::MODE_ENABLED; break; } diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c b/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c index defe335751f3..161e9d3cabe0 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c +++ b/src/drivers/distance_sensor/lightware_laser_i2c/parameters.c @@ -54,7 +54,7 @@ PARAM_DEFINE_INT32(SENS_EN_SF1XX, 0); * * @value 0 Disabled * @value 1 Enabled - * @value 2 Disabled during VTOL fast forward flight + * @value 2 Enabled in VTOL MC mode, listen to request from system in FW mode * * @min 0 * @max 2 From 1755b8304e689fc5ef744f03742c7e626975e01e Mon Sep 17 00:00:00 2001 From: Konrad Date: Mon, 9 Sep 2024 16:48:04 +0200 Subject: [PATCH 33/40] RTL direct: Make sure the _rtl_state captures the current status and not the next one --- src/modules/navigator/rtl_direct.cpp | 79 ++++++++++++++++++++-------- src/modules/navigator/rtl_direct.h | 6 +++ 2 files changed, 63 insertions(+), 22 deletions(-) diff --git a/src/modules/navigator/rtl_direct.cpp b/src/modules/navigator/rtl_direct.cpp index 145b99d0d1db..088ad1baebdd 100644 --- a/src/modules/navigator/rtl_direct.cpp +++ b/src/modules/navigator/rtl_direct.cpp @@ -101,10 +101,11 @@ void RtlDirect::on_active() parameters_update(); if (_rtl_state != RTLState::IDLE && is_mission_item_reached_or_completed()) { + _updateRtlState(); set_rtl_item(); } - if (_rtl_state != RTLState::IDLE) { //TODO: rename _rtl_state to _rtl_state_next (when in IDLE we're actually in LAND) + if (_rtl_state != RTLState::IDLE && _rtl_state != RTLState::LAND) { //check for terrain collision and update altitude if needed // note: it may trigger multiple times during a RTL, as every time the altitude set is reset updateAltToAvoidTerrainCollisionAndRepublishTriplet(_mission_item); @@ -154,6 +155,61 @@ void RtlDirect::setRtlPosition(PositionYawSetpoint rtl_position, loiter_point_s } } +void RtlDirect::_updateRtlState() +{ + RTLState new_state{RTLState::IDLE}; + + switch (_rtl_state) { + case RTLState::CLIMBING: + new_state = RTLState::MOVE_TO_LOITER; + break; + + case RTLState::MOVE_TO_LOITER: + new_state = RTLState::LOITER_DOWN; + break; + + case RTLState::LOITER_DOWN: + new_state = RTLState::LOITER_HOLD; + break; + + case RTLState::LOITER_HOLD: + if (_vehicle_status_sub.get().is_vtol + && _vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) { + new_state = RTLState::MOVE_TO_LAND; + + } else { + new_state = RTLState::MOVE_TO_LAND_HOVER; + } + + break; + + case RTLState::MOVE_TO_LAND: + new_state = RTLState::TRANSITION_TO_MC; + break; + + case RTLState::TRANSITION_TO_MC: + new_state = RTLState::MOVE_TO_LAND_HOVER; + break; + + case RTLState::MOVE_TO_LAND_HOVER: + new_state = RTLState::LAND; + break; + + case RTLState::LAND: + new_state = RTLState::IDLE; + break; + + case RTLState::IDLE: // Fallthrough + default: + new_state = RTLState::IDLE; + break; + } + + _rtl_state = new_state; + +} + + void RtlDirect::set_rtl_item() { position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); @@ -174,7 +230,6 @@ void RtlDirect::set_rtl_item() }; setLoiterToAltMissionItem(_mission_item, pos_yaw_sp, _navigator->get_loiter_radius()); - _rtl_state = RTLState::MOVE_TO_LOITER; break; } @@ -197,8 +252,6 @@ void RtlDirect::set_rtl_item() setMoveToPositionMissionItem(_mission_item, pos_yaw_sp); } - _rtl_state = RTLState::LOITER_DOWN; - break; } @@ -224,8 +277,6 @@ void RtlDirect::set_rtl_item() // Disable previous setpoint to prevent drift. pos_sp_triplet->previous.valid = false; - _rtl_state = RTLState::LOITER_HOLD; - break; } @@ -244,14 +295,6 @@ void RtlDirect::set_rtl_item() events::send(events::ID("rtl_completed_loiter"), events::Log::Info, "RTL: completed, loitering"); } - if (_vehicle_status_sub.get().is_vtol - && _vehicle_status_sub.get().vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING) { - _rtl_state = RTLState::MOVE_TO_LAND; - - } else { - _rtl_state = RTLState::MOVE_TO_LAND_HOVER; - } - break; } @@ -274,16 +317,12 @@ void RtlDirect::set_rtl_item() pos_sp_triplet->previous.alt = get_absolute_altitude_for_item(_mission_item); pos_sp_triplet->previous.valid = true; - _rtl_state = RTLState::TRANSITION_TO_MC; - break; } case RTLState::TRANSITION_TO_MC: { set_vtol_transition_item(&_mission_item, vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC); - _rtl_state = RTLState::MOVE_TO_LAND_HOVER; - break; } @@ -295,8 +334,6 @@ void RtlDirect::set_rtl_item() setMoveToPositionMissionItem(_mission_item, pos_yaw_sp); _navigator->reset_position_setpoint(pos_sp_triplet->previous); - _rtl_state = RTLState::LAND; - break; } @@ -309,8 +346,6 @@ void RtlDirect::set_rtl_item() startPrecLand(_mission_item.land_precision); - _rtl_state = RTLState::IDLE; - mavlink_log_info(_navigator->get_mavlink_log_pub(), "RTL: land at destination\t"); events::send(events::ID("rtl_land_at_destination"), events::Log::Info, "RTL: land at destination"); break; diff --git a/src/modules/navigator/rtl_direct.h b/src/modules/navigator/rtl_direct.h index b1f6a75b81ae..91e53dbe6b79 100644 --- a/src/modules/navigator/rtl_direct.h +++ b/src/modules/navigator/rtl_direct.h @@ -121,6 +121,12 @@ class RtlDirect : public MissionBlock, public ModuleParams } _rtl_state{RTLState::IDLE}; /*< Current state in the state machine.*/ private: + /** + * @brief Update the RTL state machine. + * + */ + void _updateRtlState(); + /** * @brief Set the return to launch control setpoint. * From aab2390e5145357c01706c29b842321364087c6b Mon Sep 17 00:00:00 2001 From: Konrad Date: Mon, 9 Sep 2024 11:06:03 +0200 Subject: [PATCH 34/40] navigator: publish distance sensor mode change request when in RTL landing phase or during mission landing --- src/modules/logger/logged_topics.cpp | 1 + src/modules/navigator/mission_base.h | 2 +- src/modules/navigator/navigator.h | 5 +++ src/modules/navigator/navigator_main.cpp | 31 +++++++++++++++++++ src/modules/navigator/rtl.cpp | 22 +++++++++++++ src/modules/navigator/rtl.h | 2 ++ src/modules/navigator/rtl_direct.h | 2 ++ .../navigator/rtl_mission_fast_reverse.cpp | 9 ++++++ .../navigator/rtl_mission_fast_reverse.h | 5 +++ 9 files changed, 78 insertions(+), 1 deletion(-) diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index f5ce636c23c9..d468563597b7 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -58,6 +58,7 @@ void LoggedTopics::add_default_topics() add_topic("commander_state"); add_topic("config_overrides"); add_topic("cpuload"); + add_topic("distance_sensor_mode_change_request"); add_optional_topic("external_ins_attitude"); add_optional_topic("external_ins_global_position"); add_optional_topic("external_ins_local_position"); diff --git a/src/modules/navigator/mission_base.h b/src/modules/navigator/mission_base.h index 1a6cbf977534..b8093ca01cf9 100644 --- a/src/modules/navigator/mission_base.h +++ b/src/modules/navigator/mission_base.h @@ -73,7 +73,7 @@ class MissionBase : public MissionBlock, public ModuleParams virtual void on_activation() override; virtual void on_active() override; - bool isLanding(); + virtual bool isLanding(); protected: diff --git a/src/modules/navigator/navigator.h b/src/modules/navigator/navigator.h index ec72881fc527..7fece40a4ecc 100644 --- a/src/modules/navigator/navigator.h +++ b/src/modules/navigator/navigator.h @@ -64,6 +64,7 @@ #include #include #include +#include #include #include #include @@ -316,6 +317,7 @@ class Navigator : public ModuleBase, public ModuleParams uORB::Publication _vehicle_cmd_pub{ORB_ID(vehicle_command)}; uORB::Publication _vehicle_roi_pub{ORB_ID(vehicle_roi)}; uORB::Publication _mode_completed_pub{ORB_ID(mode_completed)}; + uORB::PublicationData _distance_sensor_mode_change_request_pub{ORB_ID(distance_sensor_mode_change_request)}; orb_advert_t _mavlink_log_pub{nullptr}; /**< the uORB advert to send messages over mavlink */ @@ -336,6 +338,7 @@ class Navigator : public ModuleBase, public ModuleParams position_setpoint_triplet_s _takeoff_triplet{}; /**< triplet for non-mission direct takeoff command */ vehicle_roi_s _vroi{}; /**< vehicle ROI */ + perf_counter_t _loop_perf; /**< loop performance counter */ Geofence _geofence; /**< class that handles the geofence */ @@ -400,6 +403,8 @@ class Navigator : public ModuleBase, public ModuleParams void publish_vehicle_command_ack(const vehicle_command_s &cmd, uint8_t result); + void publish_distance_sensor_mode_request(); + bool geofence_allows_position(const vehicle_global_position_s &pos); DEFINE_PARAMETERS( diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 9a9f46e96282..e46decdfb19a 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -110,6 +110,11 @@ Navigator::Navigator() : _mission_sub = orb_subscribe(ORB_ID(mission)); _vehicle_status_sub = orb_subscribe(ORB_ID(vehicle_status)); + _distance_sensor_mode_change_request_pub.advertise(); + _distance_sensor_mode_change_request_pub.get().timestamp = hrt_absolute_time(); + _distance_sensor_mode_change_request_pub.get().req_mode = distance_sensor_mode_change_request_s::MODE_DISABLED; + _distance_sensor_mode_change_request_pub.update(); + // Update the timeout used in mission_block (which can't hold it's own parameters) _mission.set_payload_deployment_timeout(_param_mis_payload_delivery_timeout.get()); @@ -898,6 +903,8 @@ void Navigator::run() publish_navigator_status(); + publish_distance_sensor_mode_request(); + _geofence.run(); perf_end(_loop_perf); @@ -1447,6 +1454,30 @@ void Navigator::publish_vehicle_cmd(vehicle_command_s *vcmd) _vehicle_cmd_pub.publish(*vcmd); } +void Navigator::publish_distance_sensor_mode_request() +{ + // Send request to enable distance sensor when in the landing phase of a mission or RTL + if (((_navigation_mode == &_rtl) && _rtl.isLanding()) || ((_navigation_mode == &_mission) && _mission.isLanding())) { + + if (_distance_sensor_mode_change_request_pub.get().req_mode != + distance_sensor_mode_change_request_s::MODE_ENABLED) { + + _distance_sensor_mode_change_request_pub.get().timestamp = hrt_absolute_time(); + _distance_sensor_mode_change_request_pub.get().req_mode = + distance_sensor_mode_change_request_s::MODE_ENABLED; + _distance_sensor_mode_change_request_pub.update(); + } + + } else if (_distance_sensor_mode_change_request_pub.get().req_mode != + distance_sensor_mode_change_request_s::MODE_DISABLED) { + + _distance_sensor_mode_change_request_pub.get().timestamp = hrt_absolute_time(); + _distance_sensor_mode_change_request_pub.get().req_mode = + distance_sensor_mode_change_request_s::MODE_DISABLED; + _distance_sensor_mode_change_request_pub.update(); + } +} + void Navigator::publish_vehicle_command_ack(const vehicle_command_s &cmd, uint8_t result) { vehicle_command_ack_s command_ack = {}; diff --git a/src/modules/navigator/rtl.cpp b/src/modules/navigator/rtl.cpp index 63e2ab185ff1..cb33f350b7b1 100644 --- a/src/modules/navigator/rtl.cpp +++ b/src/modules/navigator/rtl.cpp @@ -304,6 +304,28 @@ void RTL::on_active() } } +bool RTL::isLanding() +{ + bool is_landing{false}; + + switch (_rtl_type) { + case RtlType::RTL_MISSION_FAST: + case RtlType::RTL_MISSION_FAST_REVERSE: + case RtlType::RTL_DIRECT_MISSION_LAND: + is_landing = _rtl_mission_type_handle->isLanding(); + break; + + case RtlType::RTL_DIRECT: + is_landing = _rtl_direct.isLanding(); + break; + + default: + break; + } + + return is_landing; +} + void RTL::setRtlTypeAndDestination() { diff --git a/src/modules/navigator/rtl.h b/src/modules/navigator/rtl.h index e7b720bd6152..4ef13cb7874d 100644 --- a/src/modules/navigator/rtl.h +++ b/src/modules/navigator/rtl.h @@ -89,6 +89,8 @@ class RTL : public NavigatorMode, public ModuleParams void updateSafePoints(uint32_t new_safe_point_id) { _initiate_safe_points_updated = true; _safe_points_id = new_safe_point_id; } + bool isLanding(); + private: enum class DestinationType { DESTINATION_TYPE_HOME, diff --git a/src/modules/navigator/rtl_direct.h b/src/modules/navigator/rtl_direct.h index 91e53dbe6b79..aed7cf3e4c6d 100644 --- a/src/modules/navigator/rtl_direct.h +++ b/src/modules/navigator/rtl_direct.h @@ -103,6 +103,8 @@ class RtlDirect : public MissionBlock, public ModuleParams void setRtlPosition(PositionYawSetpoint position, loiter_point_s loiter_pos); + bool isLanding() { return (_rtl_state != RTLState::IDLE) && (_rtl_state >= RTLState::LOITER_DOWN);}; + private: /** * @brief Return to launch state machine. diff --git a/src/modules/navigator/rtl_mission_fast_reverse.cpp b/src/modules/navigator/rtl_mission_fast_reverse.cpp index d7c42516e41d..d78f6c7fa627 100644 --- a/src/modules/navigator/rtl_mission_fast_reverse.cpp +++ b/src/modules/navigator/rtl_mission_fast_reverse.cpp @@ -60,6 +60,12 @@ void RtlMissionFastReverse::on_inactive() _mission.current_seq : -1; } +void RtlMissionFastReverse::on_inactivation() +{ + MissionBase::on_inactivation(); + _in_landing_phase = false; +} + void RtlMissionFastReverse::on_activation() { _home_pos_sub.update(); @@ -120,6 +126,7 @@ void RtlMissionFastReverse::setActiveMissionItems() _mission_item.nav_cmd == NAV_CMD_VTOL_TAKEOFF || num_found_items == 0) { handleLanding(new_work_item_type); + _in_landing_phase = true; } else { // convert mission item to a simple waypoint, keep loiter to alt @@ -131,6 +138,8 @@ void RtlMissionFastReverse::setActiveMissionItems() _mission_item.time_inside = 0.0f; pos_sp_triplet->previous = pos_sp_triplet->current; + + _in_landing_phase = false; } if (num_found_items > 0) { diff --git a/src/modules/navigator/rtl_mission_fast_reverse.h b/src/modules/navigator/rtl_mission_fast_reverse.h index f1301a5ccafd..168d20c2e341 100644 --- a/src/modules/navigator/rtl_mission_fast_reverse.h +++ b/src/modules/navigator/rtl_mission_fast_reverse.h @@ -58,6 +58,9 @@ class RtlMissionFastReverse : public RtlBase void on_activation() override; void on_active() override; void on_inactive() override; + void on_inactivation() override; + + bool isLanding() override {return _in_landing_phase;}; rtl_time_estimate_s calc_rtl_time_estimate() override; @@ -68,5 +71,7 @@ class RtlMissionFastReverse : public RtlBase int _mission_index_prior_rtl{-1}; + bool _in_landing_phase{false}; + uORB::SubscriptionData _home_pos_sub{ORB_ID(home_position)}; /**< home position subscription */ }; From 82a7d0410cdca5be4c324c57be8c9edaf50fcffd Mon Sep 17 00:00:00 2001 From: Konrad Date: Wed, 11 Sep 2024 18:10:52 +0200 Subject: [PATCH 35/40] DistanceSensorModeChangeRequest: renaming of variable --- msg/DistanceSensorModeChangeRequest.msg | 6 +++--- .../lightware_laser_i2c.cpp | 8 ++++---- src/modules/navigator/navigator_main.cpp | 18 +++++++++--------- 3 files changed, 16 insertions(+), 16 deletions(-) diff --git a/msg/DistanceSensorModeChangeRequest.msg b/msg/DistanceSensorModeChangeRequest.msg index 294e225e354f..01d5a49cd330 100644 --- a/msg/DistanceSensorModeChangeRequest.msg +++ b/msg/DistanceSensorModeChangeRequest.msg @@ -1,5 +1,5 @@ uint64 timestamp # time since system start (microseconds) -uint8 req_mode # requested mode of operation -uint8 MODE_DISABLED = 0 -uint8 MODE_ENABLED = 1 +uint8 request_on_off # request to disable/enable the distance sensor +uint8 REQUEST_OFF = 0 +uint8 REQUEST_ON = 1 diff --git a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp index 152073f2ac5c..614d408a5e30 100644 --- a/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp +++ b/src/drivers/distance_sensor/lightware_laser_i2c/lightware_laser_i2c.cpp @@ -145,7 +145,7 @@ class LightwareLaser : public device::I2C, public I2CSPIDriver, uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; typeof(px4::msg::VehicleStatus::vehicle_type) _vehicle_type{px4::msg::VehicleStatus::VEHICLE_TYPE_UNKNOWN}; uORB::Subscription _dist_sense_mode_change_sub{ORB_ID(distance_sensor_mode_change_request)}; - typeof(px4::msg::DistanceSensorModeChangeRequest::req_mode) _req_mode{px4::msg::DistanceSensorModeChangeRequest::MODE_DISABLED}; + typeof(px4::msg::DistanceSensorModeChangeRequest::request_on_off) _req_mode{px4::msg::DistanceSensorModeChangeRequest::REQUEST_OFF}; bool _restriction{false}; bool _auto_restriction{false}; bool _prev_restriction{false}; @@ -419,10 +419,10 @@ int LightwareLaser::updateRestriction() distance_sensor_mode_change_request_s dist_sense_mode_change; if (_dist_sense_mode_change_sub.copy(&dist_sense_mode_change)) { - _req_mode = dist_sense_mode_change.req_mode; + _req_mode = dist_sense_mode_change.request_on_off; } else { - _req_mode = distance_sensor_mode_change_request_s::MODE_DISABLED; + _req_mode = distance_sensor_mode_change_request_s::REQUEST_OFF; } } @@ -466,7 +466,7 @@ int LightwareLaser::updateRestriction() break; case 2: - _restriction = _auto_restriction && _req_mode != distance_sensor_mode_change_request_s::MODE_ENABLED; + _restriction = _auto_restriction && _req_mode != distance_sensor_mode_change_request_s::REQUEST_ON; break; } diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index e46decdfb19a..cd73e7e7d37c 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -112,7 +112,7 @@ Navigator::Navigator() : _distance_sensor_mode_change_request_pub.advertise(); _distance_sensor_mode_change_request_pub.get().timestamp = hrt_absolute_time(); - _distance_sensor_mode_change_request_pub.get().req_mode = distance_sensor_mode_change_request_s::MODE_DISABLED; + _distance_sensor_mode_change_request_pub.get().request_on_off = distance_sensor_mode_change_request_s::REQUEST_OFF; _distance_sensor_mode_change_request_pub.update(); // Update the timeout used in mission_block (which can't hold it's own parameters) @@ -1459,21 +1459,21 @@ void Navigator::publish_distance_sensor_mode_request() // Send request to enable distance sensor when in the landing phase of a mission or RTL if (((_navigation_mode == &_rtl) && _rtl.isLanding()) || ((_navigation_mode == &_mission) && _mission.isLanding())) { - if (_distance_sensor_mode_change_request_pub.get().req_mode != - distance_sensor_mode_change_request_s::MODE_ENABLED) { + if (_distance_sensor_mode_change_request_pub.get().request_on_off != + distance_sensor_mode_change_request_s::REQUEST_ON) { _distance_sensor_mode_change_request_pub.get().timestamp = hrt_absolute_time(); - _distance_sensor_mode_change_request_pub.get().req_mode = - distance_sensor_mode_change_request_s::MODE_ENABLED; + _distance_sensor_mode_change_request_pub.get().request_on_off = + distance_sensor_mode_change_request_s::REQUEST_ON; _distance_sensor_mode_change_request_pub.update(); } - } else if (_distance_sensor_mode_change_request_pub.get().req_mode != - distance_sensor_mode_change_request_s::MODE_DISABLED) { + } else if (_distance_sensor_mode_change_request_pub.get().request_on_off != + distance_sensor_mode_change_request_s::REQUEST_OFF) { _distance_sensor_mode_change_request_pub.get().timestamp = hrt_absolute_time(); - _distance_sensor_mode_change_request_pub.get().req_mode = - distance_sensor_mode_change_request_s::MODE_DISABLED; + _distance_sensor_mode_change_request_pub.get().request_on_off = + distance_sensor_mode_change_request_s::REQUEST_OFF; _distance_sensor_mode_change_request_pub.update(); } } From 1c9c5e51c2b34f8cad4e19b9bed63191d2fe3686 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Fri, 13 Sep 2024 14:13:36 +0200 Subject: [PATCH 36/40] boards: cuav x7pro: remove build of ROVER and Q_ATTITUDE_ESTIMATOR to save flash Signed-off-by: Silvan Fuhrer --- boards/cuav/x7pro/default.px4board | 2 -- 1 file changed, 2 deletions(-) diff --git a/boards/cuav/x7pro/default.px4board b/boards/cuav/x7pro/default.px4board index 4ba4d4a17754..c7c30b1a1ed2 100644 --- a/boards/cuav/x7pro/default.px4board +++ b/boards/cuav/x7pro/default.px4board @@ -39,7 +39,6 @@ CONFIG_DRIVERS_TONE_ALARM=y CONFIG_DRIVERS_UAVCAN=y CONFIG_BOARD_UAVCAN_TIMER_OVERRIDE=2 CONFIG_MODULES_AIRSPEED_SELECTOR=y -CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=y CONFIG_MODULES_BATTERY_STATUS=y CONFIG_MODULES_CAMERA_FEEDBACK=y CONFIG_MODULES_COMMANDER=y @@ -70,7 +69,6 @@ CONFIG_MODULES_MC_POS_CONTROL=y CONFIG_MODULES_MC_RATE_CONTROL=y CONFIG_MODULES_NAVIGATOR=y CONFIG_MODULES_RC_UPDATE=y -CONFIG_MODULES_ROVER_POS_CONTROL=y CONFIG_MODULES_SENSORS=y CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y CONFIG_MODULES_TEMPERATURE_COMPENSATION=y From 81747f35bb153cf3bae553d147e8d22c06ff2970 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Fri, 13 Sep 2024 15:11:56 +0200 Subject: [PATCH 37/40] rover: add descend navigation state to land detection --- src/modules/land_detector/RoverLandDetector.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/src/modules/land_detector/RoverLandDetector.cpp b/src/modules/land_detector/RoverLandDetector.cpp index 2011419db8c3..8e59c0c5d296 100644 --- a/src/modules/land_detector/RoverLandDetector.cpp +++ b/src/modules/land_detector/RoverLandDetector.cpp @@ -55,12 +55,13 @@ bool RoverLandDetector::_get_landed_state() const float distance_to_home = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), _home_position(0), _home_position(1)); - if (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND) { + if (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND + || _vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_DESCEND) { return true; // If Landing has been requested then say we have landed. } else if (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL && distance_to_home < _param_nav_acc_rad.get() && _param_rtl_land_delay.get() > -FLT_EPSILON) { - return true; // If the rover reaches the home position during RTL we say we have landed + return true; // If the rover reaches the home position during RTL we say we have landed. } else { return !_armed; // If we are armed we are not landed. From 2fd4150b389b0bac3812d577be0db70b3360587f Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Mon, 16 Sep 2024 12:09:51 +0200 Subject: [PATCH 38/40] differential: Add stabilized and position mode (#23669) * differential: add position and stabilized mode * differential: add hardcoded stick input deadzones --- .../init.d-posix/airframes/4009_gz_r1_rover | 1 + .../airframes/50001_aion_robotics_r1_rover | 1 + src/lib/pure_pursuit/PurePursuit.cpp | 16 ++-- src/lib/pure_pursuit/PurePursuit.hpp | 6 +- .../rover_differential/RoverDifferential.cpp | 92 ++++++++++++++++++- .../rover_differential/RoverDifferential.hpp | 15 ++- .../RoverDifferentialGuidance.cpp | 2 +- .../RoverDifferentialGuidance.hpp | 1 + src/modules/rover_differential/module.yaml | 16 +++- 9 files changed, 136 insertions(+), 14 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover b/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover index 4bf8815520af..b41d61355c35 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4009_gz_r1_rover @@ -21,6 +21,7 @@ param set-default RD_YAW_RATE_P 0.1 param set-default RD_YAW_RATE_I 0 param set-default RD_YAW_P 5 param set-default RD_YAW_I 0 +param set-default RD_MAX_SPEED 5 param set-default RD_MAX_THR_SPD 7 param set-default RD_SPEED_P 1 param set-default RD_SPEED_I 0 diff --git a/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover b/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover index d00063c573c3..901127f09bd2 100644 --- a/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover +++ b/ROMFS/px4fmu_common/init.d/airframes/50001_aion_robotics_r1_rover @@ -31,6 +31,7 @@ param set-default RD_YAW_RATE_P 0.1 param set-default RD_YAW_RATE_I 0 param set-default RD_YAW_P 5 param set-default RD_YAW_I 0 +param set-default RD_MAX_SPEED 1.8 param set-default RD_MAX_THR_SPD 2 param set-default RD_SPEED_P 0.5 param set-default RD_SPEED_I 0.1 diff --git a/src/lib/pure_pursuit/PurePursuit.cpp b/src/lib/pure_pursuit/PurePursuit.cpp index 324a504959ba..e28e7b0924a8 100644 --- a/src/lib/pure_pursuit/PurePursuit.cpp +++ b/src/lib/pure_pursuit/PurePursuit.cpp @@ -78,18 +78,16 @@ float PurePursuit::calcDesiredHeading(const Vector2f &curr_wp_ned, const Vector2 const Vector2f prev_wp_to_curr_pos = curr_pos_ned - prev_wp_ned; const Vector2f prev_wp_to_curr_wp_u = prev_wp_to_curr_wp.unit_or_zero(); - const Vector2f distance_on_line_segment = (prev_wp_to_curr_pos * prev_wp_to_curr_wp_u) * - prev_wp_to_curr_wp_u; // Projection of prev_wp_to_curr_pos onto prev_wp_to_curr_wp - const Vector2f curr_pos_to_path = distance_on_line_segment - - prev_wp_to_curr_pos; // Shortest vector from the current position to the path + _distance_on_line_segment = (prev_wp_to_curr_pos * prev_wp_to_curr_wp_u) * prev_wp_to_curr_wp_u; + _curr_pos_to_path = _distance_on_line_segment - prev_wp_to_curr_pos; - if (curr_pos_to_path.norm() > _lookahead_distance) { // Target closest point on path if there is no intersection point - return atan2f(curr_pos_to_path(1), curr_pos_to_path(0)); + if (_curr_pos_to_path.norm() > _lookahead_distance) { // Target closest point on path if there is no intersection point + return atan2f(_curr_pos_to_path(1), _curr_pos_to_path(0)); } - const float line_extension = sqrt(powf(_lookahead_distance, 2.f) - powf(curr_pos_to_path.norm(), - 2.f)); // Length of the vector from the endpoint of distance_on_line_segment to the intersection point - const Vector2f prev_wp_to_intersection_point = distance_on_line_segment + line_extension * + const float line_extension = sqrt(powf(_lookahead_distance, 2.f) - powf(_curr_pos_to_path.norm(), + 2.f)); // Length of the vector from the endpoint of _distance_on_line_segment to the intersection point + const Vector2f prev_wp_to_intersection_point = _distance_on_line_segment + line_extension * prev_wp_to_curr_wp_u; const Vector2f curr_pos_to_intersection_point = prev_wp_to_intersection_point - prev_wp_to_curr_pos; return atan2f(curr_pos_to_intersection_point(1), curr_pos_to_intersection_point(0)); diff --git a/src/lib/pure_pursuit/PurePursuit.hpp b/src/lib/pure_pursuit/PurePursuit.hpp index 9de498c2e1b1..5740d0184c7a 100644 --- a/src/lib/pure_pursuit/PurePursuit.hpp +++ b/src/lib/pure_pursuit/PurePursuit.hpp @@ -103,6 +103,8 @@ class PurePursuit : public ModuleParams float vehicle_speed); float getLookaheadDistance() {return _lookahead_distance;}; + float getCrosstrackError() {return _curr_pos_to_path.norm();}; + float getDistanceOnLineSegment() {return _distance_on_line_segment.norm();}; protected: /** @@ -122,5 +124,7 @@ class PurePursuit : public ModuleParams float lookahead_min{1.f}; } _params{}; private: - float _lookahead_distance{0.f}; + float _lookahead_distance{0.f}; // Radius of the circle around the vehicle + Vector2f _distance_on_line_segment{}; // Projection of prev_wp_to_curr_pos onto prev_wp_to_curr_wp + Vector2f _curr_pos_to_path{}; // Shortest vector from the current position to the path }; diff --git a/src/modules/rover_differential/RoverDifferential.cpp b/src/modules/rover_differential/RoverDifferential.cpp index 411c5c4b5559..a7a9e82d0217 100644 --- a/src/modules/rover_differential/RoverDifferential.cpp +++ b/src/modules/rover_differential/RoverDifferential.cpp @@ -99,12 +99,94 @@ void RoverDifferential::Run() } break; + case vehicle_status_s::NAVIGATION_STATE_STAB: { + manual_control_setpoint_s manual_control_setpoint{}; + + if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { + rover_differential_setpoint_s rover_differential_setpoint{}; + rover_differential_setpoint.timestamp = timestamp; + rover_differential_setpoint.forward_speed_setpoint = NAN; + rover_differential_setpoint.forward_speed_setpoint_normalized = manual_control_setpoint.throttle; + rover_differential_setpoint.yaw_rate_setpoint = math::interpolate(math::deadzone(manual_control_setpoint.roll, + STICK_DEADZONE), -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate); + rover_differential_setpoint.yaw_rate_setpoint_normalized = NAN; + rover_differential_setpoint.yaw_setpoint = NAN; + + if (fabsf(rover_differential_setpoint.yaw_rate_setpoint) > FLT_EPSILON + || fabsf(rover_differential_setpoint.forward_speed_setpoint_normalized) < FLT_EPSILON) { // Closed loop yaw rate control + _yaw_ctl = false; + + + } else { // Closed loop yaw control if the yaw rate input is zero (keep current yaw) + if (!_yaw_ctl) { + _stab_desired_yaw = _vehicle_yaw; + _yaw_ctl = true; + } + + rover_differential_setpoint.yaw_setpoint = _stab_desired_yaw; + rover_differential_setpoint.yaw_rate_setpoint = NAN; + + } + + _rover_differential_setpoint_pub.publish(rover_differential_setpoint); + } + + } break; + + case vehicle_status_s::NAVIGATION_STATE_POSCTL: { + manual_control_setpoint_s manual_control_setpoint{}; + + if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { + rover_differential_setpoint_s rover_differential_setpoint{}; + rover_differential_setpoint.timestamp = timestamp; + rover_differential_setpoint.forward_speed_setpoint = math::interpolate(manual_control_setpoint.throttle, + -1.f, 1.f, -_param_rd_max_speed.get(), _param_rd_max_speed.get()); + rover_differential_setpoint.forward_speed_setpoint_normalized = NAN; + rover_differential_setpoint.yaw_rate_setpoint = math::interpolate(math::deadzone(manual_control_setpoint.roll, + STICK_DEADZONE), -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate); + rover_differential_setpoint.yaw_rate_setpoint_normalized = NAN; + rover_differential_setpoint.yaw_setpoint = NAN; + + if (fabsf(rover_differential_setpoint.yaw_rate_setpoint) > FLT_EPSILON + || fabsf(rover_differential_setpoint.forward_speed_setpoint) < FLT_EPSILON) { // Closed loop yaw rate control + _yaw_ctl = false; + + + } else { // Course control if the yaw rate input is zero (keep driving on a straight line) + if (!_yaw_ctl) { + _pos_ctl_course_direction = Vector2f(cos(_vehicle_yaw), sin(_vehicle_yaw)); + _pos_ctl_start_position_ned = _curr_pos_ned; + _yaw_ctl = true; + } + + // Construct a 'target waypoint' for course control s.t. it is never within the maximum lookahead of the rover + const float vector_scaling = sqrtf(powf(_param_pp_lookahd_max.get(), + 2) + powf(_posctl_pure_pursuit.getCrosstrackError(), 2)) + _posctl_pure_pursuit.getDistanceOnLineSegment(); + const Vector2f target_waypoint_ned = _pos_ctl_start_position_ned + sign( + rover_differential_setpoint.forward_speed_setpoint) * + vector_scaling * _pos_ctl_course_direction; + // Calculate yaw setpoint + const float yaw_setpoint = _posctl_pure_pursuit.calcDesiredHeading(target_waypoint_ned, + _pos_ctl_start_position_ned, _curr_pos_ned, fabsf(_vehicle_forward_speed)); + rover_differential_setpoint.yaw_setpoint = sign(rover_differential_setpoint.forward_speed_setpoint) >= 0 ? + yaw_setpoint : matrix::wrap_pi(M_PI_F + yaw_setpoint); // Flip yaw setpoint when driving backwards + rover_differential_setpoint.yaw_rate_setpoint = NAN; + + } + + _rover_differential_setpoint_pub.publish(rover_differential_setpoint); + } + + } break; + case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL: _rover_differential_guidance.computeGuidance(_vehicle_yaw, _vehicle_forward_speed, _nav_state); break; default: // Unimplemented nav states will stop the rover + _rover_differential_control.resetControllers(); + _yaw_ctl = false; rover_differential_setpoint_s rover_differential_setpoint{}; rover_differential_setpoint.forward_speed_setpoint = NAN; rover_differential_setpoint.forward_speed_setpoint_normalized = 0.f; @@ -115,8 +197,9 @@ void RoverDifferential::Run() break; } - if (!_armed) { // Reset on disarm + if (!_armed) { // Reset when disarmed _rover_differential_control.resetControllers(); + _yaw_ctl = false; } _rover_differential_control.computeMotorCommands(_vehicle_yaw, _vehicle_yaw_rate, _vehicle_forward_speed); @@ -135,6 +218,12 @@ void RoverDifferential::updateSubscriptions() if (_vehicle_status_sub.updated()) { vehicle_status_s vehicle_status{}; _vehicle_status_sub.copy(&vehicle_status); + + if (vehicle_status.nav_state != _nav_state) { // Reset on mode change + _rover_differential_control.resetControllers(); + _yaw_ctl = false; + } + _nav_state = vehicle_status.nav_state; _armed = vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED; } @@ -155,6 +244,7 @@ void RoverDifferential::updateSubscriptions() if (_vehicle_local_position_sub.updated()) { vehicle_local_position_s vehicle_local_position{}; _vehicle_local_position_sub.copy(&vehicle_local_position); + _curr_pos_ned = Vector2f(vehicle_local_position.x, vehicle_local_position.y); Vector3f velocity_in_local_frame(vehicle_local_position.vx, vehicle_local_position.vy, vehicle_local_position.vz); Vector3f velocity_in_body_frame = _vehicle_attitude_quaternion.rotateVectorInverse(velocity_in_local_frame); _vehicle_forward_speed = fabsf(velocity_in_body_frame(0)) > SPEED_THRESHOLD ? velocity_in_body_frame(0) : 0.f; diff --git a/src/modules/rover_differential/RoverDifferential.hpp b/src/modules/rover_differential/RoverDifferential.hpp index eee464ede127..ad238aa428dc 100644 --- a/src/modules/rover_differential/RoverDifferential.hpp +++ b/src/modules/rover_differential/RoverDifferential.hpp @@ -39,6 +39,7 @@ #include #include #include +#include // uORB includes #include @@ -103,8 +104,10 @@ class RoverDifferential : public ModuleBase, public ModulePar // Instances RoverDifferentialGuidance _rover_differential_guidance{this}; RoverDifferentialControl _rover_differential_control{this}; + PurePursuit _posctl_pure_pursuit{this}; // Pure pursuit library // Variables + Vector2f _curr_pos_ned{}; matrix::Quatf _vehicle_attitude_quaternion{}; float _vehicle_yaw_rate{0.f}; float _vehicle_forward_speed{0.f}; @@ -112,6 +115,10 @@ class RoverDifferential : public ModuleBase, public ModulePar float _max_yaw_rate{0.f}; int _nav_state{0}; bool _armed{false}; + bool _yaw_ctl{false}; // Indicates if the rover is doing yaw or yaw rate control in Stabilized and Position mode + float _stab_desired_yaw{0.f}; // Yaw setpoint for Stabilized mode + Vector2f _pos_ctl_course_direction{}; // Course direction for Position mode + Vector2f _pos_ctl_start_position_ned{}; // Initial rover position for course control in Position mode // Thresholds to avoid moving at rest due to measurement noise static constexpr float YAW_RATE_THRESHOLD = @@ -119,8 +126,14 @@ class RoverDifferential : public ModuleBase, public ModulePar static constexpr float SPEED_THRESHOLD = 0.1f; // [m/s] The minimum threshold for the speed measurement not to be interpreted as zero + // Stick input deadzone + static constexpr float STICK_DEADZONE = + 0.1f; // [0, 1] Percentage of stick input range that will be interpreted as zero around the stick centered value + DEFINE_PARAMETERS( (ParamFloat) _param_rd_man_yaw_scale, - (ParamFloat) _param_rd_max_yaw_rate + (ParamFloat) _param_rd_max_yaw_rate, + (ParamFloat) _param_rd_max_speed, + (ParamFloat) _param_pp_lookahd_max ) }; diff --git a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp index c56830ad08a2..848a7f513acf 100644 --- a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp +++ b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp @@ -216,7 +216,7 @@ void RoverDifferentialGuidance::updateWaypoints() // Waypoint cruising speed if (position_setpoint_triplet.current.cruising_speed > 0.f) { - _max_forward_speed = position_setpoint_triplet.current.cruising_speed; + _max_forward_speed = math::constrain(position_setpoint_triplet.current.cruising_speed, 0.f, _param_rd_max_speed.get()); } else { _max_forward_speed = _param_rd_miss_spd_def.get(); diff --git a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp index d2b9862b2cc0..4b3815247e59 100644 --- a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp +++ b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp @@ -143,6 +143,7 @@ class RoverDifferentialGuidance : public ModuleParams (ParamFloat) _param_nav_acc_rad, (ParamFloat) _param_rd_max_jerk, (ParamFloat) _param_rd_max_accel, + (ParamFloat) _param_rd_max_speed, (ParamFloat) _param_rd_miss_spd_def, (ParamFloat) _param_rd_trans_trn_drv, (ParamFloat) _param_rd_trans_drv_trn diff --git a/src/modules/rover_differential/module.yaml b/src/modules/rover_differential/module.yaml index 8ef9f62f5e30..3bad343f2e8b 100644 --- a/src/modules/rover_differential/module.yaml +++ b/src/modules/rover_differential/module.yaml @@ -113,6 +113,19 @@ parameters: decimal: 2 default: 0.5 + RD_MAX_SPEED: + description: + short: Maximum speed setpoint + long: | + This parameter is used to cap desired forward speed and map controller inputs to desired speeds in Position mode. + type: float + unit: m/s + min: 0 + max: 100 + increment: 0.01 + decimal: 2 + default: 1 + RD_MAX_THR_SPD: description: short: Speed the rover drives at maximum throttle @@ -133,7 +146,8 @@ parameters: description: short: Maximum allowed yaw rate for the rover long: | - This parameter is used to cap desired yaw rates and map controller inputs to desired yaw rates in acro mode. + This parameter is used to cap desired yaw rates and map controller inputs to desired yaw rates + in Acro,Stabilized and Position mode. type: float unit: deg/s min: 0.01 From 8aece9bff21c0d830c7dfeae6921095a619d5997 Mon Sep 17 00:00:00 2001 From: chfriedrich98 Date: Tue, 17 Sep 2024 16:58:46 +0200 Subject: [PATCH 39/40] differential: fix CI issue --- .../rover_differential/RoverDifferential.hpp | 18 ++++++++---------- 1 file changed, 8 insertions(+), 10 deletions(-) diff --git a/src/modules/rover_differential/RoverDifferential.hpp b/src/modules/rover_differential/RoverDifferential.hpp index ad238aa428dc..8d83519410ad 100644 --- a/src/modules/rover_differential/RoverDifferential.hpp +++ b/src/modules/rover_differential/RoverDifferential.hpp @@ -61,6 +61,14 @@ using namespace time_literals; +// Constants +static constexpr float STICK_DEADZONE = + 0.1f; // [0, 1] Percentage of stick input range that will be interpreted as zero around the stick centered value +static constexpr float YAW_RATE_THRESHOLD = + 0.02f; // [rad/s] The minimum threshold for the yaw rate measurement not to be interpreted as zero +static constexpr float SPEED_THRESHOLD = + 0.1f; // [m/s] The minimum threshold for the speed measurement not to be interpreted as zero + class RoverDifferential : public ModuleBase, public ModuleParams, public px4::ScheduledWorkItem { @@ -120,16 +128,6 @@ class RoverDifferential : public ModuleBase, public ModulePar Vector2f _pos_ctl_course_direction{}; // Course direction for Position mode Vector2f _pos_ctl_start_position_ned{}; // Initial rover position for course control in Position mode - // Thresholds to avoid moving at rest due to measurement noise - static constexpr float YAW_RATE_THRESHOLD = - 0.02f; // [rad/s] The minimum threshold for the yaw rate measurement not to be interpreted as zero - static constexpr float SPEED_THRESHOLD = - 0.1f; // [m/s] The minimum threshold for the speed measurement not to be interpreted as zero - - // Stick input deadzone - static constexpr float STICK_DEADZONE = - 0.1f; // [0, 1] Percentage of stick input range that will be interpreted as zero around the stick centered value - DEFINE_PARAMETERS( (ParamFloat) _param_rd_man_yaw_scale, (ParamFloat) _param_rd_max_yaw_rate, From 4a99a51fb19de668a9d56bc0cb9fd506bc0ff227 Mon Sep 17 00:00:00 2001 From: Marco Hauswirth Date: Fri, 13 Sep 2024 13:55:38 +0200 Subject: [PATCH 40/40] update upload-artifact v2->v4 --- .github/workflows/mavros_mission_tests.yml | 8 ++++---- .github/workflows/mavros_offboard_tests.yml | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/.github/workflows/mavros_mission_tests.yml b/.github/workflows/mavros_mission_tests.yml index a90d51804ef5..7cd95e207744 100644 --- a/.github/workflows/mavros_mission_tests.yml +++ b/.github/workflows/mavros_mission_tests.yml @@ -88,7 +88,7 @@ jobs: run: gdb build/px4_sitl_default/bin/px4 px4.core -ex "thread apply all bt" -ex "quit" - name: Upload px4 coredump if: failure() - uses: actions/upload-artifact@v2-preview + uses: actions/upload-artifact@v4 with: name: coredump path: px4.core @@ -103,21 +103,21 @@ jobs: - name: Upload px4 binary if: failure() - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v4 with: name: binary path: build/px4_sitl_default/bin/px4 - name: Store PX4 log if: failure() - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v4 with: name: px4_log path: ~/.ros/log/*/*.ulg - name: Store ROS log if: failure() - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v4 with: name: ros_log path: ~/.ros/**/rostest-*.log diff --git a/.github/workflows/mavros_offboard_tests.yml b/.github/workflows/mavros_offboard_tests.yml index 020caaa2d048..2305b8da13ab 100644 --- a/.github/workflows/mavros_offboard_tests.yml +++ b/.github/workflows/mavros_offboard_tests.yml @@ -83,7 +83,7 @@ jobs: run: gdb build/px4_sitl_default/bin/px4 px4.core -ex "thread apply all bt" -ex "quit" - name: Upload px4 coredump if: failure() - uses: actions/upload-artifact@v2-preview + uses: actions/upload-artifact@v4 with: name: coredump path: px4.core @@ -98,21 +98,21 @@ jobs: - name: Upload px4 binary if: failure() - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v4 with: name: binary path: build/px4_sitl_default/bin/px4 - name: Store PX4 log if: failure() - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v4 with: name: px4_log path: ~/.ros/log/*/*.ulg - name: Store ROS log if: failure() - uses: actions/upload-artifact@v2 + uses: actions/upload-artifact@v4 with: name: ros_log path: ~/.ros/**/rostest-*.log