From b2f663648e9858c0f63e50a87faa347431a12e8c Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 21 Aug 2024 07:56:37 -0700 Subject: [PATCH 01/87] ci: github actions runs-on Dronecode AWS Infra * ci: try runs-on Dronecode Infra * ci: comment on how to disable RunsOn * Update .github/workflows/build_all_targets.yml --- .github/workflows/build_all_targets.yml | 11 +++++++++-- 1 file changed, 9 insertions(+), 2 deletions(-) diff --git a/.github/workflows/build_all_targets.yml b/.github/workflows/build_all_targets.yml index 119236b3198e..0aa6ce92e592 100644 --- a/.github/workflows/build_all_targets.yml +++ b/.github/workflows/build_all_targets.yml @@ -1,3 +1,8 @@ +# NOTE: this workflow is now running on Dronecode / PX4 AWS account. +# - If you want to keep the tests running in GitHub Actions you need to uncomment the "runs-on: ubuntu-latest" lines +# and comment the "runs-on: [runs-on,runner=..." lines. +# - If you would like to duplicate this setup try setting up "RunsOn" on your own AWS account try https://runs-on.com + name: Build all targets on: @@ -14,7 +19,8 @@ on: jobs: group_targets: name: Scan for Board Targets - runs-on: ubuntu-latest + # runs-on: ubuntu-latest + runs-on: [runs-on,runner=1cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}"] outputs: matrix: ${{ steps.set-matrix.outputs.matrix }} timestamp: ${{ steps.set-timestamp.outputs.timestamp }} @@ -34,7 +40,8 @@ jobs: setup: name: ${{ matrix.group }} - runs-on: ubuntu-latest + # runs-on: ubuntu-latest + runs-on: [runs-on,runner=8cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}"] needs: group_targets strategy: matrix: ${{ fromJson(needs.group_targets.outputs.matrix) }} From ae165561076541efd2db00b28a05ad42c190b9ff Mon Sep 17 00:00:00 2001 From: Jaeyoung Lim Date: Wed, 21 Aug 2024 17:41:47 +0200 Subject: [PATCH 02/87] simulation/gz_bridge: follow model in gz GUI (#22808) --- src/modules/simulation/gz_bridge/GZBridge.cpp | 118 ++++++++++++++++-- src/modules/simulation/gz_bridge/GZBridge.hpp | 41 ++++++ 2 files changed, 151 insertions(+), 8 deletions(-) diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 3464c628694c..f7d80d32cac6 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -150,16 +150,31 @@ int GZBridge::init() // If PX4_GZ_STANDALONE has been set, you can try to connect but GZ_SIM_RESOURCE_PATH needs to be set correctly to work. else { - if (_node.Request(create_service, req, 1000, rep, result)) { - if (!rep.data() || !result) { - PX4_ERR("EntityFactory service call failed."); - return PX4_ERROR; - } - - } else { - PX4_ERR("Service call timed out. Check GZ_SIM_RESOURCE_PATH is set correctly."); + if (!callEntityFactoryService(create_service, req)) { return PX4_ERROR; } + + std::string scene_info_service = "/world/default/scene/info"; + bool scene_created = false; + + while (scene_created == false) { + if (!callSceneInfoMsgService(scene_info_service)) { + PX4_WARN("Service call timed out as Gazebo has not been detected."); + system_usleep(2000000); + + } else { + scene_created = true; + } + } + + gz::msgs::StringMsg follow_msg{}; + follow_msg.set_data(_model_name); + bool call_string_service = callStringMsgService("/gui/follow", follow_msg); + gz::msgs::Vector3d follow_offset_msg{}; + follow_offset_msg.set_x(-2.0); + follow_offset_msg.set_y(-2.0); + follow_offset_msg.set_z(2.0); + callVector3dService("/gui/follow/offset", follow_offset_msg); } } @@ -829,6 +844,93 @@ void GZBridge::laserScanCallback(const gz::msgs::LaserScan &scan) _obstacle_distance_pub.publish(obs); } +bool GZBridge::callEntityFactoryService(const std::string &service, const gz::msgs::EntityFactory &req) +{ + bool result; + gz::msgs::Boolean rep; + + if (_node.Request(service, req, 1000, rep, result)) { + if (!rep.data() || !result) { + PX4_ERR("EntityFactory service call failed."); + return false; + } + + } else { + PX4_ERR("Service call timed out. Check GZ_SIM_RESOURCE_PATH is set correctly."); + return false; + } + + return true; +} + +bool GZBridge::callSceneInfoMsgService(const std::string &service) +{ + bool result; + gz::msgs::Empty req; + gz::msgs::Scene rep; + + if (_node.Request(service, req, 1000, rep, result)) { + if (!result) { + PX4_ERR("Scene Info service call failed."); + return false; + + } else { + return true; + } + + } else { + PX4_ERR("Service call timed out. Check GZ_SIM_RESOURCE_PATH is set correctly."); + return false; + } + + return true; +} + +bool GZBridge::callStringMsgService(const std::string &service, const gz::msgs::StringMsg &req) +{ + bool result; + + gz::msgs::Boolean rep; + + if (_node.Request(service, req, 1000, rep, result)) { + if (!rep.data() || !result) { + PX4_ERR("String service call failed"); + return false; + + } + } + + else { + PX4_ERR("Service call timed out: %s", service.c_str()); + return false; + } + + return true; +} + +bool GZBridge::callVector3dService(const std::string &service, const gz::msgs::Vector3d &req) +{ + bool result; + + gz::msgs::Boolean rep; + + if (_node.Request(service, req, 1000, rep, result)) { + if (!rep.data() || !result) { + PX4_ERR("String service call failed"); + return false; + + } + } + + else { + PX4_ERR("Service call timed out: %s", service.c_str()); + return false; + } + + return true; +} + + void GZBridge::rotateQuaternion(gz::math::Quaterniond &q_FRD_to_NED, const gz::math::Quaterniond q_FLU_to_ENU) { // FLU (ROS) to FRD (PX4) static rotation diff --git a/src/modules/simulation/gz_bridge/GZBridge.hpp b/src/modules/simulation/gz_bridge/GZBridge.hpp index 8a832f7961b2..fc2cb3a6e9ad 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.hpp +++ b/src/modules/simulation/gz_bridge/GZBridge.hpp @@ -69,6 +69,8 @@ #include #include #include +#include +#include using namespace time_literals; @@ -110,6 +112,45 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S void navSatCallback(const gz::msgs::NavSat &nav_sat); void laserScanCallback(const gz::msgs::LaserScan &scan); + /** + * @brief Call Entityfactory service + * + * @param req + * @return true + * @return false + */ + bool callEntityFactoryService(const std::string &service, const gz::msgs::EntityFactory &req); + + + /** + * @brief Call scene info service + * + * @param service + * @param req + * @return true + * @return false + */ + bool callSceneInfoMsgService(const std::string &service); + + /** + * @brief Call String service + * + * @param service + * @param req + * @return true + * @return false + */ + bool callStringMsgService(const std::string &service, const gz::msgs::StringMsg &req); + + /** + * @brief Call Vector3d Service + * + * @param service + * @param req + * @return true + * @return false + */ + bool callVector3dService(const std::string &service, const gz::msgs::Vector3d &req); /** * * Convert a quaterion from FLU_to_ENU frames (ROS convention) From b33b0398ddb97b0ba3295cf57a8d90d6e6de69fa Mon Sep 17 00:00:00 2001 From: jmackay2 <1.732mackay@gmail.com> Date: Wed, 21 Aug 2024 20:30:10 -0400 Subject: [PATCH 03/87] Fix param typo in quadtailsitter airframe (#23588) --- .../init.d-posix/airframes/1045_gazebo-classic_quadtailsitter | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter index 87afb523b1a7..9539ba6d7402 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/1045_gazebo-classic_quadtailsitter @@ -33,7 +33,7 @@ param set-default PWM_MAIN_FUNC3 103 param set-default PWM_MAIN_FUNC4 104 param set-default PWM_MAIN_FUNC5 0 -parm set-default FD_FAIL_R 70 +param set-default FD_FAIL_R 70 param set-default FW_P_TC 0.6 From 02ed1162ed42b2d85d5b51da37989e268e2a1321 Mon Sep 17 00:00:00 2001 From: ZeroOne-Aero Date: Thu, 22 Aug 2024 16:02:02 +0800 Subject: [PATCH 04/87] Update pab_manifest.c (#23594) * Update pab_manifest.c I have rebased on main and squash my commits into 1. * Update pab_manifest.c I have updated pab_manifest.c: // BASE ID 0x150 ZeroOne Pixhawk Baseboard Alaised to ID 0 {HW_BASE_ID(0x150), base_configuration_0, arraySize(base_configuration_0)}, // ZeroOne Pixhawk Baseboard ver 0x150 --- platforms/common/pab_manifest.c | 2 ++ 1 file changed, 2 insertions(+) diff --git a/platforms/common/pab_manifest.c b/platforms/common/pab_manifest.c index 05cfa809969d..5750846672d4 100644 --- a/platforms/common/pab_manifest.c +++ b/platforms/common/pab_manifest.c @@ -357,6 +357,7 @@ static const px4_hw_mft_item_t base_configuration_17[] = { }; // BASE ID 0x100 Holybro Pixhawk Jetson Baseboard Alaised to ID 0 +// BASE ID 0x150 ZeroOne Pixhawk Baseboard Alaised to ID 0 static px4_hw_mft_list_entry_t mft_lists[] = { // ver_rev @@ -372,6 +373,7 @@ static px4_hw_mft_list_entry_t mft_lists[] = { {HW_BASE_ID(16), base_configuration_0, arraySize(base_configuration_0)}, // Auterion Skynode ver 16 {HW_BASE_ID(17), base_configuration_17, arraySize(base_configuration_17)}, // Auterion Skynode ver 17 {HW_BASE_ID(0x100), base_configuration_0, arraySize(base_configuration_0)}, // Holybro Pixhawk Jetson Baseboard ver 0x100 Alaised to ID 0 + {HW_BASE_ID(0x150), base_configuration_0, arraySize(base_configuration_0)}, // ZeroOne Pixhawk Baseboard ver 0x150 }; /************************************************************************************ From 20b6f343a3ab56050521cb80e3ffa17b6cced4bd Mon Sep 17 00:00:00 2001 From: Konrad Date: Wed, 21 Aug 2024 11:49:28 +0200 Subject: [PATCH 05/87] mission_base: make sure all mission_items during landing phase have yaw set to NaN --- src/modules/navigator/mission_base.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/src/modules/navigator/mission_base.cpp b/src/modules/navigator/mission_base.cpp index 8963a0685d08..cee250095be1 100644 --- a/src/modules/navigator/mission_base.cpp +++ b/src/modules/navigator/mission_base.cpp @@ -566,6 +566,13 @@ void MissionBase::handleLanding(WorkItemType &new_work_item_type, mission_item_s (_mission_item.nav_cmd == NAV_CMD_VTOL_LAND) && !_land_detected_sub.get().landed; + /* ignore yaw for landing items */ + /* XXX: if specified heading for landing is desired we could add another step before the descent + * that aligns the vehicle first */ + if (_mission_item.nav_cmd == NAV_CMD_LAND || _mission_item.nav_cmd == NAV_CMD_VTOL_LAND) { + _mission_item.yaw = NAN; + } + /* move to land wp as fixed wing */ if (needs_vtol_landing) { if (_work_item_type == WorkItemType::WORK_ITEM_TYPE_DEFAULT) { @@ -654,13 +661,6 @@ void MissionBase::handleLanding(WorkItemType &new_work_item_type, mission_item_s } } } - - /* ignore yaw for landing items */ - /* XXX: if specified heading for landing is desired we could add another step before the descent - * that aligns the vehicle first */ - if (_mission_item.nav_cmd == NAV_CMD_LAND || _mission_item.nav_cmd == NAV_CMD_VTOL_LAND) { - _mission_item.yaw = NAN; - } } bool MissionBase::position_setpoint_equal(const position_setpoint_s *p1, const position_setpoint_s *p2) const From 6ef82ada6ecc43b266a836d1716264fd33bd27cf Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 22 Aug 2024 14:02:32 +0200 Subject: [PATCH 06/87] Navigator: make sure VTOL transitions in Descend mode are alays triggered (#23578) It previously didn't catch switches to Descend from a manual mode, as both modes have navigation_mode_new=nullptr. Signed-off-by: Silvan Fuhrer --- src/modules/navigator/navigator_main.cpp | 26 +++++++++++------------- 1 file changed, 12 insertions(+), 14 deletions(-) diff --git a/src/modules/navigator/navigator_main.cpp b/src/modules/navigator/navigator_main.cpp index 15db1abdc44d..dbf3324b867e 100644 --- a/src/modules/navigator/navigator_main.cpp +++ b/src/modules/navigator/navigator_main.cpp @@ -854,21 +854,19 @@ void Navigator::run() if (did_not_switch_takeoff_to_loiter && did_not_switch_to_loiter_with_valid_loiter_setpoint) { reset_triplets(); } + } - - // transition to hover in Descend mode - if (_vstatus.nav_state == vehicle_status_s::NAVIGATION_STATE_DESCEND && - _vstatus.is_vtol && _vstatus.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && - force_vtol()) { - vehicle_command_s vcmd = {}; - vcmd.command = NAV_CMD_DO_VTOL_TRANSITION; - vcmd.param1 = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC; - publish_vehicle_cmd(&vcmd); - mavlink_log_info(&_mavlink_log_pub, "Transition to hover mode and descend.\t"); - events::send(events::ID("navigator_transition_descend"), events::Log::Critical, - "Transition to hover mode and descend"); - } - + // VTOL: transition to hover in Descend mode if force_vtol() is true + if (_vstatus.nav_state == vehicle_status_s::NAVIGATION_STATE_DESCEND && + _vstatus.is_vtol && _vstatus.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING && + force_vtol()) { + vehicle_command_s vcmd = {}; + vcmd.command = NAV_CMD_DO_VTOL_TRANSITION; + vcmd.param1 = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC; + publish_vehicle_cmd(&vcmd); + mavlink_log_info(&_mavlink_log_pub, "Transition to hover mode and descend.\t"); + events::send(events::ID("navigator_transition_descend"), events::Log::Critical, + "Transition to hover mode and descend"); } _navigation_mode = navigation_mode_new; From e0bb56b6a740f035a2915e8cb6744c3eb69d0502 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 22 Aug 2024 14:03:24 +0200 Subject: [PATCH 07/87] Commander: Failsafe: set clear condition for action Land like for RTL (#23569) For many failsafes, it is possible to select RTL and Land as actions. In this commit I synchronize the clear condition for these two action options, to always only clear on Disarm or manual mode change. Reasoning is that for the user RTL and Land is a similar action and I would thus expect them to be as similar as possible. And I in general would rather not clear a failsafe state instead of too often clearing it. Example: GF failsafe with action Land --> even if the drone is marginally within the GF again, I want it to proceed with the Landing unless I manually intervene. Signed-off-by: Silvan Fuhrer --- src/modules/commander/failsafe/failsafe.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/src/modules/commander/failsafe/failsafe.cpp b/src/modules/commander/failsafe/failsafe.cpp index 11285af40352..f868d6740835 100644 --- a/src/modules/commander/failsafe/failsafe.cpp +++ b/src/modules/commander/failsafe/failsafe.cpp @@ -60,6 +60,7 @@ FailsafeBase::ActionOptions Failsafe::fromNavDllOrRclActParam(int param_value) case gcs_connection_loss_failsafe_mode::Land_mode: options.action = Action::Land; + options.clear_condition = ClearCondition::OnModeChangeOrDisarm; break; case gcs_connection_loss_failsafe_mode::Terminate: @@ -113,6 +114,7 @@ FailsafeBase::ActionOptions Failsafe::fromGfActParam(int param_value) case geofence_violation_action::Land_mode: options.action = Action::Land; + options.clear_condition = ClearCondition::OnModeChangeOrDisarm; break; default: @@ -355,6 +357,7 @@ FailsafeBase::ActionOptions Failsafe::fromHighWindLimitActParam(int param_value) case command_after_high_wind_failsafe::Land_mode: options.action = Action::Land; + options.clear_condition = ClearCondition::OnModeChangeOrDisarm; break; default: From ee022a70c1c979f292634112130e128ab76f3dc0 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Thu, 22 Aug 2024 14:10:36 +0200 Subject: [PATCH 08/87] Navigator: Land: Improve it for VTOL by taking breaking distance into account (#23566) * vtol adjust landing setpoint * improve comment Co-authored-by: Silvan Fuhrer --------- Co-authored-by: Silvan Fuhrer --- src/modules/navigator/land.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/src/modules/navigator/land.cpp b/src/modules/navigator/land.cpp index 8277378a6670..0a2346154a46 100644 --- a/src/modules/navigator/land.cpp +++ b/src/modules/navigator/land.cpp @@ -86,10 +86,8 @@ Land::on_active() _navigator->get_vstatus()->in_transition_mode) { struct position_setpoint_triplet_s *pos_sp_triplet = _navigator->get_position_setpoint_triplet(); - // create a virtual wp 1m in front of the vehicle to track during the backtransition - waypoint_from_heading_and_distance(_navigator->get_global_position()->lat, _navigator->get_global_position()->lon, - _navigator->get_local_position()->heading, 1.f, - &pos_sp_triplet->current.lat, &pos_sp_triplet->current.lon); + // create a wp in front of the VTOL while in back-transition, based on MPC settings that will apply in MC phase afterwards + _navigator->calculate_breaking_stop(pos_sp_triplet->current.lat, pos_sp_triplet->current.lon); _navigator->set_position_setpoint_triplet_updated(); } From ebbd2c18259d74fde56892a0a563b35d2b6694b5 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 21 Aug 2024 13:58:14 -0400 Subject: [PATCH 09/87] ekf2: organize aid source parameters --- src/modules/ekf2/CMakeLists.txt | 21 +- src/modules/ekf2/module.yaml | 1220 +---------------- src/modules/ekf2/params_airspeed.yaml | 45 + .../ekf2/params_aux_global_position.yaml | 45 + src/modules/ekf2/params_aux_velocity.yaml | 14 + src/modules/ekf2/params_barometer.yaml | 130 ++ src/modules/ekf2/params_drag.yaml | 75 + src/modules/ekf2/params_external_vision.yaml | 121 ++ src/modules/ekf2/params_gnss.yaml | 196 +++ src/modules/ekf2/params_gravity.yaml | 13 + src/modules/ekf2/params_magnetometer.yaml | 153 +++ src/modules/ekf2/params_optical_flow.yaml | 103 ++ src/modules/ekf2/params_range_finder.yaml | 152 ++ src/modules/ekf2/params_sideslip.yaml | 32 + src/modules/ekf2/params_terrain.yaml | 34 + src/modules/ekf2/params_wind.yaml | 15 + 16 files changed, 1220 insertions(+), 1149 deletions(-) create mode 100644 src/modules/ekf2/params_airspeed.yaml create mode 100644 src/modules/ekf2/params_aux_global_position.yaml create mode 100644 src/modules/ekf2/params_aux_velocity.yaml create mode 100644 src/modules/ekf2/params_barometer.yaml create mode 100644 src/modules/ekf2/params_drag.yaml create mode 100644 src/modules/ekf2/params_external_vision.yaml create mode 100644 src/modules/ekf2/params_gnss.yaml create mode 100644 src/modules/ekf2/params_gravity.yaml create mode 100644 src/modules/ekf2/params_magnetometer.yaml create mode 100644 src/modules/ekf2/params_optical_flow.yaml create mode 100644 src/modules/ekf2/params_range_finder.yaml create mode 100644 src/modules/ekf2/params_sideslip.yaml create mode 100644 src/modules/ekf2/params_terrain.yaml create mode 100644 src/modules/ekf2/params_wind.yaml diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 35c6a7b77962..52a3c02806df 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -111,6 +111,7 @@ if(EKF2_SYMFORCE_GEN AND (${PYTHON_SYMFORCE_EXIT_CODE} EQUAL 0)) ) endif() +set(EKF_MODULE_PARAMS) set(EKF_LIBS) set(EKF_SRCS) list(APPEND EKF_SRCS @@ -135,24 +136,27 @@ list(APPEND EKF_SRCS if(CONFIG_EKF2_AIRSPEED) list(APPEND EKF_SRCS EKF/aid_sources/airspeed/airspeed_fusion.cpp) + list(APPEND EKF_MODULE_PARAMS params_airspeed.yaml) endif() if(CONFIG_EKF2_AUX_GLOBAL_POSITION) list(APPEND EKF_SRCS EKF/aid_sources/aux_global_position/aux_global_position.cpp) + list(APPEND EKF_MODULE_PARAMS params_aux_global_position.yaml) endif() if(CONFIG_EKF2_AUXVEL) list(APPEND EKF_SRCS EKF/aid_sources/auxvel/auxvel_fusion.cpp) + list(APPEND EKF_MODULE_PARAMS params_aux_velocity.yaml) endif() if(CONFIG_EKF2_BAROMETER) - list(APPEND EKF_SRCS - EKF/aid_sources/barometer/baro_height_control.cpp - ) + list(APPEND EKF_SRCS EKF/aid_sources/barometer/baro_height_control.cpp) + list(APPEND EKF_MODULE_PARAMS params_barometer.yaml) endif() if(CONFIG_EKF2_DRAG_FUSION) list(APPEND EKF_SRCS EKF/aid_sources/drag/drag_fusion.cpp) + list(APPEND EKF_MODULE_PARAMS params_drag.yaml) endif() if(CONFIG_EKF2_EXTERNAL_VISION) @@ -163,6 +167,7 @@ if(CONFIG_EKF2_EXTERNAL_VISION) EKF/aid_sources/external_vision/ev_vel_control.cpp EKF/aid_sources/external_vision/ev_yaw_control.cpp ) + list(APPEND EKF_MODULE_PARAMS params_external_vision.yaml) endif() if(CONFIG_EKF2_GNSS) @@ -177,10 +182,13 @@ if(CONFIG_EKF2_GNSS) endif() list(APPEND EKF_LIBS yaw_estimator) + + list(APPEND EKF_MODULE_PARAMS params_gnss.yaml) endif() if(CONFIG_EKF2_GRAVITY_FUSION) list(APPEND EKF_SRCS EKF/aid_sources/gravity/gravity_fusion.cpp) + list(APPEND EKF_MODULE_PARAMS params_gravity.yaml) endif() if(CONFIG_EKF2_MAGNETOMETER) @@ -188,6 +196,7 @@ if(CONFIG_EKF2_MAGNETOMETER) EKF/aid_sources/magnetometer/mag_control.cpp EKF/aid_sources/magnetometer/mag_fusion.cpp ) + list(APPEND EKF_MODULE_PARAMS params_magnetometer.yaml) endif() if(CONFIG_EKF2_OPTICAL_FLOW) @@ -195,6 +204,7 @@ if(CONFIG_EKF2_OPTICAL_FLOW) EKF/aid_sources/optical_flow/optical_flow_control.cpp EKF/aid_sources/optical_flow/optical_flow_fusion.cpp ) + list(APPEND EKF_MODULE_PARAMS params_optical_flow.yaml) endif() if(CONFIG_EKF2_RANGE_FINDER) @@ -204,18 +214,22 @@ if(CONFIG_EKF2_RANGE_FINDER) EKF/aid_sources/range_finder/range_height_fusion.cpp EKF/aid_sources/range_finder/sensor_range_finder.cpp ) + list(APPEND EKF_MODULE_PARAMS params_range_finder.yaml) endif() if(CONFIG_EKF2_SIDESLIP) list(APPEND EKF_SRCS EKF/aid_sources/sideslip/sideslip_fusion.cpp) + list(APPEND EKF_MODULE_PARAMS params_sideslip.yaml) endif() if(CONFIG_EKF2_TERRAIN) list(APPEND EKF_SRCS EKF/terrain_control.cpp) + list(APPEND EKF_MODULE_PARAMS params_terrain.yaml) endif() if(CONFIG_EKF2_WIND) list(APPEND EKF_SRCS EKF/wind.cpp) + list(APPEND EKF_MODULE_PARAMS params_wind.yaml) endif () add_subdirectory(EKF) @@ -251,6 +265,7 @@ px4_add_module( params_multi.yaml params_volatile.yaml params_selector.yaml + ${EKF_MODULE_PARAMS} DEPENDS geo diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index 8ed6e700dbad..e1eeab881a17 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -41,167 +41,6 @@ parameters: unit: ms reboot_required: true decimal: 1 - EKF2_MAG_DELAY: - description: - short: Magnetometer measurement delay relative to IMU measurements - type: float - default: 0 - min: 0 - max: 300 - unit: ms - reboot_required: true - decimal: 1 - EKF2_BARO_DELAY: - description: - short: Barometer measurement delay relative to IMU measurements - type: float - default: 0 - min: 0 - max: 300 - unit: ms - reboot_required: true - decimal: 1 - EKF2_GPS_DELAY: - description: - short: GPS measurement delay relative to IMU measurements - type: float - default: 110 - min: 0 - max: 300 - unit: ms - reboot_required: true - decimal: 1 - EKF2_OF_DELAY: - description: - short: Optical flow measurement delay relative to IMU measurements - long: Assumes measurement is timestamped at trailing edge of integration period - type: float - default: 20 - min: 0 - max: 300 - unit: ms - reboot_required: true - decimal: 1 - EKF2_RNG_DELAY: - description: - short: Range finder measurement delay relative to IMU measurements - type: float - default: 5 - min: 0 - max: 300 - unit: ms - reboot_required: true - decimal: 1 - EKF2_ASP_DELAY: - description: - short: Airspeed measurement delay relative to IMU measurements - type: float - default: 100 - min: 0 - max: 300 - unit: ms - reboot_required: true - decimal: 1 - EKF2_EV_DELAY: - description: - short: Vision Position Estimator delay relative to IMU measurements - type: float - default: 0 - min: 0 - max: 300 - unit: ms - reboot_required: true - decimal: 1 - EKF2_AVEL_DELAY: - description: - short: Auxiliary Velocity Estimate delay relative to IMU measurements - type: float - default: 5 - min: 0 - max: 300 - unit: ms - reboot_required: true - decimal: 1 - EKF2_GPS_CHECK: - description: - short: Integer bitmask controlling GPS checks - long: 'Each threshold value is defined by the parameter indicated next to the check. - Drift and offset checks only run when the vehicle is on ground and stationary.' - type: bitmask - bit: - 0: Sat count (EKF2_REQ_NSATS) - 1: PDOP (EKF2_REQ_PDOP) - 2: EPH (EKF2_REQ_EPH) - 3: EPV (EKF2_REQ_EPV) - 4: Speed accuracy (EKF2_REQ_SACC) - 5: Horizontal position drift (EKF2_REQ_HDRIFT) - 6: Vertical position drift (EKF2_REQ_VDRIFT) - 7: Horizontal speed offset (EKF2_REQ_HDRIFT) - 8: Vertical speed offset (EKF2_REQ_VDRIFT) - 9: Spoofing - default: 1023 - min: 0 - max: 1023 - EKF2_REQ_EPH: - description: - short: Required EPH to use GPS - type: float - default: 3.0 - min: 2 - max: 100 - unit: m - decimal: 1 - EKF2_REQ_EPV: - description: - short: Required EPV to use GPS - type: float - default: 5.0 - min: 2 - max: 100 - unit: m - decimal: 1 - EKF2_REQ_SACC: - description: - short: Required speed accuracy to use GPS - type: float - default: 0.5 - min: 0.5 - max: 5.0 - unit: m/s - decimal: 2 - EKF2_REQ_NSATS: - description: - short: Required satellite count to use GPS - type: int32 - default: 6 - min: 4 - max: 12 - EKF2_REQ_PDOP: - description: - short: Maximum PDOP to use GPS - type: float - default: 2.5 - min: 1.5 - max: 5.0 - decimal: 1 - EKF2_REQ_HDRIFT: - description: - short: Maximum horizontal drift speed to use GPS - type: float - default: 0.1 - min: 0.1 - max: 1.0 - unit: m/s - decimal: 2 - EKF2_REQ_VDRIFT: - description: - short: Maximum vertical drift speed to use GPS - type: float - default: 0.2 - min: 0.1 - max: 1.5 - decimal: 2 - unit: m/s EKF2_GYR_NOISE: description: short: Rate gyro noise for covariance prediction @@ -210,682 +49,113 @@ parameters: min: 0.0001 max: 0.1 unit: rad/s - decimal: 4 - EKF2_ACC_NOISE: - description: - short: Accelerometer noise for covariance prediction - type: float - default: 0.35 - min: 0.01 - max: 1.0 - unit: m/s^2 - decimal: 2 - EKF2_GYR_B_NOISE: - description: - short: Process noise for IMU rate gyro bias prediction - type: float - default: 0.001 - min: 0.0 - max: 0.01 - unit: rad/s^2 - decimal: 6 - EKF2_ACC_B_NOISE: - description: - short: Process noise for IMU accelerometer bias prediction - type: float - default: 0.003 - min: 0.0 - max: 0.01 - unit: m/s^3 - decimal: 6 - EKF2_MAG_B_NOISE: - description: - short: Process noise for body magnetic field prediction - type: float - default: 0.0001 - min: 0.0 - max: 0.1 - unit: gauss/s - decimal: 6 - EKF2_MAG_E_NOISE: - description: - short: Process noise for earth magnetic field prediction - type: float - default: 0.001 - min: 0.0 - max: 0.1 - unit: gauss/s - decimal: 6 - EKF2_WIND_NSD: - description: - short: Process noise spectral density for wind velocity prediction - long: When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases - by this amount every second. - type: float - default: 0.05 - min: 0.0 - max: 1.0 - unit: m/s^2/sqrt(Hz) - decimal: 3 - EKF2_GPS_V_NOISE: - description: - short: Measurement noise for GNSS velocity - type: float - default: 0.3 - min: 0.01 - max: 5.0 - unit: m/s - decimal: 2 - EKF2_GPS_P_NOISE: - description: - short: Measurement noise for GNSS position - type: float - default: 0.5 - min: 0.01 - max: 10.0 - unit: m - decimal: 2 - EKF2_NOAID_NOISE: - description: - short: Measurement noise for non-aiding position hold - type: float - default: 10.0 - min: 0.5 - max: 50.0 - unit: m - decimal: 1 - EKF2_BARO_NOISE: - description: - short: Measurement noise for barometric altitude - type: float - default: 3.5 - min: 0.01 - max: 15.0 - unit: m - decimal: 2 - EKF2_HEAD_NOISE: - description: - short: Measurement noise for magnetic heading fusion - type: float - default: 0.3 - min: 0.01 - max: 1.0 - unit: rad - decimal: 2 - EKF2_MAG_NOISE: - description: - short: Measurement noise for magnetometer 3-axis fusion - type: float - default: 0.05 - min: 0.001 - max: 1.0 - unit: gauss - decimal: 3 - EKF2_EAS_NOISE: - description: - short: Measurement noise for airspeed fusion - type: float - default: 1.4 - min: 0.5 - max: 5.0 - unit: m/s - decimal: 1 - EKF2_BETA_GATE: - description: - short: Gate size for synthetic sideslip fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 5.0 - min: 1.0 - unit: SD - decimal: 1 - EKF2_BETA_NOISE: - description: - short: Noise for synthetic sideslip fusion - type: float - default: 0.3 - min: 0.1 - max: 1.0 - unit: m/s - decimal: 2 - EKF2_HDG_GATE: - description: - short: Gate size for heading fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 2.6 - min: 1.0 - unit: SD - decimal: 1 - EKF2_MAG_GATE: - description: - short: Gate size for magnetometer XYZ component fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 3.0 - min: 1.0 - unit: SD - decimal: 1 - EKF2_DECL_TYPE: - description: - short: Integer bitmask controlling handling of magnetic declination - long: 'Set bits in the following positions to enable functions. 0 : Set to - true to use the declination from the geo_lookup library when the GPS position - becomes available, set to false to always use the EKF2_MAG_DECL value. 1 - : Set to true to save the EKF2_MAG_DECL parameter to the value returned - by the EKF when the vehicle disarms.' - type: bitmask - bit: - 0: use geo_lookup declination - 1: save EKF2_MAG_DECL on disarm - default: 3 - min: 0 - max: 3 - reboot_required: true - EKF2_MAG_TYPE: - description: - short: Type of magnetometer fusion - long: Integer controlling the type of magnetometer fusion used - magnetic - heading or 3-component vector. The fusion of magnetometer data as a three - component vector enables vehicle body fixed hard iron errors to be learned, - but requires a stable earth field. If set to 'Automatic' magnetic heading - fusion is used when on-ground and 3-axis magnetic field fusion in-flight. - If set to 'Magnetic heading' magnetic heading fusion is used at all times. - If set to 'None' the magnetometer will not be used under any circumstance. - If no external source of yaw is available, it is possible to use post-takeoff - horizontal movement combined with GNSS velocity measurements to align the yaw angle. - If set to 'Init' the magnetometer is only used to initalize the heading. - type: enum - values: - 0: Automatic - 1: Magnetic heading - 5: None - 6: Init - default: 0 - reboot_required: true - EKF2_MAG_ACCLIM: - description: - short: Horizontal acceleration threshold used for heading observability check - long: The heading is assumed to be observable when the body acceleration is - greater than this parameter when a global position/velocity aiding source - is active. - type: float - default: 0.5 - min: 0.0 - max: 5.0 - unit: m/s^2 - decimal: 2 - EKF2_BARO_GATE: - description: - short: Gate size for barometric and GPS height fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 5.0 - min: 1.0 - unit: SD - decimal: 1 - EKF2_GND_EFF_DZ: - description: - short: Baro deadzone range for height fusion - long: Sets the value of deadzone applied to negative baro innovations. Deadzone - is enabled when EKF2_GND_EFF_DZ > 0. - type: float - default: 4.0 - min: 0.0 - max: 10.0 - unit: m - decimal: 1 - EKF2_GND_MAX_HGT: - description: - short: Height above ground level for ground effect zone - long: Sets the maximum distance to the ground level where negative baro innovations - are expected. - type: float - default: 0.5 - min: 0.0 - max: 5.0 - unit: m - decimal: 1 - EKF2_GPS_P_GATE: - description: - short: Gate size for GNSS position fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 5.0 - min: 1.0 - unit: SD - decimal: 1 - EKF2_GPS_V_GATE: - description: - short: Gate size for GNSS velocity fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 5.0 - min: 1.0 - unit: SD - decimal: 1 - EKF2_TAS_GATE: - description: - short: Gate size for TAS fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 5.0 - min: 1.0 - unit: SD - decimal: 1 - EKF2_HGT_REF: - description: - short: Determines the reference source of height data used by the EKF - long: When multiple height sources are enabled at the same time, the height - estimate will always converge towards the reference height source selected - by this parameter. The range sensor and vision options should only be used - when for operation over a flat surface as the local NED origin will move - up and down with ground level. - type: enum - values: - 0: Barometric pressure - 1: GPS - 2: Range sensor - 3: Vision - default: 1 - reboot_required: true - EKF2_BARO_CTRL: - description: - short: Barometric sensor height aiding - long: If this parameter is enabled then the estimator will make use of the - barometric height measurements to estimate its height in addition to other - height sources (if activated). - type: boolean - default: 1 - EKF2_EV_CTRL: - description: - short: External vision (EV) sensor aiding - long: 'Set bits in the following positions to enable: 0 : Horizontal position - fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw' - type: bitmask - bit: - 0: Horizontal position - 1: Vertical position - 2: 3D velocity - 3: Yaw - default: 0 - min: 0 - max: 15 - EKF2_GPS_CTRL: - description: - short: GNSS sensor aiding - long: 'Set bits in the following positions to enable: 0 : Longitude and latitude - fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading - fusion' - type: bitmask - bit: - 0: Lon/lat - 1: Altitude - 2: 3D velocity - 3: Dual antenna heading - default: 7 - min: 0 - max: 15 - EKF2_RNG_CTRL: - description: - short: Range sensor height aiding - long: 'WARNING: Range finder measurements are less reliable and can experience - unexpected errors. For these reasons, if accurate control of height relative - to ground is required, it is recommended to use the MPC_ALT_MODE parameter - instead, unless baro errors are severe enough to cause problems with landing - and takeoff. If this parameter is enabled then the estimator - will make use of the range finder measurements to estimate its height in - addition to other height sources (if activated). Range sensor aiding can - be enabled (i.e.: always use) or set in "conditional" mode. Conditional - mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) - and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, - where baro interference from rotor wash is excessive and can corrupt EKF - state estimates. It is intended to be used where a vertical takeoff and - landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.' - type: enum - values: - 0: Disable range fusion - 1: Enabled (conditional mode) - 2: Enabled - default: 1 - EKF2_NOAID_TOUT: - description: - short: Maximum inertial dead-reckoning time - long: Maximum lapsed time from last fusion of measurements that constrain - velocity drift before the EKF will report the horizontal nav solution as - invalid - type: int32 - default: 5000000 - min: 500000 - max: 10000000 - unit: us - EKF2_RNG_NOISE: - description: - short: Measurement noise for range finder fusion - type: float - default: 0.1 - min: 0.01 - unit: m - decimal: 2 - EKF2_RNG_SFE: - description: - short: Range finder range dependent noise scaler - long: Specifies the increase in range finder noise with range. - type: float - default: 0.05 - min: 0.0 - max: 0.2 - unit: m/m - EKF2_RNG_GATE: - description: - short: Gate size for range finder fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 5.0 - min: 1.0 - unit: SD - decimal: 1 - EKF2_MIN_RNG: - description: - short: Expected range finder reading when on ground - long: If the vehicle is on ground, is not moving as determined by the motion - test and the range finder is returning invalid or no data, then an assumed - range value of EKF2_MIN_RNG will be used by the terrain estimator so that - a terrain height estimate is available at the start of flight in situations - where the range finder may be inside its minimum measurements distance when - on ground. - type: float - default: 0.1 - min: 0.01 - unit: m - decimal: 2 - EKF2_EV_NOISE_MD: - description: - short: External vision (EV) noise mode - long: If set to 0 (default) the measurement noise is taken from the vision - message and the EV noise parameters are used as a lower bound. If set to - 1 the observation noise is set from the parameters directly, - type: enum - values: - 0: EV reported variance (parameter lower bound) - 1: EV noise parameters - default: 0 - EKF2_EV_QMIN: - description: - short: External vision (EV) minimum quality (optional) - long: External vision will only be started and fused if the quality metric - is above this threshold. The quality metric is a completely optional field - provided by some VIO systems. - type: int32 - default: 0 - min: 0 - max: 100 - decimal: 1 - EKF2_EVP_NOISE: - description: - short: Measurement noise for vision position measurements - long: Used to lower bound or replace the uncertainty included in the message - type: float - default: 0.1 - min: 0.01 - unit: m - decimal: 2 - EKF2_EVV_NOISE: - description: - short: Measurement noise for vision velocity measurements - long: Used to lower bound or replace the uncertainty included in the message - type: float - default: 0.1 - min: 0.01 - unit: m/s - decimal: 2 - EKF2_EVA_NOISE: - description: - short: Measurement noise for vision angle measurements - long: Used to lower bound or replace the uncertainty included in the message - type: float - default: 0.1 - min: 0.05 - unit: rad - decimal: 2 - EKF2_GRAV_NOISE: - description: - short: Accelerometer measurement noise for gravity based observations - type: float - default: 1.0 - min: 0.1 - max: 10.0 - unit: g0 - decimal: 2 - EKF2_OF_CTRL: - description: - short: Optical flow aiding - long: Enable optical flow fusion. - type: boolean - default: 1 - EKF2_OF_GYR_SRC: - description: - short: Optical flow angular rate compensation source - long: 'Auto: use gyro from optical flow message if available, internal gyro otherwise. - Internal: always use internal gyro' - type: enum - values: - 0: Auto - 1: Internal - default: 0 - EKF2_OF_N_MIN: - description: - short: Optical flow minimum noise - long: Measurement noise for the optical flow sensor when it's reported quality - metric is at the maximum - type: float - default: 0.15 - min: 0.05 - unit: rad/s - decimal: 2 - EKF2_OF_N_MAX: - description: - short: Optical flow maximum noise - long: Measurement noise for the optical flow sensor when it's reported quality - metric is at the minimum - type: float - default: 0.5 - min: 0.05 - unit: rad/s - decimal: 2 - EKF2_OF_QMIN: - description: - short: In air optical flow minimum quality - long: Optical Flow data will only be used in air if the sensor reports a - quality metric >= EKF2_OF_QMIN - type: int32 - default: 1 - min: 0 - max: 255 - EKF2_OF_QMIN_GND: - description: - short: On ground optical flow minimum quality - long: Optical Flow data will only be used on the ground if the sensor reports - a quality metric >= EKF2_OF_QMIN_GND - type: int32 - default: 0 - min: 0 - max: 255 - EKF2_OF_GATE: - description: - short: Gate size for optical flow fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 3.0 - min: 1.0 - unit: SD - decimal: 1 - EKF2_TERR_NOISE: - description: - short: Terrain altitude process noise - type: float - default: 5.0 - min: 0.5 - unit: m/s - decimal: 1 - EKF2_TERR_GRAD: - description: - short: Magnitude of terrain gradient - type: float - default: 0.5 - min: 0.0 - unit: m/m - decimal: 2 - EKF2_IMU_POS_X: - description: - short: X position of IMU in body frame - long: Forward axis with origin relative to vehicle centre of gravity - type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_IMU_POS_Y: - description: - short: Y position of IMU in body frame - long: Forward axis with origin relative to vehicle centre of gravity - type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_IMU_POS_Z: - description: - short: Z position of IMU in body frame - long: Forward axis with origin relative to vehicle centre of gravity - type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_GPS_POS_X: - description: - short: X position of GPS antenna in body frame - long: Forward axis with origin relative to vehicle centre of gravity - type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_GPS_POS_Y: + decimal: 4 + EKF2_ACC_NOISE: description: - short: Y position of GPS antenna in body frame - long: Forward axis with origin relative to vehicle centre of gravity + short: Accelerometer noise for covariance prediction type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_GPS_POS_Z: + default: 0.35 + min: 0.01 + max: 1.0 + unit: m/s^2 + decimal: 2 + EKF2_GYR_B_NOISE: description: - short: Z position of GPS antenna in body frame - long: Forward axis with origin relative to vehicle centre of gravity + short: Process noise for IMU rate gyro bias prediction type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_RNG_POS_X: + default: 0.001 + min: 0.0 + max: 0.01 + unit: rad/s^2 + decimal: 6 + EKF2_ACC_B_NOISE: description: - short: X position of range finder origin in body frame - long: Forward axis with origin relative to vehicle centre of gravity + short: Process noise for IMU accelerometer bias prediction type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_RNG_POS_Y: + default: 0.003 + min: 0.0 + max: 0.01 + unit: m/s^3 + decimal: 6 + EKF2_NOAID_NOISE: description: - short: Y position of range finder origin in body frame - long: Forward axis with origin relative to vehicle centre of gravity + short: Measurement noise for non-aiding position hold type: float - default: 0.0 + default: 10.0 + min: 0.5 + max: 50.0 unit: m - decimal: 3 - EKF2_RNG_POS_Z: + decimal: 1 + EKF2_HEAD_NOISE: description: - short: Z position of range finder origin in body frame - long: Forward axis with origin relative to vehicle centre of gravity + short: Measurement noise for magnetic heading fusion type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_OF_POS_X: + default: 0.3 + min: 0.01 + max: 1.0 + unit: rad + decimal: 2 + EKF2_HDG_GATE: description: - short: X position of optical flow focal point in body frame - long: Forward axis with origin relative to vehicle centre of gravity + short: Gate size for heading fusion + long: Sets the number of standard deviations used by the innovation consistency + test. type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_OF_POS_Y: + default: 2.6 + min: 1.0 + unit: SD + decimal: 1 + EKF2_HGT_REF: description: - short: Y position of optical flow focal point in body frame - long: Forward axis with origin relative to vehicle centre of gravity - type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_OF_POS_Z: + short: Determines the reference source of height data used by the EKF + long: When multiple height sources are enabled at the same time, the height + estimate will always converge towards the reference height source selected + by this parameter. The range sensor and vision options should only be used + when for operation over a flat surface as the local NED origin will move + up and down with ground level. + type: enum + values: + 0: Barometric pressure + 1: GPS + 2: Range sensor + 3: Vision + default: 1 + reboot_required: true + EKF2_NOAID_TOUT: description: - short: Z position of optical flow focal point in body frame - long: Forward axis with origin relative to vehicle centre of gravity - type: float - default: 0.0 - unit: m - decimal: 3 - EKF2_EV_POS_X: + short: Maximum inertial dead-reckoning time + long: Maximum lapsed time from last fusion of measurements that constrain + velocity drift before the EKF will report the horizontal nav solution as + invalid + type: int32 + default: 5000000 + min: 500000 + max: 10000000 + unit: us + EKF2_IMU_POS_X: description: - short: X position of VI sensor focal point in body frame + short: X position of IMU in body frame long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 - EKF2_EV_POS_Y: + EKF2_IMU_POS_Y: description: - short: Y position of VI sensor focal point in body frame + short: Y position of IMU in body frame long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 - EKF2_EV_POS_Z: + EKF2_IMU_POS_Z: description: - short: Z position of VI sensor focal point in body frame + short: Z position of IMU in body frame long: Forward axis with origin relative to vehicle centre of gravity type: float default: 0.0 unit: m decimal: 3 - EKF2_ARSP_THR: - description: - short: Airspeed fusion threshold - long: Airspeed data is fused for wind estimation if above this threshold. - Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip - (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies - to fixed-wing vehicles (or VTOLs in fixed-wing mode). - type: float - default: 0.0 - min: 0.0 - unit: m/s - decimal: 1 - EKF2_FUSE_BETA: - description: - short: Enable synthetic sideslip fusion - long: 'For reliable wind estimation both sideslip and airspeed fusion (see - EKF2_ARSP_THR) should be enabled. Only applies to fixed-wing vehicles (or - VTOLs in fixed-wing mode). Note: side slip fusion is currently not supported - for tailsitters.' - type: boolean - default: 0 EKF2_TAU_VEL: description: short: Time constant of the velocity output prediction and smoothing filter @@ -934,229 +204,6 @@ parameters: unit: rad reboot_required: true decimal: 3 - EKF2_RNG_PITCH: - description: - short: Range sensor pitch offset - type: float - default: 0.0 - min: -0.75 - max: 0.75 - unit: rad - decimal: 3 - EKF2_RNG_A_VMAX: - description: - short: Maximum horizontal velocity allowed for conditional range aid mode - long: If the vehicle horizontal speed exceeds this value then the estimator - will not fuse range measurements to estimate its height. This only applies - when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). - type: float - default: 1.0 - min: 0.1 - max: 2 - unit: m/s - EKF2_RNG_A_HMAX: - description: - short: Maximum height above ground allowed for conditional range aid mode - long: If the vehicle absolute altitude exceeds this value then the estimator - will not fuse range measurements to estimate its height. This only applies - when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). - type: float - default: 5.0 - min: 1.0 - max: 10.0 - unit: m - EKF2_RNG_A_IGATE: - description: - short: Gate size used for innovation consistency checks for range aid fusion - long: A lower value means HAGL needs to be more stable in order to use range - finder for height estimation in range aid mode - type: float - default: 1.0 - unit: SD - min: 0.1 - max: 5.0 - EKF2_RNG_QLTY_T: - description: - short: Minumum range validity period - long: Minimum duration during which the reported range finder signal quality - needs to be non-zero in order to be declared valid (s) - type: float - default: 1.0 - unit: s - min: 0.1 - max: 5 - EKF2_RNG_K_GATE: - description: - short: Gate size used for range finder kinematic consistency check - long: 'To be used, the time derivative of the distance sensor measurements - projected on the vertical axis needs to be statistically consistent with - the estimated vertical velocity of the drone. Decrease this value to make - the filter more robust against range finder faulty data (stuck, reflections, - ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) - before tuning this gate.' - type: float - default: 1.0 - unit: SD - min: 0.1 - max: 5.0 - EKF2_EVV_GATE: - description: - short: Gate size for vision velocity estimate fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 3.0 - min: 1.0 - unit: SD - decimal: 1 - EKF2_EVP_GATE: - description: - short: Gate size for vision position fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 5.0 - min: 1.0 - unit: SD - decimal: 1 - EKF2_DRAG_CTRL: - description: - short: Multirotor wind estimation selection - long: Activate wind speed estimation using specific-force measurements and - a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles - that have their thrust aligned with the Z axis and no thrust in the XY plane. - type: boolean - default: 0 - EKF2_DRAG_NOISE: - description: - short: Specific drag force observation noise variance - long: Used by the multi-rotor specific drag force model. - Increasing this makes the multi-rotor wind estimates adjust more slowly. - type: float - default: 2.5 - min: 0.5 - max: 10.0 - unit: (m/s^2)^2 - decimal: 2 - EKF2_BCOEF_X: - description: - short: X-axis ballistic coefficient used for multi-rotor wind estimation - long: This parameter controls the prediction of drag produced by bluff body - drag along the forward/reverse axis when flying a multi-copter which enables - estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The - drag produced by this effect scales with speed squared. The predicted drag - from the rotors is specified separately by the EKF2_MCOEF parameter. Set - this parameter to zero to turn off the bluff body drag model for this axis. - type: float - default: 100.0 - min: 0.0 - max: 200.0 - unit: kg/m^2 - decimal: 1 - EKF2_BCOEF_Y: - description: - short: Y-axis ballistic coefficient used for multi-rotor wind estimation - long: This parameter controls the prediction of drag produced by bluff body - drag along the right/left axis when flying a multi-copter, which enables - estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The - drag produced by this effect scales with speed squared. The predicted drag - from the rotors is specified separately by the EKF2_MCOEF parameter. Set - this parameter to zero to turn off the bluff body drag model for this axis. - type: float - default: 100.0 - min: 0.0 - max: 200.0 - unit: kg/m^2 - decimal: 1 - EKF2_MCOEF: - description: - short: Propeller momentum drag coefficient for multi-rotor wind estimation - long: This parameter controls the prediction of drag produced by the propellers - when flying a multi-copter, which enables estimation of wind drift when - enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect - scales with speed not speed squared and is produced because some of the - air velocity normal to the propeller axis of rotation is lost when passing - through the rotor disc. This changes the momentum of the flow which creates - a drag reaction force. When comparing un-ducted propellers of the same diameter, - the effect is roughly proportional to the area of the propeller blades when - viewed side on and changes with propeller selection. Momentum drag is significantly - higher for ducted rotors. To account for the drag produced by the body which - scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y - parameters. Set this parameter to zero to turn off the momentum drag model - for both axis. - type: float - default: 0.15 - min: 0 - max: 1.0 - unit: 1/s - decimal: 2 - EKF2_ASPD_MAX: - description: - short: Maximum airspeed used for baro static pressure compensation - type: float - default: 20.0 - min: 5.0 - max: 50.0 - unit: m/s - decimal: 1 - EKF2_PCOEF_XP: - description: - short: Static pressure position error coefficient for the positive X axis - long: This is the ratio of static pressure error to dynamic pressure generated - by a positive wind relative velocity along the X body axis. If the baro - height estimate rises during forward flight, then this will be a negative - number. - type: float - default: 0.0 - min: -0.5 - max: 0.5 - decimal: 2 - EKF2_PCOEF_XN: - description: - short: Static pressure position error coefficient for the negative X axis - long: This is the ratio of static pressure error to dynamic pressure generated - by a negative wind relative velocity along the X body axis. If the baro - height estimate rises during backwards flight, then this will be a negative - number. - type: float - default: 0.0 - min: -0.5 - max: 0.5 - decimal: 2 - EKF2_PCOEF_YP: - description: - short: Pressure position error coefficient for the positive Y axis - long: This is the ratio of static pressure error to dynamic pressure generated - by a wind relative velocity along the positive Y (RH) body axis. If the - baro height estimate rises during sideways flight to the right, then this - will be a negative number. - type: float - default: 0.0 - min: -0.5 - max: 0.5 - decimal: 2 - EKF2_PCOEF_YN: - description: - short: Pressure position error coefficient for the negative Y axis - long: This is the ratio of static pressure error to dynamic pressure generated - by a wind relative velocity along the negative Y (LH) body axis. If the - baro height estimate rises during sideways flight to the left, then this - will be a negative number. - type: float - default: 0.0 - min: -0.5 - max: 0.5 - decimal: 2 - EKF2_PCOEF_Z: - description: - short: Static pressure position error coefficient for the Z axis - long: This is the ratio of static pressure error to dynamic pressure generated - by a wind relative velocity along the Z body axis. - type: float - default: 0.0 - min: -0.5 - max: 0.5 - decimal: 2 EKF2_ABL_LIM: description: short: Accelerometer bias learning limit @@ -1217,125 +264,6 @@ parameters: max: 0.4 unit: rad/s decimal: 3 - EKF2_REQ_GPS_H: - description: - short: Required GPS health time on startup - long: Minimum continuous period without GPS failure required to mark a healthy - GPS status. It can be reduced to speed up initialization, but it's recommended - to keep this unchanged for a vehicle. - type: float - default: 10.0 - min: 0.1 - decimal: 1 - unit: s - reboot_required: true - EKF2_MAG_CHECK: - description: - short: Magnetic field strength test selection - long: 'Bitmask to set which check is used to decide whether the magnetometer - data is valid. If GNSS data is received, the magnetic field is compared - to a World Magnetic Model (WMM), otherwise an average value is used. This - check is useful to reject occasional hard iron disturbance. Set bits to - 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic - field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field - inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find - the theoretical strength and inclination using the WMM' - type: bitmask - bit: - 0: Strength (EKF2_MAG_CHK_STR) - 1: Inclination (EKF2_MAG_CHK_INC) - 2: Wait for WMM - default: 1 - min: 0 - max: 7 - EKF2_MAG_CHK_STR: - description: - short: Magnetic field strength check tolerance - long: Maximum allowed deviation from the expected magnetic field strength - to pass the check. - type: float - default: 0.2 - min: 0.0 - max: 1.0 - unit: gauss - decimal: 2 - EKF2_MAG_CHK_INC: - description: - short: Magnetic field inclination check tolerance - long: Maximum allowed deviation from the expected magnetic field inclination - to pass the check. - type: float - default: 20.0 - min: 0.0 - max: 90.0 - unit: deg - decimal: 1 - EKF2_SYNT_MAG_Z: - description: - short: Enable synthetic magnetometer Z component measurement - long: Use for vehicles where the measured body Z magnetic field is subject - to strong magnetic interference. For magnetic heading fusion the magnetometer - Z measurement will be replaced by a synthetic value calculated using the - knowledge of the 3D magnetic field vector at the location of the drone. - Therefore, this parameter will only have an effect if the global position - of the drone is known. For 3D mag fusion the magnetometer Z measurement - will simply be ignored instead of fusing the synthetic value. - type: boolean - default: 0 - EKF2_GSF_TAS: - description: - short: Default value of true airspeed used in EKF-GSF AHRS calculation - long: If no airspeed measurements are available, the EKF-GSF AHRS calculation - will assume this value of true airspeed when compensating for centripetal - acceleration during turns. Set to zero to disable centripetal acceleration - compensation during fixed wing flight modes. - type: float - default: 15.0 - min: 0.0 - unit: m/s - max: 100.0 - decimal: 1 - EKF2_AGP_CTRL: - description: - short: Aux global position (AGP) sensor aiding - long: 'Set bits in the following positions to enable: 0 : Horizontal position - fusion 1 : Vertical position fusion' - type: bitmask - bit: - 0: Horizontal position - 1: Vertical position - default: 0 - min: 0 - max: 3 - EKF2_AGP_DELAY: - description: - short: Aux global position estimator delay relative to IMU measurements - type: float - default: 0 - min: 0 - max: 300 - unit: ms - reboot_required: true - decimal: 1 - EKF2_AGP_NOISE: - description: - short: Measurement noise for aux global position measurements - long: Used to lower bound or replace the uncertainty included in the message - type: float - default: 0.9 - min: 0.01 - unit: m - decimal: 2 - EKF2_AGP_GATE: - description: - short: Gate size for aux global position fusion - long: Sets the number of standard deviations used by the innovation consistency - test. - type: float - default: 3.0 - min: 1.0 - unit: SD - decimal: 1 EKF2_LOG_VERBOSE: description: short: Verbose logging diff --git a/src/modules/ekf2/params_airspeed.yaml b/src/modules/ekf2/params_airspeed.yaml new file mode 100644 index 000000000000..b9563336a47a --- /dev/null +++ b/src/modules/ekf2/params_airspeed.yaml @@ -0,0 +1,45 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_ARSP_THR: + description: + short: Airspeed fusion threshold + long: Airspeed data is fused for wind estimation if above this threshold. + Set to 0 to disable airspeed fusion. For reliable wind estimation both sideslip + (see EKF2_FUSE_BETA) and airspeed fusion should be enabled. Only applies + to fixed-wing vehicles (or VTOLs in fixed-wing mode). + type: float + default: 0.0 + min: 0.0 + unit: m/s + decimal: 1 + EKF2_ASP_DELAY: + description: + short: Airspeed measurement delay relative to IMU measurements + type: float + default: 100 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_TAS_GATE: + description: + short: Gate size for TAS fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_EAS_NOISE: + description: + short: Measurement noise for airspeed fusion + type: float + default: 1.4 + min: 0.5 + max: 5.0 + unit: m/s + decimal: 1 diff --git a/src/modules/ekf2/params_aux_global_position.yaml b/src/modules/ekf2/params_aux_global_position.yaml new file mode 100644 index 000000000000..77f348776b12 --- /dev/null +++ b/src/modules/ekf2/params_aux_global_position.yaml @@ -0,0 +1,45 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_AGP_CTRL: + description: + short: Aux global position (AGP) sensor aiding + long: 'Set bits in the following positions to enable: 0 : Horizontal position + fusion 1 : Vertical position fusion' + type: bitmask + bit: + 0: Horizontal position + 1: Vertical position + default: 0 + min: 0 + max: 3 + EKF2_AGP_DELAY: + description: + short: Aux global position estimator delay relative to IMU measurements + type: float + default: 0 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_AGP_NOISE: + description: + short: Measurement noise for aux global position measurements + long: Used to lower bound or replace the uncertainty included in the message + type: float + default: 0.9 + min: 0.01 + unit: m + decimal: 2 + EKF2_AGP_GATE: + description: + short: Gate size for aux global position fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 3.0 + min: 1.0 + unit: SD + decimal: 1 diff --git a/src/modules/ekf2/params_aux_velocity.yaml b/src/modules/ekf2/params_aux_velocity.yaml new file mode 100644 index 000000000000..93b38587c02b --- /dev/null +++ b/src/modules/ekf2/params_aux_velocity.yaml @@ -0,0 +1,14 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_AVEL_DELAY: + description: + short: Auxiliary Velocity Estimate delay relative to IMU measurements + type: float + default: 5 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 diff --git a/src/modules/ekf2/params_barometer.yaml b/src/modules/ekf2/params_barometer.yaml new file mode 100644 index 000000000000..cefa503039b7 --- /dev/null +++ b/src/modules/ekf2/params_barometer.yaml @@ -0,0 +1,130 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_BARO_CTRL: + description: + short: Barometric sensor height aiding + long: If this parameter is enabled then the estimator will make use of the + barometric height measurements to estimate its height in addition to other + height sources (if activated). + type: boolean + default: 1 + EKF2_BARO_DELAY: + description: + short: Barometer measurement delay relative to IMU measurements + type: float + default: 0 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_BARO_GATE: + description: + short: Gate size for barometric and GPS height fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_BARO_NOISE: + description: + short: Measurement noise for barometric altitude + type: float + default: 3.5 + min: 0.01 + max: 15.0 + unit: m + decimal: 2 + EKF2_GND_EFF_DZ: + description: + short: Baro deadzone range for height fusion + long: Sets the value of deadzone applied to negative baro innovations. Deadzone + is enabled when EKF2_GND_EFF_DZ > 0. + type: float + default: 4.0 + min: 0.0 + max: 10.0 + unit: m + decimal: 1 + EKF2_GND_MAX_HGT: + description: + short: Height above ground level for ground effect zone + long: Sets the maximum distance to the ground level where negative baro innovations + are expected. + type: float + default: 0.5 + min: 0.0 + max: 5.0 + unit: m + decimal: 1 + EKF2_PCOEF_XP: + description: + short: Static pressure position error coefficient for the positive X axis + long: This is the ratio of static pressure error to dynamic pressure generated + by a positive wind relative velocity along the X body axis. If the baro + height estimate rises during forward flight, then this will be a negative + number. + type: float + default: 0.0 + min: -0.5 + max: 0.5 + decimal: 2 + EKF2_PCOEF_XN: + description: + short: Static pressure position error coefficient for the negative X axis + long: This is the ratio of static pressure error to dynamic pressure generated + by a negative wind relative velocity along the X body axis. If the baro + height estimate rises during backwards flight, then this will be a negative + number. + type: float + default: 0.0 + min: -0.5 + max: 0.5 + decimal: 2 + EKF2_PCOEF_YP: + description: + short: Pressure position error coefficient for the positive Y axis + long: This is the ratio of static pressure error to dynamic pressure generated + by a wind relative velocity along the positive Y (RH) body axis. If the + baro height estimate rises during sideways flight to the right, then this + will be a negative number. + type: float + default: 0.0 + min: -0.5 + max: 0.5 + decimal: 2 + EKF2_PCOEF_YN: + description: + short: Pressure position error coefficient for the negative Y axis + long: This is the ratio of static pressure error to dynamic pressure generated + by a wind relative velocity along the negative Y (LH) body axis. If the + baro height estimate rises during sideways flight to the left, then this + will be a negative number. + type: float + default: 0.0 + min: -0.5 + max: 0.5 + decimal: 2 + EKF2_PCOEF_Z: + description: + short: Static pressure position error coefficient for the Z axis + long: This is the ratio of static pressure error to dynamic pressure generated + by a wind relative velocity along the Z body axis. + type: float + default: 0.0 + min: -0.5 + max: 0.5 + decimal: 2 + EKF2_ASPD_MAX: + description: + short: Maximum airspeed used for baro static pressure compensation + type: float + default: 20.0 + min: 5.0 + max: 50.0 + unit: m/s + decimal: 1 diff --git a/src/modules/ekf2/params_drag.yaml b/src/modules/ekf2/params_drag.yaml new file mode 100644 index 000000000000..79fa919ea8d6 --- /dev/null +++ b/src/modules/ekf2/params_drag.yaml @@ -0,0 +1,75 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_DRAG_CTRL: + description: + short: Multirotor wind estimation selection + long: Activate wind speed estimation using specific-force measurements and + a drag model defined by EKF2_BCOEF_[XY] and EKF2_MCOEF. Only use on vehicles + that have their thrust aligned with the Z axis and no thrust in the XY plane. + type: boolean + default: 0 + EKF2_DRAG_NOISE: + description: + short: Specific drag force observation noise variance + long: Used by the multi-rotor specific drag force model. + Increasing this makes the multi-rotor wind estimates adjust more slowly. + type: float + default: 2.5 + min: 0.5 + max: 10.0 + unit: (m/s^2)^2 + decimal: 2 + EKF2_BCOEF_X: + description: + short: X-axis ballistic coefficient used for multi-rotor wind estimation + long: This parameter controls the prediction of drag produced by bluff body + drag along the forward/reverse axis when flying a multi-copter which enables + estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The + drag produced by this effect scales with speed squared. The predicted drag + from the rotors is specified separately by the EKF2_MCOEF parameter. Set + this parameter to zero to turn off the bluff body drag model for this axis. + type: float + default: 100.0 + min: 0.0 + max: 200.0 + unit: kg/m^2 + decimal: 1 + EKF2_BCOEF_Y: + description: + short: Y-axis ballistic coefficient used for multi-rotor wind estimation + long: This parameter controls the prediction of drag produced by bluff body + drag along the right/left axis when flying a multi-copter, which enables + estimation of wind drift when enabled by the EKF2_DRAG_CTRL parameter. The + drag produced by this effect scales with speed squared. The predicted drag + from the rotors is specified separately by the EKF2_MCOEF parameter. Set + this parameter to zero to turn off the bluff body drag model for this axis. + type: float + default: 100.0 + min: 0.0 + max: 200.0 + unit: kg/m^2 + decimal: 1 + EKF2_MCOEF: + description: + short: Propeller momentum drag coefficient for multi-rotor wind estimation + long: This parameter controls the prediction of drag produced by the propellers + when flying a multi-copter, which enables estimation of wind drift when + enabled by the EKF2_DRAG_CTRL parameter. The drag produced by this effect + scales with speed not speed squared and is produced because some of the + air velocity normal to the propeller axis of rotation is lost when passing + through the rotor disc. This changes the momentum of the flow which creates + a drag reaction force. When comparing un-ducted propellers of the same diameter, + the effect is roughly proportional to the area of the propeller blades when + viewed side on and changes with propeller selection. Momentum drag is significantly + higher for ducted rotors. To account for the drag produced by the body which + scales with speed squared, see documentation for the EKF2_BCOEF_X and EKF2_BCOEF_Y + parameters. Set this parameter to zero to turn off the momentum drag model + for both axis. + type: float + default: 0.15 + min: 0 + max: 1.0 + unit: 1/s + decimal: 2 diff --git a/src/modules/ekf2/params_external_vision.yaml b/src/modules/ekf2/params_external_vision.yaml new file mode 100644 index 000000000000..e1f058176665 --- /dev/null +++ b/src/modules/ekf2/params_external_vision.yaml @@ -0,0 +1,121 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_EV_CTRL: + description: + short: External vision (EV) sensor aiding + long: 'Set bits in the following positions to enable: 0 : Horizontal position + fusion 1 : Vertical position fusion 2 : 3D velocity fusion 3 : Yaw' + type: bitmask + bit: + 0: Horizontal position + 1: Vertical position + 2: 3D velocity + 3: Yaw + default: 0 + min: 0 + max: 15 + EKF2_EV_DELAY: + description: + short: Vision Position Estimator delay relative to IMU measurements + type: float + default: 0 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_EV_NOISE_MD: + description: + short: External vision (EV) noise mode + long: If set to 0 (default) the measurement noise is taken from the vision + message and the EV noise parameters are used as a lower bound. If set to + 1 the observation noise is set from the parameters directly, + type: enum + values: + 0: EV reported variance (parameter lower bound) + 1: EV noise parameters + default: 0 + EKF2_EV_QMIN: + description: + short: External vision (EV) minimum quality (optional) + long: External vision will only be started and fused if the quality metric + is above this threshold. The quality metric is a completely optional field + provided by some VIO systems. + type: int32 + default: 0 + min: 0 + max: 100 + decimal: 1 + EKF2_EVA_NOISE: + description: + short: Measurement noise for vision angle measurements + long: Used to lower bound or replace the uncertainty included in the message + type: float + default: 0.1 + min: 0.05 + unit: rad + decimal: 2 + EKF2_EVP_GATE: + description: + short: Gate size for vision position fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_EVP_NOISE: + description: + short: Measurement noise for vision position measurements + long: Used to lower bound or replace the uncertainty included in the message + type: float + default: 0.1 + min: 0.01 + unit: m + decimal: 2 + EKF2_EVV_GATE: + description: + short: Gate size for vision velocity estimate fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 3.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_EVV_NOISE: + description: + short: Measurement noise for vision velocity measurements + long: Used to lower bound or replace the uncertainty included in the message + type: float + default: 0.1 + min: 0.01 + unit: m/s + decimal: 2 + EKF2_EV_POS_X: + description: + short: X position of VI sensor focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_EV_POS_Y: + description: + short: Y position of VI sensor focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_EV_POS_Z: + description: + short: Z position of VI sensor focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 diff --git a/src/modules/ekf2/params_gnss.yaml b/src/modules/ekf2/params_gnss.yaml new file mode 100644 index 000000000000..55c530a125c9 --- /dev/null +++ b/src/modules/ekf2/params_gnss.yaml @@ -0,0 +1,196 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_GPS_CTRL: + description: + short: GNSS sensor aiding + long: 'Set bits in the following positions to enable: 0 : Longitude and latitude + fusion 1 : Altitude fusion 2 : 3D velocity fusion 3 : Dual antenna heading + fusion' + type: bitmask + bit: + 0: Lon/lat + 1: Altitude + 2: 3D velocity + 3: Dual antenna heading + default: 7 + min: 0 + max: 15 + EKF2_GPS_DELAY: + description: + short: GPS measurement delay relative to IMU measurements + type: float + default: 110 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_GPS_P_NOISE: + description: + short: Measurement noise for GNSS position + type: float + default: 0.5 + min: 0.01 + max: 10.0 + unit: m + decimal: 2 + EKF2_GPS_P_GATE: + description: + short: Gate size for GNSS position fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_GPS_V_GATE: + description: + short: Gate size for GNSS velocity fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_GPS_V_NOISE: + description: + short: Measurement noise for GNSS velocity + type: float + default: 0.3 + min: 0.01 + max: 5.0 + unit: m/s + decimal: 2 + EKF2_GPS_POS_X: + description: + short: X position of GPS antenna in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_GPS_POS_Y: + description: + short: Y position of GPS antenna in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_GPS_POS_Z: + description: + short: Z position of GPS antenna in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_GPS_CHECK: + description: + short: Integer bitmask controlling GPS checks + long: 'Each threshold value is defined by the parameter indicated next to the check. + Drift and offset checks only run when the vehicle is on ground and stationary.' + type: bitmask + bit: + 0: Sat count (EKF2_REQ_NSATS) + 1: PDOP (EKF2_REQ_PDOP) + 2: EPH (EKF2_REQ_EPH) + 3: EPV (EKF2_REQ_EPV) + 4: Speed accuracy (EKF2_REQ_SACC) + 5: Horizontal position drift (EKF2_REQ_HDRIFT) + 6: Vertical position drift (EKF2_REQ_VDRIFT) + 7: Horizontal speed offset (EKF2_REQ_HDRIFT) + 8: Vertical speed offset (EKF2_REQ_VDRIFT) + 9: Spoofing + default: 1023 + min: 0 + max: 1023 + EKF2_REQ_EPH: + description: + short: Required EPH to use GPS + type: float + default: 3.0 + min: 2 + max: 100 + unit: m + decimal: 1 + EKF2_REQ_EPV: + description: + short: Required EPV to use GPS + type: float + default: 5.0 + min: 2 + max: 100 + unit: m + decimal: 1 + EKF2_REQ_SACC: + description: + short: Required speed accuracy to use GPS + type: float + default: 0.5 + min: 0.5 + max: 5.0 + unit: m/s + decimal: 2 + EKF2_REQ_NSATS: + description: + short: Required satellite count to use GPS + type: int32 + default: 6 + min: 4 + max: 12 + EKF2_REQ_PDOP: + description: + short: Maximum PDOP to use GPS + type: float + default: 2.5 + min: 1.5 + max: 5.0 + decimal: 1 + EKF2_REQ_HDRIFT: + description: + short: Maximum horizontal drift speed to use GPS + type: float + default: 0.1 + min: 0.1 + max: 1.0 + unit: m/s + decimal: 2 + EKF2_REQ_VDRIFT: + description: + short: Maximum vertical drift speed to use GPS + type: float + default: 0.2 + min: 0.1 + max: 1.5 + decimal: 2 + unit: m/s + EKF2_REQ_GPS_H: + description: + short: Required GPS health time on startup + long: Minimum continuous period without GPS failure required to mark a healthy + GPS status. It can be reduced to speed up initialization, but it's recommended + to keep this unchanged for a vehicle. + type: float + default: 10.0 + min: 0.1 + decimal: 1 + unit: s + reboot_required: true + EKF2_GSF_TAS: + description: + short: Default value of true airspeed used in EKF-GSF AHRS calculation + long: If no airspeed measurements are available, the EKF-GSF AHRS calculation + will assume this value of true airspeed when compensating for centripetal + acceleration during turns. Set to zero to disable centripetal acceleration + compensation during fixed wing flight modes. + type: float + default: 15.0 + min: 0.0 + unit: m/s + max: 100.0 + decimal: 1 diff --git a/src/modules/ekf2/params_gravity.yaml b/src/modules/ekf2/params_gravity.yaml new file mode 100644 index 000000000000..916536c4c4ad --- /dev/null +++ b/src/modules/ekf2/params_gravity.yaml @@ -0,0 +1,13 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_GRAV_NOISE: + description: + short: Accelerometer measurement noise for gravity based observations + type: float + default: 1.0 + min: 0.1 + max: 10.0 + unit: g0 + decimal: 2 diff --git a/src/modules/ekf2/params_magnetometer.yaml b/src/modules/ekf2/params_magnetometer.yaml new file mode 100644 index 000000000000..1790d113db4b --- /dev/null +++ b/src/modules/ekf2/params_magnetometer.yaml @@ -0,0 +1,153 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_MAG_TYPE: + description: + short: Type of magnetometer fusion + long: Integer controlling the type of magnetometer fusion used - magnetic + heading or 3-component vector. The fusion of magnetometer data as a three + component vector enables vehicle body fixed hard iron errors to be learned, + but requires a stable earth field. If set to 'Automatic' magnetic heading + fusion is used when on-ground and 3-axis magnetic field fusion in-flight. + If set to 'Magnetic heading' magnetic heading fusion is used at all times. + If set to 'None' the magnetometer will not be used under any circumstance. + If no external source of yaw is available, it is possible to use post-takeoff + horizontal movement combined with GNSS velocity measurements to align the yaw angle. + If set to 'Init' the magnetometer is only used to initalize the heading. + type: enum + values: + 0: Automatic + 1: Magnetic heading + 5: None + 6: Init + default: 0 + reboot_required: true + EKF2_MAG_DELAY: + description: + short: Magnetometer measurement delay relative to IMU measurements + type: float + default: 0 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_MAG_GATE: + description: + short: Gate size for magnetometer XYZ component fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 3.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_MAG_NOISE: + description: + short: Measurement noise for magnetometer 3-axis fusion + type: float + default: 0.05 + min: 0.001 + max: 1.0 + unit: gauss + decimal: 3 + EKF2_MAG_B_NOISE: + description: + short: Process noise for body magnetic field prediction + type: float + default: 0.0001 + min: 0.0 + max: 0.1 + unit: gauss/s + decimal: 6 + EKF2_MAG_E_NOISE: + description: + short: Process noise for earth magnetic field prediction + type: float + default: 0.001 + min: 0.0 + max: 0.1 + unit: gauss/s + decimal: 6 + EKF2_DECL_TYPE: + description: + short: Integer bitmask controlling handling of magnetic declination + long: 'Set bits in the following positions to enable functions. 0 : Set to + true to use the declination from the geo_lookup library when the GPS position + becomes available, set to false to always use the EKF2_MAG_DECL value. 1 + : Set to true to save the EKF2_MAG_DECL parameter to the value returned + by the EKF when the vehicle disarms.' + type: bitmask + bit: + 0: use geo_lookup declination + 1: save EKF2_MAG_DECL on disarm + default: 3 + min: 0 + max: 3 + reboot_required: true + EKF2_MAG_ACCLIM: + description: + short: Horizontal acceleration threshold used for heading observability check + long: The heading is assumed to be observable when the body acceleration is + greater than this parameter when a global position/velocity aiding source + is active. + type: float + default: 0.5 + min: 0.0 + max: 5.0 + unit: m/s^2 + decimal: 2 + EKF2_MAG_CHECK: + description: + short: Magnetic field strength test selection + long: 'Bitmask to set which check is used to decide whether the magnetometer + data is valid. If GNSS data is received, the magnetic field is compared + to a World Magnetic Model (WMM), otherwise an average value is used. This + check is useful to reject occasional hard iron disturbance. Set bits to + 1 to enable checks. Checks enabled by the following bit positions 0 : Magnetic + field strength. Set tolerance using EKF2_MAG_CHK_STR 1 : Magnetic field + inclination. Set tolerance using EKF2_MAG_CHK_INC 2 : Wait for GNSS to find + the theoretical strength and inclination using the WMM' + type: bitmask + bit: + 0: Strength (EKF2_MAG_CHK_STR) + 1: Inclination (EKF2_MAG_CHK_INC) + 2: Wait for WMM + default: 1 + min: 0 + max: 7 + EKF2_MAG_CHK_STR: + description: + short: Magnetic field strength check tolerance + long: Maximum allowed deviation from the expected magnetic field strength + to pass the check. + type: float + default: 0.2 + min: 0.0 + max: 1.0 + unit: gauss + decimal: 2 + EKF2_MAG_CHK_INC: + description: + short: Magnetic field inclination check tolerance + long: Maximum allowed deviation from the expected magnetic field inclination + to pass the check. + type: float + default: 20.0 + min: 0.0 + max: 90.0 + unit: deg + decimal: 1 + EKF2_SYNT_MAG_Z: + description: + short: Enable synthetic magnetometer Z component measurement + long: Use for vehicles where the measured body Z magnetic field is subject + to strong magnetic interference. For magnetic heading fusion the magnetometer + Z measurement will be replaced by a synthetic value calculated using the + knowledge of the 3D magnetic field vector at the location of the drone. + Therefore, this parameter will only have an effect if the global position + of the drone is known. For 3D mag fusion the magnetometer Z measurement + will simply be ignored instead of fusing the synthetic value. + type: boolean + default: 0 diff --git a/src/modules/ekf2/params_optical_flow.yaml b/src/modules/ekf2/params_optical_flow.yaml new file mode 100644 index 000000000000..961b6a03dbb6 --- /dev/null +++ b/src/modules/ekf2/params_optical_flow.yaml @@ -0,0 +1,103 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_OF_CTRL: + description: + short: Optical flow aiding + long: Enable optical flow fusion. + type: boolean + default: 1 + EKF2_OF_DELAY: + description: + short: Optical flow measurement delay relative to IMU measurements + long: Assumes measurement is timestamped at trailing edge of integration period + type: float + default: 20 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_OF_GATE: + description: + short: Gate size for optical flow fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 3.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_OF_N_MIN: + description: + short: Optical flow minimum noise + long: Measurement noise for the optical flow sensor when it's reported quality + metric is at the maximum + type: float + default: 0.15 + min: 0.05 + unit: rad/s + decimal: 2 + EKF2_OF_N_MAX: + description: + short: Optical flow maximum noise + long: Measurement noise for the optical flow sensor when it's reported quality + metric is at the minimum + type: float + default: 0.5 + min: 0.05 + unit: rad/s + decimal: 2 + EKF2_OF_QMIN: + description: + short: In air optical flow minimum quality + long: Optical Flow data will only be used in air if the sensor reports a + quality metric >= EKF2_OF_QMIN + type: int32 + default: 1 + min: 0 + max: 255 + EKF2_OF_QMIN_GND: + description: + short: On ground optical flow minimum quality + long: Optical Flow data will only be used on the ground if the sensor reports + a quality metric >= EKF2_OF_QMIN_GND + type: int32 + default: 0 + min: 0 + max: 255 + EKF2_OF_GYR_SRC: + description: + short: Optical flow angular rate compensation source + long: 'Auto: use gyro from optical flow message if available, internal gyro otherwise. + Internal: always use internal gyro' + type: enum + values: + 0: Auto + 1: Internal + default: 0 + EKF2_OF_POS_X: + description: + short: X position of optical flow focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_OF_POS_Y: + description: + short: Y position of optical flow focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_OF_POS_Z: + description: + short: Z position of optical flow focal point in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 diff --git a/src/modules/ekf2/params_range_finder.yaml b/src/modules/ekf2/params_range_finder.yaml new file mode 100644 index 000000000000..5baa4fb26775 --- /dev/null +++ b/src/modules/ekf2/params_range_finder.yaml @@ -0,0 +1,152 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_RNG_CTRL: + description: + short: Range sensor height aiding + long: 'WARNING: Range finder measurements are less reliable and can experience + unexpected errors. For these reasons, if accurate control of height relative + to ground is required, it is recommended to use the MPC_ALT_MODE parameter + instead, unless baro errors are severe enough to cause problems with landing + and takeoff. If this parameter is enabled then the estimator + will make use of the range finder measurements to estimate its height in + addition to other height sources (if activated). Range sensor aiding can + be enabled (i.e.: always use) or set in "conditional" mode. Conditional + mode: This enables the range finder to be used during low speed (< EKF2_RNG_A_VMAX) + and low altitude (< EKF2_RNG_A_HMAX) operation, eg takeoff and landing, + where baro interference from rotor wash is excessive and can corrupt EKF + state estimates. It is intended to be used where a vertical takeoff and + landing is performed, and horizontal flight does not occur until above EKF2_RNG_A_HMAX.' + type: enum + values: + 0: Disable range fusion + 1: Enabled (conditional mode) + 2: Enabled + default: 1 + EKF2_RNG_DELAY: + description: + short: Range finder measurement delay relative to IMU measurements + type: float + default: 5 + min: 0 + max: 300 + unit: ms + reboot_required: true + decimal: 1 + EKF2_RNG_GATE: + description: + short: Gate size for range finder fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_RNG_NOISE: + description: + short: Measurement noise for range finder fusion + type: float + default: 0.1 + min: 0.01 + unit: m + decimal: 2 + EKF2_RNG_PITCH: + description: + short: Range sensor pitch offset + type: float + default: 0.0 + min: -0.75 + max: 0.75 + unit: rad + decimal: 3 + EKF2_RNG_A_VMAX: + description: + short: Maximum horizontal velocity allowed for conditional range aid mode + long: If the vehicle horizontal speed exceeds this value then the estimator + will not fuse range measurements to estimate its height. This only applies + when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). + type: float + default: 1.0 + min: 0.1 + max: 2 + unit: m/s + EKF2_RNG_A_HMAX: + description: + short: Maximum height above ground allowed for conditional range aid mode + long: If the vehicle absolute altitude exceeds this value then the estimator + will not fuse range measurements to estimate its height. This only applies + when conditional range aid mode is activated (EKF2_RNG_CTRL = 1). + type: float + default: 5.0 + min: 1.0 + max: 10.0 + unit: m + EKF2_RNG_A_IGATE: + description: + short: Gate size used for innovation consistency checks for range aid fusion + long: A lower value means HAGL needs to be more stable in order to use range + finder for height estimation in range aid mode + type: float + default: 1.0 + unit: SD + min: 0.1 + max: 5.0 + EKF2_RNG_QLTY_T: + description: + short: Minumum range validity period + long: Minimum duration during which the reported range finder signal quality + needs to be non-zero in order to be declared valid (s) + type: float + default: 1.0 + unit: s + min: 0.1 + max: 5 + EKF2_RNG_K_GATE: + description: + short: Gate size used for range finder kinematic consistency check + long: 'To be used, the time derivative of the distance sensor measurements + projected on the vertical axis needs to be statistically consistent with + the estimated vertical velocity of the drone. Decrease this value to make + the filter more robust against range finder faulty data (stuck, reflections, + ...). Note: tune the range finder noise parameters (EKF2_RNG_NOISE and EKF2_RNG_SFE) + before tuning this gate.' + type: float + default: 1.0 + unit: SD + min: 0.1 + max: 5.0 + EKF2_RNG_SFE: + description: + short: Range finder range dependent noise scaler + long: Specifies the increase in range finder noise with range. + type: float + default: 0.05 + min: 0.0 + max: 0.2 + unit: m/m + EKF2_RNG_POS_X: + description: + short: X position of range finder origin in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_RNG_POS_Y: + description: + short: Y position of range finder origin in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 + EKF2_RNG_POS_Z: + description: + short: Z position of range finder origin in body frame + long: Forward axis with origin relative to vehicle centre of gravity + type: float + default: 0.0 + unit: m + decimal: 3 diff --git a/src/modules/ekf2/params_sideslip.yaml b/src/modules/ekf2/params_sideslip.yaml new file mode 100644 index 000000000000..49d5467fccb7 --- /dev/null +++ b/src/modules/ekf2/params_sideslip.yaml @@ -0,0 +1,32 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_FUSE_BETA: + description: + short: Enable synthetic sideslip fusion + long: 'For reliable wind estimation both sideslip and airspeed fusion (see + EKF2_ARSP_THR) should be enabled. Only applies to fixed-wing vehicles (or + VTOLs in fixed-wing mode). Note: side slip fusion is currently not supported + for tailsitters.' + type: boolean + default: 0 + EKF2_BETA_GATE: + description: + short: Gate size for synthetic sideslip fusion + long: Sets the number of standard deviations used by the innovation consistency + test. + type: float + default: 5.0 + min: 1.0 + unit: SD + decimal: 1 + EKF2_BETA_NOISE: + description: + short: Noise for synthetic sideslip fusion + type: float + default: 0.3 + min: 0.1 + max: 1.0 + unit: m/s + decimal: 2 diff --git a/src/modules/ekf2/params_terrain.yaml b/src/modules/ekf2/params_terrain.yaml new file mode 100644 index 000000000000..5fc361c5cd65 --- /dev/null +++ b/src/modules/ekf2/params_terrain.yaml @@ -0,0 +1,34 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_TERR_NOISE: + description: + short: Terrain altitude process noise + type: float + default: 5.0 + min: 0.5 + unit: m/s + decimal: 1 + EKF2_TERR_GRAD: + description: + short: Magnitude of terrain gradient + type: float + default: 0.5 + min: 0.0 + unit: m/m + decimal: 2 + EKF2_MIN_RNG: + description: + short: Expected range finder reading when on ground + long: If the vehicle is on ground, is not moving as determined by the motion + test and the range finder is returning invalid or no data, then an assumed + range value of EKF2_MIN_RNG will be used by the terrain estimator so that + a terrain height estimate is available at the start of flight in situations + where the range finder may be inside its minimum measurements distance when + on ground. + type: float + default: 0.1 + min: 0.01 + unit: m + decimal: 2 diff --git a/src/modules/ekf2/params_wind.yaml b/src/modules/ekf2/params_wind.yaml new file mode 100644 index 000000000000..7e4f7578d024 --- /dev/null +++ b/src/modules/ekf2/params_wind.yaml @@ -0,0 +1,15 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_WIND_NSD: + description: + short: Process noise spectral density for wind velocity prediction + long: When unaided, the wind estimate uncertainty (1-sigma, in m/s) increases + by this amount every second. + type: float + default: 0.05 + min: 0.0 + max: 1.0 + unit: m/s^2/sqrt(Hz) + decimal: 3 From 7250ee1b32699c631eeaaea0e86677b8b6451c2c Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Wed, 21 Aug 2024 14:30:15 -0400 Subject: [PATCH 10/87] ekf2: organize gyro_bias/accel_bias param yaml --- src/modules/ekf2/CMakeLists.txt | 2 + src/modules/ekf2/module.yaml | 227 +++++++----------------- src/modules/ekf2/params_accel_bias.yaml | 72 ++++++++ src/modules/ekf2/params_gyro_bias.yaml | 34 ++++ 4 files changed, 173 insertions(+), 162 deletions(-) create mode 100644 src/modules/ekf2/params_accel_bias.yaml create mode 100644 src/modules/ekf2/params_gyro_bias.yaml diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index 52a3c02806df..62e6f2910330 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -262,6 +262,8 @@ px4_add_module( MODULE_CONFIG module.yaml + params_gyro_bias.yaml + params_accel_bias.yaml params_multi.yaml params_volatile.yaml params_selector.yaml diff --git a/src/modules/ekf2/module.yaml b/src/modules/ekf2/module.yaml index e1eeab881a17..da68460445a8 100644 --- a/src/modules/ekf2/module.yaml +++ b/src/modules/ekf2/module.yaml @@ -7,6 +7,11 @@ parameters: short: EKF2 enable type: boolean default: 1 + EKF2_LOG_VERBOSE: + description: + short: Verbose logging + type: boolean + default: 1 EKF2_PREDICT_US: description: short: EKF prediction period @@ -18,17 +23,6 @@ parameters: min: 1000 max: 20000 unit: us - EKF2_IMU_CTRL: - description: - short: IMU control - type: bitmask - bit: - 0: Gyro Bias - 1: Accel Bias - 2: Gravity vector fusion - default: 7 - min: 0 - max: 7 EKF2_DELAY_MAX: description: short: Maximum delay of all the aiding sensors @@ -41,50 +35,25 @@ parameters: unit: ms reboot_required: true decimal: 1 - EKF2_GYR_NOISE: - description: - short: Rate gyro noise for covariance prediction - type: float - default: 0.015 - min: 0.0001 - max: 0.1 - unit: rad/s - decimal: 4 - EKF2_ACC_NOISE: - description: - short: Accelerometer noise for covariance prediction - type: float - default: 0.35 - min: 0.01 - max: 1.0 - unit: m/s^2 - decimal: 2 - EKF2_GYR_B_NOISE: - description: - short: Process noise for IMU rate gyro bias prediction - type: float - default: 0.001 - min: 0.0 - max: 0.01 - unit: rad/s^2 - decimal: 6 - EKF2_ACC_B_NOISE: + EKF2_ANGERR_INIT: description: - short: Process noise for IMU accelerometer bias prediction + short: 1-sigma tilt angle uncertainty after gravity vector alignment type: float - default: 0.003 + default: 0.1 min: 0.0 - max: 0.01 - unit: m/s^3 - decimal: 6 - EKF2_NOAID_NOISE: + max: 0.5 + unit: rad + reboot_required: true + decimal: 3 + EKF2_HDG_GATE: description: - short: Measurement noise for non-aiding position hold + short: Gate size for heading fusion + long: Sets the number of standard deviations used by the innovation consistency + test. type: float - default: 10.0 - min: 0.5 - max: 50.0 - unit: m + default: 2.6 + min: 1.0 + unit: SD decimal: 1 EKF2_HEAD_NOISE: description: @@ -95,16 +64,26 @@ parameters: max: 1.0 unit: rad decimal: 2 - EKF2_HDG_GATE: + EKF2_NOAID_NOISE: description: - short: Gate size for heading fusion - long: Sets the number of standard deviations used by the innovation consistency - test. + short: Measurement noise for non-aiding position hold type: float - default: 2.6 - min: 1.0 - unit: SD + default: 10.0 + min: 0.5 + max: 50.0 + unit: m decimal: 1 + EKF2_NOAID_TOUT: + description: + short: Maximum inertial dead-reckoning time + long: Maximum lapsed time from last fusion of measurements that constrain + velocity drift before the EKF will report the horizontal nav solution as + invalid + type: int32 + default: 5000000 + min: 500000 + max: 10000000 + unit: us EKF2_HGT_REF: description: short: Determines the reference source of height data used by the EKF @@ -121,17 +100,35 @@ parameters: 3: Vision default: 1 reboot_required: true - EKF2_NOAID_TOUT: + EKF2_IMU_CTRL: description: - short: Maximum inertial dead-reckoning time - long: Maximum lapsed time from last fusion of measurements that constrain - velocity drift before the EKF will report the horizontal nav solution as - invalid - type: int32 - default: 5000000 - min: 500000 - max: 10000000 - unit: us + short: IMU control + type: bitmask + bit: + 0: Gyro Bias + 1: Accel Bias + 2: Gravity vector fusion + default: 7 + min: 0 + max: 7 + EKF2_GYR_NOISE: + description: + short: Rate gyro noise for covariance prediction + type: float + default: 0.015 + min: 0.0001 + max: 0.1 + unit: rad/s + decimal: 4 + EKF2_ACC_NOISE: + description: + short: Accelerometer noise for covariance prediction + type: float + default: 0.35 + min: 0.01 + max: 1.0 + unit: m/s^2 + decimal: 2 EKF2_IMU_POS_X: description: short: X position of IMU in body frame @@ -156,6 +153,7 @@ parameters: default: 0.0 unit: m decimal: 3 + EKF2_TAU_VEL: description: short: Time constant of the velocity output prediction and smoothing filter @@ -174,98 +172,3 @@ parameters: max: 1.0 unit: s decimal: 2 - EKF2_GBIAS_INIT: - description: - short: 1-sigma IMU gyro switch-on bias - type: float - default: 0.1 - min: 0.0 - max: 0.2 - unit: rad/s - reboot_required: true - decimal: 2 - EKF2_ABIAS_INIT: - description: - short: 1-sigma IMU accelerometer switch-on bias - type: float - default: 0.2 - min: 0.0 - max: 0.5 - unit: m/s^2 - reboot_required: true - decimal: 2 - EKF2_ANGERR_INIT: - description: - short: 1-sigma tilt angle uncertainty after gravity vector alignment - type: float - default: 0.1 - min: 0.0 - max: 0.5 - unit: rad - reboot_required: true - decimal: 3 - EKF2_ABL_LIM: - description: - short: Accelerometer bias learning limit - long: The ekf accel bias states will be limited to within a range equivalent - to +- of this value. - type: float - default: 0.4 - min: 0.0 - max: 0.8 - unit: m/s^2 - decimal: 2 - EKF2_ABL_ACCLIM: - description: - short: Maximum IMU accel magnitude that allows IMU bias learning - long: If the magnitude of the IMU accelerometer vector exceeds this value, - the EKF accel bias state estimation will be inhibited. This reduces the - adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale - factor errors on the accel bias estimates. - type: float - default: 25.0 - min: 20.0 - max: 200.0 - unit: m/s^2 - decimal: 1 - EKF2_ABL_GYRLIM: - description: - short: Maximum IMU gyro angular rate magnitude that allows IMU bias learning - long: If the magnitude of the IMU angular rate vector exceeds this value, - the EKF accel bias state estimation will be inhibited. This reduces the - adverse effect of rapid rotation rates and associated errors on the accel - bias estimates. - type: float - default: 3.0 - min: 2.0 - max: 20.0 - unit: rad/s - decimal: 1 - EKF2_ABL_TAU: - description: - short: Accel bias learning inhibit time constant - long: The vector magnitude of angular rate and acceleration used to check - if learning should be inhibited has a peak hold filter applied to it with - an exponential decay. This parameter controls the time constant of the decay. - type: float - default: 0.5 - min: 0.1 - max: 1.0 - unit: s - decimal: 2 - EKF2_GYR_B_LIM: - description: - short: Gyro bias learning limit - long: The ekf gyro bias states will be limited to within a range equivalent - to +- of this value. - type: float - default: 0.15 - min: 0.0 - max: 0.4 - unit: rad/s - decimal: 3 - EKF2_LOG_VERBOSE: - description: - short: Verbose logging - type: boolean - default: 1 diff --git a/src/modules/ekf2/params_accel_bias.yaml b/src/modules/ekf2/params_accel_bias.yaml new file mode 100644 index 000000000000..22989ae9e1de --- /dev/null +++ b/src/modules/ekf2/params_accel_bias.yaml @@ -0,0 +1,72 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_ABIAS_INIT: + description: + short: 1-sigma IMU accelerometer switch-on bias + type: float + default: 0.2 + min: 0.0 + max: 0.5 + unit: m/s^2 + reboot_required: true + decimal: 2 + EKF2_ACC_B_NOISE: + description: + short: Process noise for IMU accelerometer bias prediction + type: float + default: 0.003 + min: 0.0 + max: 0.01 + unit: m/s^3 + decimal: 6 + EKF2_ABL_LIM: + description: + short: Accelerometer bias learning limit + long: The ekf accel bias states will be limited to within a range equivalent + to +- of this value. + type: float + default: 0.4 + min: 0.0 + max: 0.8 + unit: m/s^2 + decimal: 2 + EKF2_ABL_ACCLIM: + description: + short: Maximum IMU accel magnitude that allows IMU bias learning + long: If the magnitude of the IMU accelerometer vector exceeds this value, + the EKF accel bias state estimation will be inhibited. This reduces the + adverse effect of high manoeuvre accelerations and IMU nonlinerity and scale + factor errors on the accel bias estimates. + type: float + default: 25.0 + min: 20.0 + max: 200.0 + unit: m/s^2 + decimal: 1 + EKF2_ABL_GYRLIM: + description: + short: Maximum IMU gyro angular rate magnitude that allows IMU bias learning + long: If the magnitude of the IMU angular rate vector exceeds this value, + the EKF accel bias state estimation will be inhibited. This reduces the + adverse effect of rapid rotation rates and associated errors on the accel + bias estimates. + type: float + default: 3.0 + min: 2.0 + max: 20.0 + unit: rad/s + decimal: 1 + EKF2_ABL_TAU: + description: + short: Accel bias learning inhibit time constant + long: The vector magnitude of angular rate and acceleration used to check + if learning should be inhibited has a peak hold filter applied to it with + an exponential decay. This parameter controls the time constant of the decay. + type: float + default: 0.5 + min: 0.1 + max: 1.0 + unit: s + decimal: 2 diff --git a/src/modules/ekf2/params_gyro_bias.yaml b/src/modules/ekf2/params_gyro_bias.yaml new file mode 100644 index 000000000000..dcb1f36b65f9 --- /dev/null +++ b/src/modules/ekf2/params_gyro_bias.yaml @@ -0,0 +1,34 @@ +module_name: ekf2 +parameters: +- group: EKF2 + definitions: + EKF2_GBIAS_INIT: + description: + short: 1-sigma IMU gyro switch-on bias + type: float + default: 0.1 + min: 0.0 + max: 0.2 + unit: rad/s + reboot_required: true + decimal: 2 + EKF2_GYR_B_NOISE: + description: + short: Process noise for IMU rate gyro bias prediction + type: float + default: 0.001 + min: 0.0 + max: 0.01 + unit: rad/s^2 + decimal: 6 + EKF2_GYR_B_LIM: + description: + short: Gyro bias learning limit + long: The ekf gyro bias states will be limited to within a range equivalent + to +- of this value. + type: float + default: 0.15 + min: 0.0 + max: 0.4 + unit: rad/s + decimal: 3 From d617bf4129b5472565f7803af7d751b0240b2691 Mon Sep 17 00:00:00 2001 From: Jaeyoung Lim Date: Thu, 22 Aug 2024 17:48:46 +0200 Subject: [PATCH 11/87] simulation/gz_bridge: Fix build issues with unused variable --- src/modules/simulation/gz_bridge/GZBridge.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index f7d80d32cac6..7b45600e57fb 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -169,7 +169,7 @@ int GZBridge::init() gz::msgs::StringMsg follow_msg{}; follow_msg.set_data(_model_name); - bool call_string_service = callStringMsgService("/gui/follow", follow_msg); + callStringMsgService("/gui/follow", follow_msg); gz::msgs::Vector3d follow_offset_msg{}; follow_offset_msg.set_x(-2.0); follow_offset_msg.set_y(-2.0); From 7f33dcfcfb1cbfad21790ec70e4b526737f2762b Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 21 Aug 2024 10:03:23 -0700 Subject: [PATCH 12/87] ci: upgrade sitl mavsdk tests workflow --- .github/workflows/sitl_tests.yml | 243 ++++++++++++++++--------------- 1 file changed, 129 insertions(+), 114 deletions(-) diff --git a/.github/workflows/sitl_tests.yml b/.github/workflows/sitl_tests.yml index 3282c797c5f7..58f35f3437a1 100644 --- a/.github/workflows/sitl_tests.yml +++ b/.github/workflows/sitl_tests.yml @@ -10,126 +10,141 @@ on: jobs: build: - runs-on: ubuntu-latest + name: Testing PX4 ${{ matrix.config.model }} + runs-on: [runs-on,runner=16cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}"] + # outputs: + # timestamp: ${{ steps.set-timestamp.outputs.timestamp }} + container: + image: px4io/px4-dev-simulation-focal:2021-09-08 + options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined strategy: fail-fast: false matrix: config: - {model: "iris", latitude: "59.617693", longitude: "-151.145316", altitude: "48", build_type: "RelWithDebInfo" } # Alaska - # - {model: "standard_vtol", latitude: "-38.071235", longitude: "145.281220", altitude: "31", build_type: "AddressSanitizer" } # Australia - {model: "tailsitter" , latitude: "29.660316", longitude: "-82.316658", altitude: "30", build_type: "RelWithDebInfo" } # Florida - {model: "standard_vtol", latitude: "47.397742", longitude: "8.545594", altitude: "488", build_type: "Coverage" } # Zurich - container: - image: px4io/px4-dev-simulation-focal:2021-09-08 - options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined steps: - - uses: actions/checkout@v1 - with: - token: ${{ secrets.ACCESS_TOKEN }} - - - name: Download MAVSDK - run: wget "https://github.com/mavlink/MAVSDK/releases/download/v$(cat test/mavsdk_tests/MAVSDK_VERSION)/libmavsdk-dev_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb" - - name: Install MAVSDK - run: dpkg -i "libmavsdk-dev_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb" - - - name: Prepare ccache timestamp - id: ccache_cache_timestamp - shell: cmake -P {0} - run: | - string(TIMESTAMP current_date "%Y-%m-%d-%H;%M;%S" UTC) - message("::set-output name=timestamp::${current_date}") - - name: ccache cache files - uses: actions/cache@v2 - with: - path: ~/.ccache - key: sitl_tests-${{matrix.config.build_type}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} - restore-keys: sitl_tests-${{matrix.config.build_type}}-ccache- - - name: setup ccache - run: | - mkdir -p ~/.ccache - echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf - echo "compression = true" >> ~/.ccache/ccache.conf - echo "compression_level = 6" >> ~/.ccache/ccache.conf - echo "max_size = 100M" >> ~/.ccache/ccache.conf - echo "hash_dir = false" >> ~/.ccache/ccache.conf - ccache -s - ccache -z - - - name: check environment - env: - PX4_HOME_LAT: ${{matrix.config.latitude}} - PX4_HOME_LON: ${{matrix.config.longitude}} - PX4_HOME_ALT: ${{matrix.config.altitude}} - PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} - run: | - export - ulimit -a - - name: Build PX4 - env: - PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} - run: make px4_sitl_default - - name: ccache post-run px4/firmware - run: ccache -s - - name: Build SITL Gazebo - env: - PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} - run: make px4_sitl_default sitl_gazebo-classic - - name: ccache post-run sitl_gazebo-classic - run: ccache -s - - name: Build MAVSDK tests - env: - PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} - DONT_RUN: 1 - run: make px4_sitl_default sitl_gazebo-classic mavsdk_tests - - name: ccache post-run mavsdk_tests - run: ccache -s - - - name: Core dump settings - run: | - ulimit -c unlimited - echo "`pwd`/%e.core" > /proc/sys/kernel/core_pattern - - - name: Run SITL tests - env: - PX4_HOME_LAT: ${{matrix.config.latitude}} - PX4_HOME_LON: ${{matrix.config.longitude}} - PX4_HOME_ALT: ${{matrix.config.altitude}} - PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} - run: test/mavsdk_tests/mavsdk_test_runner.py --speed-factor 20 --abort-early --model ${{matrix.config.model}} --upload test/mavsdk_tests/configs/sitl.json --verbose - timeout-minutes: 45 - - - name: Look at core files - if: failure() - 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 - with: - name: coredump - path: px4.core - - - name: Upload px4 binary - if: failure() - uses: actions/upload-artifact@v2-preview - with: - name: binary - path: build/px4_sitl_default/bin/px4 - - # Report test coverage - - name: Upload coverage - if: contains(matrix.config.build_type, 'Coverage') - run: | - git config --global credential.helper "" # disable the keychain credential helper - git config --global --add credential.helper store # enable the local store credential helper - echo "https://x-access-token:${{ secrets.ACCESS_TOKEN }}@github.com" >> ~/.git-credentials # add credential - git config --global url."https://github.com/".insteadof git@github.com: # credentials add credential - mkdir -p coverage - lcov --directory build/px4_sitl_default --base-directory build/px4_sitl_default --gcov-tool gcov --capture -o coverage/lcov.info - - name: Upload coverage information to Codecov - if: contains(matrix.config.build_type, 'Coverage') - uses: codecov/codecov-action@v1 - with: - token: ${{ secrets.CODECOV_TOKEN }} - flags: mavsdk - file: coverage/lcov.info + - uses: actions/checkout@v4 + with: + fetch-depth: 0 + + - name: Git Ownership Workaround + run: git config --system --add safe.directory '*' + + - id: set-timestamp + name: Set timestamp for cache + run: echo "::set-output name=timestamp::$(date +"%Y%m%d%H%M%S")" + + - name: Cache Key Config + uses: actions/cache@v4 + with: + path: ~/.ccache + key: sitl-ccache-${{ steps.set-timestamp.outputs.timestamp }} + restore-keys: sitl-ccache-${{ steps.set-timestamp.outputs.timestamp }} + + - name: Cache Conf Config + run: | + mkdir -p ~/.ccache + echo "base_dir = ${GITHUB_WORKSPACE}" > ~/.ccache/ccache.conf + echo "compression = true" >> ~/.ccache/ccache.conf + echo "compression_level = 6" >> ~/.ccache/ccache.conf + echo "max_size = 120M" >> ~/.ccache/ccache.conf + echo "hash_dir = false" >> ~/.ccache/ccache.conf + ccache -s + ccache -z + + - name: Build PX4 + env: + PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} + run: make px4_sitl_default + + - name: Cache Post-Run [px4_sitl_default] + run: ccache -s + + - name: Build SITL Gazebo + env: + PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} + run: make px4_sitl_default sitl_gazebo-classic + + - name: Cache Post-Run [sitl_gazebo-classic] + run: ccache -s + + - name: Download MAVSDK + run: wget "https://github.com/mavlink/MAVSDK/releases/download/v$(cat test/mavsdk_tests/MAVSDK_VERSION)/libmavsdk-dev_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb" + + - name: Install MAVSDK + run: dpkg -i "libmavsdk-dev_$(cat test/mavsdk_tests/MAVSDK_VERSION)_ubuntu20.04_amd64.deb" + + - name: Check PX4 Environment Variables + env: + PX4_HOME_LAT: ${{matrix.config.latitude}} + PX4_HOME_LON: ${{matrix.config.longitude}} + PX4_HOME_ALT: ${{matrix.config.altitude}} + PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} + run: | + export + ulimit -a + + - name: Build PX4 / MAVSDK tests + env: + PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} + DONT_RUN: 1 + run: make px4_sitl_default sitl_gazebo-classic mavsdk_tests + + - name: Cache Post-Run [px4_sitl_default sitl_gazebo-classic mavsdk_tests] + run: ccache -s + + - name: Core Dump Settings + run: | + ulimit -c unlimited + echo "`pwd`/%e.core" > /proc/sys/kernel/core_pattern + + - name: Run SITL / MAVSDK Tests + env: + PX4_HOME_LAT: ${{matrix.config.latitude}} + PX4_HOME_LON: ${{matrix.config.longitude}} + PX4_HOME_ALT: ${{matrix.config.altitude}} + PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} + run: test/mavsdk_tests/mavsdk_test_runner.py --speed-factor 20 --abort-early --model ${{matrix.config.model}} --upload test/mavsdk_tests/configs/sitl.json --verbose + timeout-minutes: 45 + + - name: Upload failed logs + if: failure() + uses: actions/upload-artifact@v4 + with: + name: failed-${{matrix.config.model}}-logs.zip + path: | + logs/**/**/**/*.log + logs/**/**/**/*.ulg + build/px4_sitl_default/tmp_mavsdk_tests/rootfs/*.ulg + + - name: Look at Core files + if: failure() && ${{ hashFiles('px4.core') != '' }} + run: gdb build/px4_sitl_default/bin/px4 px4.core -ex "thread apply all bt" -ex "quit" + + - name: Upload PX4 coredump + if: failure() && ${{ hashFiles('px4.core') != '' }} + uses: actions/upload-artifact@v4 + with: + name: coredump + path: px4.core + + - name: Setup & Generate Coverage Report + if: contains(matrix.config.build_type, 'Coverage') + run: | + git config --global credential.helper "" # disable the keychain credential helper + git config --global --add credential.helper store # enable the local store credential helper + echo "https://x-access-token:${{ secrets.ACCESS_TOKEN }}@github.com" >> ~/.git-credentials # add credential + git config --global url."https://github.com/".insteadof git@github.com: # credentials add credential + mkdir -p coverage + lcov --directory build/px4_sitl_default --base-directory build/px4_sitl_default --gcov-tool gcov --capture -o coverage/lcov.info + + - name: Upload Coverage Information to Codecov + if: contains(matrix.config.build_type, 'Coverage') + uses: codecov/codecov-action@v4 + with: + token: ${{ secrets.CODECOV_TOKEN }} + flags: mavsdk + file: coverage/lcov.info From 89f29e91de5d9f1d8ffb40b7506b6a6f2a0a76dc Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 21 Aug 2024 10:33:26 -0700 Subject: [PATCH 13/87] ci: slow down sitl test realtime --- .github/workflows/sitl_tests.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/sitl_tests.yml b/.github/workflows/sitl_tests.yml index 58f35f3437a1..638fb37d5ce5 100644 --- a/.github/workflows/sitl_tests.yml +++ b/.github/workflows/sitl_tests.yml @@ -107,7 +107,7 @@ jobs: PX4_HOME_LON: ${{matrix.config.longitude}} PX4_HOME_ALT: ${{matrix.config.altitude}} PX4_CMAKE_BUILD_TYPE: ${{matrix.config.build_type}} - run: test/mavsdk_tests/mavsdk_test_runner.py --speed-factor 20 --abort-early --model ${{matrix.config.model}} --upload test/mavsdk_tests/configs/sitl.json --verbose + run: test/mavsdk_tests/mavsdk_test_runner.py --speed-factor 10 --abort-early --model ${{matrix.config.model}} --upload test/mavsdk_tests/configs/sitl.json --verbose timeout-minutes: 45 - name: Upload failed logs From 00c30173348d16f42ef75495bb5a466ccbc67eed Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 21 Aug 2024 10:49:54 -0700 Subject: [PATCH 14/87] ci: add note regarding RunsOn --- .github/workflows/sitl_tests.yml | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/.github/workflows/sitl_tests.yml b/.github/workflows/sitl_tests.yml index 638fb37d5ce5..0492137a4990 100644 --- a/.github/workflows/sitl_tests.yml +++ b/.github/workflows/sitl_tests.yml @@ -1,3 +1,8 @@ +# NOTE: this workflow is now running on Dronecode / PX4 AWS account. +# - If you want to keep the tests running in GitHub Actions you need to uncomment the "runs-on: ubuntu-latest" lines +# and comment the "runs-on: [runs-on,runner=..." lines. +# - If you would like to duplicate this setup try setting up "RunsOn" on your own AWS account try https://runs-on.com + name: SITL Tests on: @@ -12,8 +17,6 @@ jobs: build: name: Testing PX4 ${{ matrix.config.model }} runs-on: [runs-on,runner=16cpu-linux-x64,image=ubuntu22-full-x64,"run-id=${{ github.run_id }}"] - # outputs: - # timestamp: ${{ steps.set-timestamp.outputs.timestamp }} container: image: px4io/px4-dev-simulation-focal:2021-09-08 options: --privileged --ulimit core=-1 --security-opt seccomp=unconfined From b1dfe1d7311a0c113c3b39945c06dee14eac3fc7 Mon Sep 17 00:00:00 2001 From: Jaeyoung Lim Date: Thu, 22 Aug 2024 22:55:06 +0200 Subject: [PATCH 15/87] Update gz version to harmonic --- Tools/setup/ubuntu.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/setup/ubuntu.sh b/Tools/setup/ubuntu.sh index 077cfda56bf1..346e071cdcc1 100755 --- a/Tools/setup/ubuntu.sh +++ b/Tools/setup/ubuntu.sh @@ -233,7 +233,7 @@ if [[ $INSTALL_SIM == "true" ]]; then sudo apt-get update -y --quiet # Install Gazebo - gazebo_packages="gz-garden" + gazebo_packages="gz-harmonic" elif [[ "${UBUNTU_RELEASE}" == "21.3" ]]; then echo "Gazebo (Garden) will be installed" echo "Earlier versions will be removed" From 13c413622b973ef7a959db15414dda8fb4988271 Mon Sep 17 00:00:00 2001 From: jfbblue0922 Date: Thu, 22 Aug 2024 11:27:44 +0900 Subject: [PATCH 16/87] Nuttx with stm32h7: STM32H7X5XX selects hardware files backport --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index 39bb38d82b12..ac2c2c428313 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 39bb38d82b128a57d0ca40c25ba3ad6601ec0a83 +Subproject commit ac2c2c428313823cb6b3e3bcdcd2a95300e19e22 From cf941b18df082366c6968a1da4783d5335186a0e Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Fri, 23 Aug 2024 02:11:15 -0700 Subject: [PATCH 17/87] Nuttx with stm32h7: STM32H7X5XX selects hardware files backport --- platforms/nuttx/NuttX/nuttx | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/NuttX/nuttx b/platforms/nuttx/NuttX/nuttx index ac2c2c428313..d140f96627bd 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit ac2c2c428313823cb6b3e3bcdcd2a95300e19e22 +Subproject commit d140f96627bd55edd24060cb90fe4c55ed3b9efd From 64b0586dad59b9c02a8445c2d7007362c2536fd9 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 19 Aug 2024 10:29:01 +0200 Subject: [PATCH 18/87] ekf2: return validity based on dead-reckoning time only --- src/modules/ekf2/EKF/ekf.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index a7c43567df52..d9ff978e20e7 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -294,17 +294,17 @@ class Ekf final : public EstimatorInterface // return true if the local position estimate is valid bool local_position_is_valid() const { - return (!_horizontal_deadreckon_time_exceeded && !_control_status.flags.fake_pos); + return !_horizontal_deadreckon_time_exceeded; } bool isLocalVerticalPositionValid() const { - return !_vertical_position_deadreckon_time_exceeded && !_control_status.flags.fake_hgt; + return !_vertical_position_deadreckon_time_exceeded; } bool isLocalVerticalVelocityValid() const { - return !_vertical_velocity_deadreckon_time_exceeded && !_control_status.flags.fake_hgt; + return !_vertical_velocity_deadreckon_time_exceeded; } bool isYawFinalAlignComplete() const From 1a0f97ebbd67870d4686ee7ebb6d38e11662eabc Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 19 Aug 2024 15:36:04 +0200 Subject: [PATCH 19/87] ekf2-fake pos: add valid fake position fusion This is similar to fake pos but is only used when the ekf has an external information telling it that the vehicle is not changing position. This information can then be used to keep a valid local position even when the vehicle isn't exactly at rest. --- msg/EstimatorStatusFlags.msg | 2 + .../ekf2/EKF/aid_sources/fake_pos_control.cpp | 98 +++++++------- src/modules/ekf2/EKF/common.h | 3 + src/modules/ekf2/EKF/control.cpp | 2 + src/modules/ekf2/EKF/ekf.h | 2 +- src/modules/ekf2/EKF/ekf_helper.cpp | 10 +- src/modules/ekf2/EKF/estimator_interface.h | 2 + src/modules/ekf2/EKF2.cpp | 11 ++ src/modules/ekf2/EKF2.hpp | 2 + src/modules/ekf2/test/CMakeLists.txt | 1 + .../ekf2/test/sensor_simulator/airspeed.cpp | 17 ++- src/modules/ekf2/test/test_EKF_airspeed.cpp | 4 +- src/modules/ekf2/test/test_EKF_fake_pos.cpp | 121 ++++++++++++++++++ 13 files changed, 215 insertions(+), 60 deletions(-) create mode 100644 src/modules/ekf2/test/test_EKF_fake_pos.cpp diff --git a/msg/EstimatorStatusFlags.msg b/msg/EstimatorStatusFlags.msg index 23e6e15fd48f..79b900f6a8b0 100644 --- a/msg/EstimatorStatusFlags.msg +++ b/msg/EstimatorStatusFlags.msg @@ -45,6 +45,8 @@ bool cs_mag_heading_consistent # 37 - true when the heading obtained from mag d bool cs_aux_gpos # 38 - true if auxiliary global position measurement fusion is intended bool cs_rng_terrain # 39 - true if we are fusing range finder data for terrain bool cs_opt_flow_terrain # 40 - true if we are fusing flow data for terrain +bool cs_valid_fake_pos # 41 - true if a valid constant position is being fused +bool cs_constant_pos # 42 - true if the vehicle is at a constant position # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp index df7257d9b038..b87e14654fb2 100644 --- a/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/fake_pos_control.cpp @@ -75,55 +75,20 @@ void Ekf::controlFakePosFusion() Vector2f(getStateVariance()) + obs_var, // innovation variance innov_gate); // innovation gate - const bool enable_conditions_passing = !isHorizontalAidingActive() - && ((getTiltVariance() > sq(math::radians(3.f))) || _control_status.flags.vehicle_at_rest) - && (!(_params.imu_ctrl & static_cast(ImuCtrl::GravityVector)) || _control_status.flags.vehicle_at_rest) - && _horizontal_deadreckon_time_exceeded; - - if (_control_status.flags.fake_pos) { - if (enable_conditions_passing) { - - // always protect against extreme values that could result in a NaN - if ((aid_src.test_ratio[0] < sq(100.0f / innov_gate)) - && (aid_src.test_ratio[1] < sq(100.0f / innov_gate)) - ) { - if (!aid_src.innovation_rejected - && fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], - State::pos.idx + 0) - && fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], - State::pos.idx + 1) - ) { - aid_src.fused = true; - aid_src.time_last_fuse = _time_delayed_us; - } - } - - const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, (uint64_t)4e5); - - if (is_fusion_failing) { - ECL_WARN("fake position fusion failing, resetting"); - resetFakePosFusion(); - } - - } else { - stopFakePosFusion(); - } - - } else { - if (enable_conditions_passing) { - ECL_INFO("start fake position fusion"); - _control_status.flags.fake_pos = true; - resetFakePosFusion(); + const bool enable_valid_fake_pos = _control_status.flags.constant_pos || _control_status.flags.vehicle_at_rest; + const bool enable_fake_pos = !enable_valid_fake_pos + && (getTiltVariance() > sq(math::radians(3.f))) + && !(_params.imu_ctrl & static_cast(ImuCtrl::GravityVector)) + && _horizontal_deadreckon_time_exceeded; - if (_control_status.flags.tilt_align) { - // The fake position fusion is not started for initial alignement - ECL_WARN("stopping navigation"); - } - } - } + _control_status.flags.fake_pos = runFakePosStateMachine(enable_fake_pos, _control_status.flags.fake_pos, aid_src); + _control_status.flags.valid_fake_pos = runFakePosStateMachine(enable_valid_fake_pos, + _control_status.flags.valid_fake_pos, aid_src); - } else if (_control_status.flags.fake_pos && isHorizontalAidingActive()) { - stopFakePosFusion(); + } else if ((_control_status.flags.fake_pos || _control_status.flags.valid_fake_pos) && isHorizontalAidingActive()) { + ECL_INFO("stop fake position fusion"); + _control_status.flags.fake_pos = false; + _control_status.flags.valid_fake_pos = false; } } @@ -138,10 +103,41 @@ void Ekf::resetFakePosFusion() _aid_src_fake_pos.time_last_fuse = _time_delayed_us; } -void Ekf::stopFakePosFusion() +bool Ekf::runFakePosStateMachine(const bool enable_conditions_passing, bool status_flag, + estimator_aid_source2d_s &aid_src) { - if (_control_status.flags.fake_pos) { - ECL_INFO("stop fake position fusion"); - _control_status.flags.fake_pos = false; + if (status_flag) { + if (enable_conditions_passing) { + if (!aid_src.innovation_rejected + && fuseDirectStateMeasurement(aid_src.innovation[0], aid_src.innovation_variance[0], aid_src.observation_variance[0], + State::pos.idx + 0) + && fuseDirectStateMeasurement(aid_src.innovation[1], aid_src.innovation_variance[1], aid_src.observation_variance[1], + State::pos.idx + 1) + ) { + aid_src.fused = true; + aid_src.time_last_fuse = _time_delayed_us; + } + + const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, (uint64_t)4e5); + + if (is_fusion_failing) { + ECL_WARN("fake position fusion failing, resetting"); + resetFakePosFusion(); + } + + } else { + ECL_INFO("stop fake position fusion"); + status_flag = false; + } + + } else { + if (enable_conditions_passing) { + ECL_INFO("start fake position fusion"); + status_flag = true; + + resetFakePosFusion(); + } } + + return status_flag; } diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index af03d2a8db84..13c2767f754b 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -261,6 +261,7 @@ struct systemFlagUpdate { bool in_air{true}; bool is_fixed_wing{false}; bool gnd_effect{false}; + bool constant_pos{false}; }; struct parameters { @@ -614,6 +615,8 @@ uint64_t mag_heading_consistent : uint64_t aux_gpos : 1; ///< 38 - true if auxiliary global position measurement fusion is intended uint64_t rng_terrain : 1; ///< 39 - true if we are fusing range finder data for terrain uint64_t opt_flow_terrain : 1; ///< 40 - true if we are fusing flow data for terrain + uint64_t valid_fake_pos : 1; ///< 41 - true if a valid constant position is being fused + uint64_t constant_pos : 1; ///< 42 - true if the vehicle is at a constant position } flags; uint64_t value; diff --git a/src/modules/ekf2/EKF/control.cpp b/src/modules/ekf2/EKF/control.cpp index b8aca027e769..ceefc01f6fd1 100644 --- a/src/modules/ekf2/EKF/control.cpp +++ b/src/modules/ekf2/EKF/control.cpp @@ -62,6 +62,8 @@ void Ekf::controlFusionModes(const imuSample &imu_delayed) if (system_flags_delayed.gnd_effect) { set_gnd_effect(); } + + set_constant_pos(system_flags_delayed.constant_pos); } } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index d9ff978e20e7..e6c182171aff 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -1132,7 +1132,7 @@ class Ekf final : public EstimatorInterface } void resetFakePosFusion(); - void stopFakePosFusion(); + bool runFakePosStateMachine(bool enable_condition_passing, bool status_flag, estimator_aid_source2d_s &aid_src); // reset the quaternion states and covariances to the new yaw value, preserving the roll and pitch // yaw : Euler yaw angle (rad) diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index ae3e9e355e0a..e88d3b483a63 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -642,7 +642,8 @@ uint16_t Ekf::get_ekf_soln_status() const #endif // CONFIG_EKF2_TERRAIN // 128 ESTIMATOR_CONST_POS_MODE True if the EKF is in a constant position mode and is not using external measurements (eg GPS or optical flow) - soln_status.flags.const_pos_mode = _control_status.flags.fake_pos || _control_status.flags.vehicle_at_rest; + soln_status.flags.const_pos_mode = _control_status.flags.fake_pos || _control_status.flags.valid_fake_pos + || _control_status.flags.vehicle_at_rest; // 256 ESTIMATOR_PRED_POS_HORIZ_REL True if the EKF has sufficient data to enter a mode that will provide a (relative) position estimate soln_status.flags.pred_pos_horiz_rel = isHorizontalAidingActive(); @@ -793,6 +794,13 @@ void Ekf::updateHorizontalDeadReckoningstatus() } } + if (_control_status.flags.valid_fake_pos && isRecent(_aid_src_fake_pos.time_last_fuse, _params.no_aid_timeout_max)) { + // only respect as a valid aiding source now if we expect to have another valid source once in air + if (aiding_expected_in_air) { + inertial_dead_reckoning = false; + } + } + if (inertial_dead_reckoning) { if (isTimedOut(_time_last_horizontal_aiding, (uint64_t)_params.valid_timeout_max)) { // deadreckon time exceeded diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 75e65268304d..57e6fc06b029 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -179,6 +179,8 @@ class EstimatorInterface _control_status.flags.vehicle_at_rest = at_rest; } + void set_constant_pos(bool constant_pos) { _control_status.flags.constant_pos = constant_pos; } + // return true if the attitude is usable bool attitude_valid() const { return _control_status.flags.tilt_align; } diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index af2eb6615f40..bb986208de84 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1925,6 +1925,8 @@ void EKF2::PublishStatusFlags(const hrt_abstime ×tamp) status_flags.cs_aux_gpos = _ekf.control_status_flags().aux_gpos; status_flags.cs_rng_terrain = _ekf.control_status_flags().rng_terrain; status_flags.cs_opt_flow_terrain = _ekf.control_status_flags().opt_flow_terrain; + status_flags.cs_valid_fake_pos = _ekf.control_status_flags().valid_fake_pos; + status_flags.cs_constant_pos = _ekf.control_status_flags().constant_pos; status_flags.fault_status_changes = _filter_fault_status_changes; status_flags.fs_bad_mag_x = _ekf.fault_status_flags().bad_mag_x; @@ -2592,6 +2594,15 @@ void EKF2::UpdateSystemFlagsSample(ekf2_timestamps_s &ekf2_timestamps) flags.gnd_effect = vehicle_land_detected.in_ground_effect; } + launch_detection_status_s launch_detection_status; + + if (_launch_detection_status_sub.copy(&launch_detection_status) + && (ekf2_timestamps.timestamp < launch_detection_status.timestamp + 3_s)) { + + flags.constant_pos = (launch_detection_status.launch_detection_state == + launch_detection_status_s::STATE_WAITING_FOR_LAUNCH); + } + _ekf.setSystemFlagData(flags); } } diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index ef7280e88c18..867cf9ae5758 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -72,6 +72,7 @@ #include #include #include +#include #include #include #include @@ -388,6 +389,7 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem uORB::Subscription _sensor_selection_sub{ORB_ID(sensor_selection)}; uORB::Subscription _status_sub{ORB_ID(vehicle_status)}; uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; + uORB::Subscription _launch_detection_status_sub{ORB_ID(launch_detection_status)}; uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)}; uORB::Publication _vehicle_command_ack_pub{ORB_ID(vehicle_command_ack)}; diff --git a/src/modules/ekf2/test/CMakeLists.txt b/src/modules/ekf2/test/CMakeLists.txt index 800b568d96d7..c1ecb992b99b 100644 --- a/src/modules/ekf2/test/CMakeLists.txt +++ b/src/modules/ekf2/test/CMakeLists.txt @@ -40,6 +40,7 @@ px4_add_unit_gtest(SRC test_EKF_accelerometer.cpp LINKLIBS ecl_EKF ecl_sensor_si px4_add_unit_gtest(SRC test_EKF_airspeed.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_basics.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_externalVision.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) +px4_add_unit_gtest(SRC test_EKF_fake_pos.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_flow.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_flow_generated.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_gyroscope.cpp LINKLIBS ecl_EKF ecl_sensor_sim) diff --git a/src/modules/ekf2/test/sensor_simulator/airspeed.cpp b/src/modules/ekf2/test/sensor_simulator/airspeed.cpp index 520aca024ed3..67d89224d23f 100644 --- a/src/modules/ekf2/test/sensor_simulator/airspeed.cpp +++ b/src/modules/ekf2/test/sensor_simulator/airspeed.cpp @@ -15,13 +15,18 @@ Airspeed::~Airspeed() void Airspeed::send(uint64_t time) { - if (_true_airspeed_data > FLT_EPSILON && _indicated_airspeed_data > FLT_EPSILON) { - airspeedSample airspeed_sample; - airspeed_sample.time_us = time; - airspeed_sample.eas2tas = _true_airspeed_data / _indicated_airspeed_data; - airspeed_sample.true_airspeed = _true_airspeed_data; - _ekf->setAirspeedData(airspeed_sample); + float ias2tas = 1.f; + + if (PX4_ISFINITE(_indicated_airspeed_data) + && (_indicated_airspeed_data > FLT_EPSILON)) { + ias2tas = _true_airspeed_data / _indicated_airspeed_data; } + + airspeedSample airspeed_sample; + airspeed_sample.time_us = time; + airspeed_sample.eas2tas = ias2tas; + airspeed_sample.true_airspeed = _true_airspeed_data; + _ekf->setAirspeedData(airspeed_sample); } void Airspeed::setData(float true_airspeed, float indicated_airspeed) diff --git a/src/modules/ekf2/test/test_EKF_airspeed.cpp b/src/modules/ekf2/test/test_EKF_airspeed.cpp index d284b959e3be..61865dfc7a9a 100644 --- a/src/modules/ekf2/test/test_EKF_airspeed.cpp +++ b/src/modules/ekf2/test/test_EKF_airspeed.cpp @@ -78,7 +78,6 @@ class EkfAirspeedTest : public ::testing::Test TEST_F(EkfAirspeedTest, testWindVelocityEstimation) { - const Vector3f simulated_velocity_earth(0.0f, 1.5f, 0.0f); const Vector2f airspeed_body(2.4f, 0.0f); _ekf_wrapper.enableExternalVisionVelocityFusion(); @@ -86,6 +85,9 @@ TEST_F(EkfAirspeedTest, testWindVelocityEstimation) _sensor_simulator._vio.setVelocityFrameToLocalNED(); _sensor_simulator.startExternalVision(); + // Let the EV fusion start first to reset the velocity estimate + _sensor_simulator.runSeconds(0.5); + _ekf->set_in_air_status(true); _ekf->set_vehicle_at_rest(false); _ekf->set_is_fixed_wing(true); diff --git a/src/modules/ekf2/test/test_EKF_fake_pos.cpp b/src/modules/ekf2/test/test_EKF_fake_pos.cpp new file mode 100644 index 000000000000..3cd755a3a56e --- /dev/null +++ b/src/modules/ekf2/test/test_EKF_fake_pos.cpp @@ -0,0 +1,121 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#include +#include "EKF/ekf.h" +#include "sensor_simulator/sensor_simulator.h" +#include "sensor_simulator/ekf_wrapper.h" + + +class EkfFakePosTest : public ::testing::Test +{ +public: + + EkfFakePosTest(): ::testing::Test(), + _ekf{std::make_shared()}, + _sensor_simulator(_ekf), + _ekf_wrapper(_ekf), + _quat_sim(Eulerf(0.0f, 0.0f, math::radians(45.0f))) {}; + + std::shared_ptr _ekf; + SensorSimulator _sensor_simulator; + EkfWrapper _ekf_wrapper; + const Quatf _quat_sim; + + // Setup the Ekf with synthetic measurements + void SetUp() override + { + // run briefly to init, then manually set in air and at rest (default for a real vehicle) + _ekf->init(0); + _sensor_simulator.runSeconds(0.1); + _ekf->set_in_air_status(false); + _ekf->set_vehicle_at_rest(true); + + _sensor_simulator.simulateOrientation(_quat_sim); + _sensor_simulator.runSeconds(7); + } + + // Use this method to clean up any memory, network etc. after each test + void TearDown() override + { + } +}; + +TEST_F(EkfFakePosTest, testValidFakePos) +{ + _ekf->set_vehicle_at_rest(false); + _ekf->set_constant_pos(true); + _sensor_simulator.runSeconds(1); + + EXPECT_EQ(1, (int) _ekf->control_status_flags().constant_pos); + EXPECT_EQ(0, (int) _ekf->control_status_flags().fake_pos); + EXPECT_EQ(1, (int) _ekf->control_status_flags().valid_fake_pos); +} + +TEST_F(EkfFakePosTest, testFakePosStopGnss) +{ + _ekf->set_vehicle_at_rest(false); + _ekf->set_constant_pos(true); + _sensor_simulator.startGps(); + _sensor_simulator.runSeconds(12); + + EXPECT_TRUE(_ekf_wrapper.isIntendingGpsFusion()); + EXPECT_EQ(1, (int) _ekf->control_status_flags().constant_pos); + EXPECT_EQ(0, (int) _ekf->control_status_flags().fake_pos); + EXPECT_EQ(0, (int) _ekf->control_status_flags().valid_fake_pos); +} + +TEST_F(EkfFakePosTest, testValidFakePosValidLocalPos) +{ + _ekf->set_is_fixed_wing(true); + _sensor_simulator.startAirspeedSensor(); + _sensor_simulator._airspeed.setData(-0.01f, 0.f); // airspeed close to 0 + _ekf_wrapper.enableBetaFusion(); + + // WHEN: the vehicle is not as rest but is known to be at a constant position + _ekf->set_vehicle_at_rest(false); + _ekf->set_constant_pos(true); + _sensor_simulator.runSeconds(1); + + // THEN: the valid fake position is fused + EXPECT_EQ(1, (int) _ekf->control_status_flags().constant_pos); + EXPECT_EQ(0, (int) _ekf->control_status_flags().fake_pos); + EXPECT_EQ(1, (int) _ekf->control_status_flags().valid_fake_pos); + + // AND: since airspeed is expected to provide wind-relative dead-reckoning after takeoff + // the local position is considered valid + _sensor_simulator.runSeconds(60); + + EXPECT_EQ(1, (int) _ekf->control_status_flags().valid_fake_pos); + EXPECT_TRUE(_ekf->local_position_is_valid()); +} From 54f7b580078b50e36bda5cd64bda4d1250c0e303 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Fri, 23 Aug 2024 07:20:54 -0700 Subject: [PATCH 20/87] Commander: lock down mav sys and comp id - keeps them as local params at init - only allow to set at init --- src/modules/commander/Commander.cpp | 27 ++++++++++++++------------- src/modules/commander/Commander.hpp | 2 -- 2 files changed, 14 insertions(+), 15 deletions(-) diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 2f326deb01ce..fe0b89e8b2f4 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -698,11 +698,23 @@ Commander::Commander() : // default for vtol is rotary wing _vtol_vehicle_status.vehicle_vtol_state = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC; - _param_mav_comp_id = param_find("MAV_COMP_ID"); - _param_mav_sys_id = param_find("MAV_SYS_ID"); + param_t param_mav_comp_id = param_find("MAV_COMP_ID"); + param_t param_mav_sys_id = param_find("MAV_SYS_ID"); _param_mav_type = param_find("MAV_TYPE"); _param_rc_map_fltmode = param_find("RC_MAP_FLTMODE"); + int32_t value_int32 = 0; + + // MAV_SYS_ID => vehicle_status.system_id + if ((param_mav_sys_id != PARAM_INVALID) && (param_get(param_mav_sys_id, &value_int32) == PX4_OK)) { + _vehicle_status.system_id = value_int32; + } + + // MAV_COMP_ID => vehicle_status.component_id + if ((param_mav_comp_id != PARAM_INVALID) && (param_get(param_mav_comp_id, &value_int32) == PX4_OK)) { + _vehicle_status.component_id = value_int32; + } + updateParameters(); } @@ -1682,22 +1694,11 @@ void Commander::updateParameters() int32_t value_int32 = 0; - // MAV_SYS_ID => vehicle_status.system_id - if ((_param_mav_sys_id != PARAM_INVALID) && (param_get(_param_mav_sys_id, &value_int32) == PX4_OK)) { - _vehicle_status.system_id = value_int32; - } - - // MAV_COMP_ID => vehicle_status.component_id - if ((_param_mav_comp_id != PARAM_INVALID) && (param_get(_param_mav_comp_id, &value_int32) == PX4_OK)) { - _vehicle_status.component_id = value_int32; - } - // MAV_TYPE -> vehicle_status.system_type if ((_param_mav_type != PARAM_INVALID) && (param_get(_param_mav_type, &value_int32) == PX4_OK)) { _vehicle_status.system_type = value_int32; } - _vehicle_status.avoidance_system_required = _param_com_obs_avoid.get(); _auto_disarm_killed.set_hysteresis_time_from(false, _param_com_kill_disarm.get() * 1_s); diff --git a/src/modules/commander/Commander.hpp b/src/modules/commander/Commander.hpp index 7453cb2a1b7e..6dddf0777f4d 100644 --- a/src/modules/commander/Commander.hpp +++ b/src/modules/commander/Commander.hpp @@ -324,8 +324,6 @@ class Commander : public ModuleBase, public ModuleParams perf_counter_t _preflight_check_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": preflight check")}; // optional parameters - param_t _param_mav_comp_id{PARAM_INVALID}; - param_t _param_mav_sys_id{PARAM_INVALID}; param_t _param_mav_type{PARAM_INVALID}; param_t _param_rc_map_fltmode{PARAM_INVALID}; From d7b165991f4f07f9c0d5e34274f67f443aed0997 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 23 Aug 2024 12:05:34 -0400 Subject: [PATCH 21/87] cmake: relax git tag requirements - default to v0.0.0 if tag isn't available - src/lib/px_update_git_header.py use same PX4_GIT_TAG as cmake - update lingering master branch references to main --- CMakeLists.txt | 10 +++++++++- src/lib/version/CMakeLists.txt | 3 ++- src/lib/version/px_update_git_header.py | 26 ++++++++++--------------- 3 files changed, 21 insertions(+), 18 deletions(-) diff --git a/CMakeLists.txt b/CMakeLists.txt index fc57b95efc79..b63a44dfe9ed 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -113,12 +113,20 @@ include(px4_parse_function_args) include(px4_git) execute_process( - COMMAND git describe --exclude ext/* --always --tags + COMMAND git describe --exclude ext/* --tags --match "v[0-9]*" OUTPUT_VARIABLE PX4_GIT_TAG OUTPUT_STRIP_TRAILING_WHITESPACE + RESULTS_VARIABLE GIT_DESCRIBE_RESULT WORKING_DIRECTORY ${PX4_SOURCE_DIR} ) +# if proper git tag unavilable default to v0.0.0 +if(NOT ${GIT_DESCRIBE_RESULT} MATCHES "0") + set(PX4_GIT_TAG "v0.0.0") +endif() + +message(STATUS "PX4_GIT_TAG: ${PX4_GIT_TAG}") + # git describe to X.Y.Z version string(REPLACE "." ";" VERSION_LIST ${PX4_GIT_TAG}) diff --git a/src/lib/version/CMakeLists.txt b/src/lib/version/CMakeLists.txt index 6b91e9cb11f7..ad2e516b4f57 100644 --- a/src/lib/version/CMakeLists.txt +++ b/src/lib/version/CMakeLists.txt @@ -53,7 +53,8 @@ endif() set(px4_git_ver_header ${CMAKE_CURRENT_BINARY_DIR}/build_git_version.h) add_custom_command(OUTPUT ${px4_git_ver_header} - COMMAND ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/px_update_git_header.py ${px4_git_ver_header} --validate + COMMAND + ${PYTHON_EXECUTABLE} ${CMAKE_CURRENT_SOURCE_DIR}/px_update_git_header.py ${px4_git_ver_header} --validate --git_tag '${PX4_GIT_TAG}' DEPENDS ${CMAKE_CURRENT_SOURCE_DIR}/px_update_git_header.py ${git_dir_path}/HEAD diff --git a/src/lib/version/px_update_git_header.py b/src/lib/version/px_update_git_header.py index 3a4fdff98ed6..bd1836fb0360 100755 --- a/src/lib/version/px_update_git_header.py +++ b/src/lib/version/px_update_git_header.py @@ -10,6 +10,7 @@ generate a version header file. The working directory is expected to be the root of Firmware.""") parser.add_argument('filename', metavar='version.h', help='Header output file') +parser.add_argument('--git_tag', help='git tag string') parser.add_argument('-v', '--verbose', dest='verbose', action='store_true', help='Verbose output', default=False) parser.add_argument('--validate', dest='validate', action='store_true', @@ -36,8 +37,11 @@ # PX4 -git_describe_cmd = 'git describe --exclude ext/* --always --tags --dirty' -git_tag = subprocess.check_output(git_describe_cmd.split(), +if args.git_tag: + git_tag = args.git_tag +else: + git_describe_cmd = 'git describe --exclude ext/* --always --tags --dirty' + git_tag = subprocess.check_output(git_describe_cmd.split(), stderr=subprocess.STDOUT).decode('utf-8').strip() try: @@ -57,17 +61,7 @@ # now check the version format m = re.match(r'v([0-9]+)\.([0-9]+)\.[0-9]+(((-dev)|(-alpha[0-9]+)|(-beta[0-9]+)|(-rc[0-9]+))|'\ r'(-[0-9]+\.[0-9]+\.[0-9]+((-dev)|(-alpha[0-9]+)|(-beta[0-9]+)|([-]?rc[0-9]+))?))?$', git_tag_test) - if m: - # format matches, check the major and minor numbers - major = int(m.group(1)) - minor = int(m.group(2)) - if major < 1 or (major == 1 and minor < 9): - print("") - print("Error: PX4 version too low, expected at least v1.9.0") - print("Check the git tag (current tag: '{:}')".format(git_tag_test)) - print("") - sys.exit(1) - else: + if not m: print("") print("Error: the git tag '{:}' does not match the expected format.".format(git_tag_test)) print("") @@ -103,9 +97,9 @@ if tag_or_branch is None: # replace / so it can be used as directory name tag_or_branch = git_branch_name.replace('/', '-') - # either a release or master branch (used for metadata) + # either a release or main branch (used for metadata) if not tag_or_branch.startswith('release-'): - tag_or_branch = 'master' + tag_or_branch = 'main' header += f""" #define PX4_GIT_VERSION_STR "{git_version}" @@ -115,7 +109,7 @@ #define PX4_GIT_OEM_VERSION_STR "{oem_tag}" -#define PX4_GIT_TAG_OR_BRANCH_NAME "{tag_or_branch}" // special variable: git tag, release or master branch +#define PX4_GIT_TAG_OR_BRANCH_NAME "{tag_or_branch}" // special variable: git tag, release or main branch """ From 56560726d37489b9670631a844f52ddca7b99495 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 23 Aug 2024 13:57:49 -0400 Subject: [PATCH 22/87] ekf2: sensor simulator fix GPS replay scaling --- .../test/change_indication/ekf_gsf_reset.csv | 750 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 652 +++++++-------- .../sensor_simulator/sensor_simulator.cpp | 14 +- 3 files changed, 712 insertions(+), 704 deletions(-) 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 ba51b8a17aba..357bfb7370d0 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -14,378 +14,378 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.025,0.025,0.00051,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00032,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.33 1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.026,0.026,0.00038,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.028,0.028,0.00043,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 -1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 -1590000,1,-0.01,-0.014,0.00014,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 -1690000,1,-0.011,-0.014,0.00012,0.028,-0.00014,-0.19,0.0045,0.00062,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 -1790000,1,-0.011,-0.014,9.3e-05,0.035,-0.002,-0.2,0.0076,0.00053,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 -1890000,1,-0.011,-0.015,7.3e-05,0.043,-0.0033,-0.22,0.011,0.00027,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 -1990000,1,-0.011,-0.014,8.4e-05,0.036,-0.0048,-0.23,0.0082,-0.00029,-0.19,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 -2090000,1,-0.011,-0.014,4.5e-05,0.041,-0.0073,-0.24,0.012,-0.00089,-0.22,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 -2190000,1,-0.011,-0.014,5.6e-05,0.033,-0.007,-0.26,0.0079,-0.00099,-0.24,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 -2290000,1,-0.011,-0.014,4.2e-05,0.039,-0.0095,-0.27,0.011,-0.0018,-0.27,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 -2390000,1,-0.011,-0.013,5.9e-05,0.03,-0.0089,-0.29,0.0074,-0.0015,-0.3,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 -2490000,1,-0.011,-0.013,4.1e-05,0.035,-0.011,-0.3,0.011,-0.0025,-0.32,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 -2590000,1,-0.011,-0.013,5.5e-05,0.026,-0.0093,-0.31,0.0068,-0.0018,-0.36,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 -2690000,1,-0.011,-0.013,5.1e-05,0.03,-0.011,-0.33,0.0097,-0.0028,-0.39,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 -2790000,1,-0.011,-0.013,4.5e-05,0.023,-0.0096,-0.34,0.0062,-0.002,-0.42,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 -2890000,1,-0.011,-0.013,-5.4e-06,0.027,-0.012,-0.35,0.0087,-0.003,-0.46,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 -2990000,1,-0.011,-0.013,4.2e-05,0.022,-0.0098,-0.36,0.0057,-0.0021,-0.49,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 -3090000,1,-0.011,-0.013,4.4e-05,0.025,-0.011,-0.38,0.008,-0.0032,-0.53,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 -3190000,1,-0.011,-0.013,-1.3e-05,0.02,-0.009,-0.39,0.0053,-0.0022,-0.57,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 -3290000,1,-0.011,-0.013,2.6e-05,0.023,-0.011,-0.4,0.0074,-0.0032,-0.61,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 -3390000,1,-0.011,-0.012,-2.6e-06,0.018,-0.0095,-0.42,0.0049,-0.0022,-0.65,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 -3490000,1,-0.011,-0.013,-1.1e-05,0.022,-0.012,-0.43,0.0069,-0.0033,-0.69,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 -3590000,1,-0.011,-0.012,1.2e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 -3690000,1,-0.011,-0.012,0.00013,0.019,-0.014,-0.46,0.0065,-0.0036,-0.78,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 -3790000,1,-0.011,-0.012,0.00018,0.016,-0.014,-0.47,0.0044,-0.0027,-0.82,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 -3890000,1,-0.011,-0.012,0.00015,0.017,-0.015,-0.48,0.006,-0.0041,-0.87,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -3990000,1,-0.011,-0.012,0.00015,0.02,-0.017,-0.5,0.0079,-0.0057,-0.92,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -4090000,1,-0.011,-0.012,0.00014,0.017,-0.015,-0.51,0.0056,-0.0042,-0.97,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4190000,1,-0.011,-0.012,0.00012,0.02,-0.017,-0.53,0.0075,-0.0058,-1,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4290000,1,-0.01,-0.012,7.2e-05,0.017,-0.012,-0.54,0.0054,-0.0042,-1.1,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4390000,1,-0.01,-0.012,9.4e-05,0.018,-0.013,-0.55,0.0071,-0.0055,-1.1,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4490000,1,-0.01,-0.012,0.00015,0.014,-0.01,-0.57,0.0051,-0.0038,-1.2,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4590000,1,-0.01,-0.012,0.00018,0.017,-0.012,-0.58,0.0067,-0.0049,-1.2,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4690000,1,-0.01,-0.012,0.00018,0.014,-0.01,-0.6,0.0048,-0.0035,-1.3,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4790000,1,-0.01,-0.012,0.00017,0.015,-0.012,-0.61,0.0062,-0.0045,-1.4,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4890000,1,-0.01,-0.011,0.00016,0.012,-0.01,-0.63,0.0044,-0.0033,-1.4,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -4990000,1,-0.01,-0.012,0.00014,0.015,-0.011,-0.64,0.0058,-0.0043,-1.5,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5090000,1,-0.01,-0.011,0.00018,0.011,-0.0085,-0.66,0.0041,-0.0031,-1.6,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5190000,1,-0.01,-0.011,0.00021,0.013,-0.0098,-0.67,0.0053,-0.004,-1.6,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5290000,1,-0.01,-0.011,0.0002,0.0086,-0.0073,-0.68,0.0037,-0.0029,-1.7,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5390000,1,-0.0099,-0.011,0.00026,0.0081,-0.0081,-0.7,0.0045,-0.0036,-1.8,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5490000,1,-0.0098,-0.011,0.00027,0.0055,-0.0062,-0.71,0.0031,-0.0026,-1.8,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5590000,1,-0.0097,-0.011,0.00025,0.0061,-0.0066,-0.73,0.0036,-0.0032,-1.9,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5690000,1,-0.0096,-0.011,0.00032,0.0041,-0.0038,-0.74,0.0025,-0.0022,-2,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5790000,1,-0.0095,-0.011,0.00032,0.0044,-0.0028,-0.75,0.0029,-0.0025,-2,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5890000,1,-0.0095,-0.011,0.00029,0.0038,-0.00092,0.0028,0.002,-0.0016,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5990000,1,-0.0094,-0.011,0.00032,0.0041,0.00056,0.015,0.0023,-0.0016,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -6090000,1,-0.0094,-0.011,0.0003,0.0051,0.0017,-0.011,0.0028,-0.0015,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6190000,1,-0.0094,-0.011,0.00022,0.0038,0.0042,-0.005,0.002,-0.00053,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6290000,1,-0.0094,-0.011,0.0002,0.005,0.0043,-0.012,0.0025,-0.00012,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-3.6e+02,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6390000,1,-0.0093,-0.011,0.00022,0.0043,0.0053,-0.05,0.0019,0.00038,-3.7e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,-3.6e+02,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6490000,1,-0.0093,-0.011,0.00022,0.0049,0.0055,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.0001,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6590000,1,-0.0093,-0.011,0.00015,0.0037,0.0055,-0.099,0.0018,0.001,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,3e-05,0,0,0,0,0,0,0,0,-3.6e+02,0.0015,0.0015,9.6e-05,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6690000,1,-0.0093,-0.011,7.8e-05,0.0046,0.0051,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,-3.6e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6790000,0.78,-0.024,0.0048,-0.62,-0.22,-0.05,-0.11,-0.13,-0.029,-3.7e+02,-0.00035,-0.01,-0.0002,0,0,0.0012,-0.092,-0.021,0.51,-0.00079,-0.075,-0.061,0,0,-3.6e+02,0.0013,0.0013,0.075,0.18,0.18,0.6,0.11,0.11,0.2,7.5e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1,1.7 -6890000,0.78,-0.025,0.0057,-0.62,-0.27,-0.065,-0.12,-0.16,-0.04,-3.7e+02,-0.00017,-0.011,-0.00022,0,0,0.0012,-0.1,-0.023,0.51,-0.0012,-0.083,-0.067,0,0,-3.6e+02,0.0012,0.0013,0.062,0.2,0.2,0.46,0.13,0.13,0.18,7.4e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00025,0.0013,0.00089,0.0014,0.0013,1,1,1.8 -6990000,0.78,-0.025,0.0059,-0.62,-0.3,-0.076,-0.12,-0.2,-0.05,-3.7e+02,-7e-05,-0.011,-0.00022,-0.00057,-7.3e-05,0.00095,-0.1,-0.024,0.5,-0.0016,-0.084,-0.067,0,0,-3.6e+02,0.0013,0.0013,0.059,0.23,0.23,0.36,0.16,0.16,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.00085,0.0014,0.0013,1,1,1.8 -7090000,0.78,-0.025,0.0062,-0.62,-0.33,-0.088,-0.12,-0.23,-0.063,-3.7e+02,4.4e-05,-0.011,-0.00023,-0.0013,-0.0003,0.00061,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.058,0.26,0.26,0.29,0.2,0.2,0.16,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00016,0.0013,0.00083,0.0014,0.0013,1,1,1.8 -7190000,0.78,-0.025,0.0064,-0.62,-0.36,-0.097,-0.15,-0.26,-0.075,-3.7e+02,0.00011,-0.011,-0.00023,-0.0017,-0.00046,0.00083,-0.1,-0.024,0.5,-0.002,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.057,0.3,0.29,0.24,0.25,0.24,0.15,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00014,0.0013,0.00082,0.0013,0.0013,1,1,1.8 -7290000,0.78,-0.025,0.0067,-0.62,-0.38,-0.098,-0.14,-0.3,-0.082,-3.7e+02,5.3e-05,-0.011,-0.00022,-0.0016,-0.00042,0.00015,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0013,0.056,0.33,0.33,0.2,0.3,0.3,0.14,7.3e-05,7.5e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00081,0.0013,0.0013,1,1,1.9 -7390000,0.78,-0.024,0.0068,-0.62,-0.41,-0.11,-0.16,-0.34,-0.093,-3.7e+02,7.4e-05,-0.011,-0.00022,-0.0017,-0.00046,8.6e-07,-0.1,-0.024,0.5,-0.0018,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.056,0.37,0.37,0.18,0.36,0.36,0.13,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00012,0.0013,0.00081,0.0013,0.0013,1,1,1.9 -7490000,0.78,-0.024,0.0069,-0.62,-0.43,-0.12,-0.16,-0.38,-0.11,-3.7e+02,0.00021,-0.011,-0.00023,-0.0019,-0.00054,-0.00076,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.055,0.42,0.42,0.15,0.43,0.43,0.12,7.2e-05,7.4e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 -7590000,0.78,-0.024,0.007,-0.62,-0.45,-0.12,-0.16,-0.41,-0.12,-3.7e+02,0.0002,-0.011,-0.00022,-0.0018,-0.00052,-0.0016,-0.1,-0.024,0.5,-0.0019,-0.085,-0.068,0,0,-3.6e+02,0.0013,0.0014,0.055,0.46,0.46,0.14,0.52,0.51,0.12,7.2e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.0008,0.0013,0.0013,1,1,1.9 -7690000,0.78,-0.024,0.007,-0.62,-0.011,-0.0016,-0.16,-0.44,-0.14,-3.7e+02,0.00029,-0.011,-0.00022,-0.0019,-0.00051,-0.0036,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.13,1e+02,1e+02,0.11,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.0008,0.0013,0.0013,1,1,2 -7790000,0.78,-0.024,0.0073,-0.62,-0.038,-0.0061,-0.16,-0.44,-0.14,-3.7e+02,0.00035,-0.011,-0.00023,-0.0019,-0.00051,-0.0056,-0.1,-0.024,0.5,-0.002,-0.085,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.12,1e+02,1e+02,0.11,7e-05,7.2e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.0001,0.0013,0.00079,0.0013,0.0013,1,1,2 -7890000,0.78,-0.024,0.0072,-0.62,-0.063,-0.011,-0.15,-0.44,-0.14,-3.7e+02,0.00039,-0.011,-0.00022,-0.0019,-0.00051,-0.0081,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.11,50,50,0.1,6.9e-05,7e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.8e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 -7990000,0.78,-0.024,0.0072,-0.62,-0.089,-0.016,-0.16,-0.45,-0.14,-3.7e+02,0.0004,-0.011,-0.00022,-0.0019,-0.00051,-0.0094,-0.1,-0.024,0.5,-0.0021,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.1,51,51,0.099,6.7e-05,6.9e-05,2.4e-06,0.04,0.04,0.038,0.0013,9.5e-05,0.0013,0.00079,0.0013,0.0013,1,1,2 -8090000,0.78,-0.024,0.0071,-0.62,-0.11,-0.021,-0.17,-0.45,-0.14,-3.7e+02,0.00044,-0.01,-0.00021,-0.0019,-0.00051,-0.0096,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,24,24,0.1,35,35,0.097,6.6e-05,6.8e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.4e-05,0.0013,0.00079,0.0013,0.0013,1,1,2.1 -8190000,0.78,-0.024,0.0073,-0.62,-0.14,-0.025,-0.18,-0.47,-0.14,-3.7e+02,0.00043,-0.01,-0.00021,-0.0019,-0.00051,-0.012,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.055,25,25,0.099,36,36,0.094,6.4e-05,6.6e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.2e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 -8290000,0.78,-0.024,0.0073,-0.62,-0.16,-0.03,-0.17,-0.47,-0.14,-3.7e+02,0.00053,-0.01,-0.00021,-0.0019,-0.00051,-0.016,-0.1,-0.024,0.5,-0.0023,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,28,28,0.091,6.2e-05,6.4e-05,2.4e-06,0.04,0.04,0.036,0.0013,9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 -8390000,0.78,-0.024,0.007,-0.63,-0.18,-0.036,-0.17,-0.48,-0.15,-3.7e+02,0.00055,-0.01,-0.00021,-0.0019,-0.00051,-0.019,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,24,24,0.097,29,29,0.091,6.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.9e-05,0.0013,0.00078,0.0013,0.0013,1,1,2.1 -8490000,0.78,-0.024,0.007,-0.63,-0.2,-0.04,-0.17,-0.49,-0.15,-3.7e+02,0.00056,-0.0099,-0.0002,-0.0019,-0.00051,-0.024,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,24,24,0.089,5.9e-05,6.1e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.8e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 -8590000,0.78,-0.023,0.0072,-0.63,-0.22,-0.038,-0.17,-0.51,-0.15,-3.7e+02,0.00036,-0.0099,-0.0002,-0.0019,-0.00051,-0.028,-0.1,-0.024,0.5,-0.0022,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.095,26,26,0.088,5.6e-05,5.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,8.7e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 -8690000,0.78,-0.023,0.0068,-0.63,-0.23,-0.044,-0.16,-0.53,-0.15,-3.7e+02,0.00037,-0.0096,-0.00019,-0.0019,-0.00051,-0.033,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,23,23,0.096,29,29,0.088,5.5e-05,5.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,8.6e-05,0.0013,0.00077,0.0013,0.0013,1,1,2.2 -8790000,0.78,-0.023,0.0069,-0.63,-0.25,-0.047,-0.15,-0.53,-0.15,-3.7e+02,0.0004,-0.0095,-0.00019,-0.0019,-0.00051,-0.039,-0.1,-0.024,0.5,-0.0024,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,21,21,0.096,25,25,0.087,5.2e-05,5.4e-05,2.4e-06,0.04,0.04,0.032,0.0013,8.5e-05,0.0013,0.00076,0.0013,0.0013,1,1,2.2 -8890000,0.78,-0.023,0.0068,-0.63,-0.27,-0.051,-0.15,-0.55,-0.16,-3.7e+02,0.0004,-0.0094,-0.00018,-0.0019,-0.00051,-0.043,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0014,0.0014,0.054,21,21,0.095,27,27,0.086,5e-05,5.2e-05,2.4e-06,0.04,0.04,0.03,0.0012,8.4e-05,0.0013,0.00076,0.0013,0.0013,1,1,2.3 -8990000,0.78,-0.023,0.0068,-0.63,-0.27,-0.053,-0.14,-0.55,-0.16,-3.7e+02,0.00045,-0.0093,-0.00018,-0.0019,-0.00051,-0.049,-0.1,-0.024,0.5,-0.0026,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.096,24,24,0.087,4.8e-05,5e-05,2.4e-06,0.04,0.04,0.029,0.0012,8.3e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3 -9090000,0.78,-0.022,0.0068,-0.63,-0.29,-0.054,-0.14,-0.58,-0.17,-3.7e+02,0.00037,-0.0092,-0.00018,-0.0019,-0.00051,-0.052,-0.1,-0.024,0.5,-0.0025,-0.086,-0.069,0,0,-3.6e+02,0.0013,0.0014,0.054,19,19,0.095,27,27,0.086,4.6e-05,4.8e-05,2.4e-06,0.04,0.04,0.028,0.0012,8.2e-05,0.0013,0.00075,0.0013,0.0013,1,1,2.3 -9190000,0.78,-0.022,0.0061,-0.63,-0.3,-0.064,-0.14,-0.6,-0.17,-3.7e+02,0.00038,-0.0088,-0.00017,-0.0018,-0.0003,-0.055,-0.11,-0.025,0.5,-0.0027,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.094,30,30,0.085,4.3e-05,4.5e-05,2.4e-06,0.04,0.04,0.027,0.0012,8.2e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.3 -9290000,0.78,-0.022,0.0058,-0.63,-0.31,-0.073,-0.14,-0.62,-0.18,-3.7e+02,0.0004,-0.0086,-0.00016,-0.0018,-6.6e-05,-0.059,-0.11,-0.025,0.5,-0.0029,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,34,34,0.085,4.1e-05,4.3e-05,2.4e-06,0.04,0.04,0.025,0.0012,8.1e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 -9390000,0.78,-0.022,0.0057,-0.63,-0.33,-0.082,-0.13,-0.65,-0.19,-3.7e+02,0.00043,-0.0085,-0.00016,-0.0019,0.00012,-0.063,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.093,38,38,0.086,3.9e-05,4.1e-05,2.4e-06,0.04,0.04,0.024,0.0012,8e-05,0.0013,0.00074,0.0013,0.0013,1,1,2.4 -9490000,0.78,-0.022,0.0052,-0.63,-0.33,-0.095,-0.13,-0.67,-0.21,-3.7e+02,0.00046,-0.0082,-0.00015,-0.0018,0.00038,-0.067,-0.11,-0.025,0.5,-0.0032,-0.087,-0.069,0,0,-3.6e+02,0.0013,0.0013,0.054,19,19,0.091,42,42,0.085,3.7e-05,3.9e-05,2.4e-06,0.04,0.04,0.023,0.0012,8e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 -9590000,0.78,-0.022,0.0049,-0.63,-0.34,-0.094,-0.13,-0.7,-0.22,-3.7e+02,0.00031,-0.008,-0.00014,-0.0018,0.00066,-0.07,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0013,0.054,20,20,0.09,47,47,0.085,3.5e-05,3.7e-05,2.4e-06,0.04,0.04,0.022,0.0012,7.9e-05,0.0013,0.00073,0.0013,0.0013,1,1,2.4 -9690000,0.78,-0.022,0.0051,-0.63,-0.36,-0.092,-0.12,-0.73,-0.22,-3.7e+02,0.00022,-0.008,-0.00014,-0.0021,0.0009,-0.075,-0.11,-0.025,0.5,-0.003,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.089,53,53,0.086,3.3e-05,3.5e-05,2.4e-06,0.04,0.04,0.02,0.0012,7.9e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 -9790000,0.78,-0.022,0.0047,-0.63,-0.37,-0.1,-0.11,-0.75,-0.24,-3.7e+02,0.00023,-0.0078,-0.00014,-0.0021,0.0012,-0.081,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.087,58,58,0.085,3.1e-05,3.3e-05,2.4e-06,0.04,0.04,0.019,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 -9890000,0.78,-0.021,0.0045,-0.63,-0.37,-0.11,-0.11,-0.78,-0.24,-3.7e+02,0.00014,-0.0077,-0.00013,-0.0021,0.0014,-0.083,-0.11,-0.025,0.5,-0.0031,-0.087,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.084,64,64,0.085,2.9e-05,3.2e-05,2.4e-06,0.04,0.04,0.018,0.0012,7.8e-05,0.0013,0.00072,0.0013,0.0013,1,1,2.5 -9990000,0.78,-0.021,0.0045,-0.63,-0.39,-0.11,-0.1,-0.81,-0.25,-3.7e+02,9.8e-05,-0.0077,-0.00013,-0.0023,0.0016,-0.087,-0.11,-0.025,0.5,-0.0031,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.083,71,71,0.086,2.8e-05,3e-05,2.4e-06,0.04,0.04,0.017,0.0012,7.8e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.5 -10090000,0.78,-0.021,0.0043,-0.63,-0.39,-0.11,-0.096,-0.84,-0.26,-3.7e+02,-9.2e-06,-0.0075,-0.00012,-0.0023,0.0018,-0.09,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0012,0.0012,0.054,20,20,0.08,78,78,0.085,2.6e-05,2.9e-05,2.4e-06,0.04,0.04,0.016,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 -10190000,0.78,-0.021,0.0045,-0.63,-0.42,-0.1,-0.096,-0.88,-0.26,-3.7e+02,-4.1e-05,-0.0076,-0.00012,-0.0024,0.0019,-0.091,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.078,85,85,0.084,2.5e-05,2.7e-05,2.4e-06,0.04,0.04,0.015,0.0012,7.7e-05,0.0013,0.00071,0.0013,0.0013,1,1,2.6 -10290000,0.78,-0.021,0.0047,-0.63,-0.44,-0.1,-0.083,-0.92,-0.27,-3.7e+02,-6.8e-05,-0.0076,-0.00012,-0.0026,0.0022,-0.097,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,20,20,0.076,92,92,0.085,2.4e-05,2.6e-05,2.4e-06,0.04,0.04,0.014,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6 -10390000,0.78,-0.021,0.0045,-0.63,-0.0085,-0.022,0.0097,8e-05,-0.0019,-3.7e+02,-5.8e-05,-0.0075,-0.00012,-0.0026,0.0023,-0.1,-0.11,-0.025,0.5,-0.003,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,2.3e-06,0.04,0.04,0.013,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.6 -10490000,0.78,-0.021,0.0046,-0.63,-0.028,-0.025,0.023,-0.0017,-0.0043,-3.7e+02,-8e-05,-0.0075,-0.00012,-0.0028,0.0025,-0.1,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.25,0.25,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7 -10590000,0.78,-0.02,0.0043,-0.63,-0.026,-0.014,0.026,0.0015,-0.00091,-3.7e+02,-0.00026,-0.0074,-0.00011,-0.0019,0.0024,-0.1,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.0011,0.0011,0.054,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.2e-05,2.3e-06,0.04,0.04,0.012,0.0012,7.6e-05,0.0013,0.0007,0.0013,0.0013,1,1,2.7 -10690000,0.78,-0.02,0.0042,-0.63,-0.043,-0.015,0.03,-0.002,-0.0024,-3.7e+02,-0.00028,-0.0073,-0.00011,-0.0019,0.0025,-0.11,-0.11,-0.025,0.5,-0.0028,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.13,0.13,0.26,0.14,0.14,0.078,1.9e-05,2.1e-05,2.3e-06,0.04,0.04,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 -10790000,0.78,-0.02,0.0038,-0.63,-0.04,-0.011,0.024,0.001,-0.0011,-3.7e+02,-0.00033,-0.0072,-0.0001,-0.00015,0.0013,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.001,0.001,0.054,0.091,0.091,0.17,0.09,0.09,0.072,1.7e-05,1.9e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.7 -10890000,0.78,-0.02,0.0037,-0.63,-0.057,-0.013,0.02,-0.0036,-0.0024,-3.7e+02,-0.00035,-0.0071,-0.0001,-9.7e-05,0.0014,-0.11,-0.11,-0.025,0.5,-0.0029,-0.088,-0.069,0,0,-3.6e+02,0.00099,0.00099,0.054,0.099,0.099,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,2.3e-06,0.039,0.039,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 -10990000,0.78,-0.02,0.003,-0.63,-0.048,-0.011,0.015,0.00017,-0.0012,-3.7e+02,-0.00038,-0.0069,-9.7e-05,0.0036,-0.00085,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.069,0,0,-3.6e+02,0.00093,0.00094,0.053,0.078,0.078,0.12,0.098,0.098,0.071,1.5e-05,1.7e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00069,0.0013,0.0013,1,1,2.8 -11090000,0.78,-0.02,0.0026,-0.63,-0.06,-0.015,0.02,-0.0047,-0.0027,-3.7e+02,-0.00042,-0.0068,-9.2e-05,0.0037,-0.00042,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00092,0.00092,0.053,0.087,0.088,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,2.3e-06,0.038,0.038,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8 -11190000,0.78,-0.019,0.0021,-0.63,-0.053,-0.011,0.0082,0.00075,-0.00057,-3.7e+02,-0.00052,-0.0067,-8.9e-05,0.0082,-0.0036,-0.11,-0.11,-0.025,0.5,-0.0031,-0.089,-0.07,0,0,-3.6e+02,0.00085,0.00086,0.053,0.073,0.073,0.084,0.11,0.11,0.069,1.3e-05,1.5e-05,2.3e-06,0.037,0.037,0.011,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0013,1,1,2.8 -11290000,0.78,-0.019,0.0022,-0.63,-0.069,-0.013,0.008,-0.0056,-0.0018,-3.7e+02,-0.00049,-0.0067,-9.1e-05,0.0083,-0.0038,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00084,0.00085,0.053,0.083,0.084,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,2.3e-06,0.037,0.037,0.01,0.0012,7.6e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9 -11390000,0.78,-0.019,0.0018,-0.63,-0.064,-0.011,0.0024,0.00037,-0.00044,-3.7e+02,-0.00058,-0.0067,-8.9e-05,0.012,-0.0074,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00077,0.052,0.067,0.068,0.063,0.081,0.081,0.068,1.2e-05,1.3e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00068,0.0013,0.0012,1,1,2.9 -11490000,0.78,-0.019,0.002,-0.63,-0.078,-0.012,0.0032,-0.0071,-0.0014,-3.7e+02,-0.00056,-0.0068,-9.2e-05,0.012,-0.0079,-0.11,-0.11,-0.025,0.5,-0.0032,-0.089,-0.07,0,0,-3.6e+02,0.00076,0.00076,0.052,0.078,0.079,0.058,0.088,0.088,0.069,1.1e-05,1.2e-05,2.3e-06,0.035,0.035,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 -11590000,0.78,-0.019,0.0015,-0.63,-0.069,-0.012,-0.0027,-0.0021,-0.00084,-3.7e+02,-0.00061,-0.0067,-9.1e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0033,-0.089,-0.07,0,0,-3.6e+02,0.00068,0.00069,0.052,0.066,0.066,0.049,0.068,0.068,0.066,1e-05,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,2.9 -11690000,0.78,-0.019,0.0016,-0.63,-0.08,-0.016,-0.0071,-0.0097,-0.0025,-3.7e+02,-0.00057,-0.0067,-9.2e-05,0.017,-0.012,-0.11,-0.11,-0.025,0.5,-0.0034,-0.089,-0.07,0,0,-3.6e+02,0.00067,0.00068,0.052,0.076,0.077,0.046,0.074,0.074,0.066,9.9e-06,1.1e-05,2.3e-06,0.033,0.033,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 -11790000,0.78,-0.019,0.001,-0.63,-0.072,-0.011,-0.0089,-0.0061,-0.00025,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.015,-0.11,-0.11,-0.025,0.5,-0.0036,-0.09,-0.07,0,0,-3.6e+02,0.0006,0.00061,0.051,0.064,0.065,0.039,0.06,0.06,0.063,9.1e-06,9.9e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 -11890000,0.78,-0.019,0.0011,-0.63,-0.083,-0.012,-0.0098,-0.014,-0.0014,-3.7e+02,-0.00061,-0.0066,-9.1e-05,0.023,-0.016,-0.11,-0.11,-0.025,0.5,-0.0036,-0.09,-0.07,0,0,-3.6e+02,0.00059,0.00061,0.051,0.075,0.075,0.037,0.066,0.066,0.063,8.7e-06,9.5e-06,2.3e-06,0.03,0.03,0.01,0.0012,7.5e-05,0.0013,0.00067,0.0013,0.0012,1,1,3 -11990000,0.78,-0.019,0.00053,-0.63,-0.071,-0.0068,-0.015,-0.009,0.00086,-3.7e+02,-0.00076,-0.0065,-8.7e-05,0.027,-0.018,-0.11,-0.11,-0.025,0.5,-0.0035,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.063,0.064,0.033,0.055,0.055,0.061,8e-06,8.8e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3 -12090000,0.78,-0.018,0.00037,-0.63,-0.078,-0.0091,-0.021,-0.016,-3.2e-05,-3.7e+02,-0.00081,-0.0065,-8.3e-05,0.026,-0.017,-0.11,-0.11,-0.025,0.5,-0.0034,-0.09,-0.07,0,0,-3.6e+02,0.00052,0.00054,0.051,0.073,0.074,0.031,0.061,0.061,0.061,7.7e-06,8.4e-06,2.3e-06,0.028,0.028,0.01,0.0012,7.5e-05,0.0013,0.00066,0.0013,0.0012,1,1,3.1 -12190000,0.78,-0.018,-0.00031,-0.62,-0.064,-0.011,-0.016,-0.0085,-0.0004,-3.7e+02,-0.00082,-0.0064,-8.3e-05,0.032,-0.022,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00048,0.051,0.062,0.062,0.028,0.052,0.052,0.059,7.2e-06,7.8e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 -12290000,0.78,-0.019,-0.00032,-0.62,-0.07,-0.014,-0.015,-0.015,-0.0021,-3.7e+02,-0.00079,-0.0064,-8.3e-05,0.033,-0.021,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00046,0.00047,0.051,0.07,0.071,0.028,0.058,0.058,0.059,6.9e-06,7.5e-06,2.3e-06,0.026,0.026,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 -12390000,0.78,-0.018,-0.00073,-0.62,-0.057,-0.012,-0.013,-0.0083,-0.001,-3.7e+02,-0.00086,-0.0063,-8.3e-05,0.037,-0.026,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.059,0.06,0.026,0.05,0.05,0.057,6.4e-06,7e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.1 -12490000,0.78,-0.018,-0.00059,-0.62,-0.064,-0.013,-0.016,-0.015,-0.0022,-3.7e+02,-0.00083,-0.0064,-8.5e-05,0.038,-0.026,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.0004,0.00042,0.05,0.067,0.068,0.026,0.056,0.057,0.057,6.2e-06,6.8e-06,2.3e-06,0.024,0.024,0.01,0.0012,7.5e-05,0.0012,0.00066,0.0013,0.0012,1,1,3.2 -12590000,0.78,-0.018,-0.00079,-0.62,-0.06,-0.011,-0.022,-0.013,-0.001,-3.7e+02,-0.00092,-0.0063,-8.3e-05,0.039,-0.027,-0.11,-0.11,-0.025,0.5,-0.0037,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00038,0.05,0.057,0.057,0.025,0.048,0.048,0.055,5.8e-06,6.4e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 -12690000,0.78,-0.018,-0.00072,-0.62,-0.065,-0.011,-0.025,-0.019,-0.0013,-3.7e+02,-0.00099,-0.0064,-8.2e-05,0.036,-0.027,-0.11,-0.11,-0.025,0.5,-0.0035,-0.091,-0.07,0,0,-3.6e+02,0.00036,0.00037,0.05,0.064,0.064,0.025,0.055,0.055,0.055,5.6e-06,6.1e-06,2.3e-06,0.022,0.023,0.0099,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 -12790000,0.78,-0.018,-0.001,-0.62,-0.061,-0.0098,-0.029,-0.017,-0.0012,-3.7e+02,-0.00097,-0.0063,-8.2e-05,0.04,-0.029,-0.11,-0.11,-0.025,0.5,-0.0036,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.054,0.054,0.024,0.048,0.048,0.053,5.3e-06,5.8e-06,2.3e-06,0.021,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.2 -12890000,0.78,-0.018,-0.00099,-0.62,-0.068,-0.011,-0.028,-0.024,-0.0027,-3.7e+02,-0.00093,-0.0063,-8.2e-05,0.041,-0.029,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00032,0.00034,0.05,0.06,0.061,0.025,0.055,0.055,0.054,5.1e-06,5.6e-06,2.3e-06,0.02,0.021,0.0097,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3 -12990000,0.78,-0.018,-0.0015,-0.62,-0.055,-0.01,-0.028,-0.018,-0.0026,-3.7e+02,-0.00097,-0.0062,-8e-05,0.045,-0.031,-0.11,-0.11,-0.025,0.5,-0.0038,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.054,0.054,0.025,0.057,0.057,0.052,4.9e-06,5.3e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0013,0.0012,1,1,3.3 -13090000,0.78,-0.018,-0.0014,-0.62,-0.061,-0.01,-0.028,-0.024,-0.0034,-3.7e+02,-0.00095,-0.0063,-8.3e-05,0.045,-0.032,-0.11,-0.11,-0.025,0.5,-0.0039,-0.091,-0.07,0,0,-3.6e+02,0.00029,0.00031,0.05,0.061,0.061,0.025,0.065,0.065,0.052,4.7e-06,5.2e-06,2.3e-06,0.019,0.02,0.0094,0.0012,7.4e-05,0.0012,0.00065,0.0012,0.0012,1,1,3.3 -13190000,0.78,-0.018,-0.0017,-0.62,-0.049,-0.0096,-0.025,-0.017,-0.0028,-3.7e+02,-0.001,-0.0063,-8.3e-05,0.047,-0.035,-0.11,-0.11,-0.025,0.5,-0.0039,-0.091,-0.07,0,0,-3.6e+02,0.00027,0.00029,0.05,0.054,0.054,0.025,0.066,0.066,0.051,4.5e-06,4.9e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.3 -13290000,0.78,-0.018,-0.0018,-0.62,-0.053,-0.013,-0.022,-0.022,-0.0049,-3.7e+02,-0.00095,-0.0062,-8.2e-05,0.05,-0.034,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00027,0.00028,0.05,0.06,0.06,0.027,0.075,0.075,0.051,4.4e-06,4.8e-06,2.3e-06,0.018,0.019,0.0091,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 -13390000,0.78,-0.018,-0.002,-0.62,-0.044,-0.012,-0.018,-0.016,-0.004,-3.7e+02,-0.00099,-0.0062,-8e-05,0.051,-0.035,-0.12,-0.11,-0.025,0.5,-0.004,-0.091,-0.07,0,0,-3.6e+02,0.00025,0.00027,0.05,0.053,0.053,0.026,0.076,0.076,0.05,4.2e-06,4.6e-06,2.3e-06,0.017,0.018,0.0088,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 -13490000,0.78,-0.018,-0.0021,-0.62,-0.046,-0.013,-0.016,-0.021,-0.0057,-3.7e+02,-0.00097,-0.0062,-7.9e-05,0.052,-0.034,-0.12,-0.11,-0.025,0.5,-0.0041,-0.091,-0.07,0,0,-3.6e+02,0.00025,0.00026,0.05,0.059,0.059,0.028,0.086,0.086,0.05,4e-06,4.4e-06,2.3e-06,0.017,0.018,0.0087,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 -13590000,0.78,-0.018,-0.0022,-0.62,-0.038,-0.012,-0.019,-0.014,-0.0042,-3.7e+02,-0.001,-0.0062,-8e-05,0.053,-0.036,-0.12,-0.11,-0.025,0.5,-0.0041,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.052,0.052,0.028,0.086,0.086,0.05,3.9e-06,4.3e-06,2.3e-06,0.016,0.017,0.0084,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.4 -13690000,0.78,-0.018,-0.0023,-0.62,-0.041,-0.015,-0.023,-0.018,-0.006,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.035,-0.12,-0.11,-0.025,0.5,-0.0041,-0.091,-0.07,0,0,-3.6e+02,0.00023,0.00025,0.049,0.057,0.057,0.029,0.096,0.096,0.05,3.7e-06,4.1e-06,2.3e-06,0.016,0.017,0.0083,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 -13790000,0.78,-0.018,-0.0024,-0.62,-0.029,-0.013,-0.024,-0.0067,-0.0046,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.054,-0.037,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.044,0.044,0.029,0.071,0.071,0.049,3.6e-06,4e-06,2.3e-06,0.015,0.016,0.0079,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 -13890000,0.78,-0.018,-0.0025,-0.62,-0.033,-0.015,-0.029,-0.01,-0.0066,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.056,-0.037,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.00021,0.00023,0.049,0.048,0.048,0.03,0.079,0.079,0.05,3.5e-06,3.9e-06,2.3e-06,0.015,0.016,0.0078,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 -13990000,0.78,-0.018,-0.0026,-0.62,-0.025,-0.014,-0.028,-0.0036,-0.0056,-3.7e+02,-0.001,-0.0061,-7.9e-05,0.057,-0.038,-0.12,-0.11,-0.025,0.5,-0.0041,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.039,0.039,0.03,0.062,0.062,0.05,3.3e-06,3.7e-06,2.3e-06,0.014,0.015,0.0074,0.0012,7.4e-05,0.0012,0.00064,0.0012,0.0012,1,1,3.5 -14090000,0.78,-0.018,-0.0027,-0.62,-0.026,-0.015,-0.029,-0.0058,-0.0071,-3.7e+02,-0.0011,-0.0061,-7.6e-05,0.056,-0.036,-0.12,-0.11,-0.025,0.5,-0.004,-0.092,-0.07,0,0,-3.6e+02,0.0002,0.00021,0.049,0.042,0.042,0.031,0.07,0.07,0.05,3.2e-06,3.6e-06,2.4e-06,0.014,0.015,0.0073,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 -14190000,0.78,-0.017,-0.0028,-0.62,-0.021,-0.013,-0.031,-0.00023,-0.005,-3.7e+02,-0.0011,-0.0061,-7.5e-05,0.058,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.5e-06,2.4e-06,0.014,0.015,0.0069,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 -14290000,0.78,-0.017,-0.0029,-0.62,-0.022,-0.015,-0.03,-0.0022,-0.0063,-3.7e+02,-0.0011,-0.006,-7.4e-05,0.057,-0.036,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00019,0.0002,0.049,0.039,0.039,0.032,0.063,0.063,0.051,3e-06,3.4e-06,2.4e-06,0.013,0.014,0.0067,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 -14390000,0.78,-0.017,-0.003,-0.62,-0.017,-0.015,-0.032,0.0018,-0.0049,-3.7e+02,-0.0011,-0.006,-7.3e-05,0.06,-0.035,-0.12,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.033,0.033,0.031,0.053,0.053,0.05,2.9e-06,3.3e-06,2.4e-06,0.013,0.014,0.0063,0.0012,7.4e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.6 -14490000,0.78,-0.017,-0.0031,-0.62,-0.019,-0.018,-0.035,-0.00044,-0.0069,-3.7e+02,-0.001,-0.006,-7.4e-05,0.062,-0.036,-0.12,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00018,0.00019,0.049,0.036,0.036,0.032,0.059,0.059,0.051,2.8e-06,3.2e-06,2.4e-06,0.013,0.014,0.0062,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 -14590000,0.78,-0.017,-0.003,-0.62,-0.02,-0.018,-0.035,-0.0013,-0.0065,-3.7e+02,-0.001,-0.006,-7.4e-05,0.063,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.031,0.031,0.031,0.05,0.05,0.051,2.8e-06,3.1e-06,2.4e-06,0.012,0.013,0.0058,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 -14690000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.017,-0.032,-0.0034,-0.0085,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.064,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00017,0.00019,0.049,0.034,0.034,0.032,0.056,0.056,0.051,2.7e-06,3e-06,2.4e-06,0.012,0.013,0.0056,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 -14790000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.016,-0.028,-0.0036,-0.0079,-3.7e+02,-0.00099,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.03,0.03,0.031,0.048,0.048,0.051,2.6e-06,2.9e-06,2.4e-06,0.012,0.013,0.0053,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.7 -14890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.019,-0.031,-0.006,-0.0098,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.065,-0.035,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00018,0.049,0.032,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,2.4e-06,0.012,0.013,0.0051,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 -14990000,0.78,-0.017,-0.0031,-0.62,-0.024,-0.016,-0.027,-0.0046,-0.0077,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.066,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,2.4e-06,0.012,0.012,0.0048,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 -15090000,0.78,-0.017,-0.003,-0.62,-0.026,-0.017,-0.03,-0.0072,-0.0093,-3.7e+02,-0.00098,-0.006,-7.4e-05,0.066,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00016,0.00017,0.049,0.031,0.031,0.031,0.052,0.052,0.052,2.4e-06,2.7e-06,2.4e-06,0.011,0.012,0.0046,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 -15190000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.027,-0.0058,-0.0075,-3.7e+02,-0.00097,-0.006,-7.4e-05,0.067,-0.037,-0.12,-0.11,-0.026,0.5,-0.0043,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.027,0.027,0.03,0.046,0.046,0.052,2.3e-06,2.6e-06,2.4e-06,0.011,0.012,0.0043,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.8 -15290000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.025,-0.0081,-0.0092,-3.7e+02,-0.00098,-0.006,-7.3e-05,0.067,-0.036,-0.12,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00017,0.049,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,2.4e-06,0.011,0.012,0.0041,0.0012,7.3e-05,0.0012,0.00063,0.0012,0.0012,1,1,3.9 -15390000,0.78,-0.017,-0.0031,-0.62,-0.025,-0.018,-0.023,-0.0075,-0.0094,-3.7e+02,-0.001,-0.006,-7e-05,0.067,-0.035,-0.13,-0.11,-0.026,0.5,-0.0041,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.028,0.029,0.029,0.053,0.053,0.051,2.2e-06,2.5e-06,2.4e-06,0.011,0.012,0.0038,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 -15490000,0.78,-0.017,-0.003,-0.62,-0.027,-0.018,-0.023,-0.01,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.036,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.4e-06,2.4e-06,0.011,0.012,0.0037,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 -15590000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.022,-0.0097,-0.01,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.037,-0.13,-0.11,-0.026,0.5,-0.0042,-0.091,-0.069,0,0,-3.6e+02,0.00015,0.00016,0.049,0.029,0.029,0.028,0.062,0.062,0.052,2.1e-06,2.4e-06,2.4e-06,0.011,0.011,0.0035,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,3.9 -15690000,0.78,-0.017,-0.0029,-0.62,-0.027,-0.017,-0.022,-0.012,-0.012,-3.7e+02,-0.001,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.3e-06,2.4e-06,0.01,0.011,0.0033,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 -15790000,0.78,-0.017,-0.003,-0.62,-0.025,-0.016,-0.025,-0.0085,-0.0098,-3.7e+02,-0.001,-0.006,-7.2e-05,0.067,-0.038,-0.12,-0.11,-0.026,0.5,-0.0042,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00016,0.049,0.026,0.027,0.027,0.056,0.056,0.051,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.0031,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 -15890000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.023,-0.011,-0.011,-3.7e+02,-0.001,-0.006,-7.2e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.028,0.028,0.027,0.062,0.062,0.052,1.9e-06,2.2e-06,2.4e-06,0.01,0.011,0.003,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 -15990000,0.78,-0.017,-0.003,-0.62,-0.024,-0.016,-0.018,-0.0078,-0.01,-3.7e+02,-0.0011,-0.006,-7e-05,0.066,-0.037,-0.13,-0.11,-0.026,0.5,-0.0041,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.024,0.024,0.026,0.052,0.052,0.051,1.8e-06,2.1e-06,2.4e-06,0.0099,0.011,0.0028,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4 -16090000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.018,-0.015,-0.0099,-0.012,-3.7e+02,-0.0011,-0.006,-6.7e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00014,0.00015,0.049,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.1e-06,2.4e-06,0.0097,0.011,0.0027,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 -16190000,0.78,-0.017,-0.0031,-0.62,-0.024,-0.016,-0.014,-0.0073,-0.0094,-3.7e+02,-0.0011,-0.006,-6.6e-05,0.066,-0.035,-0.13,-0.11,-0.026,0.5,-0.004,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00015,0.049,0.023,0.023,0.025,0.049,0.05,0.051,1.7e-06,2e-06,2.4e-06,0.0096,0.011,0.0025,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 -16290000,0.78,-0.017,-0.0032,-0.62,-0.026,-0.018,-0.015,-0.0098,-0.012,-3.7e+02,-0.0011,-0.0059,-6.4e-05,0.066,-0.034,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00015,0.049,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2e-06,2.4e-06,0.0095,0.01,0.0024,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 -16390000,0.78,-0.017,-0.0031,-0.62,-0.023,-0.015,-0.014,-0.0073,-0.009,-3.7e+02,-0.0011,-0.006,-6.3e-05,0.065,-0.034,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.022,0.022,0.023,0.047,0.047,0.051,1.6e-06,1.9e-06,2.4e-06,0.0093,0.01,0.0022,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.1 -16490000,0.78,-0.017,-0.0031,-0.62,-0.022,-0.016,-0.017,-0.0093,-0.01,-3.7e+02,-0.0011,-0.006,-6.3e-05,0.064,-0.034,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,1.9e-06,2.4e-06,0.0092,0.01,0.0021,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 -16590000,0.78,-0.017,-0.0031,-0.62,-0.022,-0.012,-0.018,-0.0097,-0.0065,-3.7e+02,-0.0011,-0.006,-6e-05,0.064,-0.034,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.021,0.021,0.022,0.046,0.046,0.051,1.6e-06,1.8e-06,2.4e-06,0.0091,0.01,0.002,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 -16690000,0.78,-0.017,-0.0031,-0.62,-0.024,-0.013,-0.014,-0.012,-0.0075,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.022,0.022,0.022,0.05,0.05,0.051,1.5e-06,1.8e-06,2.4e-06,0.009,0.0099,0.0019,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 -16790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.0094,-0.013,-0.012,-0.0042,-3.7e+02,-0.0011,-0.006,-5.9e-05,0.065,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,2.4e-06,0.0089,0.0098,0.0018,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.2 -16890000,0.78,-0.017,-0.003,-0.62,-0.024,-0.01,-0.01,-0.014,-0.005,-3.7e+02,-0.0011,-0.006,-6e-05,0.064,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00013,0.00014,0.049,0.021,0.021,0.021,0.049,0.049,0.051,1.5e-06,1.7e-06,2.4e-06,0.0088,0.0097,0.0017,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 -16990000,0.78,-0.017,-0.0029,-0.62,-0.023,-0.01,-0.0099,-0.013,-0.0049,-3.7e+02,-0.0011,-0.006,-6.1e-05,0.064,-0.036,-0.13,-0.11,-0.026,0.5,-0.0039,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00014,0.049,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,2.4e-06,0.0087,0.0095,0.0016,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 -17090000,0.78,-0.017,-0.0029,-0.62,-0.024,-0.012,-0.0098,-0.015,-0.0059,-3.7e+02,-0.0012,-0.006,-6e-05,0.063,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00014,0.049,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,2.4e-06,0.0086,0.0094,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 -17190000,0.78,-0.017,-0.003,-0.62,-0.023,-0.014,-0.011,-0.013,-0.0062,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.019,0.042,0.042,0.049,1.3e-06,1.6e-06,2.4e-06,0.0085,0.0093,0.0015,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.3 -17290000,0.78,-0.017,-0.0029,-0.62,-0.026,-0.016,-0.0061,-0.016,-0.0073,-3.7e+02,-0.0012,-0.006,-6e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0038,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.6e-06,2.4e-06,0.0084,0.0093,0.0014,0.0012,7.3e-05,0.0012,0.00062,0.0012,0.0012,1,1,4.4 -17390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.017,-0.0042,-0.013,-0.0075,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.091,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.5e-06,2.4e-06,0.0083,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 -17490000,0.78,-0.017,-0.003,-0.62,-0.025,-0.018,-0.0025,-0.016,-0.0094,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.018,0.046,0.046,0.049,1.3e-06,1.5e-06,2.4e-06,0.0082,0.0091,0.0013,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 -17590000,0.78,-0.017,-0.003,-0.62,-0.024,-0.018,0.003,-0.013,-0.009,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,2.4e-06,0.0081,0.009,0.0012,0.0012,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.4 -17690000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0024,-0.016,-0.011,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.062,-0.035,-0.13,-0.11,-0.026,0.5,-0.0037,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.019,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0089,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -17790000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.001,-0.014,-0.012,-3.7e+02,-0.0012,-0.006,-5.3e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.4e-06,2.4e-06,0.008,0.0088,0.0011,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -17890000,0.78,-0.017,-0.0031,-0.62,-0.026,-0.022,0.0011,-0.017,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00012,0.00013,0.049,0.02,0.02,0.016,0.052,0.053,0.048,1.2e-06,1.4e-06,2.4e-06,0.0079,0.0087,0.001,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -17990000,0.78,-0.017,-0.003,-0.62,-0.025,-0.02,0.0023,-0.015,-0.014,-3.7e+02,-0.0012,-0.006,-5.1e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,2.4e-06,0.0078,0.0086,0.00099,0.0011,7.3e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.5 -18090000,0.78,-0.017,-0.003,-0.62,-0.027,-0.02,0.0047,-0.018,-0.016,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.021,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.3e-06,2.4e-06,0.0078,0.0086,0.00096,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 -18190000,0.78,-0.017,-0.003,-0.62,-0.023,-0.019,0.0061,-0.013,-0.013,-3.7e+02,-0.0012,-0.006,-5e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.3e-06,2.3e-06,0.0077,0.0085,0.0009,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 -18290000,0.78,-0.017,-0.0029,-0.62,-0.025,-0.02,0.0072,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-5.2e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.019,0.019,0.015,0.056,0.056,0.046,1.1e-06,1.3e-06,2.4e-06,0.0076,0.0084,0.00087,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 -18390000,0.78,-0.017,-0.003,-0.62,-0.023,-0.021,0.0084,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.063,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.00083,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.6 -18490000,0.78,-0.017,-0.003,-0.62,-0.024,-0.022,0.0081,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.7e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.018,0.018,0.014,0.053,0.053,0.046,1e-06,1.2e-06,2.3e-06,0.0075,0.0083,0.0008,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 -18590000,0.78,-0.016,-0.003,-0.62,-0.022,-0.022,0.0062,-0.011,-0.013,-3.7e+02,-0.0013,-0.006,-4.2e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.016,0.016,0.014,0.046,0.046,0.045,9.8e-07,1.2e-06,2.3e-06,0.0074,0.0082,0.00076,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 -18690000,0.78,-0.017,-0.003,-0.62,-0.024,-0.022,0.0043,-0.014,-0.015,-3.7e+02,-0.0012,-0.006,-4.3e-05,0.063,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.017,0.018,0.013,0.05,0.05,0.045,9.6e-07,1.2e-06,2.3e-06,0.0074,0.0081,0.00074,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 -18790000,0.78,-0.016,-0.0029,-0.62,-0.022,-0.021,0.004,-0.012,-0.012,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.062,-0.034,-0.13,-0.11,-0.026,0.5,-0.0036,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.015,0.016,0.013,0.044,0.044,0.045,9.4e-07,1.1e-06,2.3e-06,0.0073,0.008,0.0007,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.7 -18890000,0.78,-0.016,-0.003,-0.62,-0.022,-0.023,0.0046,-0.013,-0.015,-3.7e+02,-0.0013,-0.006,-3.9e-05,0.062,-0.033,-0.13,-0.11,-0.026,0.5,-0.0035,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00012,0.049,0.016,0.017,0.013,0.048,0.048,0.045,9.2e-07,1.1e-06,2.3e-06,0.0072,0.008,0.00068,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 -18990000,0.78,-0.016,-0.003,-0.62,-0.019,-0.023,0.0033,-0.0092,-0.013,-3.7e+02,-0.0013,-0.006,-3.5e-05,0.061,-0.032,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00011,0.049,0.015,0.015,0.012,0.043,0.043,0.044,9e-07,1.1e-06,2.3e-06,0.0072,0.0079,0.00065,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 -19090000,0.78,-0.016,-0.003,-0.62,-0.018,-0.025,0.0063,-0.011,-0.015,-3.7e+02,-0.0013,-0.006,-3.5e-05,0.061,-0.032,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.069,0,0,-3.6e+02,0.00011,0.00011,0.049,0.016,0.016,0.012,0.046,0.047,0.044,8.9e-07,1.1e-06,2.3e-06,0.0071,0.0079,0.00063,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 -19190000,0.78,-0.016,-0.0031,-0.62,-0.015,-0.024,0.0063,-0.0072,-0.014,-3.7e+02,-0.0013,-0.006,-3.1e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.012,0.041,0.042,0.044,8.6e-07,1.1e-06,2.3e-06,0.0071,0.0078,0.0006,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.8 -19290000,0.78,-0.016,-0.003,-0.62,-0.016,-0.024,0.0091,-0.0089,-0.016,-3.7e+02,-0.0013,-0.006,-3.2e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.012,0.045,0.045,0.044,8.5e-07,1e-06,2.3e-06,0.007,0.0077,0.00058,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 -19390000,0.78,-0.016,-0.003,-0.62,-0.015,-0.022,0.013,-0.0079,-0.014,-3.7e+02,-0.0013,-0.006,-2.8e-05,0.06,-0.032,-0.13,-0.11,-0.026,0.5,-0.0034,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.015,0.012,0.04,0.041,0.043,8.3e-07,1e-06,2.3e-06,0.007,0.0077,0.00056,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 -19490000,0.78,-0.016,-0.0031,-0.62,-0.015,-0.024,0.0093,-0.0095,-0.017,-3.7e+02,-0.0013,-0.006,-2.5e-05,0.061,-0.032,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.011,0.044,0.044,0.043,8.2e-07,1e-06,2.3e-06,0.0069,0.0076,0.00055,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 -19590000,0.78,-0.016,-0.0032,-0.62,-0.013,-0.022,0.0085,-0.0079,-0.015,-3.7e+02,-0.0013,-0.0059,-1.8e-05,0.061,-0.031,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.015,0.011,0.04,0.04,0.042,7.9e-07,9.7e-07,2.3e-06,0.0069,0.0075,0.00052,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,4.9 -19690000,0.78,-0.016,-0.0031,-0.62,-0.013,-0.021,0.01,-0.0088,-0.017,-3.7e+02,-0.0013,-0.006,-2e-05,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.016,0.011,0.043,0.044,0.042,7.8e-07,9.6e-07,2.3e-06,0.0068,0.0075,0.00051,0.0011,7.2e-05,0.0012,0.00061,0.0012,0.0012,1,1,5 -19790000,0.78,-0.016,-0.0032,-0.62,-0.012,-0.018,0.01,-0.0075,-0.015,-3.7e+02,-0.0013,-0.006,-1.6e-05,0.06,-0.031,-0.13,-0.11,-0.026,0.5,-0.0033,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.014,0.014,0.011,0.039,0.039,0.042,7.7e-07,9.4e-07,2.3e-06,0.0068,0.0074,0.00049,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 -19890000,0.78,-0.016,-0.0032,-0.62,-0.011,-0.02,0.012,-0.0091,-0.018,-3.7e+02,-0.0013,-0.0059,-1.3e-05,0.061,-0.031,-0.13,-0.11,-0.026,0.5,-0.0032,-0.092,-0.068,0,0,-3.6e+02,0.0001,0.00011,0.049,0.015,0.015,0.011,0.043,0.043,0.042,7.6e-07,9.3e-07,2.3e-06,0.0067,0.0074,0.00048,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 -19990000,0.78,-0.016,-0.0032,-0.62,-0.0095,-0.02,0.014,-0.0079,-0.017,-3.7e+02,-0.0013,-0.0059,-3.8e-06,0.061,-0.03,-0.13,-0.11,-0.026,0.5,-0.0031,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.014,0.01,0.039,0.039,0.041,7.4e-07,9e-07,2.3e-06,0.0067,0.0073,0.00046,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5 -20090000,0.78,-0.016,-0.0033,-0.62,-0.0095,-0.021,0.015,-0.0085,-0.02,-3.7e+02,-0.0013,-0.0059,9.8e-07,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.9e-05,0.00011,0.049,0.014,0.015,0.01,0.042,0.042,0.042,7.3e-07,8.9e-07,2.3e-06,0.0066,0.0073,0.00045,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 -20190000,0.78,-0.016,-0.0034,-0.62,-0.01,-0.019,0.017,-0.0087,-0.018,-3.7e+02,-0.0013,-0.0059,6.9e-06,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.013,0.014,0.01,0.038,0.038,0.041,7.1e-07,8.7e-07,2.3e-06,0.0066,0.0072,0.00043,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 -20290000,0.78,-0.016,-0.0034,-0.62,-0.0088,-0.019,0.015,-0.0091,-0.02,-3.7e+02,-0.0013,-0.0059,8.7e-06,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.8e-05,0.00011,0.048,0.014,0.015,0.0099,0.042,0.042,0.041,7e-07,8.6e-07,2.3e-06,0.0065,0.0072,0.00042,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 -20390000,0.78,-0.016,-0.0033,-0.62,-0.0084,-0.016,0.017,-0.009,-0.017,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,8.4e-07,2.3e-06,0.0065,0.0071,0.00041,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.1 -20490000,0.78,-0.016,-0.0034,-0.62,-0.0087,-0.017,0.017,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.7e-05,0.0001,0.048,0.014,0.015,0.0096,0.041,0.042,0.041,6.8e-07,8.3e-07,2.3e-06,0.0065,0.0071,0.0004,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 -20590000,0.78,-0.016,-0.0033,-0.62,-0.0081,-0.014,0.014,-0.0085,-0.016,-3.7e+02,-0.0013,-0.0059,1.3e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.5e-05,0.0001,0.048,0.013,0.014,0.0093,0.037,0.038,0.04,6.6e-07,8.1e-07,2.3e-06,0.0064,0.007,0.00038,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 -20690000,0.78,-0.016,-0.0034,-0.62,-0.0089,-0.015,0.015,-0.0094,-0.018,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.6e-05,0.0001,0.048,0.014,0.015,0.0093,0.041,0.041,0.04,6.5e-07,8e-07,2.3e-06,0.0064,0.007,0.00037,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 -20790000,0.78,-0.016,-0.0034,-0.62,-0.0065,-0.014,0.015,-0.0078,-0.016,-3.7e+02,-0.0013,-0.0059,1.9e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.013,0.014,0.0091,0.037,0.038,0.04,6.4e-07,7.8e-07,2.3e-06,0.0063,0.0069,0.00036,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.2 -20890000,0.78,-0.016,-0.0035,-0.62,-0.0068,-0.014,0.014,-0.0083,-0.018,-3.7e+02,-0.0013,-0.0059,2.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.5e-05,0.0001,0.048,0.014,0.015,0.009,0.041,0.041,0.04,6.3e-07,7.7e-07,2.3e-06,0.0063,0.0069,0.00035,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 -20990000,0.78,-0.016,-0.0035,-0.62,-0.0052,-0.012,0.015,-0.008,-0.018,-3.7e+02,-0.0013,-0.0059,2.5e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.014,0.015,0.0088,0.043,0.043,0.039,6.2e-07,7.6e-07,2.3e-06,0.0063,0.0069,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 -21090000,0.78,-0.016,-0.0035,-0.62,-0.0063,-0.012,0.015,-0.0089,-0.02,-3.7e+02,-0.0013,-0.0059,2.7e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.4e-05,0.0001,0.048,0.015,0.016,0.0088,0.047,0.047,0.039,6.1e-07,7.5e-07,2.3e-06,0.0062,0.0068,0.00034,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 -21190000,0.78,-0.016,-0.0035,-0.62,-0.0064,-0.011,0.014,-0.0094,-0.02,-3.7e+02,-0.0013,-0.0059,2.8e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.3e-05,0.0001,0.048,0.015,0.016,0.0086,0.049,0.05,0.039,6e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00033,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.3 -21290000,0.78,-0.016,-0.0036,-0.62,-0.0059,-0.012,0.016,-0.0094,-0.023,-3.7e+02,-0.0013,-0.0059,3.3e-05,0.062,-0.027,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.6e+02,9.3e-05,0.0001,0.048,0.016,0.017,0.0085,0.053,0.054,0.039,5.9e-07,7.3e-07,2.3e-06,0.0062,0.0068,0.00032,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 -21390000,0.78,-0.016,-0.0036,-0.62,-0.0053,-0.0073,0.016,-0.0082,-0.017,-3.7e+02,-0.0013,-0.0059,3.6e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.2e-05,9.8e-05,0.048,0.014,0.015,0.0084,0.046,0.047,0.039,5.8e-07,7.1e-07,2.3e-06,0.0061,0.0067,0.00031,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 -21490000,0.78,-0.016,-0.0036,-0.62,-0.006,-0.0083,0.016,-0.0093,-0.019,-3.7e+02,-0.0013,-0.0059,3.8e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.2e-05,9.8e-05,0.048,0.015,0.016,0.0083,0.05,0.051,0.038,5.7e-07,7e-07,2.3e-06,0.0061,0.0067,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 -21590000,0.78,-0.016,-0.0035,-0.62,-0.0046,-0.0066,0.016,-0.0077,-0.014,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9e-05,9.7e-05,0.048,0.013,0.014,0.0081,0.044,0.045,0.038,5.6e-07,6.8e-07,2.3e-06,0.0061,0.0066,0.0003,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.4 -21690000,0.78,-0.016,-0.0036,-0.62,-0.0061,-0.0077,0.017,-0.009,-0.016,-3.7e+02,-0.0013,-0.0059,4.4e-05,0.063,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9.1e-05,9.7e-05,0.048,0.014,0.015,0.0081,0.048,0.049,0.038,5.5e-07,6.8e-07,2.3e-06,0.006,0.0066,0.00029,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 -21790000,0.78,-0.016,-0.0034,-0.62,-0.0052,-0.0054,0.016,-0.0079,-0.01,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 -21890000,0.78,-0.016,-0.0034,-0.62,-0.0058,-0.0063,0.016,-0.0086,-0.011,-3.7e+02,-0.0013,-0.0059,4.9e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.6e+02,9e-05,9.6e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.006,0.0065,0.00028,0.0011,7.2e-05,0.0012,0.0006,0.0012,0.0012,1,1,5.5 -21990000,0.78,-0.016,-0.0034,-0.62,-0.0057,-0.0035,0.017,-0.008,-0.0069,-3.7e+02,-0.0013,-0.0059,5.6e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.7e+02,8.8e-05,9.4e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.0006,0.0012,0.0012,1,1,0.01 -22090000,0.78,-0.016,-0.0034,-0.62,-0.0054,-0.0051,0.015,-0.0084,-0.0074,-3.7e+02,-0.0013,-0.0059,5.6e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.9e-05,9.5e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0059,0.0065,0.00027,0.0011,7.1e-05,0.0012,0.0006,0.0012,0.0012,1,1,0.01 -22190000,0.78,-0.016,-0.0034,-0.62,-0.0041,-0.0056,0.015,-0.007,-0.0066,-3.7e+02,-0.0013,-0.0059,5.9e-05,0.062,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.7e-05,9.3e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0059,0.0064,0.00026,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22290000,0.78,-0.016,-0.0034,-0.62,-0.0036,-0.0053,0.016,-0.0077,-0.007,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0059,0.0064,0.00025,0.0011,7.1e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22390000,0.78,-0.016,-0.0034,-0.62,-0.0011,-0.0052,0.017,-0.0059,-0.0063,-3.7e+02,-0.0013,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0058,0.0064,0.00025,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22490000,0.78,-0.016,-0.0034,-0.62,1.4e-05,-0.0059,0.018,-0.0053,-0.0067,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22590000,0.78,-0.016,-0.0034,-0.62,0.0019,-0.0048,0.017,-0.0036,-0.0061,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22690000,0.78,-0.016,-0.0035,-0.62,0.0034,-0.0061,0.019,-0.0029,-0.0072,-3.7e+02,-0.0014,-0.0059,7e-05,0.06,-0.027,-0.13,-0.11,-0.026,0.5,-0.0028,-0.092,-0.068,0,0,-3.7e+02,8.7e-05,9.2e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0058,0.0063,0.00024,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22790000,0.78,-0.016,-0.0034,-0.62,0.0045,-0.0054,0.02,-0.0024,-0.0058,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22890000,0.78,-0.016,-0.0034,-0.62,0.0051,-0.0063,0.021,-0.0025,-0.0066,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.6e-05,9.2e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0062,0.00023,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -22990000,0.78,-0.016,-0.0034,-0.62,0.0048,-0.0065,0.022,-0.0026,-0.0074,-3.7e+02,-0.0014,-0.0059,6.8e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.5e-05,9.1e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23090000,0.78,-0.016,-0.0033,-0.62,0.0051,-0.0062,0.023,-0.0023,-0.0071,-3.7e+02,-0.0014,-0.0059,6.4e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.6e-05,9.1e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0057,0.0062,0.00022,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23190000,0.78,-0.016,-0.0034,-0.62,0.0027,-0.0051,0.024,-0.0051,-0.0071,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.06,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0057,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23290000,0.78,-0.016,-0.0033,-0.62,0.0023,-0.0048,0.025,-0.0054,-0.008,-3.7e+02,-0.0014,-0.0059,6.8e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9.1e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23390000,0.78,-0.016,-0.0034,-0.62,-0.001,-0.0046,0.022,-0.0095,-0.0082,-3.7e+02,-0.0014,-0.0059,7e-05,0.061,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.093,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.00021,0.0011,6.9e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23490000,0.78,-0.013,-0.0055,-0.62,0.0046,-0.0042,-0.011,-0.01,-0.0098,-3.7e+02,-0.0013,-0.0059,7.4e-05,0.061,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.5e-05,9e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0056,0.0061,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23590000,0.78,-0.0046,-0.0097,-0.62,0.015,-0.00011,-0.043,-0.0094,-0.0059,-3.7e+02,-0.0013,-0.0059,7.7e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23690000,0.78,0.0011,-0.0087,-0.62,0.043,0.014,-0.093,-0.007,-0.0057,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.062,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.068,0,0,-3.7e+02,8.3e-05,8.8e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0056,0.006,0.0002,0.0011,6.8e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23790000,0.78,-0.0026,-0.0062,-0.62,0.064,0.031,-0.15,-0.007,-0.0037,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.092,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23890000,0.78,-0.0089,-0.0043,-0.62,0.077,0.043,-0.2,0.0005,6.3e-05,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.063,-0.029,-0.13,-0.11,-0.026,0.5,-0.0031,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -23990000,0.78,-0.014,-0.0035,-0.62,0.072,0.043,-0.25,-0.005,-0.0014,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -24090000,0.78,-0.012,-0.0046,-0.62,0.073,0.042,-0.3,0.0014,0.002,-3.7e+02,-0.0013,-0.0059,8.8e-05,0.064,-0.029,-0.13,-0.11,-0.026,0.5,-0.003,-0.091,-0.067,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0055,0.006,0.00019,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -24190000,0.78,-0.01,-0.0055,-0.62,0.07,0.041,-0.35,-0.0058,-0.00021,-3.7e+02,-0.0013,-0.0059,8.6e-05,0.065,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.7e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -24290000,0.78,-0.0092,-0.0058,-0.62,0.078,0.046,-0.4,0.00065,0.0042,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.065,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.7e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00059,0.0012,0.0012,1,1,0.01 -24390000,0.79,-0.0096,-0.006,-0.62,0.075,0.044,-0.46,-0.012,-0.0022,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.1e-05,8.6e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0055,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 -24490000,0.79,-0.0054,-0.0064,-0.62,0.086,0.051,-0.51,-0.0037,0.0025,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.026,0.5,-0.0029,-0.091,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0059,0.00018,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 -24590000,0.79,-0.0019,-0.0065,-0.62,0.09,0.055,-0.56,-0.017,-0.0063,-3.7e+02,-0.0012,-0.0059,6.5e-05,0.068,-0.028,-0.13,-0.11,-0.026,0.5,-0.0028,-0.091,-0.068,0,0,-3.7e+02,8.1e-05,8.6e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.6e-05,0.0012,0.00058,0.0012,0.0012,1,1,0.01 -24690000,0.79,-0.00097,-0.0065,-0.62,0.11,0.071,-0.64,-0.0079,-0.0013,-3.7e+02,-0.0012,-0.0059,7.2e-05,0.068,-0.028,-0.13,-0.11,-0.026,0.5,-0.0029,-0.09,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -24790000,0.79,-0.0025,-0.0064,-0.62,0.11,0.08,-0.73,-0.027,-0.006,-3.7e+02,-0.0012,-0.0059,6.1e-05,0.07,-0.029,-0.13,-0.11,-0.026,0.5,-0.0026,-0.09,-0.068,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.018,0.018,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0059,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -24890000,0.79,-0.00061,-0.0079,-0.62,0.13,0.095,-0.75,-0.016,0.0028,-3.7e+02,-0.0012,-0.0059,6.1e-05,0.07,-0.029,-0.13,-0.11,-0.026,0.5,-0.0028,-0.089,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0054,0.0058,0.00017,0.0011,6.5e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -24990000,0.79,0.0012,-0.0095,-0.62,0.13,0.1,-0.81,-0.038,-0.0035,-3.7e+02,-0.0011,-0.0059,4.6e-05,0.072,-0.029,-0.13,-0.11,-0.026,0.5,-0.0025,-0.089,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -25090000,0.79,0.00058,-0.0099,-0.62,0.16,0.12,-0.86,-0.024,0.0079,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.072,-0.029,-0.13,-0.11,-0.027,0.5,-0.0026,-0.088,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00058,0.0011,0.0012,1,1,0.01 -25190000,0.79,-0.0014,-0.0096,-0.61,0.15,0.11,-0.91,-0.068,-0.014,-3.7e+02,-0.0011,-0.0058,2.5e-05,0.076,-0.029,-0.13,-0.11,-0.027,0.5,-0.0023,-0.088,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0054,0.0058,0.00016,0.0011,6.4e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 -25290000,0.79,0.0056,-0.011,-0.62,0.18,0.13,-0.96,-0.051,-0.0029,-3.7e+02,-0.0011,-0.0058,2.7e-05,0.076,-0.029,-0.13,-0.11,-0.027,0.5,-0.0024,-0.087,-0.069,0,0,-3.7e+02,8.1e-05,8.5e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.0011,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 -25390000,0.79,0.012,-0.011,-0.61,0.18,0.13,-1,-0.099,-0.027,-3.7e+02,-0.001,-0.0058,8.4e-06,0.079,-0.029,-0.13,-0.12,-0.027,0.5,-0.0022,-0.087,-0.07,0,0,-3.7e+02,8.1e-05,8.5e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00016,0.001,6.3e-05,0.0012,0.00057,0.0011,0.0012,1,1,0.01 -25490000,0.79,0.013,-0.011,-0.61,0.22,0.16,-1.1,-0.081,-0.014,-3.7e+02,-0.001,-0.0058,1.7e-05,0.079,-0.029,-0.13,-0.12,-0.027,0.5,-0.0025,-0.086,-0.069,0,0,-3.7e+02,8.2e-05,8.5e-05,0.046,0.022,0.022,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.2e-05,0.0012,0.00057,0.0011,0.0011,1,1,0.01 -25590000,0.79,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.058,0.0026,-3.7e+02,-0.001,-0.0058,2.3e-05,0.08,-0.029,-0.13,-0.12,-0.027,0.5,-0.0028,-0.085,-0.068,0,0,-3.7e+02,8.2e-05,8.6e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6.1e-05,0.0011,0.00057,0.0011,0.0011,1,1,0.01 -25690000,0.79,0.018,-0.014,-0.62,0.29,0.22,-1.2,-0.031,0.021,-3.7e+02,-0.00099,-0.0058,3e-05,0.08,-0.029,-0.13,-0.12,-0.027,0.5,-0.0031,-0.084,-0.068,0,0,-3.7e+02,8.3e-05,8.6e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.001,6e-05,0.0011,0.00056,0.0011,0.0011,1,1,0.01 -25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0015,0.042,-3.7e+02,-0.00099,-0.0058,4.2e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0036,-0.083,-0.067,0,0,-3.7e+02,8.4e-05,8.6e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00099,5.9e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01 -25890000,0.78,0.025,-0.016,-0.62,0.41,0.29,-1.3,0.041,0.065,-3.7e+02,-0.00099,-0.0058,5.7e-05,0.08,-0.029,-0.13,-0.12,-0.028,0.5,-0.0042,-0.081,-0.066,0,0,-3.7e+02,8.4e-05,8.7e-05,0.045,0.029,0.03,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0053,0.0058,0.00015,0.00097,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1,0.01 -25990000,0.78,0.022,-0.016,-0.62,0.46,0.32,-1.3,0.084,0.093,-3.7e+02,-0.00099,-0.0058,6.6e-05,0.08,-0.03,-0.13,-0.12,-0.028,0.5,-0.0046,-0.08,-0.065,0,0,-3.7e+02,8.5e-05,8.8e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00095,5.7e-05,0.0011,0.00055,0.001,0.0011,1,1,0.01 -26090000,0.78,0.032,-0.019,-0.62,0.52,0.36,-1.3,0.13,0.13,-3.7e+02,-0.00099,-0.0058,6.4e-05,0.08,-0.03,-0.13,-0.12,-0.029,0.5,-0.0047,-0.079,-0.065,0,0,-3.7e+02,8.6e-05,8.8e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00015,0.00093,5.6e-05,0.0011,0.00055,0.00098,0.0011,1,1,0.01 -26190000,0.78,0.042,-0.021,-0.62,0.59,0.41,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.4e-05,0.08,-0.03,-0.13,-0.13,-0.03,0.5,-0.0055,-0.075,-0.063,0,0,-3.7e+02,8.7e-05,8.9e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.0009,5.4e-05,0.001,0.00054,0.00094,0.001,1,1,0.01 -26290000,0.78,0.044,-0.022,-0.62,0.67,0.46,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.8e-05,0.081,-0.03,-0.13,-0.13,-0.03,0.49,-0.0058,-0.073,-0.061,0,0,-3.7e+02,8.8e-05,8.9e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.4e-07,2e-06,0.0053,0.0058,0.00014,0.00087,5.2e-05,0.001,0.00053,0.00091,0.00099,1,1,0.01 -26390000,0.78,0.041,-0.021,-0.62,0.75,0.51,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,8.5e-05,0.081,-0.031,-0.13,-0.13,-0.03,0.49,-0.0064,-0.071,-0.06,0,0,-3.7e+02,8.8e-05,9e-05,0.041,0.042,0.046,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00084,5.1e-05,0.00097,0.00051,0.00088,0.00096,1,1,0.01 -26490000,0.78,0.057,-0.028,-0.63,0.84,0.57,-1.3,0.4,0.3,-3.7e+02,-0.00097,-0.0058,9e-05,0.081,-0.031,-0.13,-0.13,-0.031,0.49,-0.0066,-0.069,-0.058,0,0,-3.7e+02,8.9e-05,9.1e-05,0.039,0.045,0.05,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00081,4.9e-05,0.00093,0.00049,0.00084,0.00093,1,1,0.01 -26590000,0.78,0.074,-0.032,-0.62,0.95,0.65,-1.3,0.49,0.36,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.081,-0.031,-0.13,-0.14,-0.032,0.49,-0.0063,-0.066,-0.057,0,0,-3.7e+02,9e-05,9.1e-05,0.038,0.049,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00076,4.6e-05,0.00088,0.00047,0.0008,0.00088,1,1,0.01 -26690000,0.77,0.077,-0.033,-0.63,1.1,0.72,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,0.0001,0.081,-0.031,-0.13,-0.14,-0.033,0.49,-0.0074,-0.061,-0.052,0,0,-3.7e+02,9.1e-05,9.2e-05,0.035,0.053,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0058,0.00014,0.00071,4.3e-05,0.00082,0.00045,0.00074,0.00082,1,1,0.01 -26790000,0.77,0.071,-0.032,-0.63,1.2,0.8,-1.3,0.71,0.5,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.031,-0.13,-0.14,-0.034,0.48,-0.0072,-0.057,-0.049,0,0,-3.7e+02,9.2e-05,9.3e-05,0.032,0.056,0.067,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0053,0.0057,0.00014,0.00067,4.1e-05,0.00078,0.00042,0.00069,0.00077,1,1,0.01 -26890000,0.77,0.094,-0.039,-0.63,1.3,0.88,-1.3,0.84,0.58,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.031,-0.13,-0.15,-0.035,0.48,-0.0078,-0.053,-0.047,0,0,-3.7e+02,9.2e-05,9.3e-05,0.03,0.059,0.072,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00063,3.9e-05,0.00073,0.00039,0.00065,0.00073,1,1,0.01 -26990000,0.76,0.12,-0.044,-0.63,1.5,0.99,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,0.00011,0.081,-0.031,-0.13,-0.15,-0.036,0.48,-0.008,-0.047,-0.043,0,0,-3.7e+02,9.3e-05,9.4e-05,0.027,0.063,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00013,0.00057,3.5e-05,0.00066,0.00035,0.00059,0.00066,1,1,0.01 -27090000,0.76,0.12,-0.045,-0.63,1.7,1.1,-1.3,1.1,0.77,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.16,-0.037,0.47,-0.0079,-0.043,-0.039,0,0,-3.7e+02,9.3e-05,9.4e-05,0.024,0.067,0.085,0.0061,0.36,0.37,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00052,3.2e-05,0.00059,0.00032,0.00053,0.00059,1,1,0.01 -27190000,0.76,0.11,-0.042,-0.63,1.9,1.2,-1.2,1.3,0.89,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.03,-0.13,-0.16,-0.038,0.47,-0.0075,-0.04,-0.035,0,0,-3.7e+02,9.4e-05,9.5e-05,0.021,0.071,0.091,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0052,0.0057,0.00013,0.00048,3e-05,0.00055,0.00029,0.00049,0.00054,1,1,0.01 -27290000,0.76,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.029,-0.13,-0.17,-0.039,0.47,-0.0076,-0.036,-0.033,0,0,-3.7e+02,9.4e-05,9.5e-05,0.019,0.072,0.094,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00045,2.9e-05,0.00052,0.00026,0.00046,0.00051,1,1,0.01 -27390000,0.77,0.078,-0.033,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00096,-0.0058,0.00011,0.081,-0.029,-0.13,-0.17,-0.039,0.47,-0.0075,-0.035,-0.032,0,0,-3.7e+02,9.5e-05,9.6e-05,0.017,0.073,0.094,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0052,0.0056,0.00013,0.00043,2.8e-05,0.0005,0.00023,0.00044,0.00049,1,1,0.01 -27490000,0.77,0.062,-0.029,-0.64,2.2,1.5,-1.2,1.9,1.3,-3.7e+02,-0.00096,-0.0058,0.00011,0.082,-0.028,-0.13,-0.17,-0.039,0.47,-0.0072,-0.034,-0.032,0,0,-3.7e+02,9.6e-05,9.6e-05,0.015,0.074,0.093,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00042,2.7e-05,0.00049,0.00021,0.00043,0.00048,1,1,0.01 -27590000,0.77,0.05,-0.025,-0.63,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,0.0001,0.082,-0.027,-0.13,-0.17,-0.039,0.47,-0.0067,-0.033,-0.031,0,0,-3.7e+02,9.6e-05,9.7e-05,0.014,0.074,0.092,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00041,2.6e-05,0.00048,0.0002,0.00042,0.00048,1,1,0.01 -27690000,0.77,0.048,-0.025,-0.63,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,0.0001,0.082,-0.026,-0.13,-0.17,-0.04,0.47,-0.0063,-0.032,-0.031,0,0,-3.7e+02,9.7e-05,9.7e-05,0.013,0.074,0.09,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.0004,2.6e-05,0.00048,0.00019,0.00042,0.00047,1,1,0.01 -27790000,0.77,0.05,-0.025,-0.63,2.3,1.6,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,9.6e-05,0.083,-0.026,-0.13,-0.17,-0.04,0.47,-0.0057,-0.032,-0.031,0,0,-3.7e+02,9.8e-05,9.8e-05,0.012,0.074,0.089,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00039,2.6e-05,0.00047,0.00017,0.00041,0.00047,1,1,0.01 -27890000,0.77,0.048,-0.024,-0.63,2.3,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,9.5e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.46,-0.0057,-0.031,-0.031,0,0,-3.7e+02,9.9e-05,9.8e-05,0.011,0.075,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00039,2.5e-05,0.00047,0.00016,0.0004,0.00047,1,1,0.01 -27990000,0.77,0.044,-0.023,-0.63,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.083,-0.025,-0.13,-0.17,-0.04,0.47,-0.0056,-0.031,-0.031,0,0,-3.7e+02,0.0001,9.9e-05,0.01,0.075,0.088,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00038,2.5e-05,0.00047,0.00016,0.0004,0.00046,1,1,0.01 -28090000,0.78,0.058,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,8.8e-05,0.083,-0.024,-0.13,-0.17,-0.04,0.46,-0.0051,-0.03,-0.03,0,0,-3.7e+02,0.0001,9.9e-05,0.0096,0.076,0.088,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00012,0.00038,2.4e-05,0.00046,0.00015,0.00039,0.00046,1,1,0.01 -28190000,0.77,0.071,-0.031,-0.63,2.4,1.7,-0.93,3.5,2.4,-3.7e+02,-0.00095,-0.0058,8.7e-05,0.084,-0.024,-0.13,-0.17,-0.04,0.46,-0.0051,-0.03,-0.03,0,0,-3.7e+02,0.0001,0.0001,0.0091,0.077,0.088,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00037,2.4e-05,0.00046,0.00014,0.00038,0.00045,1,1,0.01 -28290000,0.78,0.054,-0.025,-0.63,2.4,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.3e-05,0.084,-0.023,-0.13,-0.17,-0.04,0.46,-0.0049,-0.029,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0086,0.077,0.086,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.4e-05,0.00045,0.00014,0.00038,0.00045,1,1,0.01 -28390000,0.78,0.021,-0.013,-0.63,2.4,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,7.9e-05,0.084,-0.022,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01 -28490000,0.78,0.0015,-0.006,-0.63,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0079,0.077,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00036,2.3e-05,0.00045,0.00013,0.00037,0.00045,1,1,0.01 -28590000,0.78,-0.0022,-0.0046,-0.63,2.3,1.7,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.2e-05,0.084,-0.021,-0.13,-0.17,-0.041,0.46,-0.0046,-0.028,-0.029,0,0,-3.7e+02,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 -28690000,0.78,-0.0031,-0.004,-0.63,2.3,1.6,0.99,4.7,3.3,-3.7e+02,-0.00097,-0.0058,6.8e-05,0.083,-0.021,-0.12,-0.17,-0.041,0.46,-0.0045,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00045,0.00012,0.00037,0.00044,1,1,0.01 -28790000,0.78,-0.0035,-0.0038,-0.63,2.2,1.6,0.99,5,3.5,-3.7e+02,-0.00097,-0.0058,6.4e-05,0.083,-0.02,-0.12,-0.17,-0.041,0.46,-0.0043,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00012,0.00035,2.3e-05,0.00044,0.00012,0.00037,0.00044,1,1,0.01 -28890000,0.78,-0.0032,-0.0038,-0.63,2.1,1.6,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,6e-05,0.082,-0.02,-0.12,-0.17,-0.041,0.46,-0.0042,-0.028,-0.029,0,0,-3.7e+02,0.00011,0.0001,0.0067,0.079,0.083,0.0061,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00044,1,1,0.01 -28990000,0.78,-0.0028,-0.0039,-0.62,2.1,1.5,0.98,5.4,3.8,-3.7e+02,-0.001,-0.0058,5.3e-05,0.082,-0.019,-0.12,-0.17,-0.041,0.46,-0.0039,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.0051,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 -29090000,0.78,-0.0024,-0.004,-0.62,2,1.5,0.97,5.6,4,-3.7e+02,-0.001,-0.0058,4.9e-05,0.081,-0.018,-0.12,-0.17,-0.041,0.46,-0.0038,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0063,0.081,0.085,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 -29190000,0.78,-0.0021,-0.0041,-0.62,2,1.5,0.97,5.8,4.1,-3.7e+02,-0.001,-0.0058,4.9e-05,0.081,-0.018,-0.12,-0.17,-0.041,0.46,-0.0039,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0061,0.082,0.087,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00044,0.00011,0.00037,0.00043,1,1,0.01 -29290000,0.78,-0.0012,-0.0044,-0.62,1.9,1.5,0.99,6,4.2,-3.7e+02,-0.001,-0.0058,4.4e-05,0.081,-0.018,-0.12,-0.17,-0.041,0.46,-0.0037,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.00011,0.00037,0.00043,1,1,0.01 -29390000,0.78,0.00011,-0.0047,-0.62,1.9,1.4,1,6.2,4.4,-3.7e+02,-0.001,-0.0058,3.8e-05,0.081,-0.017,-0.12,-0.17,-0.041,0.46,-0.0034,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 -29490000,0.78,0.0013,-0.0051,-0.62,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.5e-05,0.08,-0.016,-0.12,-0.17,-0.041,0.46,-0.0034,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0055,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 -29590000,0.78,0.0023,-0.0053,-0.62,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,3.2e-05,0.08,-0.016,-0.12,-0.17,-0.041,0.46,-0.0033,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,0.0001,0.00037,0.00043,1,1,0.01 -29690000,0.78,0.003,-0.0055,-0.62,1.7,1.4,0.99,6.7,4.8,-3.7e+02,-0.001,-0.0057,2.8e-05,0.08,-0.015,-0.12,-0.17,-0.041,0.46,-0.0032,-0.028,-0.028,0,0,-3.7e+02,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.9e-05,0.00037,0.00043,1,1,0.01 -29790000,0.78,0.0034,-0.0057,-0.62,1.7,1.4,0.98,6.9,5,-3.7e+02,-0.001,-0.0057,2.4e-05,0.079,-0.014,-0.12,-0.17,-0.041,0.46,-0.0032,-0.028,-0.027,0,0,-3.7e+02,0.00011,0.0001,0.0053,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.8e-05,0.00037,0.00042,1,1,0.01 -29890000,0.78,0.0036,-0.0057,-0.62,1.7,1.3,0.97,7.1,5.1,-3.7e+02,-0.001,-0.0057,1.8e-05,0.079,-0.013,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.7e-05,0.00037,0.00042,1,1,0.01 -29990000,0.78,0.0036,-0.0058,-0.62,1.6,1.3,0.95,7.2,5.2,-3.7e+02,-0.001,-0.0057,1.4e-05,0.079,-0.013,-0.12,-0.17,-0.041,0.46,-0.003,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.3e-05,0.00043,9.6e-05,0.00036,0.00042,1,1,0.01 -30090000,0.78,0.0035,-0.0058,-0.62,1.6,1.3,0.94,7.4,5.4,-3.7e+02,-0.001,-0.0057,1e-05,0.079,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.3e-05,0.00043,9.5e-05,0.00036,0.00042,1,1,0.01 -30190000,0.78,0.0032,-0.0057,-0.62,1.6,1.3,0.93,7.6,5.5,-3.7e+02,-0.001,-0.0057,1.1e-05,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0029,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1,0.01 -30290000,0.78,0.003,-0.0056,-0.62,1.5,1.3,0.92,7.7,5.6,-3.7e+02,-0.001,-0.0057,8.3e-06,0.078,-0.012,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1,0.01 -30390000,0.78,0.0028,-0.0056,-0.62,1.5,1.3,0.9,7.9,5.8,-3.7e+02,-0.0011,-0.0057,4.2e-06,0.077,-0.011,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00035,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 -30490000,0.78,0.0026,-0.0055,-0.62,1.5,1.2,0.89,8,5.9,-3.7e+02,-0.0011,-0.0057,3e-06,0.077,-0.01,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1,0.01 -30590000,0.78,0.0021,-0.0054,-0.62,1.4,1.2,0.85,8.2,6,-3.7e+02,-0.0011,-0.0057,9.7e-07,0.077,-0.0095,-0.12,-0.17,-0.041,0.46,-0.0028,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.005,0.0054,0.0001,0.00034,2.2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1,0.01 -30690000,0.78,0.0018,-0.0053,-0.62,1.4,1.2,0.84,8.3,6.1,-3.7e+02,-0.0011,-0.0057,-2.3e-06,0.077,-0.0087,-0.12,-0.17,-0.041,0.46,-0.0027,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01 -30790000,0.78,0.0014,-0.0052,-0.62,1.4,1.2,0.84,8.5,6.2,-3.7e+02,-0.0011,-0.0057,-5.4e-06,0.076,-0.0085,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,0.0001,0.00034,2.2e-05,0.00042,9e-05,0.00036,0.00042,1,1,0.01 -30890000,0.78,0.00095,-0.0051,-0.62,1.3,1.2,0.82,8.6,6.4,-3.7e+02,-0.0011,-0.0057,-8.4e-06,0.076,-0.0077,-0.12,-0.17,-0.041,0.46,-0.0026,-0.028,-0.027,0,0,-3.7e+02,0.00012,0.00011,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0054,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1,0.01 -30990000,0.78,0.00035,-0.0051,-0.62,1.3,1.2,0.82,8.8,6.5,-3.7e+02,-0.0011,-0.0057,-1.2e-05,0.075,-0.0069,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00034,2.2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1,0.01 -31090000,0.78,-0.00019,-0.0049,-0.62,1.3,1.1,0.81,8.9,6.6,-3.7e+02,-0.0011,-0.0057,-1.6e-05,0.075,-0.0062,-0.12,-0.17,-0.041,0.46,-0.0025,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0049,0.0053,9.8e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 -31190000,0.78,-0.00061,-0.0048,-0.62,1.2,1.1,0.8,9,6.7,-3.7e+02,-0.0011,-0.0057,-1.9e-05,0.075,-0.0054,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 -31290000,0.78,-0.0012,-0.0046,-0.62,1.2,1.1,0.8,9.2,6.8,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.075,-0.0047,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.7e-05,0.00034,2.2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1,0.01 -31390000,0.78,-0.0019,-0.0044,-0.62,1.2,1.1,0.8,9.3,6.9,-3.7e+02,-0.0011,-0.0057,-2.4e-05,0.075,-0.0041,-0.12,-0.17,-0.041,0.46,-0.0024,-0.028,-0.027,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 -31490000,0.78,-0.0025,-0.0043,-0.62,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0057,-3e-05,0.074,-0.0033,-0.12,-0.17,-0.041,0.46,-0.0023,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.6e-05,0.00034,2.2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1,0.01 -31590000,0.78,-0.0029,-0.0043,-0.62,1.1,1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0057,-3.1e-05,0.073,-0.0026,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.5e-05,0.00034,2.2e-05,0.00041,8.7e-05,0.00036,0.00041,1,1,0.01 -31690000,0.78,-0.0037,-0.0041,-0.62,1.1,1,0.8,9.7,7.2,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.073,-0.0019,-0.12,-0.17,-0.041,0.46,-0.0022,-0.028,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 -31790000,0.78,-0.0044,-0.0039,-0.62,1.1,1,0.8,9.8,7.3,-3.7e+02,-0.0011,-0.0057,-3.6e-05,0.072,-0.001,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.4e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 -31890000,0.78,-0.0051,-0.0038,-0.62,1,0.99,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0057,-4e-05,0.072,-0.00017,-0.12,-0.17,-0.041,0.46,-0.0021,-0.029,-0.026,0,0,-3.7e+02,0.00013,0.00011,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 -31990000,0.78,-0.0056,-0.0036,-0.62,1,0.97,0.79,10,7.5,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.071,0.00076,-0.12,-0.17,-0.041,0.46,-0.002,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0053,9.3e-05,0.00034,2.2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1,0.01 -32090000,0.78,-0.0064,-0.0034,-0.62,0.99,0.96,0.8,10,7.7,-3.7e+02,-0.0012,-0.0057,-4.9e-05,0.071,0.0015,-0.11,-0.17,-0.041,0.46,-0.0019,-0.029,-0.026,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0059,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.2e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 -32190000,0.78,-0.0073,-0.0032,-0.62,0.96,0.94,0.8,10,7.8,-3.7e+02,-0.0012,-0.0057,-5.8e-05,0.07,0.0024,-0.11,-0.17,-0.041,0.46,-0.0018,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 -32290000,0.78,-0.0081,-0.0031,-0.62,0.93,0.92,0.79,10,7.8,-3.7e+02,-0.0012,-0.0057,-6.2e-05,0.07,0.0034,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9.1e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 -32390000,0.78,-0.0087,-0.003,-0.62,0.9,0.9,0.79,10,7.9,-3.7e+02,-0.0012,-0.0057,-6.3e-05,0.069,0.0041,-0.11,-0.17,-0.041,0.46,-0.0017,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1,0.01 -32490000,0.78,-0.0089,-0.003,-0.62,0.87,0.88,0.8,11,8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.069,0.0048,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.7e-07,2e-06,0.0049,0.0052,9e-05,0.00034,2.2e-05,0.0004,8.5e-05,0.00036,0.0004,1,1,0.01 -32590000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.9e-05,0.069,0.0052,-0.11,-0.17,-0.041,0.46,-0.0016,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 -32690000,0.79,-0.0093,-0.0029,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.068,0.0058,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.025,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 -32790000,0.79,-0.0092,-0.0029,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0062,-0.11,-0.17,-0.041,0.46,-0.0015,-0.029,-0.024,0,0,-3.7e+02,0.00014,0.00011,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.9e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1,0.01 -32890000,0.79,-0.0091,-0.003,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.067,0.0067,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 -32990000,0.79,-0.0091,-0.0031,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.8e-05,0.066,0.0072,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 -33090000,0.79,-0.0091,-0.0031,-0.62,-1.6,-0.87,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0074,-0.11,-0.17,-0.041,0.46,-0.0013,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1,0.01 -33190000,0.79,-0.0078,-0.0063,-0.61,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.2e-05,0.066,0.0075,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1,0.01 -33290000,0.83,-0.0057,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.066,0.0074,-0.11,-0.17,-0.041,0.46,-0.0014,-0.029,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0048,0.0052,8.8e-05,0.00034,2.2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1,0.01 -33390000,0.9,-0.0064,-0.015,-0.44,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.3e-05,0.065,0.0071,-0.11,-0.18,-0.041,0.46,-0.00098,-0.027,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00031,2e-05,0.0004,8.1e-05,0.00032,0.00039,1,1,0.01 -33490000,0.96,-0.0051,-0.0069,-0.3,-1.5,-0.88,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.4e-05,0.065,0.0071,-0.11,-0.18,-0.043,0.46,-0.00048,-0.02,-0.024,0,0,-3.7e+02,0.00015,0.00011,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0048,0.0051,8.8e-05,0.00023,1.6e-05,0.00039,7.3e-05,0.00024,0.00039,1,1,0.01 -33590000,0.99,-0.0083,-0.00017,-0.13,-1.5,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.7e-05,0.065,0.0071,-0.11,-0.19,-0.044,0.46,0.00029,-0.013,-0.024,0,0,-3.7e+02,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.00015,1.2e-05,0.00039,6e-05,0.00015,0.00039,1,1,0.01 -33690000,1,-0.012,0.004,0.038,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.3e-05,0.065,0.0071,-0.11,-0.19,-0.045,0.46,0.00013,-0.0091,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0048,0.0051,8.8e-05,0.0001,9e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1,0.01 -33790000,0.98,-0.013,0.0065,0.21,-1.6,-0.9,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.8e-05,0.065,0.0071,-0.11,-0.2,-0.046,0.46,0.00049,-0.0066,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,6.9e-05,7.2e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1,0.01 -33890000,0.93,-0.013,0.0085,0.37,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.065,0.0071,-0.11,-0.2,-0.046,0.46,0.00071,-0.0053,-0.025,0,0,-3.7e+02,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0048,0.0051,8.8e-05,5e-05,6.2e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1,0.01 -33990000,0.86,-0.015,0.0071,0.51,-1.7,-0.98,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.065,0.0069,-0.11,-0.2,-0.046,0.46,0.0005,-0.0039,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0048,0.0051,8.8e-05,4e-05,5.6e-06,0.00038,2.1e-05,3e-05,0.00038,1,1,0.01 -34090000,0.8,-0.016,0.0063,0.6,-1.7,-1.1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0063,-0.11,-0.2,-0.046,0.46,0.00017,-0.0033,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.7e-07,4.3e-07,1.9e-06,0.0048,0.0051,8.9e-05,3.4e-05,5.3e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1,0.01 -34190000,0.75,-0.014,0.007,0.67,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0061,-0.11,-0.2,-0.047,0.46,0.00018,-0.0027,-0.025,0,0,-3.7e+02,0.00014,9.9e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,3e-05,5e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1,0.01 -34290000,0.71,-0.011,0.0085,0.71,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0058,-0.11,-0.2,-0.047,0.46,0.00014,-0.0023,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,2.7e-05,4.9e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1,0.01 -34390000,0.69,-0.0078,0.0099,0.73,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0054,-0.11,-0.2,-0.047,0.46,7.3e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.8e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.0051,8.9e-05,2.5e-05,4.8e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1,0.01 -34490000,0.67,-0.0056,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0054,-0.11,-0.2,-0.047,0.46,3.2e-05,-0.002,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.3e-05,4.7e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1,0.01 -34590000,0.66,-0.0042,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0053,-0.11,-0.2,-0.047,0.46,-6.4e-05,-0.0019,-0.025,0,0,-3.7e+02,0.00014,9.7e-05,0.0012,0.057,0.074,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.2e-05,4.6e-06,0.00038,9e-06,1.1e-05,0.00038,1,1,0.01 -34690000,0.65,-0.0034,0.013,0.76,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0052,-0.11,-0.2,-0.047,0.46,-5.8e-07,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.6e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1,0.01 -34790000,0.65,-0.0028,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0051,-0.11,-0.2,-0.047,0.46,0.00012,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2.1e-05,4.5e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1,0.01 -34890000,0.65,-0.0027,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,7.1e-05,-0.0016,-0.025,0,0,-3.7e+02,0.00014,9.6e-05,0.0012,0.075,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.3e-07,1.8e-06,0.0047,0.0051,8.9e-05,2e-05,4.5e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1,0.01 -34990000,0.64,-0.0062,0.02,0.76,-3,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00018,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.092,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.5e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1,0.01 -35090000,0.64,-0.0063,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0002,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.5e-05,0.0012,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,8.9e-05,1.9e-05,4.4e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1,0.01 -35190000,0.64,-0.0064,0.02,0.76,-3.2,-2.8,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00024,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.4e-06,0.00038,6.3e-06,7e-06,0.00038,1,1,0.01 -35290000,0.64,-0.0065,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00029,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.4e-06,0.00038,6e-06,6.6e-06,0.00038,1,1,0.01 -35390000,0.64,-0.0065,0.02,0.76,-3.2,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00036,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.4e-05,0.0011,0.13,0.18,0.012,0.58,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.3e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1,0.01 -35490000,0.64,-0.0066,0.02,0.77,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00043,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.8e-05,4.3e-06,0.00038,5.6e-06,6e-06,0.00037,1,1,0.01 -35590000,0.64,-0.0066,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.0004,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.3e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1,0.01 -35690000,0.64,-0.0065,0.02,0.77,-3.3,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0048,-0.11,-0.2,-0.047,0.46,0.00046,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1,0.01 -35790000,0.64,-0.0066,0.02,0.77,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.065,0.0049,-0.11,-0.2,-0.047,0.46,0.00047,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.0051,9e-05,1.7e-05,4.3e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1,0.025 -35890000,0.64,-0.0067,0.02,0.77,-3.4,-3.3,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.005,-0.11,-0.2,-0.047,0.46,0.00048,-0.0015,-0.025,0,0,-3.7e+02,0.00013,9.2e-05,0.0011,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.7e-05,4.3e-06,0.00038,5e-06,5.2e-06,0.00037,1,1,0.056 -35990000,0.64,-0.0067,0.02,0.77,-3.4,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.066,0.0048,-0.11,-0.2,-0.047,0.46,0.00045,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.2,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.3e-06,0.00038,4.9e-06,5e-06,0.00037,1,1,0.086 -36090000,0.64,-0.0067,0.02,0.77,-3.4,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0049,-0.11,-0.2,-0.047,0.46,0.00048,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.21,0.28,0.0089,0.91,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1,0.12 -36190000,0.64,-0.0068,0.02,0.77,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0051,-0.11,-0.2,-0.047,0.46,0.00055,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9.1e-05,0.0011,0.22,0.3,0.0086,0.97,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1,0.15 -36290000,0.64,-0.0067,0.02,0.77,-3.5,-3.6,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0048,-0.11,-0.2,-0.047,0.46,0.00057,-0.0016,-0.025,0,0,-3.7e+02,0.00013,9e-05,0.0011,0.24,0.31,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1,0.18 -36390000,0.64,-0.0068,0.02,0.77,-3.5,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.066,0.0049,-0.11,-0.2,-0.047,0.46,0.00056,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1,0.21 -36490000,0.64,-0.0068,0.02,0.77,-3.6,-3.7,-0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.067,0.0049,-0.11,-0.2,-0.047,0.46,0.00053,-0.0015,-0.025,0,0,-3.7e+02,0.00012,9e-05,0.0011,0.27,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1,0.24 -36590000,0.64,-0.0068,0.02,0.77,-3.6,-3.8,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.067,0.0049,-0.11,-0.2,-0.047,0.46,0.00057,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.6e-05,4.2e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1,0.27 -36690000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.067,0.0051,-0.11,-0.2,-0.047,0.46,0.00059,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.3,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1,0.31 -36790000,0.64,-0.0069,0.02,0.77,-3.6,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.005,-0.11,-0.2,-0.047,0.46,0.00063,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.3e-06,4e-06,0.00037,1,1,0.34 -36890000,0.64,-0.0069,0.02,0.77,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.067,0.0052,-0.11,-0.2,-0.047,0.46,0.00066,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.9e-05,0.0011,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.37 -36990000,0.64,-0.0069,0.02,0.77,-3.7,-4.1,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.067,0.0053,-0.11,-0.2,-0.047,0.46,0.00067,-0.0015,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.35,0.45,0.0071,1.8,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1,0.4 -37090000,0.64,-0.0069,0.02,0.77,-3.7,-4.2,-0.0065,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.37,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1,0.43 -37190000,0.64,-0.0069,0.021,0.77,-3.7,-4.2,0.0015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.00067,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.1e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.47 -37290000,0.64,-0.007,0.021,0.77,-3.8,-4.3,0.0093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.068,0.0055,-0.11,-0.2,-0.047,0.46,0.00068,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.8e-05,0.0011,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1,0.5 -37390000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.4e-05,0.068,0.0054,-0.11,-0.2,-0.047,0.46,0.0007,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.0011,0.42,0.53,0.0068,2.4,3,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.6e-06,0.00037,1,1,0.53 -37490000,0.64,-0.0069,0.021,0.77,-3.8,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.068,0.0055,-0.11,-0.2,-0.047,0.46,0.00072,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.57 -37590000,0.64,-0.0069,0.021,0.77,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.5e-05,0.068,0.0055,-0.11,-0.2,-0.047,0.46,0.00073,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,4e-06,3.5e-06,0.00037,1,1,0.6 -37690000,0.64,-0.007,0.021,0.77,-3.9,-4.6,0.042,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.9e-05,0.069,0.0056,-0.11,-0.2,-0.047,0.46,0.00074,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.5e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.64 -37790000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.7e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00012,8.7e-05,0.001,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0047,0.005,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1,0.67 -37890000,0.64,-0.0071,0.021,0.77,-3.9,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.069,0.0057,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.52,0.65,0.0066,3.4,4.3,0.036,3e-07,4.4e-07,1.8e-06,0.0047,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.7 -37990000,0.64,-0.0071,0.021,0.77,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.069,0.0055,-0.11,-0.2,-0.047,0.46,0.00075,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.54,0.67,0.0066,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1,0.74 -38090000,0.64,-0.0072,0.021,0.77,-4,-4.9,0.078,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.57,0.7,0.0065,3.9,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1,0.77 -38190000,0.64,-0.0071,0.021,0.77,-4,-5,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.069,0.0055,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.59,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1,0.81 -38290000,0.64,-0.0071,0.021,0.77,-4,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.069,0.0055,-0.11,-0.2,-0.047,0.46,0.00077,-0.0014,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.2e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.84 -38390000,0.64,-0.0071,0.021,0.77,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7e-05,0.069,0.0053,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.6e-05,0.001,0.64,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1,0.88 -38490000,0.64,-0.0071,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.8e-05,0.069,0.0054,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.66,0.8,0.0065,5.1,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.91 -38590000,0.64,-0.007,0.021,0.77,-4.1,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.9e-05,0.069,0.0056,-0.11,-0.2,-0.047,0.46,0.00077,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.68,0.82,0.0066,5.4,6.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.95 -38690000,0.64,-0.007,0.021,0.77,-4.1,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.0058,-0.11,-0.2,-0.047,0.46,0.00078,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.71,0.85,0.0066,5.8,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1,0.99 -38790000,0.64,-0.007,0.021,0.77,-4.2,-5.4,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.068,0.0056,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.73,0.87,0.0066,6.1,7.7,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1 -38890000,0.64,-0.0071,0.021,0.77,-4.2,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.068,0.0057,-0.11,-0.2,-0.047,0.46,0.00079,-0.0013,-0.025,0,0,-3.7e+02,0.00011,8.5e-05,0.001,0.75,0.89,0.0066,6.5,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0046,0.0049,9.2e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1,1.1 +1490000,1,-0.01,-0.014,0.00016,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00033,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 +1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.03,0.03,0.00037,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 +1690000,1,-0.011,-0.014,0.00013,0.028,-0.00014,-0.19,0.0045,0.00062,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.026,0.026,0.0003,1,1,2,0.14,0.14,3,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +1790000,1,-0.011,-0.014,9.8e-05,0.035,-0.002,-0.2,0.0076,0.00053,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.028,0.028,0.00033,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 +1890000,1,-0.011,-0.015,7.8e-05,0.043,-0.0033,-0.22,0.011,0.00027,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.031,0.031,0.00037,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.0001,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 +1990000,1,-0.011,-0.014,8.9e-05,0.036,-0.0048,-0.23,0.0082,-0.00029,-0.19,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.025,0.025,0.00029,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 +2090000,1,-0.011,-0.014,5.1e-05,0.041,-0.0073,-0.24,0.012,-0.00089,-0.22,0.00021,-0.0014,-3.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.027,0.027,0.00032,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,7.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 +2190000,1,-0.011,-0.014,6.4e-05,0.033,-0.007,-0.26,0.0079,-0.00099,-0.24,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.02,0.02,0.00027,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 +2290000,1,-0.011,-0.014,5.1e-05,0.039,-0.0095,-0.27,0.011,-0.0018,-0.27,0.00017,-0.002,-4.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.022,0.022,0.00029,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +2390000,1,-0.011,-0.013,6.9e-05,0.03,-0.0089,-0.29,0.0074,-0.0015,-0.3,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.017,0.017,0.00024,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 +2490000,1,-0.011,-0.013,5.1e-05,0.035,-0.011,-0.3,0.011,-0.0025,-0.32,8.5e-05,-0.0025,-5e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.018,0.018,0.00026,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,4.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 +2590000,1,-0.011,-0.013,6.6e-05,0.026,-0.0093,-0.31,0.0068,-0.0018,-0.36,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.014,0.014,0.00022,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 +2690000,1,-0.011,-0.013,6.3e-05,0.03,-0.011,-0.33,0.0097,-0.0028,-0.39,-2.2e-05,-0.0029,-5.6e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.015,0.015,0.00024,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,3.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 +2790000,1,-0.011,-0.013,5.8e-05,0.023,-0.0096,-0.34,0.0062,-0.002,-0.42,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 +2890000,1,-0.011,-0.013,8.3e-06,0.027,-0.012,-0.35,0.0087,-0.003,-0.46,-0.00013,-0.0033,-6.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.013,0.013,0.00022,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 +2990000,1,-0.011,-0.013,5.6e-05,0.022,-0.0098,-0.36,0.0057,-0.0021,-0.49,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.0099,0.0099,0.00019,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 +3090000,1,-0.011,-0.013,6e-05,0.025,-0.011,-0.38,0.008,-0.0032,-0.53,-0.00025,-0.0036,-6.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.1,0.011,0.011,0.00021,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 +3190000,1,-0.011,-0.013,2.9e-06,0.02,-0.009,-0.39,0.0053,-0.0022,-0.57,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0087,0.0087,0.00018,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +3290000,1,-0.011,-0.013,4.4e-05,0.023,-0.011,-0.4,0.0074,-0.0032,-0.61,-0.00036,-0.0039,-6.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0096,0.0096,0.00019,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 +3390000,1,-0.011,-0.012,1.5e-05,0.018,-0.0095,-0.42,0.0049,-0.0022,-0.65,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0078,0.0078,0.00017,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 +3490000,1,-0.011,-0.013,8.2e-06,0.022,-0.012,-0.43,0.0069,-0.0033,-0.69,-0.00047,-0.0041,-6.9e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0086,0.0086,0.00018,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,1.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 +3590000,1,-0.011,-0.012,3.2e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.007,0.007,0.00016,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 +3690000,1,-0.011,-0.012,0.00015,0.019,-0.014,-0.46,0.0065,-0.0036,-0.78,-0.00058,-0.0044,-7.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.1,0.0077,0.0077,0.00017,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 +3790000,1,-0.011,-0.012,0.0002,0.016,-0.014,-0.47,0.0044,-0.0027,-0.82,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0064,0.0064,0.00015,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 +3890000,1,-0.011,-0.012,0.00017,0.017,-0.015,-0.48,0.006,-0.0041,-0.87,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0069,0.0069,0.00016,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +3990000,1,-0.011,-0.012,0.00017,0.02,-0.017,-0.5,0.0079,-0.0057,-0.92,-0.0007,-0.0046,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0075,0.0075,0.00017,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,1.2e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +4090000,1,-0.011,-0.012,0.00017,0.017,-0.015,-0.51,0.0056,-0.0042,-0.97,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0062,0.0062,0.00015,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4190000,1,-0.011,-0.012,0.00014,0.02,-0.017,-0.53,0.0075,-0.0058,-1,-0.00083,-0.0047,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0067,0.0067,0.00016,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4290000,1,-0.01,-0.012,9.8e-05,0.017,-0.012,-0.54,0.0054,-0.0042,-1.1,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.0056,0.0056,0.00014,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4390000,1,-0.01,-0.012,0.00012,0.018,-0.013,-0.55,0.0071,-0.0055,-1.1,-0.00095,-0.0049,-7.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.1,0.006,0.006,0.00015,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4490000,1,-0.01,-0.012,0.00018,0.014,-0.01,-0.57,0.0051,-0.0038,-1.2,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0049,0.0049,0.00014,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4590000,1,-0.01,-0.012,0.00021,0.017,-0.012,-0.58,0.0067,-0.0049,-1.2,-0.0011,-0.005,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0053,0.0053,0.00014,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,7.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4690000,1,-0.01,-0.012,0.00021,0.014,-0.01,-0.6,0.0048,-0.0035,-1.3,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0044,0.0044,0.00013,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4790000,1,-0.01,-0.012,0.0002,0.015,-0.012,-0.61,0.0062,-0.0045,-1.4,-0.0012,-0.0052,-7.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.1,0.0047,0.0047,0.00014,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4890000,1,-0.01,-0.011,0.00019,0.012,-0.01,-0.63,0.0044,-0.0033,-1.4,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0039,0.0039,0.00012,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +4990000,1,-0.01,-0.012,0.00017,0.015,-0.011,-0.64,0.0058,-0.0043,-1.5,-0.0012,-0.0053,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0041,0.0041,0.00013,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5090000,1,-0.01,-0.011,0.00022,0.011,-0.0085,-0.66,0.0041,-0.0031,-1.6,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0034,0.0034,0.00012,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5190000,1,-0.01,-0.011,0.00024,0.013,-0.0098,-0.67,0.0053,-0.004,-1.6,-0.0013,-0.0054,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.1,0.0036,0.0036,0.00012,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5290000,1,-0.01,-0.011,0.00023,0.0086,-0.0073,-0.68,0.0037,-0.0029,-1.7,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.003,0.003,0.00011,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5390000,1,-0.0099,-0.011,0.00029,0.0081,-0.0081,-0.7,0.0045,-0.0036,-1.8,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0032,0.0032,0.00012,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,4.7e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5490000,1,-0.0098,-0.011,0.0003,0.0055,-0.0062,-0.71,0.0031,-0.0026,-1.8,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0026,0.0026,0.00011,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5590000,1,-0.0097,-0.011,0.00028,0.0061,-0.0066,-0.73,0.0036,-0.0032,-1.9,-0.0014,-0.0055,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0028,0.0028,0.00011,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,4.2e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5690000,1,-0.0096,-0.011,0.00036,0.0041,-0.0038,-0.74,0.0025,-0.0022,-2,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0023,0.0023,0.00011,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5790000,1,-0.0095,-0.011,0.00035,0.0044,-0.0028,-0.75,0.0029,-0.0025,-2,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.1,0.0025,0.0025,0.00011,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,3.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5890000,1,-0.0095,-0.011,0.00033,0.0038,-0.00092,0.0028,0.002,-0.0016,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.0001,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5990000,1,-0.0094,-0.011,0.00036,0.0041,0.00056,0.015,0.0023,-0.0016,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.00011,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +6090000,1,-0.0094,-0.011,0.00034,0.0051,0.0017,-0.011,0.0028,-0.0015,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.00011,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,3.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6190000,1,-0.0094,-0.011,0.00027,0.0038,0.0042,-0.005,0.002,-0.00053,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.0001,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6290000,1,-0.0094,-0.011,0.00024,0.005,0.0043,-0.012,0.0025,-0.00012,-3.7e+02,-0.0015,-0.0056,-7.3e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,-3.6e+02,0.002,0.002,0.00011,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,3.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6390000,1,-0.0093,-0.011,0.00026,0.0043,0.0053,-0.05,0.0019,0.00038,-3.7e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,-3.6e+02,0.0017,0.0017,9.9e-05,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6490000,1,-0.0093,-0.011,0.00026,0.0049,0.0055,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.0001,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6590000,1,-0.0093,-0.011,0.00019,0.0037,0.0055,-0.099,0.0018,0.001,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,-3.6e+02,0.0015,0.0015,9.6e-05,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6690000,1,-0.0093,-0.011,0.00012,0.0046,0.0051,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,-3.6e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6790000,0.7,0.0013,-0.014,0.71,0.003,0.0048,-0.11,0.0017,0.0014,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-5.7e-05,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.19,0.19,0.6,0.11,0.11,0.2,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.002,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6890000,0.7,0.0013,-0.014,0.71,0.0011,0.0051,-0.12,0.0019,0.0019,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.00011,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.21,0.21,0.46,0.14,0.14,0.18,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.0014,0.0025,0.0025,0.0025,0.0025,1,1,1.8 +6990000,0.7,0.0014,-0.014,0.71,0.0012,0.0057,-0.12,0.002,0.0024,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-5.1e-06,4.4e-06,-0.00041,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.25,0.25,0.36,0.17,0.17,0.16,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.001,0.0025,0.0025,0.0025,0.0025,1,1,1.8 +7090000,0.7,0.0013,-0.014,0.71,-0.00037,-0.00015,-0.13,0.002,0.0025,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.00077,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.29,1e+02,1e+02,0.16,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.00086,0.0025,0.0025,0.0025,0.0025,1,1,1.8 +7190000,0.7,0.0013,-0.014,0.71,-0.0019,-0.00023,-0.15,0.0019,0.0025,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.00055,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.24,1e+02,1e+02,0.15,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.00071,0.0025,0.0025,0.0025,0.0025,1,1,1.8 +7290000,0.7,0.0014,-0.014,0.71,-0.0033,-0.00022,-0.15,0.0017,0.0025,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0012,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.2,51,51,0.14,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.00061,0.0025,0.0025,0.0025,0.0025,1,1,1.9 +7390000,0.7,0.0014,-0.014,0.71,-0.0032,0.0011,-0.16,0.0014,0.0026,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0014,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.18,52,52,0.13,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.00054,0.0025,0.0025,0.0025,0.0025,1,1,1.9 +7490000,0.71,0.0015,-0.014,0.71,-0.0047,0.0013,-0.16,0.0012,0.0027,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0022,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.15,35,35,0.12,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.00048,0.0025,0.0025,0.0025,0.0025,1,1,1.9 +7590000,0.71,0.0015,-0.014,0.71,-0.0064,0.0023,-0.17,0.00071,0.0028,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.003,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.14,37,37,0.12,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.00043,0.0025,0.0025,0.0025,0.0025,1,1,1.9 +7690000,0.7,0.0015,-0.014,0.71,-0.0079,0.0029,-0.16,0.00044,0.003,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0051,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,24,24,0.13,28,28,0.11,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,1,1,2 +7790000,0.71,0.0016,-0.014,0.71,-0.0091,0.0036,-0.16,-0.0004,0.0033,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0071,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,24,24,0.12,30,30,0.11,8e-05,8e-05,2.4e-06,0.04,0.04,0.038,0.0025,0.00036,0.0025,0.0025,0.0025,0.0025,1,1,2 +7890000,0.71,0.0016,-0.014,0.71,-0.011,0.0052,-0.16,-0.0007,0.0035,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0096,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,23,23,0.11,25,25,0.1,8e-05,8e-05,2.4e-06,0.04,0.04,0.038,0.0025,0.00033,0.0025,0.0025,0.0025,0.0025,1,1,2 +7990000,0.71,0.0016,-0.014,0.71,-0.013,0.0061,-0.16,-0.0019,0.004,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.011,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,23,23,0.1,27,27,0.099,8e-05,8e-05,2.4e-06,0.04,0.04,0.038,0.0025,0.00031,0.0025,0.0025,0.0025,0.0025,1,1,2 +8090000,0.71,0.0016,-0.014,0.71,-0.014,0.0071,-0.17,-0.0022,0.0043,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.011,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,21,21,0.1,23,23,0.097,8e-05,8e-05,2.4e-06,0.04,0.04,0.037,0.0025,0.00029,0.0025,0.0025,0.0025,0.0025,1,1,2.1 +8190000,0.71,0.0016,-0.014,0.71,-0.017,0.0084,-0.18,-0.0037,0.0051,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.013,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,21,21,0.099,26,26,0.094,8e-05,8e-05,2.4e-06,0.04,0.04,0.037,0.0025,0.00027,0.0025,0.0025,0.0025,0.0025,1,1,2.1 +8290000,0.71,0.0016,-0.014,0.71,-0.017,0.0087,-0.17,-0.0039,0.0053,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.017,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,19,19,0.097,22,22,0.091,8e-05,8e-05,2.4e-06,0.04,0.04,0.036,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,1,1,2.1 +8390000,0.71,0.0017,-0.014,0.71,-0.019,0.0097,-0.17,-0.0057,0.0062,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.021,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,19,19,0.097,25,25,0.091,8e-05,8e-05,2.4e-06,0.04,0.04,0.035,0.0025,0.00024,0.0025,0.0025,0.0025,0.0025,1,1,2.1 +8490000,0.71,0.0017,-0.014,0.71,-0.02,0.011,-0.17,-0.0056,0.0063,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.025,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,17,17,0.096,22,22,0.089,8e-05,8e-05,2.4e-06,0.04,0.04,0.034,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,1,1,2.2 +8590000,0.71,0.0017,-0.014,0.71,-0.022,0.013,-0.17,-0.0077,0.0074,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.029,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,17,17,0.095,25,25,0.088,8e-05,8e-05,2.4e-06,0.04,0.04,0.033,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,1,1,2.2 +8690000,0.71,0.0017,-0.014,0.71,-0.023,0.013,-0.16,-0.0074,0.0074,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.035,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0017,0.0017,0.09,15,15,0.096,22,22,0.088,7.9e-05,8e-05,2.4e-06,0.04,0.04,0.033,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,1,1,2.2 +8790000,0.71,0.0017,-0.014,0.71,-0.025,0.015,-0.15,-0.0099,0.0088,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.041,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0017,0.0017,0.09,15,15,0.095,25,25,0.087,7.9e-05,8e-05,2.4e-06,0.04,0.04,0.032,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,1,1,2.2 +8890000,0.71,0.0017,-0.014,0.71,-0.027,0.015,-0.15,-0.013,0.01,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.045,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0017,0.0017,0.09,15,15,0.095,28,28,0.086,7.9e-05,8e-05,2.4e-06,0.04,0.04,0.03,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,1,1,2.3 +8990000,0.71,0.0018,-0.014,0.71,-0.027,0.015,-0.14,-0.012,0.01,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.051,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,14,14,0.096,24,24,0.087,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.029,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.3 +9090000,0.71,0.0018,-0.014,0.71,-0.03,0.016,-0.14,-0.015,0.012,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.053,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,14,14,0.095,27,27,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.028,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.3 +9190000,0.71,0.0018,-0.014,0.71,-0.029,0.016,-0.14,-0.014,0.011,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.057,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,12,12,0.094,24,24,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.027,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,1,1,2.3 +9290000,0.71,0.0018,-0.014,0.71,-0.031,0.017,-0.14,-0.017,0.013,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.061,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,12,12,0.093,26,26,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.025,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 +9390000,0.71,0.0018,-0.014,0.71,-0.03,0.017,-0.14,-0.016,0.012,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.065,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,10,10,0.093,23,23,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.024,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 +9490000,0.71,0.0018,-0.014,0.71,-0.032,0.018,-0.13,-0.019,0.014,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.068,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,10,10,0.091,26,26,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.023,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.4 +9590000,0.71,0.0019,-0.014,0.71,-0.032,0.018,-0.13,-0.017,0.013,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.072,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.002,0.002,0.09,8.9,8.9,0.09,22,22,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.021,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.4 +9690000,0.71,0.0019,-0.014,0.71,-0.034,0.02,-0.12,-0.021,0.015,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.077,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.002,0.002,0.09,9,9,0.089,25,25,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.02,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 +9790000,0.71,0.0019,-0.014,0.71,-0.032,0.021,-0.11,-0.019,0.014,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.082,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,7.8,7.8,0.087,22,22,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.019,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 +9890000,0.71,0.0019,-0.014,0.71,-0.035,0.022,-0.11,-0.022,0.016,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.085,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,7.8,7.8,0.084,24,24,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.5 +9990000,0.71,0.002,-0.014,0.71,-0.034,0.021,-0.1,-0.021,0.016,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.089,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.09,6.8,6.8,0.083,21,21,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.5 +10090000,0.71,0.002,-0.014,0.71,-0.036,0.021,-0.096,-0.024,0.018,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.091,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.09,6.9,6.9,0.08,23,23,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 +10190000,0.71,0.002,-0.014,0.71,-0.035,0.022,-0.096,-0.022,0.017,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.093,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.09,6,6,0.078,20,20,0.084,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.6 +10290000,0.71,0.002,-0.014,0.71,-0.037,0.022,-0.084,-0.026,0.019,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.098,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.09,6.1,6.1,0.076,22,22,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.6 +10390000,0.71,0.002,-0.013,0.71,0.0092,-0.02,0.0096,0.00086,-0.0018,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7e-05,5.4e-05,-0.1,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.25,0.25,0.56,0.25,0.25,0.078,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.6 +10490000,0.71,0.002,-0.013,0.71,0.0077,-0.018,0.023,0.0017,-0.0036,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-0.00015,0.00012,-0.1,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.26,0.26,0.55,0.26,0.26,0.08,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 +10590000,0.71,0.0021,-0.014,0.71,0.0072,-0.0075,0.026,0.0018,-0.00083,-3.7e+02,-0.0015,-0.0057,-7.4e-05,-0.0004,0.00047,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.13,0.13,0.27,0.13,0.13,0.073,7.8e-05,7.8e-05,2.4e-06,0.04,0.04,0.012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 +10690000,0.71,0.0022,-0.014,0.71,0.0049,-0.0074,0.03,0.0024,-0.0016,-3.7e+02,-0.0015,-0.0057,-7.4e-05,-0.00043,0.00049,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0025,0.0025,0.09,0.15,0.15,0.26,0.14,0.14,0.078,7.8e-05,7.8e-05,2.4e-06,0.04,0.04,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 +10790000,0.71,0.0022,-0.014,0.71,0.0043,-0.0046,0.024,0.0027,-0.00079,-3.7e+02,-0.0015,-0.0057,-7.3e-05,-0.00045,0.00085,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.1,0.1,0.17,0.09,0.09,0.072,7.4e-05,7.4e-05,2.4e-06,0.039,0.039,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 +10890000,0.71,0.0021,-0.014,0.71,0.0028,-0.0039,0.02,0.003,-0.0012,-3.7e+02,-0.0015,-0.0057,-7.3e-05,-0.00044,0.00085,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0025,0.0025,0.09,0.12,0.12,0.16,0.097,0.097,0.075,7.4e-05,7.4e-05,2.4e-06,0.039,0.039,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 +10990000,0.71,0.0022,-0.014,0.71,0.0052,0.0011,0.014,0.0046,-0.0024,-3.7e+02,-0.0015,-0.0056,-7.2e-05,-0.00019,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.09,0.095,0.095,0.12,0.072,0.072,0.071,6.9e-05,6.9e-05,2.4e-06,0.038,0.038,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 +11090000,0.71,0.0022,-0.014,0.71,0.0036,0.0031,0.019,0.0051,-0.0022,-3.7e+02,-0.0015,-0.0056,-7.2e-05,-0.00021,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.12,0.12,0.11,0.079,0.079,0.074,6.9e-05,6.9e-05,2.4e-06,0.038,0.038,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 +11190000,0.71,0.0021,-0.014,0.71,0.0084,0.0059,0.0076,0.0065,-0.003,-3.7e+02,-0.0015,-0.0055,-7.2e-05,0.00031,0.0029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,0.094,0.094,0.084,0.062,0.062,0.069,6.2e-05,6.2e-05,2.4e-06,0.037,0.037,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 +11290000,0.71,0.0022,-0.014,0.71,0.0077,0.0078,0.0073,0.0073,-0.0023,-3.7e+02,-0.0015,-0.0055,-7.2e-05,0.00031,0.0029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,0.12,0.12,0.078,0.069,0.069,0.072,6.2e-05,6.2e-05,2.4e-06,0.037,0.037,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 +11390000,0.71,0.0022,-0.014,0.71,0.0035,0.0071,0.0017,0.0054,-0.0021,-3.7e+02,-0.0015,-0.0056,-7.2e-05,0.00023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,0.094,0.094,0.063,0.057,0.057,0.068,5.4e-05,5.4e-05,2.4e-06,0.035,0.035,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 +11490000,0.71,0.0023,-0.014,0.71,0.00066,0.0096,0.0025,0.0056,-0.0013,-3.7e+02,-0.0015,-0.0056,-7.2e-05,0.00023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,0.12,0.12,0.058,0.064,0.064,0.069,5.4e-05,5.4e-05,2.4e-06,0.035,0.035,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 +11590000,0.71,0.0021,-0.014,0.71,-0.0032,0.0087,-0.0034,0.0043,-0.0015,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00053,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,0.093,0.093,0.049,0.053,0.053,0.066,4.7e-05,4.7e-05,2.4e-06,0.034,0.034,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 +11690000,0.71,0.0021,-0.014,0.71,-0.0063,0.012,-0.008,0.0039,-0.00053,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00054,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,0.11,0.11,0.046,0.062,0.062,0.066,4.7e-05,4.7e-05,2.4e-06,0.034,0.034,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 +11790000,0.71,0.0022,-0.014,0.71,-0.011,0.012,-0.0098,0.0017,0.00048,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00043,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0013,0.0013,0.09,0.09,0.09,0.039,0.051,0.051,0.063,4.1e-05,4.1e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 +11890000,0.71,0.0022,-0.014,0.71,-0.013,0.013,-0.011,0.00051,0.0017,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00043,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.11,0.11,0.037,0.06,0.06,0.063,4.1e-05,4.1e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 +11990000,0.71,0.0022,-0.014,0.71,-0.014,0.013,-0.016,-0.00041,0.0023,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00062,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0011,0.0011,0.09,0.085,0.085,0.033,0.05,0.05,0.061,3.6e-05,3.6e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 +12090000,0.71,0.0022,-0.014,0.71,-0.016,0.015,-0.022,-0.0019,0.0036,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00063,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0012,0.0012,0.09,0.1,0.1,0.031,0.059,0.059,0.061,3.6e-05,3.6e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 +12190000,0.71,0.0019,-0.014,0.71,-0.0095,0.013,-0.017,0.0012,0.0019,-3.7e+02,-0.0014,-0.0056,-7.7e-05,0.0016,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00099,0.00099,0.09,0.08,0.08,0.028,0.049,0.049,0.059,3.2e-05,3.2e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 +12290000,0.71,0.0019,-0.014,0.71,-0.012,0.014,-0.016,0.00011,0.0033,-3.7e+02,-0.0014,-0.0056,-7.7e-05,0.0016,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.001,0.001,0.09,0.095,0.095,0.028,0.058,0.058,0.059,3.2e-05,3.2e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 +12390000,0.71,0.0016,-0.014,0.71,-0.0067,0.011,-0.015,0.0026,0.0017,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0.0023,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00088,0.00088,0.09,0.075,0.075,0.026,0.049,0.049,0.057,2.9e-05,2.9e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 +12490000,0.71,0.0016,-0.014,0.71,-0.0081,0.013,-0.018,0.0019,0.0029,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0.0023,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0009,0.00089,0.09,0.088,0.088,0.026,0.058,0.058,0.057,2.9e-05,2.9e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 +12590000,0.71,0.0016,-0.014,0.71,-0.015,0.011,-0.023,-0.003,0.0016,-3.7e+02,-0.0013,-0.0057,-7.9e-05,0.0023,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00079,0.00079,0.09,0.07,0.07,0.025,0.049,0.049,0.055,2.7e-05,2.7e-05,2.4e-06,0.032,0.032,0.0099,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 +12690000,0.71,0.0016,-0.014,0.71,-0.016,0.013,-0.027,-0.0046,0.0028,-3.7e+02,-0.0013,-0.0057,-7.9e-05,0.0023,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00081,0.00081,0.09,0.081,0.081,0.025,0.057,0.057,0.055,2.7e-05,2.7e-05,2.4e-06,0.032,0.032,0.0098,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 +12790000,0.71,0.0017,-0.014,0.71,-0.02,0.0098,-0.03,-0.0078,0.0015,-3.7e+02,-0.0013,-0.0057,-8e-05,0.0024,0.0012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00073,0.00073,0.09,0.065,0.065,0.024,0.048,0.048,0.053,2.5e-05,2.5e-05,2.4e-06,0.032,0.032,0.0097,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 +12890000,0.71,0.0016,-0.014,0.71,-0.021,0.0099,-0.03,-0.0099,0.0025,-3.7e+02,-0.0013,-0.0057,-8e-05,0.0024,0.0012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00074,0.00074,0.09,0.075,0.075,0.025,0.057,0.057,0.054,2.5e-05,2.5e-05,2.4e-06,0.032,0.032,0.0096,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 +12990000,0.71,0.0013,-0.014,0.71,-0.0093,0.0075,-0.03,-0.0014,0.0013,-3.7e+02,-0.0012,-0.0057,-8.2e-05,0.0026,0.0017,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00068,0.00068,0.09,0.061,0.061,0.025,0.048,0.048,0.052,2.3e-05,2.3e-05,2.4e-06,0.032,0.032,0.0094,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 +13090000,0.71,0.0014,-0.014,0.71,-0.01,0.0079,-0.03,-0.0024,0.002,-3.7e+02,-0.0012,-0.0057,-8.2e-05,0.0026,0.0017,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00069,0.00069,0.09,0.069,0.069,0.025,0.056,0.056,0.052,2.3e-05,2.3e-05,2.4e-06,0.032,0.032,0.0094,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 +13190000,0.71,0.0011,-0.014,0.71,-0.001,0.0074,-0.027,0.0039,0.0012,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.0026,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00064,0.00064,0.09,0.057,0.057,0.025,0.048,0.048,0.051,2.2e-05,2.2e-05,2.4e-06,0.032,0.032,0.0091,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 +13290000,0.71,0.0012,-0.014,0.71,-0.0013,0.0085,-0.024,0.0038,0.002,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.0026,0.0021,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00066,0.00066,0.09,0.065,0.065,0.027,0.056,0.056,0.051,2.2e-05,2.2e-05,2.4e-06,0.032,0.032,0.0091,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 +13390000,0.71,0.001,-0.014,0.71,-0.00029,0.0075,-0.02,0.0028,0.0011,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0024,0.0021,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00062,0.00062,0.09,0.053,0.053,0.026,0.048,0.048,0.05,2.1e-05,2.1e-05,2.4e-06,0.032,0.032,0.0088,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 +13490000,0.71,0.001,-0.014,0.71,-0.0008,0.0078,-0.019,0.0028,0.0019,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0024,0.0022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00063,0.00063,0.09,0.06,0.06,0.028,0.056,0.056,0.05,2.1e-05,2.1e-05,2.4e-06,0.032,0.032,0.0087,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 +13590000,0.71,0.00099,-0.014,0.71,-0.00037,0.008,-0.021,0.002,0.0011,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0006,0.0006,0.09,0.05,0.05,0.028,0.048,0.048,0.05,2e-05,2e-05,2.4e-06,0.032,0.032,0.0084,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 +13690000,0.71,0.00098,-0.014,0.71,0.00032,0.01,-0.025,0.002,0.002,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00061,0.00061,0.09,0.057,0.057,0.029,0.055,0.055,0.05,2e-05,2e-05,2.4e-06,0.032,0.032,0.0083,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 +13790000,0.71,0.00089,-0.014,0.71,0.001,0.0061,-0.027,0.003,-0.00046,-3.7e+02,-0.0011,-0.0057,-8.5e-05,0.0021,0.0026,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00058,0.00058,0.066,0.047,0.047,0.029,0.047,0.047,0.049,1.9e-05,1.9e-05,2.4e-06,0.032,0.032,0.0079,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 +13890000,0.71,0.00086,-0.014,0.71,0.0015,0.0064,-0.031,0.0032,0.00014,-3.7e+02,-0.0011,-0.0057,-8.5e-05,0.0021,0.0026,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00059,0.00059,0.066,0.053,0.053,0.03,0.055,0.055,0.05,1.9e-05,1.9e-05,2.4e-06,0.032,0.032,0.0078,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 +13990000,0.71,0.00081,-0.014,0.71,0.0019,0.004,-0.03,0.004,-0.0018,-3.7e+02,-0.0011,-0.0058,-8.6e-05,0.0019,0.0029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00057,0.00057,0.066,0.045,0.045,0.03,0.047,0.047,0.05,1.8e-05,1.8e-05,2.4e-06,0.031,0.031,0.0074,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 +14090000,0.71,0.0008,-0.014,0.71,0.002,0.0046,-0.031,0.0042,-0.0014,-3.7e+02,-0.0011,-0.0058,-8.6e-05,0.0019,0.0029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00058,0.00058,0.066,0.05,0.05,0.031,0.054,0.054,0.05,1.8e-05,1.8e-05,2.4e-06,0.031,0.031,0.0073,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 +14190000,0.71,0.0007,-0.014,0.71,0.0053,0.0039,-0.033,0.0063,-0.0014,-3.7e+02,-0.001,-0.0058,-8.7e-05,0.0014,0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00056,0.00056,0.066,0.043,0.043,0.03,0.047,0.047,0.05,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0069,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 +14290000,0.71,0.00072,-0.014,0.71,0.0061,0.0051,-0.032,0.0069,-0.00095,-3.7e+02,-0.001,-0.0058,-8.7e-05,0.0014,0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00057,0.00057,0.066,0.048,0.048,0.031,0.054,0.054,0.051,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0067,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 +14390000,0.71,0.00064,-0.014,0.71,0.008,0.0059,-0.034,0.0083,-0.001,-3.7e+02,-0.001,-0.0058,-8.8e-05,0.001,0.0031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00055,0.00055,0.066,0.041,0.041,0.031,0.047,0.047,0.05,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0063,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 +14490000,0.71,0.00063,-0.014,0.71,0.008,0.0076,-0.037,0.0091,-0.00035,-3.7e+02,-0.001,-0.0058,-8.8e-05,0.001,0.0031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00056,0.00056,0.066,0.046,0.046,0.032,0.054,0.054,0.051,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0062,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 +14590000,0.71,0.00064,-0.013,0.71,0.005,0.006,-0.037,0.0057,-0.0019,-3.7e+02,-0.0011,-0.0058,-8.8e-05,0.0015,0.0037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00055,0.00055,0.066,0.039,0.039,0.031,0.046,0.046,0.051,1.6e-05,1.6e-05,2.4e-06,0.031,0.031,0.0058,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 +14690000,0.71,0.00061,-0.013,0.71,0.0064,0.0036,-0.034,0.0063,-0.0014,-3.7e+02,-0.0011,-0.0058,-8.8e-05,0.0015,0.0038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00056,0.00056,0.066,0.044,0.044,0.032,0.053,0.053,0.051,1.6e-05,1.6e-05,2.4e-06,0.031,0.031,0.0056,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 +14790000,0.71,0.00065,-0.013,0.71,0.0036,0.0019,-0.03,0.0035,-0.0027,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.002,0.0044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00054,0.00054,0.066,0.038,0.038,0.031,0.046,0.046,0.051,1.5e-05,1.5e-05,2.4e-06,0.03,0.03,0.0053,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 +14890000,0.71,0.00065,-0.013,0.71,0.0052,0.0034,-0.033,0.004,-0.0024,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.002,0.0044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00055,0.00055,0.066,0.042,0.042,0.031,0.053,0.053,0.052,1.5e-05,1.5e-05,2.4e-06,0.03,0.03,0.0051,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 +14990000,0.71,0.00064,-0.013,0.71,0.0042,0.0029,-0.029,0.0031,-0.0021,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0022,0.0046,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00053,0.00053,0.066,0.037,0.037,0.03,0.046,0.046,0.051,1.4e-05,1.4e-05,2.4e-06,0.03,0.03,0.0048,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 +15090000,0.71,0.00057,-0.013,0.71,0.0047,0.0033,-0.032,0.0035,-0.0018,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0022,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00054,0.00054,0.066,0.041,0.041,0.031,0.053,0.053,0.052,1.4e-05,1.4e-05,2.4e-06,0.03,0.03,0.0046,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 +15190000,0.71,0.00058,-0.013,0.71,0.0042,0.0041,-0.029,0.0028,-0.0015,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0023,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00053,0.00052,0.066,0.036,0.036,0.03,0.046,0.046,0.052,1.4e-05,1.4e-05,2.4e-06,0.029,0.029,0.0043,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 +15290000,0.71,0.00055,-0.013,0.71,0.005,0.0049,-0.027,0.0032,-0.0011,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0023,0.0048,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00054,0.00054,0.066,0.04,0.04,0.03,0.052,0.052,0.052,1.4e-05,1.4e-05,2.4e-06,0.029,0.029,0.0042,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 +15390000,0.71,0.00055,-0.013,0.71,0.0043,0.0048,-0.025,0.00066,-0.001,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0026,0.005,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00052,0.00052,0.066,0.035,0.035,0.029,0.046,0.046,0.051,1.3e-05,1.3e-05,2.4e-06,0.029,0.029,0.0039,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 +15490000,0.71,0.00058,-0.013,0.71,0.0058,0.005,-0.025,0.0012,-0.00055,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0026,0.005,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00053,0.00053,0.066,0.039,0.039,0.029,0.052,0.052,0.053,1.3e-05,1.3e-05,2.4e-06,0.029,0.029,0.0037,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 +15590000,0.71,0.00059,-0.013,0.71,0.004,0.0046,-0.023,-0.0011,-0.0006,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0029,0.0054,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00051,0.00051,0.066,0.034,0.034,0.028,0.045,0.045,0.052,1.2e-05,1.2e-05,2.4e-06,0.028,0.028,0.0035,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 +15690000,0.71,0.0006,-0.013,0.71,0.0045,0.005,-0.024,-0.00068,-0.00011,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0029,0.0054,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00052,0.00052,0.066,0.038,0.038,0.028,0.052,0.052,0.052,1.2e-05,1.2e-05,2.4e-06,0.028,0.028,0.0033,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 +15790000,0.71,0.00059,-0.013,0.71,0.0049,0.003,-0.026,-0.00071,-0.0015,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.003,0.0061,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0005,0.0005,0.066,0.034,0.034,0.027,0.045,0.045,0.051,1.2e-05,1.2e-05,2.4e-06,0.027,0.027,0.0031,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 +15890000,0.71,0.00055,-0.013,0.71,0.0061,0.0031,-0.024,-0.00013,-0.0012,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.0029,0.0061,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00051,0.00051,0.066,0.037,0.037,0.027,0.051,0.051,0.052,1.2e-05,1.2e-05,2.4e-06,0.027,0.027,0.003,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 +15990000,0.71,0.00052,-0.013,0.71,0.0059,0.0019,-0.02,-0.00031,-0.0024,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.003,0.0069,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00049,0.00049,0.066,0.033,0.033,0.026,0.045,0.045,0.051,1.1e-05,1.1e-05,2.4e-06,0.026,0.026,0.0028,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 +16090000,0.71,0.00053,-0.013,0.71,0.0079,0.0023,-0.016,0.00036,-0.0022,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.003,0.0069,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0005,0.0005,0.066,0.037,0.037,0.025,0.051,0.051,0.052,1.1e-05,1.1e-05,2.4e-06,0.026,0.026,0.0027,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 +16190000,0.71,0.00055,-0.013,0.71,0.0079,0.0025,-0.015,5.6e-05,-0.0019,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0034,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00048,0.00048,0.066,0.033,0.033,0.025,0.045,0.045,0.051,1e-05,1e-05,2.4e-06,0.026,0.026,0.0025,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 +16290000,0.71,0.00057,-0.013,0.71,0.0097,0.0022,-0.016,0.00094,-0.0017,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0034,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00049,0.00049,0.066,0.036,0.036,0.024,0.051,0.051,0.052,1e-05,1e-05,2.4e-06,0.026,0.026,0.0024,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 +16390000,0.71,0.00056,-0.013,0.71,0.0086,0.0014,-0.015,0.00051,-0.0015,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0039,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00046,0.00046,0.066,0.032,0.032,0.023,0.045,0.045,0.051,9.6e-06,9.6e-06,2.4e-06,0.025,0.025,0.0022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 +16490000,0.71,0.00058,-0.013,0.71,0.0081,0.0023,-0.018,0.0013,-0.0013,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0039,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00047,0.00047,0.066,0.036,0.036,0.023,0.051,0.051,0.052,9.6e-06,9.6e-06,2.4e-06,0.025,0.025,0.0021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 +16590000,0.71,0.00079,-0.013,0.71,0.0048,0.0041,-0.018,-0.0016,0.0014,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0057,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00045,0.00045,0.066,0.032,0.032,0.022,0.045,0.045,0.051,8.9e-06,8.9e-06,2.4e-06,0.024,0.024,0.002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 +16690000,0.71,0.00078,-0.013,0.71,0.0052,0.005,-0.015,-0.0011,0.0019,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0057,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00046,0.00046,0.066,0.035,0.035,0.022,0.051,0.051,0.051,8.9e-06,8.9e-06,2.4e-06,0.024,0.024,0.0019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 +16790000,0.71,0.0009,-0.013,0.71,0.002,0.0064,-0.014,-0.0035,0.004,-3.7e+02,-0.0012,-0.0058,-8.4e-05,0.0072,0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00043,0.00043,0.066,0.031,0.031,0.021,0.045,0.045,0.05,8.3e-06,8.3e-06,2.4e-06,0.023,0.023,0.0018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 +16890000,0.71,0.00092,-0.013,0.71,0.002,0.0077,-0.011,-0.0033,0.0046,-3.7e+02,-0.0012,-0.0058,-8.4e-05,0.0072,0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00044,0.00044,0.066,0.035,0.035,0.021,0.05,0.05,0.051,8.3e-06,8.3e-06,2.4e-06,0.023,0.023,0.0017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 +16990000,0.71,0.00091,-0.013,0.71,0.0019,0.0054,-0.011,-0.004,0.0025,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0075,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00042,0.00042,0.066,0.031,0.031,0.02,0.044,0.044,0.05,7.7e-06,7.7e-06,2.4e-06,0.022,0.022,0.0016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 +17090000,0.71,0.00088,-0.013,0.71,0.003,0.0068,-0.01,-0.0038,0.0031,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0075,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00043,0.00043,0.066,0.034,0.034,0.02,0.05,0.05,0.05,7.7e-06,7.7e-06,2.4e-06,0.022,0.022,0.0016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 +17190000,0.71,0.00093,-0.013,0.71,0.0032,0.0065,-0.011,-0.0044,0.0013,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0078,0.0089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0004,0.0004,0.066,0.031,0.031,0.019,0.044,0.044,0.049,7.2e-06,7.2e-06,2.4e-06,0.021,0.021,0.0015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 +17290000,0.71,0.00091,-0.013,0.71,0.0056,0.008,-0.0067,-0.004,0.002,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0078,0.009,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00041,0.00041,0.066,0.034,0.034,0.019,0.05,0.05,0.049,7.2e-06,7.2e-06,2.4e-06,0.021,0.021,0.0014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 +17390000,0.71,0.00092,-0.013,0.71,0.0059,0.0068,-0.0047,-0.0034,0.00031,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00039,0.00039,0.066,0.03,0.03,0.018,0.044,0.044,0.048,6.6e-06,6.6e-06,2.4e-06,0.02,0.02,0.0013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 +17490000,0.71,0.00092,-0.013,0.71,0.0068,0.0068,-0.003,-0.0028,0.00098,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0004,0.0004,0.066,0.034,0.034,0.018,0.05,0.05,0.049,6.6e-06,6.6e-06,2.4e-06,0.02,0.02,0.0013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 +17590000,0.71,0.00087,-0.013,0.71,0.0077,0.0053,0.0025,-0.0025,-0.00054,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00037,0.00037,0.066,0.03,0.03,0.017,0.044,0.044,0.048,6.1e-06,6.1e-06,2.4e-06,0.019,0.019,0.0012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 +17690000,0.71,0.00084,-0.013,0.71,0.0089,0.0064,0.0019,-0.0016,1.4e-05,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00038,0.00038,0.066,0.033,0.033,0.017,0.05,0.05,0.048,6.1e-06,6.1e-06,2.4e-06,0.019,0.019,0.0012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 +17790000,0.71,0.00076,-0.013,0.71,0.011,0.0055,0.00056,-0.0009,-0.00017,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0071,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00036,0.00036,0.066,0.03,0.03,0.016,0.044,0.044,0.048,5.6e-06,5.6e-06,2.4e-06,0.018,0.018,0.0011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 +17890000,0.71,0.00077,-0.013,0.71,0.013,0.0052,0.00065,0.00028,0.0004,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0071,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00036,0.00036,0.066,0.033,0.033,0.016,0.05,0.05,0.048,5.6e-06,5.7e-06,2.4e-06,0.018,0.018,0.0011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 +17990000,0.71,0.00071,-0.013,0.71,0.014,0.0029,0.0019,0.00061,0.00014,-3.7e+02,-0.0013,-0.006,-8.6e-05,0.0069,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00034,0.00034,0.066,0.029,0.029,0.016,0.044,0.044,0.047,5.2e-06,5.2e-06,2.4e-06,0.017,0.017,0.00099,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 +18090000,0.71,0.00072,-0.013,0.71,0.015,0.003,0.0043,0.0021,0.0004,-3.7e+02,-0.0013,-0.006,-8.6e-05,0.0069,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00035,0.00035,0.066,0.032,0.032,0.016,0.05,0.05,0.047,5.2e-06,5.2e-06,2.4e-06,0.017,0.017,0.00096,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 +18190000,0.71,0.00069,-0.013,0.71,0.015,0.0036,0.0056,0.0026,0.00033,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0072,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00032,0.00032,0.066,0.029,0.029,0.015,0.044,0.044,0.047,4.8e-06,4.8e-06,2.4e-06,0.016,0.016,0.00091,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 +18290000,0.71,0.00063,-0.013,0.71,0.016,0.0033,0.0068,0.0042,0.00068,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0071,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00033,0.00033,0.066,0.032,0.032,0.015,0.05,0.05,0.046,4.8e-06,4.8e-06,2.4e-06,0.016,0.016,0.00088,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 +18390000,0.71,0.00066,-0.013,0.71,0.017,0.0045,0.008,0.0044,0.0006,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0074,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00031,0.00031,0.066,0.028,0.028,0.014,0.044,0.044,0.046,4.4e-06,4.4e-06,2.4e-06,0.015,0.015,0.00083,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 +18490000,0.71,0.00068,-0.013,0.71,0.018,0.0052,0.0076,0.0062,0.0011,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0074,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00031,0.00031,0.066,0.031,0.031,0.014,0.05,0.05,0.046,4.4e-06,4.4e-06,2.4e-06,0.015,0.015,0.00081,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 +18590000,0.71,0.00072,-0.013,0.71,0.017,0.0049,0.0057,0.0049,0.00079,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0083,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00029,0.00029,0.066,0.028,0.028,0.014,0.044,0.044,0.045,4e-06,4.1e-06,2.4e-06,0.014,0.014,0.00076,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 +18690000,0.71,0.00068,-0.013,0.71,0.017,0.0045,0.0038,0.0065,0.0013,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0083,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0003,0.0003,0.066,0.031,0.031,0.013,0.049,0.049,0.045,4e-06,4.1e-06,2.4e-06,0.014,0.014,0.00074,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 +18790000,0.71,0.00074,-0.013,0.71,0.015,0.0044,0.0035,0.0052,0.001,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0091,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00028,0.00028,0.066,0.027,0.027,0.013,0.044,0.044,0.045,3.7e-06,3.7e-06,2.4e-06,0.014,0.014,0.00071,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 +18890000,0.71,0.00077,-0.013,0.71,0.016,0.0051,0.0041,0.0068,0.0016,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0091,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00028,0.00028,0.066,0.03,0.03,0.013,0.049,0.049,0.045,3.7e-06,3.7e-06,2.4e-06,0.014,0.014,0.00068,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 +18990000,0.71,0.00076,-0.013,0.71,0.017,0.0056,0.0028,0.0077,0.0012,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.009,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00027,0.00027,0.066,0.027,0.027,0.012,0.044,0.044,0.044,3.4e-06,3.4e-06,2.4e-06,0.013,0.013,0.00065,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 +19090000,0.71,0.00075,-0.013,0.71,0.018,0.0065,0.0058,0.0095,0.0019,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.009,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00027,0.00027,0.066,0.029,0.029,0.012,0.049,0.049,0.044,3.4e-06,3.4e-06,2.4e-06,0.013,0.013,0.00063,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 +19190000,0.71,0.00077,-0.012,0.71,0.018,0.006,0.0059,0.0099,0.0015,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0089,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00025,0.00025,0.066,0.026,0.026,0.012,0.044,0.044,0.044,3.1e-06,3.2e-06,2.4e-06,0.012,0.012,0.0006,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 +19290000,0.71,0.00079,-0.012,0.71,0.018,0.0055,0.0086,0.012,0.0021,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0089,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00026,0.00026,0.066,0.029,0.029,0.012,0.049,0.049,0.044,3.1e-06,3.2e-06,2.4e-06,0.012,0.012,0.00059,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 +19390000,0.71,0.00084,-0.012,0.71,0.016,0.0042,0.012,0.0095,0.0016,-3.7e+02,-0.0013,-0.006,-8.4e-05,0.0098,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00024,0.00024,0.066,0.026,0.026,0.012,0.043,0.043,0.043,2.9e-06,2.9e-06,2.4e-06,0.012,0.012,0.00056,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 +19490000,0.71,0.00086,-0.012,0.71,0.015,0.0037,0.0088,0.011,0.002,-3.7e+02,-0.0013,-0.006,-8.4e-05,0.0098,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00025,0.00025,0.066,0.028,0.028,0.011,0.049,0.049,0.043,2.9e-06,2.9e-06,2.4e-06,0.012,0.012,0.00055,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 +19590000,0.71,0.00094,-0.012,0.71,0.013,0.0023,0.0081,0.009,0.0016,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.01,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00023,0.00023,0.066,0.025,0.025,0.011,0.043,0.043,0.042,2.7e-06,2.7e-06,2.4e-06,0.011,0.011,0.00052,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 +19690000,0.71,0.00094,-0.012,0.71,0.013,0.00031,0.0096,0.01,0.0017,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.01,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00023,0.00023,0.066,0.028,0.028,0.011,0.049,0.049,0.042,2.7e-06,2.7e-06,2.4e-06,0.011,0.011,0.00051,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 +19790000,0.71,0.001,-0.012,0.71,0.011,-0.00093,0.01,0.0084,0.0014,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.011,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00022,0.00022,0.066,0.025,0.025,0.011,0.043,0.043,0.042,2.5e-06,2.5e-06,2.4e-06,0.011,0.011,0.00049,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 +19890000,0.71,0.00098,-0.012,0.71,0.0097,-0.001,0.011,0.0094,0.0013,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.011,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00022,0.00022,0.066,0.027,0.027,0.011,0.049,0.049,0.042,2.5e-06,2.5e-06,2.4e-06,0.011,0.011,0.00048,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 +19990000,0.71,0.00098,-0.012,0.71,0.007,-0.0021,0.014,0.0077,0.00099,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00021,0.00021,0.066,0.024,0.024,0.01,0.043,0.043,0.041,2.3e-06,2.3e-06,2.4e-06,0.01,0.01,0.00046,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 +20090000,0.71,0.00098,-0.012,0.71,0.0069,-0.0039,0.014,0.0084,0.00071,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00021,0.00021,0.066,0.026,0.026,0.01,0.048,0.048,0.042,2.3e-06,2.3e-06,2.4e-06,0.01,0.01,0.00045,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 +20190000,0.71,0.0011,-0.012,0.71,0.0044,-0.0049,0.017,0.0059,0.0006,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0002,0.0002,0.066,0.024,0.024,0.01,0.043,0.043,0.041,2.1e-06,2.1e-06,2.4e-06,0.0097,0.0097,0.00043,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 +20290000,0.71,0.0011,-0.012,0.71,0.0034,-0.0063,0.015,0.0063,3.9e-05,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0002,0.0002,0.066,0.026,0.026,0.0099,0.048,0.048,0.041,2.1e-06,2.1e-06,2.4e-06,0.0097,0.0097,0.00042,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 +20390000,0.71,0.0011,-0.012,0.71,0.00074,-0.0073,0.017,0.0041,6.5e-05,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00019,0.00019,0.066,0.023,0.023,0.0097,0.043,0.043,0.041,1.9e-06,1.9e-06,2.4e-06,0.0092,0.0093,0.00041,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 +20490000,0.71,0.0011,-0.012,0.71,0.00044,-0.0078,0.016,0.0041,-0.00069,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00019,0.00019,0.066,0.025,0.025,0.0096,0.048,0.048,0.041,1.9e-06,1.9e-06,2.4e-06,0.0092,0.0093,0.0004,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 +20590000,0.71,0.0012,-0.012,0.71,0.0005,-0.0081,0.013,0.0035,-0.00055,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00018,0.00018,0.066,0.023,0.023,0.0093,0.043,0.043,0.04,1.8e-06,1.8e-06,2.4e-06,0.0088,0.0089,0.00038,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 +20690000,0.71,0.0012,-0.012,0.71,0.00066,-0.0094,0.015,0.0035,-0.0014,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00018,0.00018,0.066,0.025,0.025,0.0093,0.048,0.048,0.04,1.8e-06,1.8e-06,2.4e-06,0.0088,0.0089,0.00037,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 +20790000,0.71,0.0012,-0.012,0.71,-0.00073,-0.0088,0.015,0.0029,-0.0011,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00017,0.00017,0.066,0.022,0.022,0.0091,0.043,0.043,0.04,1.7e-06,1.7e-06,2.4e-06,0.0085,0.0085,0.00036,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 +20890000,0.71,0.0012,-0.012,0.71,-0.001,-0.011,0.014,0.0028,-0.0021,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00018,0.00018,0.066,0.024,0.024,0.009,0.048,0.048,0.04,1.7e-06,1.7e-06,2.5e-06,0.0085,0.0085,0.00035,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 +20990000,0.71,0.0012,-0.012,0.71,-0.0015,-0.012,0.015,0.0041,-0.0018,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00017,0.00017,0.066,0.022,0.022,0.0088,0.042,0.042,0.039,1.6e-06,1.6e-06,2.5e-06,0.0081,0.0082,0.00034,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 +21090000,0.71,0.0012,-0.012,0.71,-0.0016,-0.014,0.015,0.004,-0.0031,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00017,0.00017,0.066,0.024,0.024,0.0088,0.047,0.047,0.039,1.6e-06,1.6e-06,2.5e-06,0.0081,0.0082,0.00033,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 +21190000,0.71,0.0012,-0.012,0.71,-0.001,-0.013,0.014,0.0051,-0.0025,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00016,0.00016,0.066,0.021,0.021,0.0086,0.042,0.042,0.039,1.5e-06,1.5e-06,2.5e-06,0.0078,0.0078,0.00032,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 +21290000,0.71,0.0012,-0.012,0.71,-0.0015,-0.016,0.016,0.005,-0.004,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00016,0.00016,0.066,0.023,0.023,0.0085,0.047,0.047,0.039,1.5e-06,1.5e-06,2.5e-06,0.0078,0.0078,0.00032,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 +21390000,0.71,0.0013,-0.012,0.71,-0.0025,-0.015,0.016,0.0042,-0.0023,-3.7e+02,-0.0014,-0.0059,-8.2e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.021,0.021,0.0084,0.042,0.042,0.039,1.4e-06,1.4e-06,2.5e-06,0.0075,0.0076,0.00031,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 +21490000,0.71,0.0013,-0.012,0.71,-0.0029,-0.016,0.015,0.0039,-0.0038,-3.7e+02,-0.0014,-0.0059,-8.2e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.023,0.023,0.0083,0.047,0.047,0.038,1.4e-06,1.4e-06,2.5e-06,0.0075,0.0076,0.0003,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 +21590000,0.71,0.0013,-0.012,0.71,-0.0037,-0.014,0.015,0.0033,-0.0021,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.02,0.02,0.0081,0.042,0.042,0.038,1.3e-06,1.3e-06,2.5e-06,0.0073,0.0073,0.00029,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 +21690000,0.71,0.0013,-0.012,0.71,-0.0035,-0.015,0.017,0.0029,-0.0035,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.022,0.022,0.0081,0.047,0.047,0.038,1.3e-06,1.3e-06,2.5e-06,0.0073,0.0073,0.00029,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.5 +21790000,0.71,0.0012,-0.013,0.71,-0.0043,-0.0098,0.015,0.0014,0.00015,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.015,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00014,0.00014,0.066,0.02,0.02,0.008,0.042,0.042,0.038,1.2e-06,1.2e-06,2.5e-06,0.007,0.007,0.00028,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.5 +21890000,0.71,0.0012,-0.012,0.71,-0.0042,-0.01,0.016,0.00098,-0.00084,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.015,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00014,0.00014,0.066,0.022,0.022,0.0079,0.047,0.047,0.038,1.2e-06,1.2e-06,2.5e-06,0.007,0.007,0.00028,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.5 +21990000,0.71,0.0013,-0.013,0.71,-0.0048,-0.0077,0.016,-0.00016,0.0023,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00014,0.00014,0.066,0.02,0.02,0.0078,0.042,0.042,0.038,1.1e-06,1.1e-06,2.5e-06,0.0068,0.0068,0.00027,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22090000,0.71,0.0013,-0.013,0.71,-0.0051,-0.0068,0.015,-0.00065,0.0016,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00014,0.00014,0.066,0.021,0.021,0.0078,0.046,0.046,0.037,1.1e-06,1.1e-06,2.5e-06,0.0068,0.0068,0.00026,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22190000,0.71,0.0012,-0.013,0.71,-0.0051,-0.006,0.015,-0.00055,0.0014,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.019,0.019,0.0076,0.042,0.042,0.037,1e-06,1e-06,2.5e-06,0.0066,0.0066,0.00026,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22290000,0.71,0.0013,-0.013,0.71,-0.0064,-0.0067,0.015,-0.0011,0.00073,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.021,0.021,0.0076,0.046,0.046,0.037,1e-06,1e-06,2.5e-06,0.0066,0.0066,0.00025,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22390000,0.71,0.0013,-0.013,0.71,-0.0071,-0.0063,0.017,-0.00099,0.00058,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.019,0.019,0.0075,0.041,0.041,0.037,9.9e-07,9.9e-07,2.5e-06,0.0064,0.0064,0.00025,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22490000,0.71,0.0013,-0.013,0.71,-0.0077,-0.0061,0.018,-0.0017,-5.8e-05,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.02,0.02,0.0074,0.046,0.046,0.037,9.9e-07,9.9e-07,2.5e-06,0.0064,0.0064,0.00024,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22590000,0.71,0.0012,-0.013,0.71,-0.0076,-0.0058,0.017,-0.0022,0.00086,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.018,0.019,0.0073,0.041,0.041,0.036,9.3e-07,9.3e-07,2.5e-06,0.0062,0.0062,0.00024,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22690000,0.71,0.0013,-0.013,0.71,-0.0087,-0.0055,0.018,-0.0031,0.0003,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.02,0.02,0.0073,0.046,0.046,0.036,9.3e-07,9.3e-07,2.5e-06,0.0062,0.0062,0.00023,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22790000,0.71,0.0012,-0.013,0.71,-0.0094,-0.0044,0.019,-0.0044,0.00027,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.018,0.018,0.0072,0.041,0.041,0.036,8.8e-07,8.8e-07,2.5e-06,0.0061,0.0061,0.00023,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22890000,0.71,0.0012,-0.013,0.71,-0.011,-0.004,0.021,-0.0054,-0.00015,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.02,0.02,0.0072,0.046,0.046,0.036,8.8e-07,8.8e-07,2.5e-06,0.0061,0.0061,0.00022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22990000,0.71,0.0012,-0.013,0.71,-0.011,-0.0045,0.022,-0.0063,-0.00017,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0099,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.018,0.018,0.0071,0.041,0.041,0.036,8.4e-07,8.3e-07,2.5e-06,0.0059,0.0059,0.00022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23090000,0.71,0.0012,-0.012,0.71,-0.012,-0.0045,0.022,-0.0075,-0.00061,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0099,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.019,0.019,0.007,0.045,0.045,0.036,8.4e-07,8.4e-07,2.5e-06,0.0059,0.0059,0.00022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23190000,0.71,0.0013,-0.012,0.71,-0.013,-0.0055,0.024,-0.011,-0.00059,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.018,0.018,0.0069,0.041,0.041,0.035,8e-07,7.9e-07,2.5e-06,0.0058,0.0058,0.00021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23290000,0.71,0.0012,-0.012,0.71,-0.014,-0.0067,0.024,-0.012,-0.0012,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.019,0.019,0.0069,0.045,0.045,0.036,8e-07,7.9e-07,2.5e-06,0.0058,0.0058,0.00021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23390000,0.71,0.0013,-0.012,0.71,-0.015,-0.0071,0.022,-0.015,-0.0011,-3.7e+02,-0.0014,-0.0059,-8e-05,0.016,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.017,0.017,0.0068,0.041,0.041,0.035,7.6e-07,7.5e-07,2.5e-06,0.0056,0.0056,0.00021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23490000,0.71,0.0037,-0.01,0.71,-0.022,-0.0078,-0.012,-0.017,-0.0019,-3.7e+02,-0.0014,-0.0059,-8e-05,0.016,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.019,0.019,0.0068,0.045,0.045,0.035,7.6e-07,7.5e-07,2.5e-06,0.0056,0.0056,0.0002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23590000,0.71,0.0089,-0.0022,0.71,-0.032,-0.0067,-0.043,-0.016,-0.00069,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0095,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.017,0.017,0.0067,0.04,0.04,0.035,7.2e-07,7.2e-07,2.5e-06,0.0055,0.0055,0.0002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23690000,0.71,0.0085,0.0036,0.71,-0.063,-0.015,-0.094,-0.02,-0.0017,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0095,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.018,0.019,0.0067,0.045,0.045,0.035,7.2e-07,7.2e-07,2.5e-06,0.0055,0.0055,0.0002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23790000,0.71,0.0055,0.00025,0.71,-0.087,-0.026,-0.15,-0.02,-0.0012,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0086,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.017,0.017,0.0066,0.04,0.04,0.035,6.9e-07,6.9e-07,2.5e-06,0.0054,0.0054,0.00019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23890000,0.71,0.0029,-0.0058,0.71,-0.1,-0.035,-0.2,-0.029,-0.0043,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0086,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.018,0.019,0.0066,0.045,0.045,0.035,6.9e-07,6.9e-07,2.5e-06,0.0054,0.0054,0.00019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23990000,0.71,0.0015,-0.01,0.71,-0.1,-0.039,-0.25,-0.033,-0.0076,-3.7e+02,-0.0014,-0.0059,-8e-05,0.014,0.0081,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.9e-05,9.9e-05,0.066,0.017,0.018,0.0066,0.04,0.04,0.035,6.6e-07,6.5e-07,2.5e-06,0.0053,0.0053,0.00019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24090000,0.71,0.0028,-0.0091,0.71,-0.11,-0.039,-0.3,-0.044,-0.011,-3.7e+02,-0.0014,-0.0059,-8e-05,0.014,0.0081,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.018,0.019,0.0065,0.044,0.045,0.035,6.6e-07,6.6e-07,2.5e-06,0.0053,0.0053,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24190000,0.71,0.0038,-0.0069,0.71,-0.11,-0.04,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.013,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.7e-05,9.6e-05,0.066,0.017,0.017,0.0065,0.04,0.04,0.034,6.3e-07,6.3e-07,2.5e-06,0.0052,0.0052,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24290000,0.71,0.0043,-0.006,0.71,-0.12,-0.044,-0.41,-0.057,-0.018,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.013,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.8e-05,9.8e-05,0.066,0.018,0.019,0.0065,0.044,0.044,0.034,6.3e-07,6.3e-07,2.5e-06,0.0052,0.0052,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24390000,0.7,0.0043,-0.0062,0.71,-0.13,-0.051,-0.46,-0.063,-0.029,-3.7e+02,-0.0013,-0.0059,-8.1e-05,0.012,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.4e-05,9.4e-05,0.066,0.016,0.017,0.0064,0.04,0.04,0.034,6e-07,6e-07,2.5e-06,0.0051,0.0051,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24490000,0.7,0.0052,-0.0021,0.71,-0.14,-0.056,-0.51,-0.076,-0.035,-3.7e+02,-0.0013,-0.0059,-8.1e-05,0.012,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.5e-05,9.5e-05,0.066,0.018,0.019,0.0064,0.044,0.044,0.034,6e-07,6e-07,2.5e-06,0.0051,0.0051,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24590000,0.7,0.0056,0.0016,0.71,-0.16,-0.068,-0.56,-0.08,-0.044,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.011,0.0075,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.2e-05,9.2e-05,0.065,0.016,0.017,0.0063,0.04,0.04,0.034,5.8e-07,5.8e-07,2.5e-06,0.005,0.005,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24690000,0.7,0.0057,0.0026,0.71,-0.18,-0.081,-0.64,-0.097,-0.052,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.011,0.0075,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,9.3e-05,0.065,0.018,0.019,0.0063,0.044,0.044,0.034,5.8e-07,5.8e-07,2.5e-06,0.005,0.005,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24790000,0.7,0.0053,0.0012,0.71,-0.2,-0.094,-0.73,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.01,0.0068,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,8.9e-05,0.065,0.016,0.018,0.0062,0.04,0.04,0.034,5.6e-07,5.6e-07,2.5e-06,0.005,0.0049,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24890000,0.7,0.0071,0.0029,0.71,-0.22,-0.11,-0.75,-0.13,-0.072,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.01,0.0068,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,9e-05,0.065,0.018,0.02,0.0062,0.044,0.044,0.034,5.6e-07,5.6e-07,2.5e-06,0.005,0.0049,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24990000,0.71,0.0088,0.0046,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.0091,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,8.7e-05,0.064,0.016,0.018,0.0062,0.04,0.04,0.034,5.4e-07,5.4e-07,2.5e-06,0.0049,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25090000,0.71,0.0091,0.004,0.71,-0.27,-0.12,-0.86,-0.15,-0.092,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.0091,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.9e-05,8.8e-05,0.064,0.018,0.02,0.0062,0.044,0.044,0.034,5.4e-07,5.4e-07,2.5e-06,0.0049,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25190000,0.7,0.0086,0.0026,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,-8.3e-05,0.0082,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,8.5e-05,0.063,0.016,0.019,0.0061,0.04,0.04,0.033,5.2e-07,5.2e-07,2.5e-06,0.0048,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25290000,0.7,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,-8.3e-05,0.0082,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,8.6e-05,0.063,0.017,0.021,0.0061,0.044,0.044,0.033,5.2e-07,5.2e-07,2.5e-06,0.0048,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25390000,0.7,0.012,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,-8.4e-05,0.0066,0.0048,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,8.3e-05,0.062,0.016,0.02,0.0061,0.039,0.04,0.033,5e-07,5e-07,2.5e-06,0.0048,0.0047,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25490000,0.7,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,-8.4e-05,0.0066,0.0048,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,8.4e-05,0.062,0.018,0.023,0.0061,0.044,0.045,0.033,5e-07,5.1e-07,2.5e-06,0.0048,0.0047,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25590000,0.7,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0053,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,8.1e-05,0.06,0.016,0.022,0.006,0.039,0.04,0.033,4.9e-07,4.9e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25690000,0.7,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0053,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,8.2e-05,0.06,0.018,0.025,0.006,0.043,0.045,0.033,4.9e-07,4.9e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,-8.6e-05,0.003,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.4e-05,8e-05,0.058,0.017,0.024,0.006,0.039,0.04,0.033,4.7e-07,4.8e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25890000,0.7,0.018,0.029,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,-8.6e-05,0.003,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,8e-05,0.058,0.018,0.029,0.006,0.043,0.045,0.033,4.7e-07,4.8e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25990000,0.7,0.017,0.026,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.0011,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7.8e-05,0.055,0.017,0.028,0.0059,0.039,0.041,0.033,4.6e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26090000,0.7,0.021,0.036,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.0011,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7.9e-05,0.055,0.019,0.032,0.0059,0.043,0.046,0.033,4.6e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,-8.8e-05,-0.0021,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7.6e-05,0.051,0.017,0.031,0.0059,0.039,0.041,0.032,4.5e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,-8.8e-05,-0.0021,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,7.7e-05,0.051,0.019,0.037,0.0059,0.043,0.046,0.033,4.5e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26390000,0.7,0.023,0.044,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0043,0.0016,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,7.5e-05,0.046,0.018,0.035,0.0058,0.039,0.042,0.032,4.4e-07,4.6e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26490000,0.7,0.031,0.06,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0043,0.0016,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,7.6e-05,0.046,0.02,0.042,0.0058,0.043,0.047,0.032,4.4e-07,4.6e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26590000,0.7,0.037,0.076,0.71,-1.1,-0.59,-1.3,-0.82,-0.66,-3.7e+02,-0.00096,-0.0059,-8.9e-05,-0.0082,-0.00089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,7.4e-05,0.041,0.019,0.041,0.0058,0.039,0.042,0.032,4.3e-07,4.6e-07,2.5e-06,0.0046,0.0044,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26690000,0.7,0.038,0.079,0.71,-1.3,-0.65,-1.3,-0.95,-0.73,-3.7e+02,-0.00096,-0.0059,-8.9e-05,-0.0082,-0.00089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,7.5e-05,0.041,0.021,0.051,0.0058,0.043,0.049,0.032,4.3e-07,4.6e-07,2.5e-06,0.0046,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26790000,0.7,0.036,0.073,0.71,-1.4,-0.74,-1.3,-1,-0.85,-3.7e+02,-0.00092,-0.0059,-9.5e-05,-0.011,-0.00024,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.9e-05,7.3e-05,0.034,0.02,0.048,0.0058,0.039,0.043,0.032,4.2e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26890000,0.7,0.045,0.095,0.71,-1.5,-0.8,-1.3,-1.2,-0.93,-3.7e+02,-0.00092,-0.0059,-9.5e-05,-0.011,-0.00024,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,7.3e-05,0.034,0.022,0.058,0.0058,0.044,0.05,0.032,4.2e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26990000,0.7,0.05,0.12,0.7,-1.7,-0.88,-1.3,-1.2,-1,-3.7e+02,-0.0008,-0.0059,-9.8e-05,-0.017,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,7.2e-05,0.028,0.021,0.054,0.0057,0.039,0.044,0.032,4.1e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27090000,0.7,0.051,0.12,0.7,-1.9,-0.97,-1.3,-1.4,-1.1,-3.7e+02,-0.0008,-0.0059,-9.8e-05,-0.017,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,7.2e-05,0.028,0.024,0.069,0.0058,0.044,0.051,0.032,4.1e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27190000,0.71,0.049,0.11,0.69,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00077,-0.0059,-8.2e-05,-0.019,-0.0039,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,7.2e-05,0.023,0.024,0.065,0.0057,0.046,0.053,0.032,4.1e-07,4.5e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27290000,0.71,0.043,0.095,0.69,-2.3,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00077,-0.0059,-8.2e-05,-0.019,-0.0039,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.2e-05,7.3e-05,0.023,0.026,0.076,0.0058,0.051,0.062,0.032,4.1e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27390000,0.72,0.037,0.079,0.69,-2.4,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.0007,-0.0059,-7.4e-05,-0.022,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.2e-05,7.2e-05,0.018,0.024,0.064,0.0057,0.053,0.062,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27490000,0.72,0.031,0.064,0.69,-2.5,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.0007,-0.0059,-7.4e-05,-0.022,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,7.3e-05,0.018,0.026,0.069,0.0057,0.059,0.072,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0044,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27590000,0.73,0.026,0.051,0.69,-2.5,-1.1,-1.2,-2.6,-1.6,-3.7e+02,-0.0007,-0.0059,-6.5e-05,-0.022,-0.0056,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,7.2e-05,0.015,0.024,0.056,0.0057,0.061,0.072,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27690000,0.73,0.026,0.05,0.69,-2.6,-1.1,-1.2,-2.8,-1.7,-3.7e+02,-0.0007,-0.0059,-6.5e-05,-0.022,-0.0056,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.4e-05,7.3e-05,0.015,0.025,0.057,0.0057,0.067,0.082,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27790000,0.73,0.026,0.051,0.68,-2.6,-1.1,-1.2,-3.1,-1.8,-3.7e+02,-0.00069,-0.006,-6e-05,-0.023,-0.0055,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.5e-05,7.2e-05,0.012,0.023,0.047,0.0057,0.069,0.081,0.032,3.9e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27890000,0.73,0.025,0.049,0.68,-2.7,-1.1,-1.2,-3.3,-1.9,-3.7e+02,-0.00069,-0.006,-6e-05,-0.023,-0.0055,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.6e-05,7.3e-05,0.012,0.024,0.049,0.0057,0.076,0.092,0.032,3.9e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27990000,0.73,0.024,0.046,0.68,-2.7,-1.1,-1.2,-3.6,-2,-3.7e+02,-0.00072,-0.006,-5.6e-05,-0.022,-0.0039,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.7e-05,7.2e-05,0.011,0.023,0.042,0.0057,0.078,0.091,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28090000,0.73,0.03,0.059,0.68,-2.7,-1.2,-1.2,-3.9,-2.1,-3.7e+02,-0.00072,-0.006,-5.6e-05,-0.022,-0.0039,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.8e-05,7.3e-05,0.011,0.024,0.043,0.0057,0.085,0.1,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28190000,0.73,0.036,0.072,0.68,-2.8,-1.2,-0.94,-4.2,-2.2,-3.7e+02,-0.00074,-0.006,-5.4e-05,-0.022,-0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.9e-05,7.2e-05,0.01,0.022,0.038,0.0057,0.087,0.1,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28290000,0.73,0.028,0.055,0.68,-2.8,-1.2,-0.08,-4.5,-2.3,-3.7e+02,-0.00074,-0.006,-5.4e-05,-0.022,-0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.01,0.022,0.038,0.0057,0.094,0.11,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28390000,0.73,0.011,0.024,0.68,-2.8,-1.2,0.78,-4.8,-2.5,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.3e-05,0.01,0.023,0.038,0.0057,0.1,0.12,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28490000,0.73,0.001,0.0062,0.68,-2.7,-1.2,1.1,-5,-2.6,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.4e-05,0.01,0.023,0.038,0.0057,0.11,0.13,0.032,3.9e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28590000,0.73,-0.00091,0.0027,0.68,-2.7,-1.2,0.97,-5.3,-2.7,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.5e-05,0.01,0.024,0.036,0.0057,0.12,0.15,0.032,3.9e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28690000,0.73,-0.0017,0.0018,0.68,-2.6,-1.2,0.98,-5.6,-2.8,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.6e-05,0.01,0.025,0.035,0.0057,0.13,0.16,0.032,3.9e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28790000,0.73,-0.0017,0.0017,0.68,-2.6,-1.1,0.98,-5.9,-2.9,-3.7e+02,-0.00078,-0.006,-5.2e-05,-0.02,-0.0014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0096,0.024,0.03,0.0057,0.13,0.16,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28890000,0.73,-0.0018,0.0019,0.68,-2.5,-1.1,0.97,-6.2,-3,-3.7e+02,-0.00078,-0.006,-5.2e-05,-0.02,-0.0012,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0096,0.025,0.029,0.0057,0.14,0.17,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28990000,0.74,-0.0013,0.0026,0.68,-2.5,-1.1,0.97,-6.5,-3.1,-3.7e+02,-0.00086,-0.006,-5.2e-05,-0.017,0.00024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0094,0.024,0.026,0.0057,0.14,0.17,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29090000,0.74,-0.0011,0.003,0.68,-2.4,-1.1,0.96,-6.7,-3.2,-3.7e+02,-0.00086,-0.006,-5.2e-05,-0.017,0.00044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0094,0.025,0.027,0.0057,0.15,0.18,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29190000,0.74,-0.00074,0.0034,0.68,-2.4,-1.1,0.95,-7,-3.3,-3.7e+02,-0.0009,-0.006,-5.4e-05,-0.015,0.0014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0093,0.024,0.025,0.0057,0.15,0.18,0.032,3.7e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29290000,0.74,-0.00041,0.0042,0.68,-2.3,-1.1,0.98,-7.3,-3.4,-3.7e+02,-0.0009,-0.006,-5.4e-05,-0.015,0.0017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0093,0.025,0.025,0.0057,0.16,0.19,0.032,3.7e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29390000,0.74,0.00042,0.0058,0.67,-2.3,-1.1,0.99,-7.6,-3.6,-3.7e+02,-0.00096,-0.006,-5.7e-05,-0.012,0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0092,0.024,0.024,0.0056,0.16,0.19,0.031,3.7e-07,4.5e-07,2.5e-06,0.0044,0.0042,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29490000,0.74,0.00093,0.0069,0.67,-2.2,-1.1,0.99,-7.8,-3.7,-3.7e+02,-0.00096,-0.006,-5.7e-05,-0.012,0.0032,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0093,0.025,0.025,0.0057,0.17,0.2,0.032,3.7e-07,4.5e-07,2.5e-06,0.0044,0.0042,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29590000,0.74,0.0015,0.0079,0.67,-2.2,-1.1,0.98,-8.1,-3.8,-3.7e+02,-0.001,-0.006,-6.4e-05,-0.01,0.0036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0093,0.024,0.024,0.0056,0.17,0.2,0.031,3.6e-07,4.4e-07,2.5e-06,0.0043,0.0042,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29690000,0.74,0.0018,0.0085,0.67,-2.2,-1.1,0.98,-8.3,-3.9,-3.7e+02,-0.00099,-0.006,-6.4e-05,-0.011,0.0038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0093,0.026,0.026,0.0056,0.18,0.21,0.031,3.6e-07,4.5e-07,2.5e-06,0.0043,0.0042,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29790000,0.74,0.0023,0.009,0.67,-2.1,-1.1,0.96,-8.6,-4,-3.7e+02,-0.001,-0.006,-7.3e-05,-0.0081,0.0042,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0092,0.024,0.025,0.0056,0.18,0.21,0.031,3.6e-07,4.4e-07,2.5e-06,0.0043,0.0042,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29890000,0.74,0.0023,0.0091,0.67,-2.1,-1.1,0.95,-8.8,-4.1,-3.7e+02,-0.001,-0.006,-7.3e-05,-0.0083,0.0046,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0092,0.026,0.027,0.0056,0.19,0.22,0.031,3.6e-07,4.4e-07,2.5e-06,0.0043,0.0042,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29990000,0.74,0.0026,0.0091,0.67,-2.1,-1.1,0.94,-9,-4.2,-3.7e+02,-0.0011,-0.006,-8.5e-05,-0.0066,0.0044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0092,0.025,0.026,0.0056,0.19,0.22,0.031,3.5e-07,4.3e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30090000,0.74,0.0025,0.009,0.67,-2.1,-1.1,0.92,-9.2,-4.3,-3.7e+02,-0.0011,-0.006,-8.5e-05,-0.0068,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0092,0.026,0.028,0.0056,0.2,0.23,0.031,3.5e-07,4.3e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30190000,0.74,0.0028,0.0088,0.67,-2,-1.1,0.91,-9.5,-4.4,-3.7e+02,-0.0011,-0.006,-9.8e-05,-0.0045,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0091,0.025,0.027,0.0056,0.2,0.23,0.031,3.5e-07,4.2e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30290000,0.74,0.0027,0.0086,0.67,-2,-1.1,0.9,-9.7,-4.5,-3.7e+02,-0.0011,-0.006,-9.8e-05,-0.0046,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0091,0.026,0.03,0.0056,0.21,0.24,0.031,3.5e-07,4.2e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30390000,0.74,0.0028,0.0083,0.67,-2,-1.1,0.89,-9.9,-4.6,-3.7e+02,-0.0011,-0.006,-0.00011,-0.0031,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.2e-05,0.009,0.025,0.029,0.0055,0.21,0.24,0.031,3.4e-07,4.1e-07,2.5e-06,0.0042,0.0041,9.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30490000,0.74,0.0026,0.008,0.67,-1.9,-1.1,0.87,-10,-4.7,-3.7e+02,-0.0011,-0.006,-0.00011,-0.0032,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.009,0.026,0.031,0.0056,0.22,0.25,0.031,3.4e-07,4.1e-07,2.5e-06,0.0042,0.0041,9.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30590000,0.74,0.0027,0.0075,0.68,-1.9,-1.1,0.83,-10,-4.8,-3.7e+02,-0.0012,-0.0059,-0.00012,-0.0012,0.0046,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.0089,0.025,0.03,0.0055,0.22,0.25,0.031,3.4e-07,3.9e-07,2.5e-06,0.0042,0.004,9.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30690000,0.74,0.0025,0.0072,0.68,-1.9,-1.1,0.83,-11,-4.9,-3.7e+02,-0.0012,-0.0059,-0.00012,-0.0014,0.0049,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0089,0.027,0.032,0.0055,0.23,0.26,0.031,3.4e-07,3.9e-07,2.5e-06,0.0042,0.004,9.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30790000,0.74,0.0026,0.0067,0.68,-1.9,-1,0.82,-11,-4.9,-3.7e+02,-0.0012,-0.0059,-0.00014,0.00039,0.0042,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.1e-05,0.0087,0.025,0.031,0.0055,0.23,0.26,0.031,3.3e-07,3.8e-07,2.5e-06,0.0042,0.004,9.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30890000,0.74,0.0024,0.0062,0.68,-1.8,-1,0.81,-11,-5,-3.7e+02,-0.0012,-0.0059,-0.00014,0.00024,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.0087,0.027,0.033,0.0055,0.24,0.27,0.031,3.3e-07,3.8e-07,2.5e-06,0.0042,0.004,9.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30990000,0.74,0.0026,0.0056,0.68,-1.8,-1,0.8,-11,-5.1,-3.7e+02,-0.0012,-0.0059,-0.00015,0.0024,0.0041,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.9e-05,7.1e-05,0.0085,0.025,0.032,0.0055,0.24,0.27,0.031,3.3e-07,3.7e-07,2.5e-06,0.0041,0.004,9.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31090000,0.74,0.0023,0.0051,0.68,-1.8,-1,0.79,-11,-5.2,-3.7e+02,-0.0012,-0.0059,-0.00015,0.0022,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.0085,0.027,0.034,0.0055,0.25,0.28,0.031,3.3e-07,3.7e-07,2.5e-06,0.0041,0.0039,9.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31190000,0.73,0.0023,0.0046,0.68,-1.8,-1,0.78,-12,-5.3,-3.7e+02,-0.0013,-0.0059,-0.00016,0.0034,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.6e-05,7.1e-05,0.0083,0.025,0.032,0.0055,0.25,0.28,0.031,3.2e-07,3.6e-07,2.5e-06,0.0041,0.0039,9.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31290000,0.73,0.0021,0.0041,0.68,-1.8,-1,0.78,-12,-5.4,-3.7e+02,-0.0013,-0.0059,-0.00016,0.0032,0.005,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.7e-05,7.1e-05,0.0083,0.027,0.035,0.0055,0.26,0.29,0.031,3.2e-07,3.6e-07,2.5e-06,0.0041,0.0039,9.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31390000,0.73,0.0021,0.0034,0.68,-1.7,-1,0.78,-12,-5.5,-3.7e+02,-0.0013,-0.0058,-0.00018,0.0049,0.0051,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,7e-05,0.008,0.026,0.033,0.0054,0.25,0.29,0.031,3.1e-07,3.4e-07,2.5e-06,0.0041,0.0039,9.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31490000,0.73,0.0018,0.0028,0.68,-1.7,-1,0.78,-12,-5.6,-3.7e+02,-0.0013,-0.0058,-0.00018,0.0047,0.0055,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.4e-05,7.1e-05,0.008,0.027,0.035,0.0055,0.27,0.3,0.031,3.2e-07,3.5e-07,2.5e-06,0.0041,0.0039,9.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31590000,0.73,0.0019,0.0022,0.68,-1.7,-0.98,0.77,-12,-5.7,-3.7e+02,-0.0013,-0.0058,-0.00019,0.0062,0.0052,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,7e-05,0.0078,0.026,0.033,0.0054,0.26,0.3,0.031,3.1e-07,3.3e-07,2.5e-06,0.004,0.0038,9.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31690000,0.73,0.0016,0.0015,0.68,-1.7,-0.98,0.78,-12,-5.8,-3.7e+02,-0.0013,-0.0058,-0.00019,0.006,0.0056,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,7e-05,0.0078,0.027,0.035,0.0054,0.28,0.31,0.031,3.1e-07,3.3e-07,2.5e-06,0.004,0.0038,9.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31790000,0.73,0.0015,0.00072,0.68,-1.6,-0.96,0.78,-13,-5.9,-3.7e+02,-0.0013,-0.0058,-0.0002,0.0077,0.0056,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,6.9e-05,0.0075,0.026,0.033,0.0054,0.27,0.31,0.031,3e-07,3.2e-07,2.5e-06,0.004,0.0038,9.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31890000,0.73,0.0012,-7.5e-06,0.68,-1.6,-0.96,0.77,-13,-6,-3.7e+02,-0.0013,-0.0058,-0.0002,0.0075,0.0061,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,7e-05,0.0075,0.027,0.035,0.0054,0.29,0.32,0.031,3.1e-07,3.2e-07,2.5e-06,0.004,0.0038,9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31990000,0.73,0.0012,-0.00065,0.68,-1.6,-0.94,0.77,-13,-6,-3.7e+02,-0.0013,-0.0058,-0.00022,0.0085,0.0059,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.4e-05,6.9e-05,0.0072,0.026,0.033,0.0054,0.28,0.32,0.031,3e-07,3.2e-07,2.5e-06,0.004,0.0038,9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32090000,0.73,0.00088,-0.0014,0.68,-1.5,-0.93,0.78,-13,-6.1,-3.7e+02,-0.0013,-0.0058,-0.00022,0.0083,0.0064,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7e-05,0.0072,0.027,0.035,0.0054,0.29,0.33,0.031,3e-07,3.2e-07,2.5e-06,0.004,0.0038,8.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32190000,0.73,0.00078,-0.0024,0.69,-1.5,-0.91,0.78,-13,-6.2,-3.7e+02,-0.0014,-0.0058,-0.00023,0.0095,0.0067,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.2e-05,6.9e-05,0.007,0.026,0.033,0.0054,0.29,0.33,0.031,3e-07,3.1e-07,2.5e-06,0.0039,0.0038,8.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32290000,0.73,0.0005,-0.0031,0.69,-1.5,-0.91,0.77,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-0.00023,0.0093,0.0072,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.3e-05,6.9e-05,0.007,0.027,0.035,0.0054,0.3,0.34,0.031,3e-07,3.1e-07,2.5e-06,0.0039,0.0038,8.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32390000,0.73,0.00041,-0.0039,0.69,-1.5,-0.89,0.77,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-0.00024,0.0099,0.0071,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.9e-05,6.8e-05,0.0067,0.025,0.033,0.0054,0.3,0.34,0.031,2.9e-07,3e-07,2.5e-06,0.0039,0.0037,8.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32490000,0.73,0.00026,-0.0041,0.69,-1.4,-0.88,0.78,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-0.00024,0.0097,0.0075,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8e-05,6.9e-05,0.0067,0.027,0.035,0.0054,0.31,0.35,0.031,2.9e-07,3e-07,2.5e-06,0.0039,0.0037,8.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32590000,0.73,0.00039,-0.0045,0.69,-1.4,-0.87,0.78,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0078,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.7e-05,6.8e-05,0.0065,0.025,0.033,0.0053,0.31,0.35,0.031,2.9e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32690000,0.73,0.00033,-0.0046,0.69,-1.4,-0.86,0.77,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0081,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.8e-05,6.8e-05,0.0065,0.027,0.035,0.0053,0.32,0.35,0.031,2.9e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32790000,0.72,0.00048,-0.0046,0.69,-1.3,-0.84,0.77,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0081,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.5e-05,6.7e-05,0.0063,0.025,0.032,0.0053,0.32,0.35,0.031,2.8e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32890000,0.72,0.00055,-0.0046,0.69,-1.3,-0.84,0.77,-14,-6.8,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0086,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.6e-05,6.8e-05,0.0063,0.027,0.034,0.0053,0.33,0.36,0.031,2.8e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32990000,0.72,0.00079,-0.0046,0.69,-1.3,-0.82,0.77,-15,-6.9,-3.7e+02,-0.0014,-0.0057,-0.00026,0.012,0.009,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.4e-05,6.7e-05,0.0061,0.025,0.032,0.0053,0.33,0.36,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33090000,0.72,0.00074,-0.0047,0.69,-1.3,-0.82,0.76,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00026,0.012,0.0094,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.4e-05,6.8e-05,0.0061,0.027,0.034,0.0053,0.34,0.37,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33190000,0.72,0.0043,-0.0039,0.7,-1.3,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00027,0.012,0.0095,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.2e-05,6.7e-05,0.0059,0.025,0.032,0.0053,0.34,0.37,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,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.00027,0.012,0.0098,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.3e-05,6.7e-05,0.0059,0.027,0.033,0.0053,0.35,0.38,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33390000,0.57,0.014,-0.0037,0.82,-1.2,-0.77,0.88,-15,-7.2,-3.7e+02,-0.0014,-0.0057,-0.00027,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.1e-05,6.6e-05,0.0057,0.025,0.03,0.0053,0.35,0.38,0.031,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33490000,0.43,0.0073,-0.0012,0.9,-1.2,-0.76,0.89,-15,-7.2,-3.7e+02,-0.0014,-0.0057,-0.00027,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.1e-05,6.7e-05,0.0057,0.026,0.032,0.0053,0.36,0.39,0.031,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33590000,0.27,0.0011,-0.0037,0.96,-1.2,-0.76,0.86,-15,-7.3,-3.7e+02,-0.0014,-0.0057,-0.00028,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.9e-05,6.5e-05,0.0055,0.025,0.03,0.0052,0.35,0.39,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33690000,0.11,-0.0025,-0.0068,0.99,-1.1,-0.75,0.87,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00028,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7e-05,6.6e-05,0.0055,0.026,0.032,0.0053,0.37,0.4,0.031,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33790000,-0.065,-0.0044,-0.0086,1,-1.1,-0.73,0.85,-16,-7.4,-3.7e+02,-0.0015,-0.0057,-0.00029,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.7e-05,6.4e-05,0.0054,0.025,0.031,0.0052,0.36,0.4,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33890000,-0.23,-0.0059,-0.0092,0.97,-1,-0.7,0.83,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00029,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.7e-05,6.4e-05,0.0054,0.026,0.033,0.0052,0.38,0.41,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33990000,-0.38,-0.0046,-0.013,0.92,-0.95,-0.65,0.81,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.0003,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.5e-05,6.2e-05,0.0052,0.026,0.032,0.0052,0.37,0.41,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +34090000,-0.49,-0.0038,-0.014,0.87,-0.89,-0.6,0.81,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.0003,0.012,0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.5e-05,6.2e-05,0.0052,0.028,0.035,0.0052,0.39,0.42,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0036,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +34190000,-0.56,-0.0036,-0.013,0.83,-0.86,-0.55,0.81,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00031,0.011,0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.1e-05,5.9e-05,0.005,0.028,0.034,0.0052,0.38,0.42,0.03,2.6e-07,2.6e-07,2.5e-06,0.0038,0.0036,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +34290000,-0.6,-0.0046,-0.0095,0.8,-0.81,-0.49,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00031,0.011,0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.1e-05,5.9e-05,0.005,0.03,0.038,0.0052,0.39,0.43,0.03,2.6e-07,2.6e-07,2.5e-06,0.0038,0.0036,8.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +34390000,-0.63,-0.0052,-0.0067,0.78,-0.79,-0.45,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00032,0.0086,0.019,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.7e-05,5.6e-05,0.0049,0.03,0.036,0.0052,0.39,0.43,0.03,2.6e-07,2.6e-07,2.5e-06,0.0037,0.0036,8.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +34490000,-0.64,-0.0061,-0.0045,0.76,-0.73,-0.4,0.81,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00032,0.0084,0.019,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.7e-05,5.6e-05,0.0049,0.033,0.04,0.0052,0.4,0.44,0.03,2.6e-07,2.6e-07,2.5e-06,0.0037,0.0036,8.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +34590000,-0.65,-0.0061,-0.0032,0.76,-0.72,-0.37,0.8,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00033,0.0041,0.025,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.3e-05,5.2e-05,0.0047,0.032,0.038,0.0052,0.4,0.44,0.03,2.6e-07,2.6e-07,2.5e-06,0.0036,0.0035,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +34690000,-0.66,-0.0065,-0.0023,0.75,-0.66,-0.32,0.8,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00033,0.004,0.025,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.3e-05,5.2e-05,0.0047,0.036,0.042,0.0052,0.41,0.45,0.03,2.6e-07,2.6e-07,2.5e-06,0.0036,0.0035,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +34790000,-0.66,-0.0058,-0.0019,0.75,-0.65,-0.3,0.79,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00035,-0.0013,0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.034,0.039,0.0052,0.41,0.45,0.03,2.6e-07,2.6e-07,2.5e-06,0.0034,0.0034,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +34890000,-0.67,-0.0059,-0.0018,0.75,-0.6,-0.25,0.79,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00035,-0.0014,0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.038,0.044,0.0052,0.42,0.46,0.03,2.6e-07,2.6e-07,2.5e-06,0.0034,0.0033,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +34990000,-0.67,-0.013,-0.0043,0.74,0.45,0.35,-0.044,-17,-8.2,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.042,0.058,0.0054,0.42,0.46,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +35090000,-0.67,-0.013,-0.0043,0.74,0.58,0.38,-0.1,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.046,0.064,0.0055,0.43,0.47,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +35190000,-0.67,-0.013,-0.0044,0.74,0.61,0.42,-0.1,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.051,0.068,0.0055,0.44,0.47,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +35290000,-0.67,-0.013,-0.0044,0.74,0.64,0.46,-0.1,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.055,0.073,0.0055,0.46,0.48,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +35390000,-0.67,-0.013,-0.0044,0.74,0.67,0.51,-0.097,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.06,0.078,0.0055,0.47,0.49,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +35490000,-0.67,-0.013,-0.0044,0.74,0.7,0.55,-0.095,-17,-7.9,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.065,0.083,0.0055,0.49,0.51,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +35590000,-0.67,-0.013,-0.0044,0.74,0.73,0.59,-0.095,-17,-7.9,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.07,0.088,0.0056,0.51,0.52,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +35690000,-0.67,-0.013,-0.0044,0.74,0.76,0.63,-0.092,-16,-7.8,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0045,0.075,0.094,0.0056,0.53,0.54,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +35790000,-0.67,-0.013,-0.0044,0.74,0.79,0.68,-0.09,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.4e-05,0.0045,0.081,0.1,0.0056,0.55,0.56,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.023 +35890000,-0.67,-0.013,-0.0044,0.74,0.82,0.72,-0.086,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.4e-05,0.0045,0.087,0.11,0.0056,0.57,0.58,0.031,2.6e-07,2.7e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.048 +35990000,-0.67,-0.013,-0.0044,0.74,0.85,0.76,-0.083,-16,-7.6,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.4e-05,0.0045,0.093,0.11,0.0056,0.6,0.6,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.073 +36090000,-0.67,-0.013,-0.0044,0.74,0.88,0.8,-0.08,-16,-7.5,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.1,0.12,0.0056,0.62,0.63,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.099 +36190000,-0.67,-0.013,-0.0044,0.74,0.92,0.85,-0.075,-16,-7.4,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0084,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.11,0.13,0.0056,0.66,0.66,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.12 +36290000,-0.67,-0.013,-0.0044,0.74,0.95,0.89,-0.07,-16,-7.4,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0083,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.11,0.13,0.0057,0.69,0.69,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.15 +36390000,-0.67,-0.013,-0.0044,0.74,0.98,0.93,-0.067,-16,-7.3,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0082,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.12,0.14,0.0057,0.72,0.73,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.17 +36490000,-0.67,-0.013,-0.0044,0.74,1,0.98,-0.063,-16,-7.2,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0082,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.13,0.15,0.0057,0.76,0.76,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.2 +36590000,-0.67,-0.013,-0.0044,0.74,1,1,-0.057,-16,-7.1,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0081,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.14,0.16,0.0057,0.81,0.81,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.23 +36690000,-0.67,-0.013,-0.0043,0.74,1.1,1.1,-0.053,-16,-7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.008,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.5e-05,0.0045,0.14,0.17,0.0057,0.85,0.86,0.032,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.25 +36790000,-0.67,-0.013,-0.0043,0.74,1.1,1.1,-0.047,-15,-6.9,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0079,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.5e-05,0.0045,0.15,0.17,0.0057,0.9,0.91,0.032,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.28 +36890000,-0.67,-0.013,-0.0043,0.74,1.1,1.1,-0.042,-15,-6.7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0078,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.5e-05,0.0045,0.16,0.18,0.0057,0.96,0.96,0.032,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.3 +36990000,-0.67,-0.013,-0.0043,0.74,1.2,1.2,-0.037,-15,-6.6,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0077,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.17,0.19,0.0057,1,1,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.33 +37090000,-0.67,-0.013,-0.0042,0.74,1.2,1.2,-0.031,-15,-6.5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0076,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.18,0.2,0.0057,1.1,1.1,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.35 +37190000,-0.67,-0.013,-0.0042,0.74,1.2,1.3,-0.025,-15,-6.4,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0076,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.19,0.21,0.0057,1.1,1.2,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.38 +37290000,-0.67,-0.013,-0.0042,0.74,1.3,1.3,-0.02,-15,-6.2,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0075,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.2,0.22,0.0057,1.2,1.2,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.41 +37390000,-0.67,-0.013,-0.0042,0.74,1.3,1.4,-0.015,-15,-6.1,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0075,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.6e-05,0.0045,0.21,0.23,0.0057,1.3,1.3,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.43 +37490000,-0.67,-0.013,-0.0041,0.74,1.3,1.4,-0.009,-15,-6,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0075,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.6e-05,0.0045,0.22,0.24,0.0057,1.4,1.4,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +37590000,-0.67,-0.013,-0.0041,0.74,1.4,1.4,-0.0023,-14,-5.8,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0074,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.6e-05,0.0045,0.23,0.25,0.0057,1.5,1.5,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.48 +37690000,-0.67,-0.013,-0.0041,0.74,1.4,1.5,0.0051,-14,-5.7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0071,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.7e-05,0.0045,0.24,0.26,0.0057,1.6,1.6,0.032,2.8e-07,2.8e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.51 +37790000,-0.67,-0.013,-0.0042,0.74,1.4,1.5,0.012,-14,-5.5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.007,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.7e-05,0.0045,0.25,0.28,0.0057,1.7,1.7,0.032,2.8e-07,2.8e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.54 +37890000,-0.67,-0.013,-0.0042,0.74,1.4,1.6,0.018,-14,-5.4,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.007,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.7e-05,0.0046,0.26,0.29,0.0057,1.8,1.8,0.032,2.8e-07,2.8e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.56 +37990000,-0.67,-0.013,-0.0042,0.74,1.5,1.6,0.026,-14,-5.2,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0069,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.7e-05,0.0046,0.27,0.3,0.0057,1.9,2,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.59 +38090000,-0.67,-0.013,-0.0042,0.74,1.5,1.7,0.035,-14,-5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0068,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.7e-05,0.0046,0.28,0.31,0.0057,2,2.1,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +38190000,-0.67,-0.013,-0.0042,0.74,1.5,1.7,0.041,-14,-4.9,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0067,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.7e-05,0.0046,0.29,0.32,0.0056,2.1,2.2,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.64 +38290000,-0.67,-0.013,-0.0041,0.74,1.6,1.8,0.047,-13,-4.7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0067,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.3,0.33,0.0057,2.3,2.4,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.67 +38390000,-0.67,-0.013,-0.0041,0.74,1.6,1.8,0.053,-13,-4.5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0066,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.32,0.35,0.0056,2.4,2.5,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.69 +38490000,-0.67,-0.013,-0.0041,0.74,1.6,1.8,0.059,-13,-4.3,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0066,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.8e-05,0.0046,0.33,0.36,0.0056,2.6,2.7,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.72 +38590000,-0.67,-0.013,-0.004,0.74,1.7,1.9,0.064,-13,-4.1,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0066,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.8e-05,0.0046,0.34,0.37,0.0056,2.8,2.9,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.75 +38690000,-0.67,-0.013,-0.004,0.74,1.7,1.9,0.07,-13,-4,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0068,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.9e-05,0.0046,0.35,0.39,0.0056,2.9,3.1,0.032,2.9e-07,2.9e-07,2.6e-06,0.0032,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.77 +38790000,-0.67,-0.013,-0.004,0.74,1.7,2,0.076,-13,-3.8,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0068,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.9e-05,0.0046,0.37,0.4,0.0056,3.1,3.3,0.032,2.9e-07,2.9e-07,2.6e-06,0.0032,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.8 +38890000,-0.67,-0.014,-0.0041,0.74,1.7,2,0.58,-12,-3.6,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0067,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.9e-05,0.0046,0.38,0.41,0.0056,3.3,3.5,0.032,2.9e-07,2.9e-07,2.6e-06,0.0032,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,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 d1b4885f8f03..91d3fb7de4fe 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -15,337 +15,337 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.095,0.026,0.026,0.00038,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.36 1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.095,0.028,0.028,0.00043,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00021,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.38 1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.2e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.095,0.027,0.027,0.00033,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.41 -1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.2e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.095,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 -1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-3.4e-07,0,0,-0.0019,0,0,0,0,0,0,0,0,0.095,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 +1590000,1,-0.012,-0.014,0.0004,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.2e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.095,0.03,0.03,0.00037,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.00014,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.43 +1690000,1,-0.012,-0.014,0.00045,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-3.4e-07,0,0,-0.0019,0,0,0,0,0,0,0,0,0.095,0.026,0.026,0.0003,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.46 1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-2.9e-07,0,0,-0.0029,0,0,0,0,0,0,0,0,0.095,0.028,0.028,0.00033,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.48 -1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-2.6e-07,0,0,-0.0033,0,0,0,0,0,0,0,0,0.095,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 -1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0054,-0.074,-0.0011,-0.0013,-3.6e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.095,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 +1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-2.7e-07,0,0,-0.0033,0,0,0,0,0,0,0,0,0.095,0.031,0.031,0.00037,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.0001,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.51 +1990000,1,-0.011,-0.014,0.00041,0.035,-0.018,-0.14,0.0082,-0.0054,-0.074,-0.0011,-0.0013,-3.6e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.095,0.025,0.025,0.00029,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.53 2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3.5e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.095,0.027,0.027,0.00032,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,7.6e-05,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.56 2190000,1,-0.011,-0.014,0.00039,0.033,-0.014,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-8.7e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.095,0.02,0.02,0.00027,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.58 -2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-8.5e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.095,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 +2290000,1,-0.011,-0.014,0.00039,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-8.5e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.095,0.022,0.022,0.00029,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,5.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.61 2390000,1,-0.011,-0.013,0.0004,0.029,-0.01,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.4e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.095,0.017,0.017,0.00024,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.63 -2490000,1,-0.011,-0.014,0.00047,0.033,-0.0091,-0.14,0.011,-0.0043,-0.079,-0.0017,-0.0023,-1.4e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.095,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 -2590000,1,-0.01,-0.013,0.00039,0.023,-0.0062,-0.15,0.0066,-0.0024,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.095,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 -2690000,1,-0.01,-0.013,0.00043,0.027,-0.0055,-0.15,0.0091,-0.003,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.095,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 -2790000,1,-0.01,-0.013,0.00037,0.022,-0.0032,-0.14,0.0059,-0.0017,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 -2890000,1,-0.01,-0.013,0.0003,0.026,-0.005,-0.14,0.0082,-0.0021,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.095,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 -2990000,1,-0.01,-0.013,0.00031,0.02,-0.0039,-0.15,0.0054,-0.0013,-0.086,-0.002,-0.0033,-3e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.095,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 -3090000,1,-0.01,-0.013,0.00052,0.025,-0.0068,-0.15,0.0077,-0.0019,-0.087,-0.002,-0.0033,-3e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 -3190000,1,-0.01,-0.013,0.00056,0.02,-0.0065,-0.15,0.0051,-0.0014,-0.097,-0.0021,-0.0036,-3.5e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.095,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 -3290000,1,-0.01,-0.013,0.00058,0.023,-0.0067,-0.15,0.0073,-0.0021,-0.11,-0.0021,-0.0036,-3.4e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.095,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 -3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0036,-0.15,0.0049,-0.0014,-0.1,-0.0021,-0.0038,-3.8e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.095,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 -3490000,1,-0.0097,-0.013,0.00058,0.025,-0.0023,-0.15,0.0072,-0.0017,-0.1,-0.0021,-0.0038,-3.8e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.095,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 -3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0018,-0.15,0.0051,-0.001,-0.11,-0.0022,-0.004,-4.2e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.095,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 -3690000,1,-0.0095,-0.013,0.00052,0.024,-0.0011,-0.15,0.0074,-0.0012,-0.11,-0.0022,-0.004,-4.2e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.095,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 -3790000,1,-0.0094,-0.012,0.00055,0.019,0.0033,-0.15,0.0051,-0.00056,-0.11,-0.0022,-0.0043,-4.7e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.095,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 -3890000,1,-0.0094,-0.013,0.00063,0.021,0.0045,-0.14,0.0072,-0.00017,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.095,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -3990000,1,-0.0094,-0.013,0.00069,0.026,0.0042,-0.14,0.0096,0.00021,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.095,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 -4090000,1,-0.0093,-0.012,0.00076,0.022,0.0037,-0.12,0.0071,0.00045,-0.098,-0.0022,-0.0044,-5.1e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.095,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4190000,1,-0.0094,-0.012,0.00072,0.024,0.0034,-0.12,0.0094,0.0008,-0.1,-0.0022,-0.0044,-5.1e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.095,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4290000,1,-0.0095,-0.012,0.00074,0.021,0.0033,-0.12,0.0068,0.00068,-0.11,-0.0022,-0.0046,-5.6e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.095,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4390000,1,-0.0094,-0.012,0.00069,0.025,0.0018,-0.11,0.0091,0.00086,-0.094,-0.0022,-0.0046,-5.6e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.095,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 -4490000,1,-0.0094,-0.012,0.00076,0.021,0.0036,-0.11,0.0067,0.00072,-0.095,-0.0022,-0.0048,-6.1e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.095,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4590000,1,-0.0094,-0.012,0.00082,0.023,0.0024,-0.11,0.0089,0.001,-0.098,-0.0022,-0.0048,-6.1e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.095,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4690000,1,-0.0094,-0.012,0.00076,0.017,0.0027,-0.1,0.0064,0.00074,-0.09,-0.0021,-0.005,-6.5e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.095,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4790000,1,-0.0093,-0.012,0.00086,0.015,0.0048,-0.099,0.008,0.0012,-0.092,-0.0021,-0.005,-6.5e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.095,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 -4890000,1,-0.0093,-0.012,0.0009,0.01,0.0024,-0.093,0.0053,0.0009,-0.088,-0.0021,-0.0051,-6.9e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.095,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -4990000,1,-0.0092,-0.012,0.00088,0.013,0.0031,-0.085,0.0065,0.0012,-0.083,-0.0021,-0.0051,-6.9e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 -5090000,1,-0.0091,-0.011,0.00096,0.01,0.0034,-0.082,0.0045,0.00087,-0.082,-0.0021,-0.0052,-7.2e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +2490000,1,-0.011,-0.014,0.00048,0.033,-0.0091,-0.14,0.011,-0.0043,-0.079,-0.0017,-0.0023,-1.4e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.095,0.018,0.018,0.00026,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,4.5e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.66 +2590000,1,-0.01,-0.013,0.0004,0.023,-0.0062,-0.15,0.0066,-0.0024,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.095,0.014,0.014,0.00022,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.68 +2690000,1,-0.01,-0.013,0.00044,0.027,-0.0055,-0.15,0.0091,-0.003,-0.084,-0.0018,-0.0027,-2e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.095,0.015,0.015,0.00024,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,3.6e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.71 +2790000,1,-0.01,-0.013,0.00038,0.022,-0.0032,-0.14,0.0059,-0.0017,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.73 +2890000,1,-0.01,-0.013,0.00031,0.026,-0.005,-0.14,0.0082,-0.0021,-0.081,-0.0019,-0.003,-2.5e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.095,0.013,0.013,0.00022,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,2.9e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.76 +2990000,1,-0.01,-0.013,0.00033,0.02,-0.0039,-0.15,0.0054,-0.0013,-0.086,-0.002,-0.0033,-3e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.095,0.0099,0.0099,0.00019,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,2.4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.78 +3090000,1,-0.01,-0.013,0.00053,0.025,-0.0068,-0.15,0.0077,-0.0019,-0.087,-0.002,-0.0033,-3e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.095,0.011,0.011,0.00021,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,2.4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.81 +3190000,1,-0.01,-0.013,0.00058,0.02,-0.0065,-0.15,0.0051,-0.0014,-0.097,-0.0021,-0.0036,-3.5e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.095,0.0088,0.0088,0.00018,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,2e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +3290000,1,-0.01,-0.013,0.0006,0.023,-0.0067,-0.15,0.0073,-0.0021,-0.11,-0.0021,-0.0036,-3.4e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.095,0.0096,0.0096,0.00019,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,2e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.86 +3390000,1,-0.0098,-0.013,0.00061,0.019,-0.0036,-0.15,0.0049,-0.0014,-0.1,-0.0021,-0.0038,-3.8e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.095,0.0078,0.0078,0.00017,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,1.7e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.88 +3490000,1,-0.0097,-0.013,0.0006,0.025,-0.0023,-0.15,0.0072,-0.0017,-0.1,-0.0021,-0.0038,-3.8e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.095,0.0086,0.0086,0.00018,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,1.7e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.91 +3590000,1,-0.0095,-0.012,0.00056,0.021,-0.0018,-0.15,0.0051,-0.001,-0.11,-0.0022,-0.004,-4.2e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.095,0.0071,0.0071,0.00016,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,1.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.93 +3690000,1,-0.0095,-0.013,0.00054,0.024,-0.0011,-0.15,0.0074,-0.0012,-0.11,-0.0022,-0.004,-4.2e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.095,0.0077,0.0077,0.00017,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,1.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.96 +3790000,1,-0.0094,-0.012,0.00057,0.019,0.0033,-0.15,0.0051,-0.00056,-0.11,-0.0022,-0.0043,-4.7e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.095,0.0064,0.0064,0.00015,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,0.98 +3890000,1,-0.0094,-0.013,0.00065,0.021,0.0046,-0.14,0.0072,-0.00017,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.095,0.0069,0.0069,0.00016,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,1.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +3990000,1,-0.0094,-0.013,0.00072,0.026,0.0042,-0.14,0.0096,0.00021,-0.11,-0.0022,-0.0042,-4.7e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.095,0.0075,0.0075,0.00017,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,1.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1 +4090000,1,-0.0093,-0.012,0.00078,0.022,0.0037,-0.12,0.0071,0.00045,-0.098,-0.0022,-0.0044,-5.1e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.095,0.0062,0.0062,0.00015,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4190000,1,-0.0094,-0.012,0.00075,0.024,0.0034,-0.12,0.0094,0.0008,-0.1,-0.0022,-0.0044,-5.1e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.095,0.0068,0.0068,0.00016,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4290000,1,-0.0095,-0.012,0.00076,0.021,0.0033,-0.12,0.0068,0.00069,-0.11,-0.0022,-0.0046,-5.6e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.095,0.0056,0.0056,0.00014,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,9.1e-06,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4390000,1,-0.0094,-0.012,0.00072,0.025,0.0018,-0.11,0.0091,0.00086,-0.094,-0.0022,-0.0046,-5.6e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.095,0.006,0.006,0.00015,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,9.1e-06,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.1 +4490000,1,-0.0094,-0.012,0.00078,0.021,0.0036,-0.11,0.0067,0.00072,-0.095,-0.0022,-0.0048,-6.1e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.095,0.005,0.005,0.00014,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,7.9e-06,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4590000,1,-0.0094,-0.012,0.00085,0.023,0.0024,-0.11,0.0089,0.001,-0.098,-0.0022,-0.0048,-6.1e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.095,0.0054,0.0054,0.00014,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,7.9e-06,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4690000,1,-0.0094,-0.012,0.00079,0.017,0.0027,-0.1,0.0064,0.00075,-0.09,-0.0021,-0.005,-6.5e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.095,0.0044,0.0044,0.00013,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,6.9e-06,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4790000,1,-0.0093,-0.012,0.00089,0.015,0.0048,-0.099,0.008,0.0012,-0.092,-0.0021,-0.005,-6.5e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.095,0.0047,0.0047,0.00014,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,6.9e-06,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.2 +4890000,1,-0.0093,-0.012,0.00093,0.01,0.0024,-0.093,0.0053,0.0009,-0.088,-0.0021,-0.0051,-6.9e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.095,0.0039,0.0039,0.00012,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +4990000,1,-0.0092,-0.012,0.00091,0.013,0.0031,-0.085,0.0065,0.0012,-0.083,-0.0021,-0.0051,-6.9e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0042,0.0042,0.00013,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,6.1e-06,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 +5090000,1,-0.0091,-0.011,0.00099,0.01,0.0034,-0.082,0.0045,0.00088,-0.082,-0.0021,-0.0052,-7.2e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.095,0.0034,0.0034,0.00012,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,5.4e-06,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 5190000,1,-0.0089,-0.012,0.001,0.0099,0.007,-0.08,0.0055,0.0014,-0.079,-0.0021,-0.0052,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0037,0.0037,0.00012,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,5.4e-06,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.3 5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0071,-0.068,0.0038,0.0013,-0.072,-0.0021,-0.0053,-7.4e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.003,0.003,0.00011,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,4.8e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0021,-0.067,-0.0021,-0.0053,-7.4e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0032,0.0032,0.00012,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,4.8e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.002,-0.065,-0.002,-0.0054,-7.7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.095,0.0027,0.0027,0.00011,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,4.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5590000,1,-0.0089,-0.012,0.00099,0.0083,0.016,-0.053,0.004,0.0033,-0.058,-0.002,-0.0054,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 -5690000,1,-0.0089,-0.011,0.00089,0.0077,0.016,-0.052,0.0028,0.0029,-0.055,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5790000,1,-0.0088,-0.011,0.00085,0.0089,0.018,-0.049,0.0036,0.0046,-0.053,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5890000,1,-0.0088,-0.011,0.00088,0.0095,0.015,-0.048,0.0027,0.0037,-0.056,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -5990000,1,-0.0088,-0.012,0.00085,0.011,0.017,-0.041,0.0038,0.0053,-0.05,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 -6090000,1,-0.0088,-0.011,0.00067,0.011,0.018,-0.039,0.0049,0.0071,-0.047,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6190000,1,-0.0089,-0.011,0.00067,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6290000,1,-0.0089,-0.011,0.0007,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6390000,1,-0.0089,-0.011,0.00071,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0018,-0.0056,-8.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 -6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0018,-0.0056,-8.7e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6590000,1,-0.0089,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6690000,1,-0.0088,-0.011,0.0005,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6790000,1,-0.0089,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.006,-0.058,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6890000,1,-0.0087,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0075,-0.055,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -6990000,-0.29,0.024,-0.0061,0.96,-0.2,-0.032,-0.037,-0.11,-0.019,-0.055,-0.00077,-0.0097,-0.0002,0,0,-0.13,-0.091,-0.021,0.51,0.069,-0.028,-0.058,0,0,0.095,0.0011,0.0012,0.076,0.16,0.16,0.031,0.1,0.1,0.066,6.3e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0014,0.00049,0.0014,0.0014,0.0012,0.0014,1,1,1.8 -7090000,-0.29,0.025,-0.0062,0.96,-0.24,-0.048,-0.038,-0.15,-0.027,-0.056,-0.00064,-0.01,-0.00021,0,0,-0.13,-0.099,-0.023,0.51,0.075,-0.029,-0.065,0,0,0.095,0.0011,0.0011,0.063,0.19,0.18,0.03,0.13,0.13,0.066,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00095,0.0013,1,1,1.8 -7190000,-0.29,0.025,-0.0062,0.96,-0.26,-0.057,-0.037,-0.17,-0.034,-0.059,-0.0006,-0.01,-0.00021,-0.00035,-7.7e-05,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.0011,0.0011,0.06,0.21,0.21,0.029,0.16,0.15,0.065,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.0009,0.0013,1,1,1.8 -7290000,-0.29,0.025,-0.0063,0.96,-0.28,-0.066,-0.034,-0.2,-0.04,-0.055,-0.00059,-0.01,-0.00021,-0.00088,-0.00019,-0.13,-0.1,-0.023,0.51,0.077,-0.03,-0.067,0,0,0.095,0.001,0.0011,0.058,0.25,0.24,0.028,0.19,0.19,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00087,0.0013,1,1,1.9 -7390000,-0.29,0.024,-0.0062,0.96,-0.3,-0.072,-0.032,-0.23,-0.047,-0.052,-0.00058,-0.01,-0.00021,-0.0011,-0.00023,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.001,0.001,0.057,0.28,0.28,0.027,0.23,0.23,0.064,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00014,0.0013,0.0013,0.00086,0.0013,1,1,1.9 -7490000,-0.29,0.024,-0.0063,0.96,-0.32,-0.08,-0.026,-0.25,-0.056,-0.046,-0.00057,-0.0099,-0.00021,-0.0015,-0.00027,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.00097,0.001,0.056,0.32,0.31,0.026,0.28,0.28,0.063,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1,1.9 -7590000,-0.29,0.024,-0.0064,0.96,-0.34,-0.088,-0.022,-0.28,-0.065,-0.041,-0.00055,-0.0098,-0.00021,-0.0016,-0.00024,-0.13,-0.1,-0.024,0.5,0.078,-0.03,-0.068,0,0,0.095,0.00094,0.00097,0.056,0.36,0.36,0.025,0.34,0.34,0.062,6.2e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00012,0.0013,0.0013,0.00085,0.0013,1,1,1.9 -7690000,-0.29,0.024,-0.0064,0.96,-0.35,-0.096,-0.022,-0.31,-0.076,-0.036,-0.00053,-0.0097,-0.00021,-0.0017,-0.00022,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00091,0.00094,0.055,0.4,0.4,0.025,0.41,0.4,0.062,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1,2 -7790000,-0.29,0.023,-0.0062,0.96,-0.36,-0.11,-0.024,-0.34,-0.09,-0.041,-0.00046,-0.0096,-0.0002,-0.0017,-0.00025,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00088,0.00091,0.055,0.45,0.45,0.024,0.48,0.48,0.061,6.1e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00011,0.0013,0.0013,0.00084,0.0013,1,1,2 -7890000,-0.29,0.023,-0.0063,0.96,-0.37,-0.11,-0.025,-0.37,-0.1,-0.045,-0.00044,-0.0095,-0.0002,-0.0016,-0.00025,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00086,0.00088,0.055,0.5,0.49,0.023,0.57,0.56,0.06,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.0001,0.0013,0.0013,0.00083,0.0013,1,1,2 -7990000,-0.29,0.023,-0.0063,0.96,-0.39,-0.12,-0.021,-0.4,-0.11,-0.041,-0.00047,-0.0094,-0.0002,-0.0016,-0.0002,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00083,0.00085,0.054,0.55,0.54,0.022,0.67,0.66,0.059,6e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,9.8e-05,0.0013,0.0012,0.00083,0.0013,1,1,2 -8090000,-0.29,0.023,-0.0062,0.96,-0.4,-0.13,-0.022,-0.43,-0.13,-0.044,-0.0004,-0.0094,-0.0002,-0.0016,-0.00025,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.0008,0.00083,0.054,0.6,0.6,0.022,0.79,0.77,0.059,5.9e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,9.6e-05,0.0013,0.0012,0.00083,0.0013,1,1,2.1 -8190000,-0.29,0.022,-0.0062,0.96,-0.41,-0.14,-0.017,-0.46,-0.15,-0.038,-0.00033,-0.0092,-0.0002,-0.0016,-0.00026,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00078,0.0008,0.054,0.66,0.65,0.021,0.91,0.9,0.058,5.8e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.4e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 -8290000,-0.29,0.022,-0.0064,0.96,-0.44,-0.15,-0.016,-0.51,-0.16,-0.038,-0.00038,-0.0093,-0.0002,-0.0017,-0.00023,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00075,0.00078,0.054,0.71,0.7,0.02,1.1,1,0.057,5.7e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0012,9.2e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 -8390000,-0.29,0.022,-0.0064,0.96,-0.45,-0.15,-0.015,-0.55,-0.17,-0.036,-0.00039,-0.0092,-0.0002,-0.0017,-0.00021,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00073,0.00075,0.054,0.77,0.76,0.02,1.2,1.2,0.057,5.6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0012,9e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.1 -8490000,-0.29,0.022,-0.0064,0.96,-0.45,-0.15,-0.016,-0.58,-0.18,-0.041,-0.00048,-0.0091,-0.00019,-0.0016,-0.00013,-0.13,-0.1,-0.024,0.5,0.079,-0.031,-0.068,0,0,0.095,0.00071,0.00073,0.053,0.82,0.81,0.019,1.4,1.4,0.056,5.5e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.9e-05,0.0013,0.0012,0.00082,0.0013,1,1,2.2 -8590000,-0.29,0.022,-0.0062,0.96,-0.45,-0.16,-0.012,-0.6,-0.2,-0.036,-0.00042,-0.0089,-0.00019,-0.0016,-0.00013,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00069,0.00071,0.053,0.88,0.87,0.019,1.6,1.5,0.055,5.3e-05,5.4e-05,2.2e-06,0.04,0.04,0.0011,0.0012,8.7e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 -8690000,-0.29,0.021,-0.0063,0.96,-0.46,-0.16,-0.014,-0.63,-0.21,-0.037,-0.00048,-0.0088,-0.00019,-0.0016,-9e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00067,0.00069,0.053,0.94,0.93,0.018,1.8,1.7,0.055,5.2e-05,5.2e-05,2.2e-06,0.04,0.04,0.001,0.0012,8.6e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 -8790000,-0.29,0.021,-0.0064,0.96,-0.48,-0.17,-0.013,-0.67,-0.23,-0.035,-0.00046,-0.0088,-0.00018,-0.0016,-8.7e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00065,0.00067,0.053,1,0.99,0.018,2,2,0.055,5e-05,5.1e-05,2.2e-06,0.04,0.04,0.00099,0.0012,8.5e-05,0.0013,0.0012,0.00081,0.0013,1,1,2.2 -8890000,-0.29,0.021,-0.0063,0.96,-0.47,-0.17,-0.0093,-0.68,-0.24,-0.029,-0.00051,-0.0085,-0.00018,-0.0016,1.9e-05,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.00063,0.00065,0.053,1.1,1,0.017,2.2,2.2,0.054,4.8e-05,4.9e-05,2.2e-06,0.04,0.04,0.00095,0.0012,8.4e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 -8990000,-0.29,0.02,-0.0061,0.96,-0.45,-0.17,-0.0088,-0.67,-0.25,-0.032,-0.00055,-0.0082,-0.00017,-0.0013,0.00012,-0.13,-0.1,-0.024,0.5,0.08,-0.032,-0.069,0,0,0.095,0.00062,0.00063,0.053,1.1,1.1,0.017,2.5,2.4,0.054,4.7e-05,4.7e-05,2.2e-06,0.04,0.04,0.00091,0.0012,8.3e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 -9090000,-0.29,0.02,-0.0063,0.96,-0.46,-0.16,-0.0099,-0.72,-0.24,-0.032,-0.00071,-0.0082,-0.00016,-0.0012,0.00029,-0.13,-0.1,-0.024,0.5,0.08,-0.031,-0.069,0,0,0.095,0.0006,0.00062,0.053,1.2,1.2,0.016,2.7,2.7,0.053,4.5e-05,4.5e-05,2.2e-06,0.04,0.04,0.00087,0.0012,8.2e-05,0.0013,0.0012,0.0008,0.0013,1,1,2.3 -9190000,-0.29,0.02,-0.0063,0.96,-0.46,-0.16,-0.0095,-0.73,-0.24,-0.033,-0.00081,-0.008,-0.00016,-0.0011,0.00042,-0.13,-0.1,-0.024,0.5,0.081,-0.031,-0.069,0,0,0.095,0.00059,0.0006,0.053,1.2,1.2,0.016,3,3,0.052,4.3e-05,4.3e-05,2.2e-06,0.04,0.04,0.00084,0.0012,8.2e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.3 -9290000,-0.29,0.02,-0.006,0.96,-0.45,-0.16,-0.0081,-0.73,-0.25,-0.03,-0.00081,-0.0078,-0.00015,-0.001,0.00048,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00058,0.00059,0.053,1.3,1.3,0.015,3.3,3.3,0.052,4.1e-05,4.1e-05,2.2e-06,0.04,0.04,0.0008,0.0012,8.1e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 -9390000,-0.29,0.02,-0.0058,0.96,-0.45,-0.18,-0.0071,-0.75,-0.29,-0.031,-0.00073,-0.0077,-0.00015,-0.00084,0.00046,-0.13,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00057,0.00058,0.053,1.4,1.4,0.015,3.7,3.6,0.052,4e-05,4e-05,2.2e-06,0.04,0.04,0.00077,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 -9490000,-0.29,0.019,-0.0059,0.96,-0.46,-0.17,-0.0055,-0.78,-0.29,-0.028,-0.0008,-0.0076,-0.00015,-0.00092,0.00055,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00056,0.00057,0.053,1.4,1.4,0.015,4,4,0.051,3.8e-05,3.8e-05,2.2e-06,0.04,0.04,0.00074,0.0012,8e-05,0.0013,0.0012,0.00079,0.0013,1,1,2.4 -9590000,-0.29,0.019,-0.0059,0.96,-0.46,-0.19,-0.0054,-0.81,-0.34,-0.029,-0.00068,-0.0075,-0.00015,-0.00085,0.00042,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00055,0.00056,0.053,1.5,1.5,0.014,4.4,4.3,0.05,3.6e-05,3.6e-05,2.2e-06,0.04,0.04,0.00072,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.4 -9690000,-0.29,0.019,-0.0058,0.96,-0.46,-0.2,-0.0026,-0.83,-0.37,-0.028,-0.00064,-0.0074,-0.00015,-0.00077,0.00041,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00056,0.053,1.6,1.6,0.014,4.8,4.8,0.05,3.5e-05,3.4e-05,2.2e-06,0.04,0.04,0.00069,0.0012,7.9e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 -9790000,-0.29,0.019,-0.0058,0.96,-0.48,-0.22,-0.0039,-0.88,-0.41,-0.029,-0.00055,-0.0074,-0.00015,-0.00075,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00054,0.00055,0.053,1.6,1.6,0.014,5.2,5.2,0.05,3.3e-05,3.3e-05,2.2e-06,0.04,0.04,0.00067,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 -9890000,-0.29,0.019,-0.0057,0.96,-0.47,-0.22,-0.0027,-0.87,-0.43,-0.03,-0.00058,-0.0072,-0.00014,-0.00051,0.00039,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.7,1.7,0.013,5.7,5.6,0.049,3.1e-05,3.1e-05,2.2e-06,0.04,0.04,0.00064,0.0012,7.8e-05,0.0013,0.0012,0.00078,0.0013,1,1,2.5 -9990000,-0.29,0.019,-0.0057,0.96,-0.48,-0.23,-0.002,-0.92,-0.47,-0.032,-0.00052,-0.0072,-0.00015,-0.00043,0.00033,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00053,0.00054,0.053,1.8,1.8,0.013,6.2,6.2,0.049,3e-05,2.9e-05,2.2e-06,0.04,0.04,0.00062,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.5 -10090000,-0.29,0.019,-0.0056,0.96,-0.49,-0.25,-0.00079,-0.95,-0.53,-0.03,-0.00041,-0.0071,-0.00015,-0.00043,0.00025,-0.14,-0.1,-0.024,0.5,0.081,-0.032,-0.069,0,0,0.095,0.00052,0.00053,0.053,1.9,1.9,0.013,6.8,6.7,0.049,2.8e-05,2.8e-05,2.2e-06,0.04,0.04,0.0006,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 -10190000,-0.29,0.019,-0.0055,0.96,-0.49,-0.27,5.1e-05,-0.97,-0.6,-0.031,-0.00028,-0.007,-0.00015,-0.00027,0.00012,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00053,0.053,2,1.9,0.013,7.3,7.3,0.048,2.7e-05,2.6e-05,2.2e-06,0.04,0.04,0.00058,0.0012,7.7e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 -10290000,-0.29,0.019,-0.0055,0.96,-0.48,-0.27,-0.0011,-0.97,-0.61,-0.03,-0.00034,-0.0069,-0.00014,-0.00015,0.00018,-0.14,-0.1,-0.024,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00052,0.00052,0.053,2,2,0.012,8,7.9,0.048,2.6e-05,2.5e-05,2.2e-06,0.04,0.04,0.00057,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 -10390000,-0.29,0.019,-0.0054,0.96,0.0032,-0.0054,-0.0025,0.00059,-0.00016,-0.029,-0.00039,-0.0067,-0.00014,9.3e-06,0.00025,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.25,0.25,0.56,0.25,0.25,0.048,2.4e-05,2.4e-05,2.2e-06,0.04,0.04,0.00055,0.0012,7.6e-05,0.0013,0.0012,0.00077,0.0013,1,1,2.6 -10490000,-0.29,0.019,-0.0053,0.96,-0.0099,-0.0093,0.0071,0.00026,-0.00086,-0.024,-0.00032,-0.0067,-0.00014,-0.00013,0.00019,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00051,0.00052,0.053,0.26,0.26,0.55,0.26,0.26,0.057,2.3e-05,2.2e-05,2.2e-06,0.04,0.04,0.00054,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 -10590000,-0.29,0.019,-0.0052,0.96,-0.02,-0.0079,0.013,-0.0011,-0.00061,-0.022,-0.00041,-0.0066,-0.00013,0.00012,0.00055,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.13,0.13,0.27,0.26,0.26,0.055,2.2e-05,2.1e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 -10690000,-0.29,0.019,-0.0051,0.96,-0.033,-0.011,0.016,-0.0038,-0.0016,-0.018,-0.00039,-0.0065,-0.00013,0.00015,0.00054,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.0005,0.00051,0.053,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,2.2e-06,0.039,0.039,0.00052,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 -10790000,-0.29,0.019,-0.005,0.96,-0.033,-0.015,0.014,0.00012,-0.0018,-0.016,-0.00042,-0.0064,-0.00013,0.002,5.9e-05,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.094,0.094,0.17,0.13,0.13,0.062,2e-05,1.9e-05,2.2e-06,0.038,0.038,0.00051,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.7 -10890000,-0.29,0.019,-0.0049,0.96,-0.043,-0.02,0.01,-0.0036,-0.0035,-0.019,-0.00054,-0.0063,-0.00012,0.0021,0.0002,-0.14,-0.11,-0.025,0.5,0.081,-0.033,-0.069,0,0,0.095,0.00048,0.00049,0.052,0.1,0.1,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,2.2e-06,0.038,0.038,0.0005,0.0012,7.6e-05,0.0013,0.0012,0.00076,0.0013,1,1,2.8 -10990000,-0.29,0.019,-0.005,0.96,-0.039,-0.022,0.016,-0.0014,-0.0019,-0.012,-0.00058,-0.0064,-0.00012,0.0058,0.00072,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.081,0.081,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 -11090000,-0.29,0.019,-0.0051,0.96,-0.05,-0.029,0.02,-0.0059,-0.0046,-0.0081,-0.00046,-0.0063,-0.00013,0.006,0.00072,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00045,0.00046,0.052,0.093,0.093,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,2.2e-06,0.036,0.036,0.00049,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 -11190000,-0.29,0.018,-0.0051,0.96,-0.041,-0.027,0.027,-0.002,-0.0028,-0.0011,-0.00047,-0.0063,-0.00013,0.013,0.0018,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00041,0.00042,0.052,0.076,0.076,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.8 -11290000,-0.29,0.018,-0.0052,0.96,-0.05,-0.029,0.026,-0.0065,-0.0056,-0.00072,-0.00048,-0.0063,-0.00013,0.013,0.0017,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00041,0.00042,0.052,0.09,0.09,0.077,0.078,0.078,0.069,1.5e-05,1.5e-05,2.2e-06,0.033,0.033,0.00048,0.0012,7.6e-05,0.0013,0.0012,0.00075,0.0013,1,1,2.9 -11390000,-0.29,0.018,-0.0051,0.96,-0.043,-0.025,0.017,-0.0037,-0.0035,-0.0091,-0.00053,-0.0063,-0.00013,0.019,0.0032,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00037,0.00037,0.052,0.075,0.075,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 -11490000,-0.29,0.018,-0.005,0.96,-0.05,-0.027,0.021,-0.0082,-0.0063,-0.003,-0.00054,-0.0063,-0.00012,0.019,0.0034,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00037,0.00037,0.052,0.089,0.089,0.057,0.068,0.068,0.067,1.4e-05,1.3e-05,2.2e-06,0.029,0.029,0.00047,0.0012,7.6e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 -11590000,-0.29,0.018,-0.0051,0.96,-0.044,-0.023,0.019,-0.005,-0.004,-0.004,-0.00058,-0.0063,-0.00012,0.025,0.0047,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00032,0.00032,0.052,0.074,0.074,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1,2.9 -11690000,-0.29,0.017,-0.0051,0.96,-0.05,-0.027,0.019,-0.0096,-0.0065,-0.0053,-0.00062,-0.0063,-0.00012,0.025,0.0047,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00032,0.00032,0.052,0.087,0.087,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,2.2e-06,0.025,0.025,0.00047,0.0012,7.5e-05,0.0013,0.0012,0.00074,0.0013,1,1,3 -11790000,-0.29,0.017,-0.005,0.96,-0.04,-0.026,0.02,-0.0055,-0.0056,-0.0023,-0.00072,-0.0063,-0.00012,0.03,0.0053,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00027,0.00027,0.052,0.073,0.073,0.037,0.053,0.053,0.063,1.2e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 -11890000,-0.29,0.017,-0.0052,0.96,-0.048,-0.029,0.018,-0.01,-0.0083,-0.0016,-0.0007,-0.0063,-0.00012,0.03,0.0052,-0.14,-0.11,-0.025,0.5,0.082,-0.033,-0.069,0,0,0.095,0.00027,0.00027,0.052,0.085,0.085,0.034,0.06,0.06,0.063,1.1e-05,1.1e-05,2.2e-06,0.021,0.021,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 -11990000,-0.29,0.017,-0.0052,0.96,-0.039,-0.022,0.015,-0.0063,-0.0055,-0.0052,-0.00073,-0.0063,-0.00012,0.037,0.0074,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00023,0.00023,0.052,0.074,0.074,0.03,0.062,0.062,0.061,1.1e-05,1e-05,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3 -12090000,-0.29,0.017,-0.0051,0.96,-0.045,-0.024,0.018,-0.011,-0.008,0.00088,-0.00071,-0.0062,-0.00012,0.037,0.0077,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00023,0.00023,0.052,0.085,0.085,0.027,0.07,0.07,0.06,1e-05,9.7e-06,2.2e-06,0.018,0.018,0.00046,0.0012,7.5e-05,0.0013,0.0012,0.00073,0.0013,1,1,3.1 -12190000,-0.29,0.017,-0.0051,0.96,-0.038,-0.014,0.017,-0.0054,-0.0031,0.0028,-0.00067,-0.0062,-0.00012,0.043,0.0095,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.0002,0.0002,0.052,0.068,0.068,0.024,0.057,0.057,0.058,9.7e-06,9.2e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 -12290000,-0.29,0.017,-0.0052,0.96,-0.04,-0.013,0.016,-0.0093,-0.0044,0.0038,-0.00064,-0.0062,-0.00012,0.043,0.0095,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.0002,0.0002,0.052,0.079,0.079,0.022,0.065,0.065,0.058,9.3e-06,8.8e-06,2.2e-06,0.015,0.015,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 -12390000,-0.29,0.016,-0.0052,0.96,-0.033,-0.0095,0.014,-0.0051,-0.0028,-0.0022,-0.00063,-0.0062,-0.00012,0.047,0.0098,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.069,0,0,0.095,0.00017,0.00017,0.051,0.064,0.064,0.02,0.054,0.054,0.056,8.9e-06,8.4e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.1 -12490000,-0.29,0.016,-0.0052,0.96,-0.036,-0.011,0.018,-0.0086,-0.0039,-0.00015,-0.00062,-0.0061,-0.00012,0.047,0.0099,-0.14,-0.11,-0.025,0.5,0.083,-0.033,-0.07,0,0,0.095,0.00017,0.00017,0.051,0.073,0.073,0.018,0.061,0.061,0.055,8.5e-06,8e-06,2.2e-06,0.013,0.013,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 -12590000,-0.29,0.016,-0.0051,0.96,-0.03,-0.0091,0.019,-0.0035,-0.0041,0.0017,-0.00062,-0.0061,-0.00012,0.05,0.0089,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00015,0.00015,0.051,0.06,0.06,0.017,0.051,0.051,0.054,8.1e-06,7.7e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 -12690000,-0.29,0.016,-0.0051,0.96,-0.033,-0.0073,0.019,-0.0066,-0.0049,0.0032,-0.00061,-0.0061,-0.00012,0.05,0.009,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00015,0.00015,0.051,0.068,0.068,0.015,0.059,0.059,0.053,7.8e-06,7.3e-06,2.2e-06,0.011,0.011,0.00045,0.0012,7.5e-05,0.0012,0.0012,0.00072,0.0013,1,1,3.2 -12790000,-0.29,0.016,-0.0049,0.96,-0.023,-0.013,0.02,-0.0015,-0.0079,0.0054,-0.00068,-0.0061,-0.00012,0.053,0.008,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00013,0.00013,0.051,0.06,0.06,0.014,0.061,0.061,0.051,7.4e-06,7e-06,2.2e-06,0.0093,0.0096,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.2 -12890000,-0.29,0.016,-0.0049,0.96,-0.025,-0.013,0.021,-0.0039,-0.0093,0.0084,-0.00071,-0.006,-0.00012,0.053,0.0085,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00013,0.00013,0.051,0.068,0.068,0.013,0.07,0.07,0.051,7.2e-06,6.7e-06,2.2e-06,0.0093,0.0095,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 -12990000,-0.29,0.016,-0.0049,0.96,-0.021,-0.011,0.022,-0.0011,-0.0065,0.0096,-0.00076,-0.0061,-0.00012,0.054,0.0091,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00012,0.00012,0.051,0.054,0.054,0.012,0.056,0.056,0.05,6.9e-06,6.4e-06,2.2e-06,0.008,0.0083,0.00044,0.0012,7.5e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 -13090000,-0.29,0.016,-0.0049,0.96,-0.023,-0.012,0.019,-0.0032,-0.0078,0.0084,-0.0008,-0.006,-0.00011,0.054,0.0097,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00012,0.00012,0.051,0.061,0.061,0.011,0.064,0.064,0.049,6.6e-06,6.2e-06,2.2e-06,0.008,0.0082,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 -13190000,-0.29,0.016,-0.0048,0.96,-0.019,-0.012,0.018,-0.0017,-0.0088,0.009,-0.00083,-0.006,-0.00011,0.055,0.0096,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00011,0.00011,0.051,0.054,0.054,0.011,0.066,0.066,0.047,6.3e-06,5.9e-06,2.2e-06,0.0072,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0013,1,1,3.3 -13290000,-0.29,0.016,-0.0048,0.96,-0.02,-0.012,0.016,-0.0037,-0.01,0.0083,-0.00081,-0.006,-0.00011,0.056,0.0099,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.00011,0.00011,0.051,0.06,0.06,0.01,0.075,0.075,0.047,6.1e-06,5.7e-06,2.2e-06,0.0071,0.0074,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 -13390000,-0.29,0.016,-0.0048,0.96,-0.017,-0.0089,0.015,-0.0013,-0.0069,0.0089,-0.00079,-0.006,-0.00011,0.057,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,0.0001,9.9e-05,0.051,0.048,0.048,0.0094,0.06,0.06,0.046,5.8e-06,5.4e-06,2.2e-06,0.0063,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 -13490000,-0.29,0.016,-0.0048,0.96,-0.019,-0.011,0.015,-0.0032,-0.0081,0.0051,-0.0008,-0.006,-0.00011,0.057,0.01,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,0.0001,0.0001,0.051,0.053,0.053,0.009,0.067,0.067,0.045,5.6e-06,5.2e-06,2.2e-06,0.0063,0.0065,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 -13590000,-0.29,0.016,-0.0048,0.96,-0.014,-0.0079,0.016,0.0017,-0.0057,0.0036,-0.00078,-0.006,-0.00011,0.059,0.01,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,9.3e-05,9.2e-05,0.051,0.044,0.044,0.0085,0.055,0.055,0.044,5.4e-06,5e-06,2.2e-06,0.0056,0.0059,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.00071,0.0012,1,1,3.4 -13690000,-0.29,0.016,-0.0047,0.96,-0.015,-0.0071,0.016,0.00029,-0.0065,0.0062,-0.0008,-0.0059,-0.00011,0.059,0.011,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,9.4e-05,9.3e-05,0.051,0.049,0.049,0.0082,0.063,0.063,0.044,5.2e-06,4.8e-06,2.2e-06,0.0056,0.0058,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 -13790000,-0.29,0.015,-0.0047,0.96,-0.011,-0.0051,0.016,0.0054,-0.0035,0.0057,-0.00079,-0.006,-0.00011,0.061,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.7e-05,8.7e-05,0.051,0.041,0.041,0.0078,0.052,0.052,0.042,5e-06,4.6e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 -13890000,-0.29,0.015,-0.0046,0.96,-0.012,-0.0062,0.017,0.0044,-0.0041,0.0078,-0.00083,-0.006,-0.00011,0.06,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.8e-05,8.8e-05,0.051,0.045,0.045,0.0076,0.059,0.059,0.042,4.8e-06,4.5e-06,2.2e-06,0.0051,0.0053,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 -13990000,-0.29,0.015,-0.0046,0.96,-0.014,-0.01,0.016,0.0039,-0.0046,0.0067,-0.00086,-0.006,-0.00011,0.061,0.011,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,8.3e-05,8.3e-05,0.051,0.038,0.038,0.0073,0.05,0.05,0.041,4.7e-06,4.3e-06,2.2e-06,0.0047,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.5 -14090000,-0.29,0.015,-0.0047,0.96,-0.013,-0.0041,0.017,0.0023,-0.0051,0.0031,-0.00078,-0.006,-0.00011,0.061,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8.4e-05,8.3e-05,0.051,0.042,0.042,0.0072,0.057,0.057,0.041,4.5e-06,4.2e-06,2.2e-06,0.0046,0.0049,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 -14190000,-0.29,0.015,-0.0048,0.96,-0.01,-0.0029,0.017,0.0036,-0.004,0.0033,-0.00074,-0.006,-0.00012,0.063,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8e-05,7.9e-05,0.051,0.036,0.036,0.007,0.049,0.049,0.04,4.3e-06,4e-06,2.2e-06,0.0043,0.0046,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 -14290000,-0.29,0.015,-0.0047,0.96,-0.013,-0.0032,0.015,0.0025,-0.0043,0.0075,-0.00074,-0.0059,-0.00011,0.063,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,8.1e-05,8e-05,0.051,0.039,0.039,0.0069,0.055,0.055,0.039,4.2e-06,3.9e-06,2.2e-06,0.0043,0.0045,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 -14390000,-0.29,0.015,-0.0047,0.96,-0.012,-0.0028,0.017,0.0036,-0.0048,0.012,-0.00075,-0.0059,-0.00011,0.063,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.7e-05,7.6e-05,0.051,0.034,0.034,0.0067,0.047,0.047,0.039,4e-06,3.7e-06,2.2e-06,0.004,0.0043,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.6 -14490000,-0.29,0.015,-0.0049,0.96,-0.012,-0.0021,0.02,0.0023,-0.0049,0.014,-0.00071,-0.0059,-0.00012,0.064,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.8e-05,7.7e-05,0.051,0.037,0.037,0.0066,0.054,0.054,0.038,3.9e-06,3.6e-06,2.2e-06,0.004,0.0042,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 -14590000,-0.29,0.015,-0.0049,0.96,-0.015,-0.0038,0.018,0.0007,-0.0053,0.01,-0.0007,-0.0059,-0.00012,0.064,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.5e-05,7.4e-05,0.051,0.032,0.032,0.0065,0.047,0.047,0.038,3.8e-06,3.5e-06,2.2e-06,0.0038,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 -14690000,-0.29,0.015,-0.0049,0.96,-0.016,-0.0041,0.018,-0.00088,-0.0058,0.01,-0.0007,-0.0059,-0.00011,0.064,0.01,-0.14,-0.11,-0.025,0.5,0.083,-0.034,-0.07,0,0,0.095,7.6e-05,7.4e-05,0.051,0.035,0.035,0.0065,0.052,0.052,0.037,3.7e-06,3.4e-06,2.2e-06,0.0037,0.004,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 -14790000,-0.29,0.015,-0.005,0.96,-0.019,-0.0015,0.018,-0.00058,-0.0013,0.013,-0.00073,-0.0058,-0.00011,0.065,0.012,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.3e-05,7.1e-05,0.051,0.03,0.03,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,2.2e-06,0.0036,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.7 -14890000,-0.29,0.015,-0.0049,0.96,-0.02,0.00041,0.022,-0.0027,-0.0017,0.014,-0.00074,-0.0058,-0.00011,0.065,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.4e-05,7.2e-05,0.051,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,2.2e-06,0.0035,0.0038,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 -14990000,-0.29,0.015,-0.0049,0.96,-0.02,-0.0016,0.025,-0.0022,-0.0029,0.016,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.1e-05,7e-05,0.051,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,2.2e-06,0.0034,0.0036,0.00044,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 -15090000,-0.29,0.015,-0.0048,0.96,-0.021,-0.0027,0.029,-0.0043,-0.0031,0.018,-0.00075,-0.0057,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7.2e-05,7e-05,0.051,0.031,0.031,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,2.2e-06,0.0033,0.0036,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 -15190000,-0.29,0.016,-0.005,0.96,-0.021,-0.00079,0.029,-0.0034,-0.0024,0.02,-0.00073,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.8e-05,0.051,0.027,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.0007,0.0012,1,1,3.8 -15290000,-0.29,0.016,-0.005,0.96,-0.024,-0.00091,0.029,-0.0058,-0.0029,0.017,-0.00075,-0.0057,-0.00011,0.067,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,7e-05,6.9e-05,0.051,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,2.2e-06,0.0032,0.0035,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 -15390000,-0.29,0.016,-0.0051,0.96,-0.023,-0.0028,0.028,-0.0046,-0.0024,0.017,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.7e-05,0.051,0.026,0.026,0.0064,0.044,0.044,0.034,2.9e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 -15490000,-0.29,0.016,-0.0051,0.96,-0.025,-0.00034,0.028,-0.007,-0.0026,0.018,-0.00075,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.9e-05,6.7e-05,0.051,0.028,0.028,0.0065,0.05,0.05,0.034,2.8e-06,2.6e-06,2.2e-06,0.0031,0.0033,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 -15590000,-0.29,0.016,-0.0051,0.96,-0.022,-0.0047,0.028,-0.0032,-0.0058,0.017,-0.00079,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.6e-05,0.051,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,2.2e-06,0.003,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,3.9 -15690000,-0.29,0.016,-0.005,0.96,-0.024,-0.0026,0.028,-0.0048,-0.0062,0.018,-0.00083,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.8e-05,6.6e-05,0.051,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,2.2e-06,0.0029,0.0032,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 -15790000,-0.29,0.015,-0.005,0.96,-0.021,-0.0013,0.028,-0.0035,-0.0053,0.019,-0.00087,-0.0058,-0.00011,0.066,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.024,0.0066,0.043,0.043,0.033,2.6e-06,2.3e-06,2.2e-06,0.0029,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 -15890000,-0.29,0.016,-0.0051,0.96,-0.021,-0.0026,0.029,-0.0059,-0.0053,0.019,-0.00084,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.7e-05,6.5e-05,0.051,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,2.2e-06,0.0028,0.0031,0.00043,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 -15990000,-0.29,0.016,-0.005,0.96,-0.02,-0.0021,0.026,-0.0049,-0.0045,0.018,-0.00083,-0.0057,-0.00011,0.067,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,2.2e-06,0.0028,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4 -16090000,-0.29,0.016,-0.005,0.96,-0.022,-0.00083,0.024,-0.0072,-0.0045,0.018,-0.00082,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.4e-05,0.051,0.024,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,2.2e-06,0.0027,0.003,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 -16190000,-0.29,0.016,-0.005,0.96,-0.02,-0.00061,0.023,-0.0071,-0.0037,0.015,-0.0008,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.3e-05,0.051,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 -16290000,-0.29,0.015,-0.005,0.96,-0.022,0.00033,0.022,-0.009,-0.0038,0.017,-0.00081,-0.0057,-0.00011,0.068,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.6e-05,6.3e-05,0.051,0.023,0.024,0.007,0.048,0.048,0.033,2.2e-06,2e-06,2.2e-06,0.0027,0.0029,0.00042,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 -16390000,-0.29,0.016,-0.0049,0.96,-0.023,-0.00021,0.023,-0.007,-0.0037,0.017,-0.00083,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.2e-05,0.051,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,2e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.1 -16490000,-0.29,0.016,-0.005,0.96,-0.027,0.00075,0.025,-0.0098,-0.0036,0.021,-0.00082,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.5e-05,6.2e-05,0.051,0.022,0.023,0.0072,0.047,0.047,0.033,2.1e-06,1.9e-06,2.2e-06,0.0026,0.0029,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 -16590000,-0.29,0.016,-0.005,0.96,-0.031,0.0011,0.029,-0.0085,-0.0031,0.021,-0.00082,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.1e-05,0.051,0.02,0.02,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,2.2e-06,0.0026,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 -16690000,-0.29,0.015,-0.0051,0.96,-0.034,0.0047,0.029,-0.011,-0.0029,0.021,-0.00084,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.4e-05,6.1e-05,0.051,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,2.2e-06,0.0025,0.0028,0.00041,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 -16790000,-0.29,0.015,-0.0049,0.96,-0.035,0.0045,0.028,-0.0095,-0.0026,0.021,-0.00086,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.019,0.02,0.0073,0.042,0.042,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0028,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.2 -16890000,-0.29,0.015,-0.0049,0.96,-0.035,0.004,0.029,-0.013,-0.0026,0.02,-0.00089,-0.0057,-0.00011,0.068,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6.1e-05,0.051,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 -16990000,-0.29,0.015,-0.0049,0.96,-0.032,0.0044,0.029,-0.011,-0.0028,0.019,-0.0009,-0.0057,-0.00011,0.069,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.021,0.021,0.0074,0.049,0.049,0.033,1.8e-06,1.7e-06,2.2e-06,0.0025,0.0027,0.0004,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 -17090000,-0.29,0.015,-0.005,0.96,-0.037,0.0063,0.028,-0.015,-0.0023,0.018,-0.00089,-0.0057,-0.00011,0.069,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.022,0.022,0.0075,0.054,0.054,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 -17190000,-0.29,0.015,-0.0051,0.96,-0.036,0.0082,0.03,-0.014,-0.0039,0.021,-0.00089,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.021,0.022,0.0076,0.056,0.057,0.033,1.8e-06,1.6e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.3 -17290000,-0.29,0.015,-0.0051,0.96,-0.039,0.0089,0.029,-0.017,-0.0027,0.021,-0.00088,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.3e-05,6e-05,0.051,0.023,0.023,0.0077,0.062,0.062,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0027,0.00039,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 -17390000,-0.29,0.015,-0.005,0.96,-0.029,0.014,0.029,-0.01,-0.0014,0.021,-0.00091,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 -17490000,-0.29,0.015,-0.0051,0.96,-0.029,0.015,0.029,-0.013,0.00019,0.023,-0.0009,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.2e-05,5.9e-05,0.051,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.5e-06,2.2e-06,0.0024,0.0026,0.00038,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 -17590000,-0.29,0.015,-0.0051,0.96,-0.029,0.013,0.028,-0.012,-0.00019,0.02,-0.00091,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.4 -17690000,-0.29,0.015,-0.0052,0.96,-0.03,0.014,0.029,-0.015,0.00095,0.023,-0.00092,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.8e-05,0.051,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.4e-06,2.2e-06,0.0023,0.0026,0.00037,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 -17790000,-0.29,0.015,-0.0052,0.96,-0.031,0.014,0.029,-0.015,0.0017,0.028,-0.00093,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.07,0,0,0.095,6.1e-05,5.7e-05,0.051,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0026,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 -17890000,-0.29,0.015,-0.0051,0.96,-0.035,0.015,0.029,-0.017,0.0029,0.032,-0.00094,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6.1e-05,5.8e-05,0.051,0.02,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 -17990000,-0.29,0.015,-0.0051,0.96,-0.034,0.016,0.029,-0.014,0.0052,0.033,-0.00094,-0.0057,-0.00011,0.069,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.7e-05,0.051,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00036,0.0012,7.4e-05,0.0012,0.0012,0.00069,0.0012,1,1,4.5 -18090000,-0.29,0.015,-0.0052,0.96,-0.036,0.017,0.028,-0.018,0.0067,0.031,-0.00094,-0.0057,-0.00011,0.07,0.013,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.7e-05,0.051,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.3e-06,2.2e-06,0.0023,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 -18190000,-0.29,0.015,-0.0051,0.96,-0.032,0.014,0.028,-0.013,0.0045,0.029,-0.00098,-0.0057,-0.00011,0.07,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.9e-05,5.6e-05,0.051,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00035,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 -18290000,-0.29,0.015,-0.0051,0.96,-0.036,0.014,0.027,-0.017,0.0056,0.028,-0.00098,-0.0057,-0.00011,0.07,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,6e-05,5.6e-05,0.051,0.018,0.018,0.008,0.053,0.053,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 -18390000,-0.29,0.015,-0.005,0.96,-0.032,0.014,0.027,-0.012,0.0047,0.027,-0.00099,-0.0057,-0.00011,0.07,0.014,-0.14,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.2e-06,2.2e-06,0.0022,0.0025,0.00034,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.6 -18490000,-0.29,0.015,-0.005,0.96,-0.036,0.013,0.026,-0.015,0.0056,0.029,-0.001,-0.0057,-0.00011,0.07,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.9e-05,5.6e-05,0.051,0.017,0.017,0.008,0.051,0.051,0.034,1.3e-06,1.1e-06,2.2e-06,0.0022,0.0025,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 -18590000,-0.29,0.015,-0.0049,0.96,-0.034,0.013,0.026,-0.013,0.005,0.031,-0.001,-0.0057,-0.00011,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.015,0.016,0.0079,0.044,0.044,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00033,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 -18690000,-0.29,0.015,-0.0049,0.96,-0.034,0.012,0.025,-0.015,0.0059,0.03,-0.001,-0.0057,-0.00011,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.5e-05,0.051,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 -18790000,-0.29,0.015,-0.0049,0.96,-0.031,0.011,0.024,-0.012,0.0051,0.028,-0.001,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,2.2e-06,0.0022,0.0024,0.00032,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.7 -18890000,-0.29,0.015,-0.0048,0.96,-0.031,0.012,0.022,-0.015,0.0064,0.024,-0.001,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.008,0.047,0.047,0.034,1.2e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 -18990000,-0.29,0.015,-0.0048,0.96,-0.029,0.012,0.023,-0.013,0.0056,0.028,-0.0011,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.4e-05,0.051,0.015,0.015,0.0079,0.042,0.042,0.034,1.1e-06,1e-06,2.2e-06,0.0021,0.0024,0.00031,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 -19090000,-0.29,0.015,-0.0048,0.96,-0.028,0.013,0.024,-0.016,0.0063,0.024,-0.0011,-0.0058,-0.00012,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.8e-05,5.4e-05,0.051,0.016,0.016,0.0079,0.045,0.046,0.035,1.1e-06,9.9e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 -19190000,-0.29,0.015,-0.0048,0.96,-0.026,0.014,0.023,-0.014,0.0062,0.023,-0.0011,-0.0058,-0.00012,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.6e-07,2.2e-06,0.0021,0.0024,0.0003,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.8 -19290000,-0.29,0.015,-0.0048,0.96,-0.027,0.014,0.024,-0.017,0.0074,0.022,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0079,0.044,0.044,0.034,1.1e-06,9.5e-07,2.2e-06,0.0021,0.0024,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 -19390000,-0.29,0.015,-0.0049,0.96,-0.026,0.012,0.025,-0.015,0.0073,0.021,-0.0011,-0.0058,-0.00012,0.068,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.3e-05,0.05,0.014,0.015,0.0078,0.04,0.04,0.035,1e-06,9.2e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 -19490000,-0.29,0.015,-0.005,0.96,-0.028,0.013,0.024,-0.018,0.0088,0.021,-0.0011,-0.0058,-0.00012,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.7e-05,5.3e-05,0.05,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,9.1e-07,2.2e-06,0.0021,0.0023,0.00029,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 -19590000,-0.29,0.015,-0.0049,0.96,-0.025,0.014,0.026,-0.015,0.007,0.021,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.014,0.014,0.0077,0.039,0.039,0.035,9.9e-07,8.8e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,4.9 -19690000,-0.29,0.015,-0.0048,0.96,-0.025,0.013,0.025,-0.018,0.0078,0.021,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.015,0.015,0.0078,0.043,0.043,0.035,9.8e-07,8.7e-07,2.2e-06,0.0021,0.0023,0.00028,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 -19790000,-0.29,0.015,-0.0049,0.96,-0.022,0.013,0.023,-0.018,0.0084,0.017,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.015,0.016,0.0077,0.045,0.045,0.035,9.6e-07,8.5e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 -19890000,-0.29,0.015,-0.005,0.96,-0.023,0.013,0.023,-0.02,0.0097,0.015,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.0021,0.0023,0.00027,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 -19990000,-0.29,0.015,-0.005,0.96,-0.02,0.014,0.021,-0.016,0.009,0.012,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5 -20090000,-0.29,0.015,-0.005,0.96,-0.023,0.016,0.021,-0.018,0.01,0.016,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.095,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,7.4e-05,0.0012,0.0012,0.00068,0.0012,1,1,5.1 -20190000,-0.29,0.015,-0.005,0.96,-0.024,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 -20290000,-0.29,0.015,-0.005,0.96,-0.022,0.016,0.022,-0.021,0.012,0.016,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 -20390000,-0.29,0.015,-0.0049,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 -20490000,-0.29,0.015,-0.0049,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.12,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.3e-05,0.0012,0.0012,0.00068,0.0012,1,1,0.01 -20590000,-0.29,0.015,-0.0048,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.2e-07,2.2e-06,0.002,0.0023,0.00024,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 -20690000,-0.29,0.015,-0.0047,0.96,-0.017,0.016,0.023,-0.025,0.014,0.014,-0.0011,-0.0058,-0.00013,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.5e-05,5.1e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 -20790000,-0.29,0.015,-0.0041,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 -20890000,-0.29,0.01,0.0045,0.96,-0.0062,0.0015,-0.11,-0.021,0.01,0.0066,-0.0011,-0.0058,-0.00014,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.034,-0.069,0,0,0.11,5.3e-05,5e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,7.2e-05,0.0012,0.0011,0.00068,0.0012,1,1,0.01 -20990000,-0.29,0.0063,0.0075,0.96,0.0089,-0.015,-0.25,-0.017,0.008,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.092,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.2e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21090000,-0.29,0.0069,0.0059,0.96,0.023,-0.028,-0.37,-0.015,0.0061,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.061,5.3e-05,4.9e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21190000,-0.29,0.0088,0.0033,0.96,0.029,-0.033,-0.5,-0.013,0.0046,-0.075,-0.0011,-0.0058,-0.00014,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,0.025,5.1e-05,4.8e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21290000,-0.29,0.01,0.0013,0.96,0.027,-0.036,-0.63,-0.01,0.002,-0.13,-0.0011,-0.0058,-0.00014,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.034,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21390000,-0.29,0.011,-0.00017,0.96,0.021,-0.029,-0.75,-0.012,0.0052,-0.2,-0.0011,-0.0058,-0.00013,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.099,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7.1e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21490000,-0.29,0.012,-0.00092,0.96,0.014,-0.028,-0.89,-0.0096,0.0021,-0.28,-0.0011,-0.0058,-0.00013,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.18,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21590000,-0.29,0.012,-0.0014,0.96,0.0029,-0.022,-1,-0.014,0.0067,-0.37,-0.0011,-0.0058,-0.00012,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.27,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.002,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21690000,-0.29,0.012,-0.0018,0.96,-0.0024,-0.019,-1.1,-0.014,0.0039,-0.49,-0.0011,-0.0058,-0.00011,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.39,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21790000,-0.29,0.012,-0.0021,0.96,-0.0082,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.51,5.1e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21890000,-0.29,0.012,-0.0025,0.96,-0.014,-0.0073,-1.4,-0.016,0.0096,-0.75,-0.0011,-0.0058,-0.0001,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-0.65,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -21990000,-0.29,0.012,-0.0032,0.96,-0.02,0.00088,-1.4,-0.022,0.017,-0.89,-0.001,-0.0058,-8.7e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.79,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,7e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22090000,-0.29,0.013,-0.0038,0.96,-0.023,0.0041,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-0.93,5.1e-05,4.7e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22190000,-0.29,0.013,-0.0042,0.96,-0.03,0.011,-1.4,-0.027,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.1,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22290000,-0.29,0.014,-0.0049,0.96,-0.038,0.015,-1.4,-0.031,0.025,-1.3,-0.0011,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.2,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22390000,-0.29,0.014,-0.0052,0.96,-0.045,0.022,-1.4,-0.038,0.029,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.4,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22490000,-0.29,0.014,-0.0054,0.96,-0.052,0.028,-1.4,-0.043,0.032,-1.6,-0.001,-0.0058,-7.2e-05,0.07,0.012,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.5,5e-05,4.6e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0022,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22590000,-0.29,0.015,-0.0052,0.96,-0.057,0.034,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.8e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.6,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22690000,-0.29,0.015,-0.0051,0.96,-0.062,0.039,-1.4,-0.05,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.8,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00067,0.0012,1,1,0.01 -22790000,-0.29,0.016,-0.005,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.2e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-1.9,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -22890000,-0.29,0.016,-0.0051,0.96,-0.073,0.048,-1.4,-0.062,0.046,-2.2,-0.0011,-0.0058,-6.8e-05,0.07,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-2.1,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.9e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -22990000,-0.29,0.016,-0.0049,0.96,-0.076,0.048,-1.4,-0.065,0.045,-2.3,-0.0011,-0.0058,-7e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.069,0,0,-2.2,4.8e-05,4.4e-05,0.049,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23090000,-0.29,0.017,-0.0049,0.96,-0.082,0.052,-1.4,-0.072,0.05,-2.5,-0.0011,-0.0058,-6.9e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.4,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23190000,-0.29,0.017,-0.0048,0.96,-0.084,0.047,-1.4,-0.072,0.046,-2.6,-0.0011,-0.0058,-8.1e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.5,4.8e-05,4.4e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23290000,-0.29,0.017,-0.0053,0.96,-0.09,0.051,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.7,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23390000,-0.29,0.017,-0.0052,0.96,-0.09,0.054,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.8e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.8,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23490000,-0.29,0.017,-0.0053,0.96,-0.096,0.054,-1.4,-0.085,0.057,-3,-0.0011,-0.0058,-8.3e-05,0.069,0.013,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-2.9,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23590000,-0.29,0.017,-0.0054,0.96,-0.095,0.048,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.6e-05,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.1,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23690000,-0.29,0.018,-0.006,0.96,-0.094,0.051,-1.3,-0.09,0.051,-3.3,-0.0011,-0.0058,-9.2e-05,0.069,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.2,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23790000,-0.29,0.021,-0.0074,0.96,-0.079,0.048,-0.95,-0.08,0.047,-3.4,-0.0012,-0.0058,-9.7e-05,0.068,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.3,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23890000,-0.29,0.025,-0.01,0.96,-0.074,0.051,-0.52,-0.087,0.051,-3.5,-0.0012,-0.0058,-9.4e-05,0.068,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.068,0,0,-3.4,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -23990000,-0.29,0.028,-0.012,0.96,-0.065,0.05,-0.13,-0.074,0.046,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.8e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -24090000,-0.29,0.027,-0.012,0.96,-0.072,0.058,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0011,6.7e-05,0.0012,0.0011,0.00066,0.0012,1,1,0.01 -24190000,-0.29,0.022,-0.0092,0.96,-0.076,0.055,0.088,-0.066,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.068,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24290000,-0.29,0.019,-0.0071,0.96,-0.081,0.057,0.066,-0.074,0.044,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24390000,-0.29,0.018,-0.0063,0.96,-0.064,0.05,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24490000,-0.29,0.018,-0.0065,0.96,-0.059,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24590000,-0.29,0.018,-0.0071,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.014,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.5,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24690000,-0.29,0.018,-0.0076,0.96,-0.045,0.044,0.075,-0.046,0.036,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0019,0.0021,0.00014,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24790000,-0.29,0.017,-0.0077,0.96,-0.039,0.043,0.067,-0.034,0.028,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24890000,-0.29,0.017,-0.0076,0.96,-0.038,0.045,0.056,-0.037,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -24990000,-0.29,0.016,-0.0074,0.96,-0.025,0.046,0.049,-0.022,0.026,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25090000,-0.29,0.016,-0.0077,0.96,-0.021,0.046,0.047,-0.023,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25190000,-0.29,0.016,-0.0079,0.96,-0.011,0.042,0.047,-0.0078,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25290000,-0.3,0.015,-0.0081,0.96,-0.006,0.045,0.042,-0.0086,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.7e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25390000,-0.3,0.015,-0.0082,0.96,0.003,0.043,0.04,0.0015,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25490000,-0.3,0.015,-0.0083,0.96,0.0074,0.044,0.04,0.0012,0.024,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25590000,-0.3,0.015,-0.0085,0.96,0.012,0.04,0.041,0.0087,0.0095,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25690000,-0.3,0.014,-0.0079,0.96,0.013,0.039,0.03,0.01,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25790000,-0.3,0.014,-0.0078,0.96,0.024,0.034,0.03,0.018,0.0034,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25890000,-0.3,0.014,-0.0078,0.96,0.03,0.034,0.033,0.02,0.0076,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -25990000,-0.3,0.014,-0.0078,0.96,0.032,0.029,0.026,0.017,-0.0036,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26090000,-0.3,0.014,-0.0075,0.96,0.037,0.029,0.025,0.021,-0.0015,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26190000,-0.3,0.014,-0.0073,0.96,0.042,0.02,0.02,0.024,-0.018,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26290000,-0.3,0.015,-0.0073,0.96,0.042,0.02,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.066,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26390000,-0.3,0.015,-0.0067,0.96,0.04,0.011,0.019,0.019,-0.03,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26490000,-0.3,0.015,-0.0065,0.96,0.043,0.0088,0.028,0.024,-0.029,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26590000,-0.3,0.015,-0.0059,0.95,0.042,-0.0012,0.028,0.023,-0.042,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26690000,-0.3,0.015,-0.0058,0.95,0.044,-0.0048,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26790000,-0.3,0.014,-0.0056,0.95,0.047,-0.011,0.026,0.025,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26890000,-0.3,0.014,-0.005,0.96,0.053,-0.013,0.022,0.03,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-3.4,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.0021,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -26990000,-0.3,0.015,-0.0044,0.95,0.054,-0.02,0.021,0.023,-0.064,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.016,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -27090000,-0.3,0.015,-0.0042,0.95,0.056,-0.026,0.025,0.028,-0.066,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1,0.01 -27190000,-0.3,0.015,-0.0043,0.96,0.057,-0.03,0.027,0.019,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27290000,-0.3,0.016,-0.0043,0.96,0.064,-0.034,0.14,0.025,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27390000,-0.3,0.018,-0.0055,0.96,0.067,-0.025,0.46,0.0071,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27490000,-0.3,0.02,-0.0066,0.95,0.072,-0.028,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.015,-0.13,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.4,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27590000,-0.3,0.019,-0.0067,0.96,0.063,-0.03,0.87,0.0077,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.3,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27690000,-0.3,0.016,-0.0058,0.96,0.058,-0.028,0.78,0.014,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.2,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27790000,-0.3,0.015,-0.0046,0.96,0.054,-0.026,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.1,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27890000,-0.3,0.015,-0.0043,0.96,0.061,-0.031,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3.1,4.5e-05,4e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -27990000,-0.3,0.015,-0.0047,0.96,0.061,-0.034,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-3,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28090000,-0.3,0.015,-0.0049,0.96,0.065,-0.034,0.8,0.026,-0.027,-3,-0.0013,-0.0058,-0.00022,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.9,4.5e-05,4e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28190000,-0.3,0.015,-0.0043,0.96,0.062,-0.033,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.8,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28290000,-0.3,0.016,-0.0037,0.96,0.066,-0.036,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.8,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28390000,-0.3,0.016,-0.0037,0.96,0.068,-0.038,0.81,0.035,-0.034,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.7,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28490000,-0.3,0.017,-0.0039,0.96,0.07,-0.041,0.81,0.043,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.6,4.5e-05,4e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28590000,-0.29,0.017,-0.0039,0.96,0.063,-0.042,0.81,0.043,-0.041,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.5,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28690000,-0.29,0.016,-0.0038,0.96,0.062,-0.043,0.81,0.049,-0.045,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.083,-0.032,-0.067,0,0,-2.5,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28790000,-0.29,0.016,-0.0032,0.96,0.06,-0.042,0.81,0.05,-0.044,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.4,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28890000,-0.29,0.015,-0.003,0.96,0.064,-0.044,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.3,4.5e-05,4e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -28990000,-0.29,0.016,-0.0027,0.96,0.062,-0.042,0.81,0.058,-0.049,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.2,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29090000,-0.29,0.016,-0.0026,0.96,0.065,-0.043,0.81,0.065,-0.053,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.2,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29190000,-0.29,0.016,-0.0025,0.96,0.066,-0.043,0.8,0.067,-0.052,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2.1,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29290000,-0.29,0.016,-0.0027,0.96,0.071,-0.048,0.81,0.075,-0.056,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-2,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29390000,-0.29,0.015,-0.0033,0.96,0.067,-0.045,0.81,0.074,-0.053,-2,-0.0013,-0.0058,-0.00014,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.9,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29490000,-0.29,0.015,-0.0032,0.96,0.07,-0.046,0.81,0.081,-0.059,-2,-0.0013,-0.0058,-0.00014,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.9,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29590000,-0.29,0.015,-0.0031,0.96,0.068,-0.045,0.81,0.079,-0.057,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.8,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29690000,-0.29,0.015,-0.0032,0.96,0.072,-0.044,0.81,0.087,-0.062,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.7,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29790000,-0.29,0.015,-0.0029,0.96,0.069,-0.038,0.8,0.084,-0.059,-1.7,-0.0013,-0.0058,-9.8e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.6,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29890000,-0.29,0.015,-0.0023,0.96,0.071,-0.039,0.8,0.092,-0.063,-1.7,-0.0013,-0.0058,-9.4e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.6,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -29990000,-0.29,0.016,-0.0025,0.96,0.066,-0.038,0.8,0.087,-0.062,-1.6,-0.0013,-0.0058,-8.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.5,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30090000,-0.29,0.016,-0.0026,0.96,0.067,-0.037,0.8,0.094,-0.064,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,-1.4,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30190000,-0.29,0.016,-0.0026,0.96,0.062,-0.031,0.8,0.089,-0.056,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.4,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30290000,-0.29,0.016,-0.0026,0.96,0.062,-0.031,0.8,0.096,-0.059,-1.4,-0.0013,-0.0058,-8.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.3,4.5e-05,3.9e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30390000,-0.29,0.015,-0.0026,0.96,0.06,-0.026,0.8,0.095,-0.053,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.2,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30490000,-0.29,0.015,-0.0026,0.96,0.063,-0.025,0.8,0.1,-0.056,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.1,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30590000,-0.29,0.016,-0.0029,0.96,0.062,-0.024,0.8,0.098,-0.053,-1.2,-0.0013,-0.0058,-5e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1.1,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30690000,-0.29,0.016,-0.0032,0.96,0.059,-0.023,0.8,0.1,-0.055,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-1,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30790000,-0.29,0.016,-0.003,0.96,0.053,-0.014,0.79,0.096,-0.044,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.92,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30890000,-0.29,0.015,-0.0024,0.96,0.051,-0.01,0.79,0.1,-0.044,-0.95,-0.0013,-0.0058,-4e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.85,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -30990000,-0.29,0.015,-0.0025,0.96,0.047,-0.0086,0.79,0.095,-0.043,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.78,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31090000,-0.29,0.015,-0.0027,0.96,0.046,-0.0074,0.79,0.099,-0.043,-0.81,-0.0012,-0.0058,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.71,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31190000,-0.29,0.016,-0.0028,0.96,0.043,-0.0042,0.8,0.094,-0.039,-0.74,-0.0012,-0.0058,-2.7e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.64,4.4e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31290000,-0.29,0.016,-0.003,0.96,0.04,-0.0027,0.8,0.097,-0.041,-0.67,-0.0012,-0.0058,-2.3e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.57,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31390000,-0.29,0.015,-0.0028,0.96,0.035,0.0022,0.8,0.091,-0.037,-0.59,-0.0012,-0.0058,-2.5e-05,0.067,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.49,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31490000,-0.29,0.016,-0.0025,0.96,0.036,0.0056,0.8,0.096,-0.036,-0.52,-0.0012,-0.0058,-2.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.42,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31590000,-0.29,0.016,-0.0023,0.96,0.037,0.0074,0.8,0.093,-0.032,-0.45,-0.0012,-0.0058,-2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.35,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31690000,-0.29,0.016,-0.0023,0.96,0.041,0.0084,0.8,0.098,-0.032,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.28,4.4e-05,3.8e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31790000,-0.29,0.017,-0.0025,0.96,0.035,0.014,0.8,0.094,-0.023,-0.3,-0.0012,-0.0058,-1e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.2,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31890000,-0.29,0.017,-0.0022,0.96,0.033,0.015,0.8,0.099,-0.021,-0.24,-0.0012,-0.0058,1.4e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.14,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -31990000,-0.29,0.016,-0.0025,0.96,0.03,0.017,0.79,0.096,-0.016,-0.17,-0.0012,-0.0058,5.2e-07,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,-0.068,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -32090000,-0.29,0.016,-0.0029,0.96,0.031,0.021,0.8,0.099,-0.014,-0.096,-0.0012,-0.0058,8.8e-08,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.0038,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -32190000,-0.29,0.016,-0.0032,0.96,0.028,0.028,0.8,0.094,-0.0046,-0.028,-0.0012,-0.0058,3.2e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.072,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -32290000,-0.29,0.016,-0.003,0.96,0.027,0.03,0.79,0.098,-0.0019,0.042,-0.0012,-0.0058,7e-06,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.14,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00064,0.0012,1,1,0.01 -32390000,-0.29,0.016,-0.0032,0.96,0.024,0.032,0.79,0.094,0.0018,0.12,-0.0012,-0.0058,5.2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32490000,-0.29,0.015,-0.0063,0.96,-0.016,0.085,-0.078,0.092,0.0094,0.12,-0.0012,-0.0058,2.9e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.22,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32590000,-0.29,0.015,-0.0063,0.96,-0.014,0.084,-0.081,0.093,0.0025,0.1,-0.0012,-0.0058,-2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.2,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32690000,-0.29,0.015,-0.0063,0.96,-0.0097,0.091,-0.082,0.091,0.011,0.087,-0.0012,-0.0058,-2e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.19,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32790000,-0.29,0.015,-0.0061,0.96,-0.0057,0.09,-0.083,0.093,0.0037,0.072,-0.0012,-0.0058,-7.5e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.17,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32890000,-0.29,0.015,-0.0061,0.96,-0.0062,0.096,-0.085,0.092,0.012,0.057,-0.0012,-0.0058,-3e-06,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.033,-0.067,0,0,0.16,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -32990000,-0.29,0.015,-0.006,0.96,-0.0023,0.091,-0.084,0.092,-0.00052,0.043,-0.0013,-0.0058,-1.1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33090000,-0.29,0.015,-0.0059,0.96,0.0014,0.097,-0.081,0.092,0.0087,0.036,-0.0013,-0.0058,-1e-05,0.066,0.013,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.14,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33190000,-0.29,0.015,-0.0059,0.96,0.0056,0.093,-0.08,0.093,-0.0059,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.13,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33290000,-0.29,0.015,-0.0059,0.96,0.0098,0.096,-0.08,0.094,0.0029,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.7e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.01 -33390000,-0.3,0.015,-0.0058,0.96,0.014,0.093,-0.078,0.094,-0.0054,0.011,-0.0013,-0.0058,-2.6e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.033 -33490000,-0.3,0.015,-0.0058,0.96,0.02,0.097,-0.077,0.097,0.004,0.0016,-0.0013,-0.0058,-2.1e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.058 -33590000,-0.3,0.015,-0.0056,0.95,0.023,0.094,-0.074,0.096,-0.0089,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.083 -33690000,-0.3,0.015,-0.0056,0.95,0.026,0.098,-0.075,0.097,9.1e-05,-0.014,-0.0013,-0.0058,-2.2e-05,0.066,0.014,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.11 -33790000,-0.3,0.015,-0.0056,0.95,0.028,0.096,-0.069,0.094,-0.013,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.13 -33890000,-0.3,0.015,-0.0055,0.95,0.033,0.097,-0.069,0.097,-0.004,-0.028,-0.0013,-0.0058,-2.5e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.16 -33990000,-0.3,0.015,-0.0054,0.95,0.035,0.096,-0.065,0.096,-0.012,-0.032,-0.0013,-0.0058,-3.6e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.18 -34090000,-0.3,0.015,-0.0054,0.95,0.038,0.1,-0.064,0.099,-0.0027,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.4e-05,0.0012,0.0011,0.00063,0.0012,1,1,0.21 -34190000,-0.3,0.015,-0.0054,0.95,0.039,0.097,-0.061,0.094,-0.014,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.23 -34290000,-0.3,0.015,-0.0052,0.95,0.041,0.1,-0.06,0.098,-0.0047,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.26 -34390000,-0.3,0.015,-0.0051,0.95,0.042,0.097,-0.055,0.093,-0.016,-0.049,-0.0013,-0.0057,-3.9e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.084,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.28 -34490000,-0.3,0.015,-0.0051,0.95,0.045,0.1,-0.053,0.097,-0.0068,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.032,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.31 -34590000,-0.3,0.014,-0.005,0.95,0.045,0.098,0.74,0.092,-0.021,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.015,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.33 -34690000,-0.3,0.014,-0.0051,0.95,0.05,0.1,1.7,0.097,-0.011,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.36 -34790000,-0.3,0.014,-0.005,0.95,0.051,0.099,2.7,0.091,-0.025,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.4e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.38 -34890000,-0.3,0.014,-0.005,0.95,0.056,0.1,3.7,0.096,-0.015,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.016,-0.12,-0.11,-0.025,0.5,0.085,-0.031,-0.067,0,0,0.12,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.3e-05,0.0012,0.0011,0.00062,0.0012,1,1,0.41 +5590000,1,-0.0088,-0.012,0.001,0.0083,0.016,-0.053,0.004,0.0033,-0.058,-0.002,-0.0054,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0028,0.0028,0.00011,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,4.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.4 +5690000,1,-0.0089,-0.011,0.00093,0.0077,0.016,-0.052,0.0028,0.0029,-0.055,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0024,0.0024,0.00011,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,3.8e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5790000,1,-0.0088,-0.011,0.00088,0.0089,0.018,-0.049,0.0036,0.0046,-0.053,-0.002,-0.0054,-7.9e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0025,0.0025,0.00011,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,3.8e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5890000,1,-0.0088,-0.011,0.00092,0.0095,0.015,-0.048,0.0027,0.0037,-0.056,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.0001,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,3.5e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +5990000,1,-0.0088,-0.012,0.00089,0.011,0.017,-0.041,0.0038,0.0053,-0.05,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0022,0.0022,0.00011,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.5 +6090000,1,-0.0088,-0.011,0.00071,0.011,0.018,-0.039,0.0049,0.0071,-0.047,-0.0019,-0.0055,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0023,0.0023,0.00011,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,3.5e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6190000,1,-0.0089,-0.011,0.00072,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.002,0.002,0.0001,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,3.1e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6290000,1,-0.0089,-0.011,0.00075,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0019,-0.0055,-8.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0021,0.0021,0.00011,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,3.1e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6390000,1,-0.0089,-0.011,0.00076,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0018,-0.0056,-8.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.095,0.0017,0.0017,9.9e-05,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,2.9e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.6 +6490000,1,-0.0089,-0.011,0.00066,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0018,-0.0056,-8.7e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0018,0.0018,0.0001,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,2.9e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6590000,1,-0.0089,-0.011,0.00059,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.6e-05,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6690000,1,-0.0088,-0.011,0.00055,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6790000,1,-0.0089,-0.011,0.00052,0.003,0.015,-0.042,0.0021,0.006,-0.058,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 +6890000,1,-0.0087,-0.011,0.00043,0.0023,0.015,-0.039,0.0024,0.0075,-0.055,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8 +6990000,0.98,-0.0066,-0.012,0.19,0.0013,0.013,-0.037,0.0016,0.0058,-0.055,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0013,0.0013,0.09,0.17,0.17,0.031,0.11,0.11,0.066,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0026,0.0025,0.002,0.0025,0.0025,0.0025,0.0025,1,1,1.8 +7090000,0.98,-0.0065,-0.012,0.19,0.00038,0.018,-0.038,0.0017,0.0074,-0.056,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0013,0.0013,0.09,0.19,0.19,0.03,0.13,0.13,0.066,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0024,0.0025,0.0014,0.0025,0.0025,0.0025,0.0025,1,1,1.8 +7190000,0.98,-0.0064,-0.012,0.19,0,0,-0.037,0.0016,0.0093,-0.058,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0014,0.0014,0.09,25,25,0.029,1e+02,1e+02,0.065,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0023,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,1,1,1.8 +7290000,0.98,-0.0064,-0.012,0.19,0.00075,0.0036,-0.034,0.0016,0.0094,-0.054,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0014,0.0014,0.09,25,25,0.028,1e+02,1e+02,0.064,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0022,0.0025,0.00086,0.0025,0.0025,0.0025,0.0025,1,1,1.9 +7390000,0.98,-0.0063,-0.012,0.19,-0.001,0.006,-0.032,0.0016,0.01,-0.052,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,25,25,0.027,1e+02,1e+02,0.064,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.002,0.0025,0.00073,0.0025,0.0025,0.0025,0.0025,1,1,1.9 +7490000,0.98,-0.0063,-0.012,0.19,0.0013,0.0084,-0.026,0.0017,0.01,-0.046,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,25,25,0.026,51,51,0.063,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0019,0.0025,0.00062,0.0025,0.0025,0.0025,0.0025,1,1,1.9 +7590000,0.98,-0.0064,-0.012,0.19,0.0022,0.011,-0.023,0.0018,0.011,-0.041,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0016,0.0016,0.09,25,25,0.025,52,52,0.062,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0018,0.0025,0.00054,0.0025,0.0025,0.0025,0.0025,1,1,1.9 +7690000,0.98,-0.0064,-0.013,0.19,0.0019,0.014,-0.022,0.002,0.012,-0.036,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0016,0.0016,0.09,24,24,0.025,35,35,0.062,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0017,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,1,1,2 +7790000,0.98,-0.0063,-0.013,0.19,0.0034,0.016,-0.025,0.0022,0.013,-0.041,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0017,0.0017,0.09,24,24,0.024,37,37,0.061,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0016,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,1,1,2 +7890000,0.98,-0.0063,-0.013,0.19,0.002,0.02,-0.025,0.0022,0.014,-0.045,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0017,0.0017,0.09,24,24,0.023,29,29,0.06,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0015,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,1,1,2 +7990000,0.98,-0.0062,-0.013,0.19,0.0023,0.022,-0.022,0.0024,0.016,-0.042,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0018,0.0018,0.09,24,24,0.022,31,31,0.059,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0015,0.0025,0.00036,0.0025,0.0025,0.0025,0.0025,1,1,2 +8090000,0.98,-0.0061,-0.013,0.19,0.0037,0.025,-0.022,0.0026,0.016,-0.044,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0019,0.0019,0.09,23,23,0.022,25,25,0.059,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0014,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,1,1,2.1 +8190000,0.98,-0.0061,-0.012,0.19,0.0043,0.03,-0.018,0.003,0.019,-0.038,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0019,0.0019,0.09,23,23,0.021,28,28,0.058,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0013,0.0025,0.00031,0.0025,0.0025,0.0025,0.0025,1,1,2.1 +8290000,0.98,-0.0061,-0.012,0.19,0.0064,0.033,-0.017,0.0032,0.02,-0.038,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.002,0.002,0.09,21,21,0.02,24,24,0.057,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0013,0.0025,0.00029,0.0025,0.0025,0.0025,0.0025,1,1,2.1 +8390000,0.98,-0.0061,-0.012,0.19,0.0042,0.035,-0.016,0.0037,0.023,-0.036,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.002,0.002,0.09,21,21,0.02,26,26,0.057,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0012,0.0025,0.00027,0.0025,0.0025,0.0025,0.0025,1,1,2.1 +8490000,0.98,-0.006,-0.012,0.19,0.0037,0.037,-0.017,0.0036,0.023,-0.041,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0021,0.0021,0.09,19,19,0.019,23,23,0.056,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0011,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,1,1,2.2 +8590000,0.98,-0.0059,-0.013,0.19,0.0048,0.04,-0.012,0.004,0.027,-0.036,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0022,0.0022,0.09,19,19,0.018,26,26,0.055,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0011,0.0025,0.00024,0.0025,0.0025,0.0025,0.0025,1,1,2.2 +8690000,0.98,-0.0059,-0.013,0.19,0.0045,0.04,-0.014,0.0038,0.027,-0.038,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0022,0.0022,0.09,17,17,0.018,23,23,0.055,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.001,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,1,1,2.2 +8790000,0.98,-0.0059,-0.013,0.19,0.006,0.043,-0.014,0.0043,0.031,-0.035,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0023,0.0023,0.09,17,17,0.018,25,25,0.055,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00099,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,1,1,2.2 +8890000,0.98,-0.006,-0.013,0.19,0.0056,0.043,-0.0093,0.0042,0.03,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0024,0.0024,0.09,15,15,0.017,22,22,0.054,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00094,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,1,1,2.3 +8990000,0.98,-0.0059,-0.013,0.19,0.0048,0.048,-0.0085,0.0047,0.034,-0.032,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0024,0.0024,0.09,15,15,0.017,25,25,0.054,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00091,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,1,1,2.3 +9090000,0.98,-0.0059,-0.013,0.19,0.0047,0.049,-0.0095,0.0044,0.033,-0.032,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0025,0.0025,0.09,13,13,0.016,22,22,0.053,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00087,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,1,1,2.3 +9190000,0.98,-0.0058,-0.013,0.19,0.0083,0.052,-0.009,0.0051,0.038,-0.032,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0026,0.0026,0.09,13,13,0.016,25,25,0.052,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00083,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.3 +9290000,0.98,-0.0057,-0.013,0.19,0.01,0.051,-0.0074,0.0051,0.036,-0.03,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0027,0.0027,0.09,12,12,0.015,22,22,0.052,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0008,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.4 +9390000,0.98,-0.0056,-0.013,0.19,0.01,0.054,-0.0063,0.0062,0.041,-0.03,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0027,0.0027,0.09,12,12,0.015,24,24,0.052,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00077,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,1,1,2.4 +9490000,0.98,-0.0056,-0.013,0.19,0.01,0.057,-0.0046,0.0072,0.047,-0.027,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0028,0.0028,0.09,12,12,0.015,27,27,0.051,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00074,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 +9590000,0.98,-0.0056,-0.013,0.19,0.0096,0.054,-0.0045,0.0069,0.044,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0029,0.0029,0.09,10,10,0.014,24,24,0.05,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00071,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 +9690000,0.98,-0.0056,-0.013,0.19,0.0096,0.057,-0.0016,0.0079,0.049,-0.027,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,10,10,0.014,26,26,0.05,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00068,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.5 +9790000,0.98,-0.0056,-0.013,0.19,0.01,0.057,-0.0029,0.0075,0.046,-0.028,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,8.9,8.9,0.014,23,23,0.05,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00066,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.5 +9890000,0.98,-0.0056,-0.013,0.19,0.013,0.059,-0.0016,0.0086,0.052,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0031,0.0031,0.09,8.9,8.9,0.013,25,25,0.049,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00063,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 +9990000,0.98,-0.0056,-0.013,0.19,0.014,0.057,-0.0009,0.0084,0.049,-0.031,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0032,0.0032,0.09,7.7,7.7,0.013,22,22,0.049,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00061,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 +10090000,0.98,-0.0055,-0.013,0.19,0.012,0.058,0.00032,0.0097,0.054,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0033,0.0033,0.09,7.8,7.8,0.013,24,24,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00059,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 +10190000,0.98,-0.0055,-0.013,0.19,0.0099,0.057,0.0012,0.0091,0.05,-0.03,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,6.8,6.8,0.012,21,21,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00057,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 +10290000,0.98,-0.0055,-0.013,0.19,0.011,0.06,0.00014,0.01,0.056,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,6.9,6.9,0.012,23,23,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00055,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 +10390000,0.98,-0.0055,-0.013,0.19,0.0071,0.0052,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0056,-9.2e-05,-4.1e-06,3.9e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0035,0.0035,0.09,0.25,0.25,0.56,0.25,0.25,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00053,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 +10490000,0.98,-0.0054,-0.012,0.19,0.0085,0.0076,0.0071,0.0015,0.00075,-0.023,-0.0016,-0.0056,-9.2e-05,-1.1e-05,1.2e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0036,0.0036,0.09,0.26,0.26,0.55,0.26,0.26,0.057,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00052,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 +10590000,0.98,-0.0053,-0.012,0.19,-0.0012,0.0054,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,-9.3e-05,-4.3e-05,-0.00011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0036,0.0036,0.09,0.13,0.13,0.27,0.13,0.13,0.055,6.4e-05,6.4e-05,2.2e-06,0.04,0.04,0.00051,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 +10690000,0.98,-0.0053,-0.012,0.19,-5.7e-05,0.0066,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,-9.3e-05,-4.4e-05,-0.00011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0037,0.0037,0.09,0.15,0.15,0.26,0.14,0.14,0.065,6.4e-05,6.4e-05,2.2e-06,0.04,0.04,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 +10790000,0.98,-0.0055,-0.012,0.19,0.0018,0.0029,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,-9.5e-05,0.00011,-0.00023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0036,0.0036,0.09,0.11,0.11,0.17,0.09,0.09,0.062,6e-05,6e-05,2.2e-06,0.04,0.04,0.00049,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 +10890000,0.98,-0.0054,-0.013,0.19,0.0019,0.0063,0.01,-0.00059,-0.0043,-0.018,-0.0016,-0.0057,-9.5e-05,0.00011,-0.00023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0037,0.0037,0.09,0.13,0.13,0.16,0.097,0.097,0.068,6e-05,6e-05,2.2e-06,0.04,0.04,0.00049,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 +10990000,0.98,-0.0055,-0.013,0.19,0.0014,0.012,0.016,-0.00045,-0.0031,-0.012,-0.0015,-0.0057,-9.6e-05,0.00018,-0.00032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,0.099,0.099,0.12,0.072,0.072,0.065,5.3e-05,5.3e-05,2.2e-06,0.04,0.04,0.00048,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 +11090000,0.98,-0.0056,-0.013,0.19,0.0024,0.017,0.02,-0.0003,-0.0017,-0.0074,-0.0015,-0.0057,-9.6e-05,0.00018,-0.00031,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,0.12,0.12,0.11,0.079,0.079,0.069,5.3e-05,5.3e-05,2.2e-06,0.04,0.04,0.00048,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 +11190000,0.98,-0.006,-0.013,0.19,0.0042,0.016,0.026,0.0011,-0.0019,-0.00041,-0.0015,-0.0057,-9.7e-05,0.00048,-0.0004,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,0.099,0.099,0.083,0.062,0.062,0.066,4.4e-05,4.4e-05,2.2e-06,0.04,0.04,0.00048,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 +11290000,0.98,-0.006,-0.013,0.19,0.0045,0.018,0.026,0.0015,-0.00014,-0.00017,-0.0015,-0.0057,-9.7e-05,0.00048,-0.0004,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,0.12,0.12,0.077,0.07,0.07,0.069,4.4e-05,4.4e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 +11390000,0.98,-0.0062,-0.013,0.19,0.0027,0.015,0.016,0.00089,-0.00098,-0.0086,-0.0014,-0.0057,-0.0001,0.00067,-0.00066,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0025,0.0025,0.09,0.1,0.1,0.062,0.057,0.057,0.066,3.5e-05,3.5e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 +11490000,0.98,-0.0061,-0.013,0.19,0.0019,0.016,0.02,0.0011,0.00055,-0.0025,-0.0014,-0.0057,-0.0001,0.00067,-0.00066,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0026,0.0026,0.09,0.12,0.12,0.057,0.065,0.065,0.067,3.5e-05,3.5e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 +11590000,0.98,-0.0065,-0.012,0.19,0.0036,0.012,0.018,0.00085,-0.00049,-0.0036,-0.0013,-0.0057,-0.0001,0.00084,-0.00084,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0021,0.0021,0.09,0.098,0.098,0.048,0.054,0.054,0.065,2.7e-05,2.7e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 +11690000,0.98,-0.0065,-0.012,0.19,0.0041,0.016,0.018,0.0012,0.00089,-0.005,-0.0013,-0.0057,-0.0001,0.00084,-0.00084,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0021,0.0021,0.09,0.12,0.12,0.044,0.062,0.062,0.066,2.7e-05,2.7e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 +11790000,0.98,-0.0069,-0.012,0.19,0.0028,0.0099,0.019,0.00069,-0.0019,-0.002,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0017,0.0017,0.09,0.094,0.094,0.037,0.052,0.052,0.063,2.1e-05,2.1e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 +11890000,0.98,-0.007,-0.012,0.19,0.0055,0.011,0.017,0.0011,-0.00093,-0.0013,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0018,0.0018,0.09,0.11,0.11,0.034,0.06,0.06,0.063,2.1e-05,2.1e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 +11990000,0.98,-0.0072,-0.012,0.19,0.0085,0.011,0.015,0.0021,-0.0019,-0.005,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,0.089,0.089,0.03,0.05,0.05,0.061,1.6e-05,1.6e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 +12090000,0.98,-0.0071,-0.012,0.19,0.01,0.011,0.018,0.0031,-0.00082,0.0011,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,0.11,0.11,0.027,0.059,0.059,0.06,1.6e-05,1.6e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 +12190000,0.98,-0.007,-0.012,0.19,0.0082,0.011,0.017,0.0018,0.00029,0.0029,-0.0012,-0.0058,-0.00011,0.0011,-0.0012,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0012,0.0012,0.09,0.083,0.083,0.024,0.05,0.05,0.058,1.2e-05,1.2e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 +12290000,0.98,-0.0071,-0.012,0.19,0.006,0.01,0.016,0.0025,0.0013,0.0039,-0.0012,-0.0058,-0.00011,0.0011,-0.0012,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0013,0.0013,0.09,0.098,0.098,0.022,0.058,0.058,0.058,1.2e-05,1.2e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 +12390000,0.98,-0.0072,-0.012,0.19,0.0045,0.0068,0.014,0.0017,0.00041,-0.0021,-0.0012,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0011,0.0011,0.09,0.077,0.077,0.02,0.049,0.049,0.056,9.8e-06,9.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 +12490000,0.98,-0.0072,-0.012,0.19,0.0047,0.0078,0.018,0.0022,0.0011,-8.1e-05,-0.0012,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0011,0.0011,0.09,0.09,0.09,0.018,0.058,0.058,0.055,9.8e-06,9.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 +12590000,0.98,-0.0074,-0.012,0.19,0.0084,0.0013,0.019,0.0033,-0.0014,0.0017,-0.0011,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00094,0.00094,0.09,0.071,0.071,0.017,0.049,0.049,0.054,7.9e-06,7.9e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 +12690000,0.98,-0.0073,-0.012,0.19,0.009,-0.00085,0.019,0.0041,-0.0014,0.0033,-0.0011,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00095,0.00095,0.09,0.083,0.083,0.015,0.057,0.057,0.053,7.9e-06,7.9e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 +12790000,0.98,-0.0076,-0.012,0.19,0.011,-0.0041,0.021,0.0041,-0.0045,0.0054,-0.0011,-0.0058,-0.00011,0.0012,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00084,0.00084,0.09,0.066,0.066,0.014,0.049,0.049,0.051,6.5e-06,6.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 +12890000,0.98,-0.0076,-0.012,0.19,0.011,-0.0049,0.022,0.0052,-0.0049,0.0084,-0.0011,-0.0058,-0.00011,0.0012,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00085,0.00085,0.09,0.076,0.076,0.013,0.057,0.057,0.051,6.5e-06,6.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 +12990000,0.98,-0.0075,-0.012,0.19,0.0087,-0.0029,0.022,0.0036,-0.0036,0.0096,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00076,0.00076,0.09,0.061,0.061,0.012,0.048,0.048,0.05,5.4e-06,5.4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 +13090000,0.98,-0.0076,-0.012,0.19,0.0098,-0.0027,0.02,0.0045,-0.0039,0.0085,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00077,0.00077,0.09,0.07,0.07,0.011,0.057,0.057,0.049,5.4e-06,5.4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 +13190000,0.98,-0.0076,-0.012,0.19,0.0048,-0.0043,0.019,0.001,-0.0046,0.0091,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00071,0.00071,0.09,0.057,0.057,0.011,0.048,0.048,0.047,4.6e-06,4.6e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 +13290000,0.98,-0.0076,-0.012,0.19,0.0047,-0.0052,0.016,0.0015,-0.005,0.0084,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00071,0.00071,0.09,0.065,0.065,0.01,0.056,0.056,0.047,4.6e-06,4.6e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 +13390000,0.98,-0.0075,-0.012,0.19,0.0037,-0.0033,0.016,0.00095,-0.0038,0.0091,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00066,0.00066,0.09,0.053,0.053,0.0094,0.048,0.048,0.046,4e-06,4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 +13490000,0.98,-0.0075,-0.012,0.19,0.0044,-0.0015,0.015,0.0014,-0.004,0.0053,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00066,0.00067,0.09,0.06,0.06,0.009,0.056,0.056,0.045,4e-06,4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 +13590000,0.98,-0.0075,-0.012,0.19,0.0086,-0.0018,0.017,0.0041,-0.0032,0.0038,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00062,0.00062,0.09,0.049,0.049,0.0085,0.048,0.048,0.044,3.5e-06,3.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 +13690000,0.98,-0.0074,-0.012,0.19,0.0088,-0.0031,0.017,0.0049,-0.0035,0.0064,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00063,0.00063,0.09,0.055,0.055,0.0082,0.055,0.055,0.044,3.5e-06,3.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 +13790000,0.98,-0.0074,-0.012,0.19,0.015,0.00083,0.017,0.0083,-0.001,0.0059,-0.0011,-0.0058,-0.00011,0.0011,-0.0015,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00059,0.00059,0.09,0.046,0.046,0.0078,0.047,0.047,0.042,3.1e-06,3.1e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 +13890000,0.98,-0.0073,-0.012,0.19,0.017,0.0016,0.018,0.0099,-0.00092,0.0081,-0.0011,-0.0058,-0.00011,0.0011,-0.0015,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0006,0.0006,0.09,0.052,0.051,0.0076,0.055,0.055,0.042,3.1e-06,3.1e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 +13990000,0.98,-0.0074,-0.012,0.19,0.016,0.002,0.017,0.0075,-0.0023,0.007,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00057,0.00057,0.066,0.043,0.043,0.0073,0.047,0.047,0.041,2.8e-06,2.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 +14090000,0.98,-0.0074,-0.012,0.19,0.014,-0.0024,0.018,0.0091,-0.0024,0.0035,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00057,0.00057,0.066,0.048,0.048,0.0072,0.054,0.054,0.041,2.8e-06,2.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 +14190000,0.98,-0.0073,-0.012,0.19,0.011,-0.0011,0.018,0.0082,-0.0018,0.0037,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00055,0.00055,0.066,0.041,0.041,0.007,0.047,0.047,0.04,2.5e-06,2.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 +14290000,0.98,-0.0073,-0.012,0.19,0.013,-0.0011,0.016,0.0093,-0.0019,0.0079,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00055,0.00055,0.066,0.045,0.045,0.0069,0.054,0.054,0.039,2.5e-06,2.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 +14390000,0.98,-0.0073,-0.011,0.19,0.013,-0.0039,0.018,0.0087,-0.003,0.012,-0.0011,-0.0059,-0.00011,0.001,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00053,0.00053,0.066,0.038,0.038,0.0067,0.047,0.047,0.039,2.3e-06,2.3e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 +14490000,0.98,-0.0075,-0.011,0.19,0.012,-0.0036,0.021,0.0099,-0.0034,0.015,-0.0011,-0.0059,-0.00011,0.001,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00054,0.00054,0.066,0.042,0.042,0.0066,0.053,0.053,0.038,2.3e-06,2.3e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 +14590000,0.98,-0.0075,-0.011,0.19,0.01,-0.0036,0.019,0.0063,-0.0041,0.011,-0.0011,-0.0059,-0.00011,0.00096,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00052,0.00052,0.066,0.036,0.036,0.0065,0.046,0.046,0.038,2.2e-06,2.2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 +14690000,0.98,-0.0075,-0.011,0.19,0.0097,-0.0034,0.019,0.0073,-0.0044,0.011,-0.0011,-0.0059,-0.00011,0.00095,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00052,0.00052,0.066,0.04,0.04,0.0065,0.053,0.053,0.037,2.2e-06,2.2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 +14790000,0.98,-0.0075,-0.011,0.19,0.011,0.0023,0.019,0.0059,0.00061,0.014,-0.0011,-0.0059,-0.00011,0.0013,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00051,0.00051,0.066,0.034,0.034,0.0064,0.046,0.046,0.036,2e-06,2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 +14890000,0.98,-0.0074,-0.011,0.19,0.01,-8.2e-05,0.023,0.0069,0.00073,0.015,-0.0011,-0.0059,-0.00011,0.0013,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00051,0.00051,0.066,0.037,0.037,0.0064,0.052,0.052,0.036,2e-06,2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 +14990000,0.98,-0.0075,-0.011,0.19,0.0093,-0.0013,0.026,0.0054,-0.00072,0.017,-0.0011,-0.0059,-0.00011,0.0012,-0.00095,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0005,0.0005,0.066,0.032,0.032,0.0064,0.046,0.046,0.036,1.9e-06,1.9e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 +15090000,0.98,-0.0075,-0.011,0.19,0.0097,-0.00019,0.03,0.0064,-0.00084,0.019,-0.0011,-0.0059,-0.00011,0.0012,-0.00095,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0005,0.0005,0.066,0.035,0.035,0.0064,0.052,0.052,0.035,1.9e-06,1.9e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 +15190000,0.98,-0.0076,-0.011,0.19,0.0079,-0.0013,0.03,0.0051,-0.00077,0.021,-0.0011,-0.0059,-0.00011,0.0012,-0.00082,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00049,0.00049,0.066,0.031,0.03,0.0064,0.046,0.046,0.035,1.8e-06,1.8e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 +15290000,0.98,-0.0077,-0.011,0.19,0.0089,-0.0023,0.03,0.0059,-0.00092,0.018,-0.0011,-0.0059,-0.00011,0.0012,-0.00081,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0005,0.0005,0.066,0.033,0.033,0.0065,0.052,0.052,0.035,1.8e-06,1.8e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 +15390000,0.98,-0.0078,-0.011,0.19,0.0091,1.3e-06,0.03,0.0048,-0.00065,0.018,-0.0011,-0.0059,-0.00011,0.0012,-0.00068,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00049,0.00049,0.066,0.029,0.029,0.0064,0.045,0.045,0.034,1.7e-06,1.7e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 +15490000,0.98,-0.0078,-0.011,0.19,0.0089,-0.0025,0.03,0.0056,-0.00075,0.019,-0.0011,-0.0059,-0.00011,0.0012,-0.00068,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00049,0.00049,0.066,0.032,0.032,0.0065,0.051,0.051,0.034,1.7e-06,1.7e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 +15590000,0.98,-0.0079,-0.011,0.19,0.012,-0.005,0.029,0.0071,-0.0042,0.018,-0.0011,-0.0059,-0.00011,0.00078,-0.00072,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.028,0.028,0.0065,0.045,0.045,0.034,1.6e-06,1.6e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 +15690000,0.98,-0.0079,-0.011,0.19,0.014,-0.008,0.03,0.0083,-0.0049,0.019,-0.0011,-0.0059,-0.00011,0.00077,-0.00071,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.03,0.03,0.0066,0.051,0.051,0.034,1.6e-06,1.6e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 +15790000,0.98,-0.0079,-0.011,0.19,0.011,-0.0079,0.03,0.0066,-0.004,0.021,-0.0011,-0.0059,-0.00011,0.00094,-0.00051,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.026,0.026,0.0066,0.045,0.045,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 +15890000,0.98,-0.0079,-0.011,0.19,0.0098,-0.0062,0.03,0.0076,-0.0047,0.02,-0.0011,-0.0059,-0.00011,0.00092,-0.0005,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.029,0.029,0.0067,0.05,0.05,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 +15990000,0.98,-0.0078,-0.011,0.19,0.0079,-0.0052,0.027,0.0061,-0.0038,0.02,-0.0011,-0.0059,-0.00011,0.001,-0.00032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.025,0.025,0.0068,0.044,0.044,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 +16090000,0.98,-0.0077,-0.011,0.19,0.0076,-0.0064,0.025,0.0069,-0.0043,0.02,-0.0011,-0.0059,-0.00011,0.001,-0.00032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.027,0.027,0.0069,0.05,0.05,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 +16190000,0.98,-0.0077,-0.011,0.19,0.0041,-0.0045,0.024,0.0044,-0.0034,0.017,-0.0011,-0.0059,-0.00011,0.0012,-1.1e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.024,0.024,0.0069,0.044,0.044,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 +16290000,0.98,-0.0077,-0.011,0.19,0.0049,-0.006,0.024,0.0048,-0.0039,0.018,-0.0011,-0.0059,-0.00011,0.0012,-8.5e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.026,0.026,0.007,0.049,0.049,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 +16390000,0.98,-0.0077,-0.011,0.19,0.0065,-0.0058,0.024,0.0052,-0.0032,0.018,-0.0011,-0.0059,-0.00011,0.0013,-8.7e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.023,0.023,0.007,0.044,0.044,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 +16490000,0.98,-0.0078,-0.011,0.19,0.009,-0.0074,0.027,0.006,-0.0039,0.022,-0.0011,-0.0059,-0.00011,0.0013,-9.1e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.025,0.025,0.0072,0.049,0.049,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 +16590000,0.98,-0.0078,-0.011,0.19,0.013,-0.0079,0.03,0.0052,-0.0032,0.022,-0.0011,-0.0059,-0.00011,0.0015,7.7e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.022,0.022,0.0072,0.043,0.043,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 +16690000,0.98,-0.0078,-0.011,0.19,0.015,-0.013,0.03,0.0066,-0.0042,0.023,-0.0011,-0.0059,-0.00011,0.0015,8.4e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.024,0.024,0.0073,0.048,0.048,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 +16790000,0.98,-0.0077,-0.011,0.19,0.016,-0.012,0.029,0.0055,-0.0034,0.023,-0.0012,-0.0059,-0.00011,0.0018,0.00037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.022,0.022,0.0073,0.043,0.043,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00043,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 +16890000,0.98,-0.0076,-0.011,0.19,0.016,-0.013,0.03,0.0071,-0.0047,0.022,-0.0012,-0.0059,-0.00011,0.0018,0.00038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.023,0.023,0.0074,0.048,0.048,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00043,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 +16990000,0.98,-0.0077,-0.011,0.19,0.014,-0.013,0.03,0.0062,-0.0039,0.02,-0.0012,-0.0059,-0.00011,0.002,0.00036,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.021,0.021,0.0074,0.043,0.043,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00043,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 +17090000,0.98,-0.0078,-0.011,0.19,0.016,-0.016,0.03,0.0077,-0.0053,0.02,-0.0012,-0.0059,-0.00011,0.002,0.00037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.023,0.023,0.0075,0.048,0.048,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00042,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 +17190000,0.98,-0.0079,-0.011,0.19,0.015,-0.02,0.031,0.0057,-0.0083,0.023,-0.0012,-0.0059,-0.00011,0.0019,0.00068,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.02,0.02,0.0076,0.042,0.042,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00042,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 +17290000,0.98,-0.0078,-0.011,0.19,0.017,-0.021,0.031,0.0073,-0.01,0.023,-0.0012,-0.0059,-0.00011,0.0019,0.00069,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.022,0.022,0.0076,0.047,0.047,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00042,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 +17390000,0.98,-0.0078,-0.011,0.19,0.012,-0.022,0.031,0.008,-0.0077,0.023,-0.0012,-0.0059,-0.00011,0.0026,0.00052,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.02,0.02,0.0076,0.042,0.042,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00041,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 +17490000,0.98,-0.0078,-0.011,0.19,0.011,-0.023,0.03,0.0091,-0.01,0.025,-0.0012,-0.0059,-0.00011,0.0026,0.00053,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.021,0.021,0.0078,0.047,0.047,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00041,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 +17590000,0.98,-0.0077,-0.011,0.19,0.0084,-0.02,0.029,0.0057,-0.0083,0.022,-0.0012,-0.0059,-0.00011,0.0034,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.019,0.019,0.0077,0.042,0.042,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.0004,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 +17690000,0.98,-0.0078,-0.011,0.19,0.008,-0.021,0.031,0.0065,-0.01,0.025,-0.0012,-0.0059,-0.00011,0.0034,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.021,0.021,0.0078,0.046,0.046,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.0004,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 +17790000,0.98,-0.0079,-0.011,0.19,0.0097,-0.021,0.031,0.0066,-0.0096,0.03,-0.0012,-0.0059,-0.00011,0.0041,0.001,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.019,0.019,0.0078,0.042,0.042,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00039,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 +17890000,0.98,-0.0078,-0.011,0.19,0.012,-0.023,0.031,0.0077,-0.012,0.034,-0.0012,-0.0059,-0.00011,0.0041,0.001,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.02,0.02,0.0079,0.046,0.046,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00039,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 +17990000,0.98,-0.0077,-0.011,0.19,0.012,-0.019,0.03,0.0066,-0.0071,0.035,-0.0012,-0.0059,-0.00011,0.0056,0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.018,0.018,0.0079,0.041,0.041,0.033,1e-06,1e-06,2.2e-06,0.038,0.038,0.00038,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 +18090000,0.98,-0.0078,-0.011,0.19,0.012,-0.02,0.03,0.0078,-0.009,0.033,-0.0012,-0.0059,-0.00011,0.0056,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.02,0.02,0.008,0.046,0.046,0.034,1e-06,1e-06,2.2e-06,0.038,0.038,0.00038,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 +18190000,0.98,-0.0078,-0.011,0.19,0.011,-0.019,0.03,0.0075,-0.0077,0.031,-0.0012,-0.0059,-0.00011,0.0061,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.018,0.018,0.0079,0.041,0.041,0.034,1e-06,1e-06,2.2e-06,0.037,0.037,0.00037,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 +18290000,0.98,-0.0078,-0.011,0.19,0.012,-0.02,0.029,0.0087,-0.0097,0.03,-0.0012,-0.0059,-0.00011,0.0061,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.019,0.019,0.008,0.046,0.046,0.034,1e-06,1e-06,2.2e-06,0.037,0.037,0.00037,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 +18390000,0.98,-0.0078,-0.011,0.19,0.012,-0.019,0.029,0.0092,-0.0083,0.029,-0.0012,-0.0059,-0.00011,0.0067,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.018,0.018,0.0079,0.041,0.041,0.034,9.8e-07,9.9e-07,2.3e-06,0.037,0.037,0.00036,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 +18490000,0.98,-0.0078,-0.011,0.19,0.015,-0.02,0.028,0.011,-0.01,0.031,-0.0012,-0.0059,-0.00011,0.0067,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.019,0.019,0.008,0.045,0.045,0.034,9.9e-07,9.9e-07,2.3e-06,0.037,0.037,0.00036,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 +18590000,0.98,-0.0076,-0.011,0.19,0.014,-0.019,0.028,0.0092,-0.0088,0.033,-0.0012,-0.0059,-0.00011,0.0074,0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.017,0.017,0.0079,0.041,0.041,0.034,9.5e-07,9.6e-07,2.3e-06,0.037,0.037,0.00035,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 +18690000,0.98,-0.0076,-0.011,0.19,0.014,-0.019,0.026,0.011,-0.011,0.032,-0.0012,-0.0059,-0.00011,0.0074,0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.019,0.019,0.008,0.045,0.045,0.034,9.6e-07,9.6e-07,2.3e-06,0.037,0.037,0.00035,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 +18790000,0.98,-0.0076,-0.011,0.19,0.013,-0.018,0.026,0.0099,-0.0093,0.03,-0.0012,-0.0059,-0.00011,0.0081,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.017,0.017,0.0079,0.04,0.04,0.034,9.3e-07,9.3e-07,2.3e-06,0.037,0.037,0.00035,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 +18890000,0.98,-0.0075,-0.011,0.19,0.012,-0.019,0.024,0.011,-0.011,0.026,-0.0012,-0.0059,-0.00011,0.008,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.018,0.018,0.008,0.045,0.045,0.034,9.3e-07,9.3e-07,2.3e-06,0.037,0.037,0.00034,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 +18990000,0.98,-0.0075,-0.011,0.19,0.01,-0.018,0.025,0.0095,-0.0097,0.03,-0.0012,-0.0059,-0.00011,0.0088,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.017,0.017,0.0079,0.04,0.04,0.034,9e-07,9e-07,2.3e-06,0.036,0.036,0.00034,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 +19090000,0.98,-0.0076,-0.011,0.19,0.0088,-0.02,0.025,0.011,-0.012,0.026,-0.0012,-0.0059,-0.00011,0.0087,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.018,0.018,0.0079,0.045,0.045,0.035,9e-07,9e-07,2.3e-06,0.036,0.036,0.00033,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 +19190000,0.98,-0.0075,-0.011,0.19,0.007,-0.019,0.025,0.009,-0.01,0.025,-0.0013,-0.0059,-0.00011,0.0095,0.0021,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.017,0.017,0.0079,0.04,0.04,0.034,8.7e-07,8.7e-07,2.3e-06,0.036,0.036,0.00033,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 +19290000,0.98,-0.0074,-0.011,0.19,0.0066,-0.02,0.025,0.0097,-0.012,0.024,-0.0013,-0.0059,-0.00011,0.0095,0.0021,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.018,0.018,0.0079,0.044,0.044,0.034,8.7e-07,8.8e-07,2.3e-06,0.036,0.036,0.00032,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 +19390000,0.98,-0.0075,-0.011,0.19,0.0057,-0.016,0.026,0.0084,-0.0094,0.023,-0.0013,-0.0059,-0.00011,0.011,0.0023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.016,0.016,0.0078,0.04,0.04,0.035,8.5e-07,8.5e-07,2.3e-06,0.036,0.036,0.00032,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 +19490000,0.98,-0.0075,-0.011,0.19,0.0054,-0.017,0.026,0.009,-0.011,0.023,-0.0013,-0.0059,-0.00011,0.01,0.0023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.018,0.018,0.0078,0.044,0.044,0.035,8.5e-07,8.5e-07,2.3e-06,0.036,0.036,0.00031,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 +19590000,0.98,-0.0075,-0.011,0.19,0.0033,-0.019,0.028,0.0084,-0.011,0.023,-0.0013,-0.0059,-0.00011,0.011,0.0022,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.016,0.016,0.0077,0.04,0.04,0.035,8.2e-07,8.2e-07,2.3e-06,0.035,0.035,0.00031,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 +19690000,0.98,-0.0075,-0.011,0.19,0.002,-0.018,0.026,0.0087,-0.012,0.023,-0.0013,-0.0059,-0.00011,0.011,0.0022,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00042,0.066,0.018,0.018,0.0078,0.044,0.044,0.035,8.2e-07,8.2e-07,2.3e-06,0.035,0.035,0.0003,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 +19790000,0.98,-0.0076,-0.011,0.19,0.00072,-0.016,0.025,0.0099,-0.011,0.019,-0.0013,-0.0059,-0.00011,0.011,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.016,0.016,0.0077,0.04,0.04,0.035,8e-07,8e-07,2.3e-06,0.035,0.035,0.0003,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 +19890000,0.98,-0.0076,-0.011,0.19,0.0011,-0.017,0.025,0.0099,-0.012,0.017,-0.0013,-0.0059,-0.00011,0.011,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.017,0.017,0.0077,0.044,0.044,0.035,8e-07,8e-07,2.3e-06,0.035,0.035,0.00029,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 +19990000,0.98,-0.0076,-0.011,0.19,0.0004,-0.016,0.022,0.0093,-0.0099,0.014,-0.0013,-0.0059,-0.00011,0.012,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.016,0.016,0.0076,0.04,0.04,0.035,7.7e-07,7.7e-07,2.3e-06,0.035,0.035,0.00029,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 +20090000,0.98,-0.0076,-0.011,0.19,0.0013,-0.019,0.022,0.0094,-0.012,0.018,-0.0013,-0.0059,-0.00011,0.012,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.017,0.017,0.0076,0.044,0.044,0.035,7.7e-07,7.8e-07,2.3e-06,0.035,0.035,0.00028,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5.1 +20190000,0.98,-0.0076,-0.011,0.19,0.0016,-0.016,0.023,0.0097,-0.01,0.017,-0.0013,-0.0059,-0.00011,0.013,0.0014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.016,0.016,0.0075,0.039,0.039,0.035,7.5e-07,7.5e-07,2.3e-06,0.035,0.035,0.00028,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +20290000,0.98,-0.0076,-0.011,0.19,-0.0012,-0.018,0.023,0.0097,-0.012,0.018,-0.0013,-0.0059,-0.00011,0.013,0.0014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.017,0.017,0.0075,0.043,0.043,0.035,7.5e-07,7.5e-07,2.3e-06,0.035,0.035,0.00028,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +20390000,0.98,-0.0076,-0.011,0.19,-0.0026,-0.016,0.024,0.0098,-0.01,0.019,-0.0013,-0.0059,-0.00011,0.014,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.016,0.016,0.0075,0.039,0.039,0.035,7.3e-07,7.3e-07,2.3e-06,0.034,0.034,0.00027,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +20490000,0.98,-0.0076,-0.011,0.18,-0.007,-0.018,0.024,0.0093,-0.012,0.017,-0.0013,-0.0059,-0.00011,0.014,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.017,0.017,0.0075,0.043,0.043,0.035,7.3e-07,7.3e-07,2.3e-06,0.034,0.034,0.00027,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +20590000,0.98,-0.0075,-0.011,0.18,-0.0069,-0.018,0.023,0.0095,-0.01,0.016,-0.0013,-0.0059,-0.00011,0.014,0.00077,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00039,0.00039,0.066,0.016,0.016,0.0074,0.039,0.039,0.035,7e-07,7.1e-07,2.3e-06,0.034,0.034,0.00026,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +20690000,0.98,-0.0075,-0.011,0.18,-0.0084,-0.018,0.024,0.0087,-0.012,0.016,-0.0013,-0.0059,-0.00011,0.014,0.00078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.017,0.017,0.0074,0.043,0.043,0.035,7.1e-07,7.1e-07,2.3e-06,0.034,0.034,0.00026,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +20790000,0.98,-0.0069,-0.011,0.18,-0.011,-0.014,0.009,0.0072,-0.011,0.015,-0.0013,-0.0059,-0.00011,0.015,0.00054,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.11,0.00039,0.00039,0.066,0.016,0.016,0.0073,0.039,0.039,0.035,6.8e-07,6.9e-07,2.3e-06,0.034,0.034,0.00025,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +20890000,0.98,0.0023,-0.0074,0.18,-0.017,-0.0032,-0.11,0.0057,-0.011,0.0085,-0.0013,-0.0059,-0.00011,0.015,0.00055,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.11,0.00039,0.00039,0.066,0.017,0.017,0.0073,0.043,0.043,0.035,6.8e-07,6.9e-07,2.3e-06,0.034,0.034,0.00025,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +20990000,0.98,0.0056,-0.0039,0.18,-0.029,0.016,-0.25,0.0041,-0.009,-0.0065,-0.0013,-0.0059,-0.00011,0.015,5.1e-05,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.093,0.00039,0.00039,0.066,0.016,0.016,0.0072,0.039,0.039,0.034,6.6e-07,6.6e-07,2.3e-06,0.033,0.033,0.00025,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +21090000,0.98,0.004,-0.0043,0.18,-0.042,0.031,-0.37,0.00064,-0.0066,-0.037,-0.0013,-0.0059,-0.00011,0.015,5e-05,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.063,0.00039,0.00039,0.066,0.017,0.017,0.0072,0.043,0.043,0.035,6.6e-07,6.7e-07,2.3e-06,0.033,0.033,0.00024,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +21190000,0.98,0.0012,-0.0059,0.19,-0.047,0.038,-0.49,-0.00032,-0.0049,-0.074,-0.0013,-0.0059,-0.00011,0.014,-0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.026,0.00038,0.00038,0.066,0.016,0.016,0.0071,0.039,0.039,0.035,6.4e-07,6.4e-07,2.3e-06,0.033,0.033,0.00024,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +21290000,0.98,-0.001,-0.0072,0.19,-0.047,0.04,-0.62,-0.005,-0.00096,-0.13,-0.0013,-0.0059,-0.00011,0.014,-0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.032,0.00038,0.00038,0.066,0.018,0.018,0.0071,0.043,0.043,0.035,6.4e-07,6.4e-07,2.3e-06,0.033,0.033,0.00024,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +21390000,0.98,-0.0025,-0.0079,0.19,-0.043,0.038,-0.75,-0.0049,0.0031,-0.2,-0.0013,-0.0059,-0.00011,0.014,-0.0025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.097,0.00038,0.00038,0.066,0.016,0.016,0.007,0.039,0.039,0.035,6.2e-07,6.2e-07,2.3e-06,0.032,0.032,0.00023,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +21490000,0.98,-0.0033,-0.0083,0.19,-0.038,0.034,-0.89,-0.009,0.0067,-0.28,-0.0013,-0.0059,-0.00011,0.014,-0.0025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.18,0.00038,0.00038,0.066,0.018,0.018,0.007,0.043,0.043,0.035,6.2e-07,6.2e-07,2.3e-06,0.032,0.032,0.00023,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +21590000,0.98,-0.0038,-0.0083,0.19,-0.03,0.031,-1,-0.0081,0.0087,-0.37,-0.0013,-0.0059,-0.00011,0.015,-0.0031,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.27,0.00037,0.00037,0.066,0.017,0.017,0.0069,0.039,0.039,0.034,6e-07,6e-07,2.3e-06,0.032,0.032,0.00023,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +21690000,0.98,-0.0041,-0.0081,0.19,-0.028,0.026,-1.1,-0.011,0.012,-0.49,-0.0013,-0.0059,-0.00011,0.014,-0.003,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.39,0.00037,0.00037,0.066,0.018,0.018,0.0069,0.043,0.043,0.035,6e-07,6e-07,2.3e-06,0.032,0.032,0.00022,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +21790000,0.98,-0.0045,-0.0083,0.19,-0.021,0.021,-1.3,-0.0047,0.01,-0.61,-0.0013,-0.0059,-0.00011,0.015,-0.0043,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.51,0.00036,0.00036,0.066,0.017,0.017,0.0069,0.039,0.039,0.034,5.8e-07,5.8e-07,2.3e-06,0.032,0.032,0.00022,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +21890000,0.98,-0.0048,-0.0085,0.19,-0.018,0.016,-1.4,-0.0066,0.012,-0.75,-0.0013,-0.0059,-0.00011,0.015,-0.0042,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.65,0.00036,0.00036,0.066,0.018,0.018,0.0068,0.043,0.043,0.034,5.8e-07,5.8e-07,2.3e-06,0.032,0.032,0.00022,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +21990000,0.98,-0.0055,-0.0087,0.19,-0.014,0.011,-1.4,-0.0012,0.0091,-0.88,-0.0013,-0.0059,-0.00011,0.015,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.78,0.00036,0.00036,0.066,0.017,0.017,0.0068,0.039,0.039,0.034,5.6e-07,5.6e-07,2.3e-06,0.031,0.031,0.00021,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22090000,0.98,-0.0062,-0.0095,0.19,-0.012,0.0068,-1.4,-0.0026,0.0099,-1,-0.0013,-0.0059,-0.00011,0.015,-0.004,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.93,0.00036,0.00036,0.066,0.018,0.018,0.0068,0.043,0.043,0.034,5.6e-07,5.6e-07,2.3e-06,0.031,0.031,0.00021,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22190000,0.98,-0.0067,-0.0098,0.19,-0.0041,0.002,-1.4,0.005,0.0053,-1.2,-0.0013,-0.0059,-0.00011,0.015,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.1,0.00035,0.00035,0.066,0.016,0.016,0.0067,0.039,0.039,0.034,5.5e-07,5.4e-07,2.3e-06,0.031,0.031,0.00021,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22290000,0.98,-0.0074,-0.01,0.19,0.00091,-0.0037,-1.4,0.0048,0.0052,-1.3,-0.0013,-0.0059,-0.00011,0.015,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.2,0.00035,0.00035,0.066,0.017,0.017,0.0067,0.043,0.043,0.034,5.5e-07,5.5e-07,2.3e-06,0.031,0.031,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22390000,0.98,-0.0077,-0.01,0.19,0.006,-0.012,-1.4,0.012,-0.003,-1.5,-0.0013,-0.0059,-0.00011,0.014,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.4,0.00034,0.00034,0.066,0.016,0.016,0.0066,0.039,0.039,0.034,5.3e-07,5.3e-07,2.3e-06,0.03,0.03,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22490000,0.98,-0.0078,-0.011,0.19,0.0098,-0.018,-1.4,0.013,-0.0046,-1.6,-0.0013,-0.0059,-0.00011,0.014,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.5,0.00034,0.00034,0.066,0.017,0.017,0.0066,0.043,0.043,0.034,5.3e-07,5.3e-07,2.3e-06,0.03,0.03,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22590000,0.98,-0.0078,-0.011,0.19,0.019,-0.026,-1.4,0.025,-0.012,-1.7,-0.0013,-0.0059,-0.00011,0.014,-0.0044,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.6,0.00034,0.00034,0.066,0.016,0.016,0.0065,0.039,0.039,0.034,5.1e-07,5.1e-07,2.3e-06,0.03,0.03,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22690000,0.98,-0.0077,-0.011,0.19,0.021,-0.031,-1.4,0.027,-0.015,-1.9,-0.0013,-0.0059,-0.00011,0.014,-0.0043,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.8,0.00034,0.00034,0.066,0.017,0.017,0.0065,0.043,0.043,0.034,5.1e-07,5.1e-07,2.3e-06,0.03,0.03,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22790000,0.98,-0.0077,-0.012,0.19,0.027,-0.038,-1.4,0.037,-0.024,-2,-0.0013,-0.0059,-0.00011,0.014,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.9,0.00033,0.00033,0.066,0.015,0.015,0.0065,0.039,0.039,0.034,5e-07,5e-07,2.3e-06,0.03,0.03,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22890000,0.98,-0.0078,-0.012,0.19,0.03,-0.044,-1.4,0.04,-0.028,-2.2,-0.0013,-0.0059,-0.00011,0.014,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.1,0.00033,0.00033,0.066,0.016,0.016,0.0065,0.043,0.043,0.034,5e-07,5e-07,2.3e-06,0.03,0.03,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +22990000,0.98,-0.0078,-0.013,0.18,0.035,-0.049,-1.4,0.05,-0.038,-2.3,-0.0013,-0.0059,-0.00011,0.015,-0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.2,0.00033,0.00033,0.066,0.015,0.015,0.0064,0.039,0.039,0.034,4.8e-07,4.8e-07,2.3e-06,0.029,0.029,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23090000,0.98,-0.0078,-0.013,0.18,0.04,-0.054,-1.4,0.054,-0.043,-2.5,-0.0013,-0.0059,-0.00011,0.014,-0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.4,0.00033,0.00033,0.066,0.016,0.016,0.0064,0.043,0.043,0.034,4.8e-07,4.8e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23190000,0.98,-0.0078,-0.013,0.18,0.046,-0.055,-1.4,0.065,-0.052,-2.6,-0.0013,-0.0059,-0.00011,0.015,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.5,0.00032,0.00032,0.066,0.015,0.015,0.0063,0.039,0.039,0.033,4.7e-07,4.7e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23290000,0.98,-0.0083,-0.013,0.18,0.051,-0.06,-1.4,0.07,-0.058,-2.8,-0.0013,-0.0059,-0.00011,0.015,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.7,0.00032,0.00032,0.066,0.016,0.016,0.0063,0.043,0.043,0.034,4.7e-07,4.7e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23390000,0.98,-0.0082,-0.013,0.18,0.057,-0.062,-1.4,0.081,-0.063,-2.9,-0.0013,-0.0059,-0.00011,0.016,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.8,0.00032,0.00032,0.066,0.015,0.015,0.0063,0.039,0.039,0.033,4.6e-07,4.6e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23490000,0.98,-0.0083,-0.014,0.18,0.061,-0.065,-1.4,0.087,-0.069,-3,-0.0013,-0.0059,-0.00011,0.016,-0.0034,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.9,0.00032,0.00032,0.066,0.016,0.016,0.0063,0.043,0.043,0.033,4.6e-07,4.6e-07,2.3e-06,0.029,0.029,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23590000,0.98,-0.0085,-0.014,0.18,0.064,-0.067,-1.4,0.095,-0.078,-3.2,-0.0013,-0.0059,-0.00011,0.017,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.1,0.00031,0.00031,0.066,0.014,0.014,0.0062,0.039,0.039,0.033,4.5e-07,4.5e-07,2.3e-06,0.029,0.029,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23690000,0.98,-0.0091,-0.014,0.18,0.062,-0.07,-1.3,0.1,-0.085,-3.3,-0.0013,-0.0059,-0.00011,0.017,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.2,0.00031,0.00031,0.066,0.015,0.015,0.0062,0.042,0.042,0.033,4.5e-07,4.5e-07,2.3e-06,0.029,0.029,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23790000,0.98,-0.011,-0.017,0.18,0.057,-0.067,-0.95,0.11,-0.089,-3.4,-0.0013,-0.0059,-0.00011,0.018,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.3,0.00031,0.00031,0.066,0.014,0.014,0.0061,0.038,0.038,0.033,4.4e-07,4.4e-07,2.3e-06,0.028,0.028,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23890000,0.98,-0.014,-0.021,0.18,0.052,-0.068,-0.52,0.12,-0.096,-3.5,-0.0013,-0.0059,-0.00011,0.018,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00031,0.00031,0.066,0.014,0.014,0.0061,0.042,0.042,0.033,4.4e-07,4.4e-07,2.3e-06,0.028,0.028,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +23990000,0.98,-0.016,-0.024,0.18,0.054,-0.066,-0.13,0.13,-0.097,-3.6,-0.0013,-0.0059,-0.00011,0.02,-0.0031,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.013,0.013,0.0061,0.038,0.038,0.033,4.3e-07,4.3e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24090000,0.98,-0.016,-0.023,0.18,0.06,-0.075,0.099,0.13,-0.1,-3.6,-0.0013,-0.0059,-0.00011,0.02,-0.003,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.014,0.014,0.0061,0.042,0.042,0.033,4.3e-07,4.3e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24190000,0.98,-0.013,-0.019,0.18,0.071,-0.08,0.089,0.14,-0.11,-3.6,-0.0013,-0.0059,-0.00011,0.021,-0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.013,0.013,0.006,0.038,0.038,0.033,4.2e-07,4.2e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24290000,0.98,-0.011,-0.016,0.18,0.075,-0.084,0.067,0.15,-0.12,-3.6,-0.0013,-0.0059,-0.00011,0.021,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.014,0.014,0.006,0.042,0.042,0.033,4.2e-07,4.2e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24390000,0.98,-0.0099,-0.015,0.18,0.069,-0.078,0.083,0.15,-0.12,-3.6,-0.0013,-0.0059,-0.00011,0.023,-0.0046,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.0003,0.0003,0.066,0.013,0.013,0.006,0.038,0.038,0.033,4.1e-07,4.1e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24490000,0.98,-0.01,-0.015,0.18,0.064,-0.076,0.081,0.16,-0.12,-3.6,-0.0013,-0.0059,-0.00011,0.023,-0.0046,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.0003,0.0003,0.066,0.014,0.014,0.006,0.041,0.041,0.033,4.1e-07,4.1e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24590000,0.98,-0.011,-0.015,0.19,0.061,-0.072,0.077,0.16,-0.12,-3.6,-0.0014,-0.0059,-0.00011,0.024,-0.0058,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.0003,0.0003,0.066,0.013,0.013,0.0059,0.038,0.038,0.033,4e-07,4e-07,2.3e-06,0.028,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24690000,0.98,-0.011,-0.015,0.19,0.059,-0.072,0.076,0.17,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.024,-0.0058,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0059,0.041,0.041,0.033,4e-07,4e-07,2.3e-06,0.028,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24790000,0.98,-0.011,-0.014,0.19,0.056,-0.069,0.068,0.17,-0.12,-3.5,-0.0014,-0.0059,-0.00011,0.026,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.013,0.013,0.0059,0.038,0.038,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24890000,0.98,-0.011,-0.014,0.19,0.054,-0.073,0.057,0.18,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.026,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0059,0.041,0.041,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +24990000,0.98,-0.011,-0.014,0.19,0.045,-0.069,0.05,0.18,-0.12,-3.5,-0.0014,-0.0059,-0.00011,0.029,-0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.013,0.013,0.0058,0.037,0.037,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25090000,0.98,-0.011,-0.014,0.19,0.042,-0.068,0.048,0.18,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.029,-0.0077,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0058,0.041,0.041,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25190000,0.98,-0.011,-0.014,0.19,0.037,-0.062,0.048,0.18,-0.12,-3.5,-0.0014,-0.0059,-0.00011,0.031,-0.0089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0058,0.037,0.037,0.032,3.8e-07,3.8e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25290000,0.98,-0.012,-0.013,0.19,0.032,-0.064,0.042,0.19,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.031,-0.0088,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0058,0.041,0.041,0.032,3.8e-07,3.8e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25390000,0.98,-0.012,-0.013,0.19,0.024,-0.056,0.041,0.18,-0.11,-3.5,-0.0014,-0.0058,-0.0001,0.033,-0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0058,0.037,0.037,0.032,3.7e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25490000,0.98,-0.012,-0.013,0.19,0.019,-0.057,0.041,0.18,-0.12,-3.5,-0.0014,-0.0058,-0.0001,0.033,-0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0058,0.041,0.041,0.032,3.7e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25590000,0.98,-0.012,-0.013,0.19,0.014,-0.052,0.042,0.18,-0.11,-3.5,-0.0014,-0.0058,-0.0001,0.035,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0057,0.037,0.037,0.032,3.6e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25690000,0.98,-0.011,-0.012,0.19,0.013,-0.052,0.031,0.18,-0.12,-3.5,-0.0014,-0.0058,-0.0001,0.035,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0057,0.041,0.041,0.032,3.7e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25790000,0.98,-0.011,-0.012,0.19,0.0025,-0.043,0.031,0.17,-0.1,-3.5,-0.0015,-0.0058,-0.0001,0.037,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0057,0.037,0.037,0.032,3.6e-07,3.6e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25890000,0.98,-0.011,-0.012,0.19,-0.0031,-0.042,0.033,0.17,-0.11,-3.5,-0.0015,-0.0058,-0.0001,0.037,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0057,0.041,0.041,0.032,3.6e-07,3.6e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +25990000,0.98,-0.011,-0.012,0.19,-0.012,-0.034,0.027,0.16,-0.098,-3.5,-0.0015,-0.0058,-0.0001,0.039,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0057,0.037,0.037,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26090000,0.98,-0.011,-0.012,0.19,-0.017,-0.035,0.025,0.16,-0.1,-3.5,-0.0015,-0.0058,-0.0001,0.039,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0057,0.041,0.041,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26190000,0.98,-0.011,-0.012,0.19,-0.023,-0.027,0.021,0.15,-0.093,-3.5,-0.0015,-0.0058,-0.0001,0.04,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0056,0.037,0.037,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26290000,0.98,-0.011,-0.013,0.19,-0.024,-0.027,0.015,0.15,-0.096,-3.5,-0.0015,-0.0058,-0.0001,0.04,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26390000,0.98,-0.01,-0.013,0.19,-0.03,-0.019,0.019,0.14,-0.086,-3.5,-0.0015,-0.0058,-0.0001,0.041,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0056,0.037,0.037,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26490000,0.98,-0.0099,-0.013,0.19,-0.033,-0.016,0.028,0.13,-0.088,-3.5,-0.0015,-0.0058,-0.0001,0.041,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26590000,0.98,-0.0093,-0.013,0.19,-0.035,-0.0072,0.029,0.12,-0.08,-3.5,-0.0015,-0.0058,-0.0001,0.042,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0056,0.037,0.037,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26690000,0.98,-0.0091,-0.013,0.19,-0.037,-0.0027,0.027,0.12,-0.08,-3.5,-0.0015,-0.0058,-0.0001,0.042,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26790000,0.98,-0.0089,-0.012,0.19,-0.044,0.0018,0.027,0.11,-0.073,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26890000,0.98,-0.0083,-0.012,0.19,-0.049,0.0045,0.022,0.1,-0.073,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +26990000,0.98,-0.0077,-0.013,0.19,-0.056,0.012,0.021,0.089,-0.065,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27090000,0.98,-0.0076,-0.013,0.19,-0.058,0.019,0.025,0.084,-0.064,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0055,0.041,0.041,0.031,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27190000,0.98,-0.0076,-0.013,0.19,-0.064,0.025,0.027,0.073,-0.056,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27290000,0.98,-0.0078,-0.014,0.19,-0.071,0.03,0.14,0.066,-0.053,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.014,0.014,0.0055,0.041,0.041,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.026,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27390000,0.98,-0.0092,-0.016,0.18,-0.077,0.037,0.46,0.056,-0.045,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27490000,0.98,-0.011,-0.018,0.18,-0.081,0.042,0.78,0.048,-0.041,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.014,0.013,0.0055,0.04,0.04,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27590000,0.98,-0.01,-0.017,0.18,-0.076,0.046,0.87,0.04,-0.035,-3.4,-0.0015,-0.0058,-0.0001,0.044,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.3,0.00029,0.00029,0.065,0.013,0.012,0.0055,0.037,0.037,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27690000,0.98,-0.0092,-0.014,0.18,-0.072,0.042,0.78,0.032,-0.03,-3.3,-0.0015,-0.0058,-0.0001,0.044,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.2,0.00029,0.00029,0.065,0.014,0.013,0.0055,0.04,0.04,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27790000,0.98,-0.0079,-0.013,0.18,-0.071,0.04,0.77,0.026,-0.027,-3.2,-0.0015,-0.0058,-0.0001,0.043,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.1,0.00029,0.00029,0.065,0.013,0.012,0.0054,0.037,0.037,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27890000,0.98,-0.0075,-0.013,0.18,-0.078,0.047,0.81,0.018,-0.022,-3.2,-0.0015,-0.0058,-0.0001,0.043,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.1,0.00029,0.00029,0.065,0.014,0.013,0.0054,0.04,0.04,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +27990000,0.98,-0.008,-0.013,0.18,-0.078,0.049,0.8,0.013,-0.019,-3.1,-0.0015,-0.0058,-0.0001,0.042,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3,0.00029,0.00029,0.065,0.013,0.012,0.0054,0.037,0.037,0.031,3.1e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28090000,0.98,-0.0083,-0.013,0.18,-0.081,0.05,0.8,0.0049,-0.014,-3,-0.0015,-0.0058,-0.0001,0.042,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.9,0.00029,0.00029,0.065,0.014,0.013,0.0054,0.04,0.04,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28190000,0.98,-0.0078,-0.013,0.18,-0.082,0.047,0.81,-0.0019,-0.012,-2.9,-0.0015,-0.0058,-0.0001,0.041,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.8,0.00029,0.00029,0.064,0.013,0.012,0.0054,0.037,0.037,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28290000,0.98,-0.0073,-0.014,0.18,-0.087,0.05,0.81,-0.01,-0.0074,-2.9,-0.0015,-0.0058,-0.0001,0.041,-0.015,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.8,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28390000,0.98,-0.0073,-0.014,0.18,-0.087,0.054,0.81,-0.015,-0.0032,-2.8,-0.0015,-0.0058,-0.0001,0.041,-0.015,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.7,0.00029,0.00029,0.064,0.013,0.012,0.0054,0.037,0.037,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28490000,0.98,-0.0076,-0.015,0.18,-0.089,0.058,0.81,-0.024,0.0024,-2.7,-0.0015,-0.0058,-0.0001,0.041,-0.015,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.6,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28590000,0.98,-0.0077,-0.015,0.18,-0.082,0.053,0.81,-0.027,0.0014,-2.6,-0.0015,-0.0058,-0.0001,0.039,-0.016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.5,0.00029,0.00029,0.064,0.013,0.012,0.0054,0.037,0.037,0.031,3e-07,2.9e-07,2.4e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28690000,0.98,-0.0075,-0.014,0.18,-0.082,0.054,0.81,-0.036,0.0069,-2.6,-0.0015,-0.0058,-0.0001,0.039,-0.016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.5,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,3e-07,3e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28790000,0.98,-0.0068,-0.014,0.18,-0.079,0.055,0.81,-0.038,0.0098,-2.5,-0.0014,-0.0058,-9.9e-05,0.039,-0.017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.4,0.00029,0.00029,0.064,0.013,0.012,0.0053,0.037,0.037,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28890000,0.98,-0.0067,-0.013,0.18,-0.083,0.056,0.81,-0.046,0.015,-2.4,-0.0014,-0.0058,-9.9e-05,0.039,-0.017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.3,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +28990000,0.98,-0.0065,-0.014,0.18,-0.079,0.054,0.81,-0.046,0.016,-2.3,-0.0014,-0.0058,-9.9e-05,0.037,-0.018,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.2,0.00029,0.00029,0.064,0.013,0.012,0.0053,0.037,0.037,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29090000,0.98,-0.0064,-0.014,0.18,-0.081,0.056,0.81,-0.054,0.021,-2.3,-0.0014,-0.0058,-9.9e-05,0.038,-0.018,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.2,0.00029,0.00029,0.064,0.013,0.013,0.0053,0.04,0.04,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29190000,0.98,-0.0064,-0.014,0.18,-0.077,0.055,0.8,-0.051,0.021,-2.2,-0.0014,-0.0058,-9.8e-05,0.036,-0.019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.1,0.00029,0.00029,0.063,0.013,0.012,0.0053,0.037,0.037,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29290000,0.98,-0.0067,-0.014,0.18,-0.079,0.061,0.81,-0.059,0.027,-2.1,-0.0014,-0.0058,-9.8e-05,0.037,-0.019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2,0.00029,0.00029,0.063,0.014,0.013,0.0053,0.04,0.04,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29390000,0.98,-0.0072,-0.013,0.18,-0.074,0.06,0.81,-0.058,0.029,-2,-0.0014,-0.0058,-9.7e-05,0.036,-0.02,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.9,0.00029,0.00029,0.063,0.013,0.012,0.0053,0.037,0.037,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29490000,0.98,-0.0072,-0.013,0.18,-0.077,0.06,0.81,-0.065,0.035,-2,-0.0014,-0.0058,-9.7e-05,0.036,-0.02,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.9,0.00029,0.00029,0.063,0.013,0.013,0.0053,0.04,0.04,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29590000,0.98,-0.0071,-0.013,0.18,-0.073,0.058,0.81,-0.063,0.035,-1.9,-0.0014,-0.0058,-9.7e-05,0.035,-0.021,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.8,0.00029,0.00029,0.063,0.013,0.012,0.0053,0.037,0.037,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29690000,0.98,-0.0072,-0.013,0.18,-0.077,0.057,0.81,-0.07,0.041,-1.8,-0.0014,-0.0058,-9.7e-05,0.035,-0.021,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.7,0.00029,0.00029,0.063,0.013,0.013,0.0053,0.04,0.04,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29790000,0.98,-0.0071,-0.013,0.18,-0.073,0.051,0.8,-0.065,0.039,-1.7,-0.0014,-0.0058,-9.6e-05,0.034,-0.022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.6,0.00029,0.00029,0.063,0.012,0.012,0.0053,0.037,0.037,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29890000,0.98,-0.0065,-0.014,0.18,-0.073,0.052,0.8,-0.073,0.044,-1.7,-0.0014,-0.0058,-9.6e-05,0.034,-0.023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.6,0.00029,0.00029,0.063,0.013,0.013,0.0053,0.04,0.04,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +29990000,0.98,-0.0068,-0.014,0.18,-0.068,0.047,0.8,-0.068,0.04,-1.6,-0.0014,-0.0058,-9.6e-05,0.033,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.5,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.8e-07,2.8e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30090000,0.98,-0.0069,-0.014,0.18,-0.068,0.048,0.8,-0.075,0.045,-1.5,-0.0014,-0.0058,-9.6e-05,0.033,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.4,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.8e-07,2.8e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30190000,0.98,-0.0069,-0.014,0.18,-0.062,0.045,0.8,-0.068,0.044,-1.5,-0.0014,-0.0058,-9.5e-05,0.032,-0.025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.4,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.031,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30290000,0.98,-0.007,-0.014,0.18,-0.061,0.045,0.8,-0.075,0.048,-1.4,-0.0014,-0.0058,-9.5e-05,0.032,-0.025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.3,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30390000,0.98,-0.007,-0.014,0.18,-0.054,0.039,0.8,-0.066,0.046,-1.3,-0.0014,-0.0057,-9.4e-05,0.032,-0.027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.2,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30490000,0.98,-0.007,-0.014,0.18,-0.057,0.039,0.8,-0.072,0.05,-1.2,-0.0014,-0.0057,-9.4e-05,0.032,-0.027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.1,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.031,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30590000,0.98,-0.0074,-0.014,0.18,-0.052,0.036,0.8,-0.065,0.046,-1.2,-0.0014,-0.0057,-9.4e-05,0.031,-0.028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.1,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30690000,0.98,-0.0078,-0.014,0.18,-0.05,0.035,0.8,-0.07,0.05,-1.1,-0.0014,-0.0057,-9.4e-05,0.031,-0.028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30790000,0.98,-0.0075,-0.014,0.18,-0.043,0.03,0.8,-0.063,0.049,-1,-0.0013,-0.0057,-9.3e-05,0.031,-0.029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.92,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30890000,0.98,-0.0069,-0.014,0.18,-0.044,0.026,0.79,-0.067,0.052,-0.95,-0.0013,-0.0057,-9.3e-05,0.031,-0.03,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.85,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +30990000,0.98,-0.0071,-0.014,0.18,-0.036,0.021,0.79,-0.057,0.045,-0.88,-0.0013,-0.0057,-9.3e-05,0.03,-0.031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.78,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31090000,0.98,-0.0073,-0.014,0.18,-0.035,0.02,0.79,-0.061,0.047,-0.81,-0.0013,-0.0057,-9.3e-05,0.03,-0.031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.71,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31190000,0.98,-0.0075,-0.014,0.18,-0.03,0.015,0.8,-0.052,0.042,-0.74,-0.0013,-0.0057,-9.3e-05,0.03,-0.032,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.64,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31290000,0.98,-0.0078,-0.014,0.18,-0.028,0.013,0.8,-0.055,0.044,-0.67,-0.0013,-0.0057,-9.3e-05,0.03,-0.032,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.57,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31390000,0.98,-0.0076,-0.014,0.18,-0.022,0.0066,0.8,-0.047,0.039,-0.59,-0.0013,-0.0057,-9.2e-05,0.03,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.49,0.00029,0.00029,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31490000,0.98,-0.0073,-0.014,0.18,-0.022,0.0035,0.8,-0.049,0.039,-0.52,-0.0013,-0.0057,-9.2e-05,0.03,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.42,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31590000,0.98,-0.0072,-0.015,0.18,-0.018,0.0016,0.8,-0.038,0.035,-0.45,-0.0013,-0.0057,-9.2e-05,0.03,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.35,0.00028,0.00029,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31690000,0.98,-0.0072,-0.015,0.18,-0.02,0.00032,0.8,-0.04,0.035,-0.38,-0.0013,-0.0057,-9.2e-05,0.03,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.28,0.00029,0.00029,0.063,0.013,0.013,0.0051,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31790000,0.98,-0.0075,-0.016,0.18,-0.011,-0.0021,0.8,-0.029,0.034,-0.3,-0.0013,-0.0057,-9.2e-05,0.031,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.2,0.00028,0.00028,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31890000,0.98,-0.0072,-0.016,0.18,-0.008,-0.0047,0.8,-0.029,0.034,-0.24,-0.0013,-0.0057,-9.2e-05,0.031,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.14,0.00028,0.00028,0.063,0.013,0.013,0.0051,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +31990000,0.98,-0.0075,-0.015,0.18,-0.00019,-0.0051,0.79,-0.018,0.031,-0.17,-0.0013,-0.0057,-9.2e-05,0.031,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.068,0.00028,0.00028,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32090000,0.98,-0.0079,-0.015,0.18,-0.00077,-0.0087,0.8,-0.018,0.03,-0.096,-0.0013,-0.0057,-9.2e-05,0.031,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.004,0.00028,0.00028,0.063,0.013,0.013,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32190000,0.98,-0.0081,-0.015,0.18,0.0045,-0.012,0.8,-0.0066,0.029,-0.028,-0.0013,-0.0057,-9.1e-05,0.032,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.072,0.00028,0.00028,0.062,0.012,0.012,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32290000,0.98,-0.008,-0.015,0.18,0.006,-0.015,0.8,-0.0061,0.028,0.042,-0.0013,-0.0057,-9.1e-05,0.032,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.14,0.00028,0.00028,0.062,0.013,0.013,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32390000,0.98,-0.0082,-0.015,0.18,0.012,-0.016,0.79,0.0052,0.026,0.12,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.22,0.00028,0.00028,0.062,0.012,0.012,0.0051,0.036,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32490000,0.98,-0.011,-0.013,0.18,0.039,-0.082,-0.077,0.0084,0.019,0.12,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.22,0.00028,0.00028,0.062,0.015,0.015,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32590000,0.98,-0.011,-0.013,0.18,0.04,-0.083,-0.08,0.02,0.016,0.1,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.2,0.00028,0.00028,0.062,0.014,0.014,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32690000,0.98,-0.011,-0.013,0.18,0.036,-0.088,-0.081,0.024,0.007,0.088,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.19,0.00028,0.00028,0.062,0.015,0.014,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32790000,0.98,-0.011,-0.013,0.18,0.035,-0.087,-0.082,0.034,0.0051,0.072,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.17,0.00028,0.00027,0.062,0.014,0.013,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32890000,0.98,-0.011,-0.013,0.18,0.035,-0.094,-0.084,0.037,-0.0039,0.058,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.16,0.00028,0.00028,0.062,0.015,0.014,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +32990000,0.98,-0.011,-0.013,0.18,0.033,-0.093,-0.083,0.045,-0.0074,0.044,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.14,0.00027,0.00027,0.062,0.014,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33090000,0.98,-0.011,-0.013,0.18,0.03,-0.097,-0.08,0.049,-0.017,0.037,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.14,0.00027,0.00027,0.062,0.015,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33190000,0.98,-0.011,-0.013,0.18,0.027,-0.097,-0.079,0.055,-0.019,0.029,-0.0014,-0.0057,-9.1e-05,0.034,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.13,0.00027,0.00027,0.061,0.014,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33290000,0.98,-0.011,-0.013,0.18,0.024,-0.1,-0.079,0.057,-0.029,0.021,-0.0014,-0.0057,-9.1e-05,0.034,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.015,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 +33390000,0.98,-0.011,-0.014,0.18,0.021,-0.094,-0.077,0.061,-0.026,0.012,-0.0014,-0.0057,-9.1e-05,0.035,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.014,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.033 +33490000,0.98,-0.01,-0.013,0.18,0.017,-0.097,-0.076,0.063,-0.036,0.0025,-0.0014,-0.0057,-9.1e-05,0.035,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.015,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.7e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.058 +33590000,0.98,-0.01,-0.014,0.18,0.014,-0.096,-0.073,0.065,-0.033,-0.0054,-0.0014,-0.0057,-9e-05,0.037,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.014,0.013,0.005,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.7e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.083 +33690000,0.98,-0.01,-0.014,0.18,0.01,-0.099,-0.074,0.066,-0.043,-0.013,-0.0014,-0.0057,-9e-05,0.037,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.014,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.7e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.11 +33790000,0.98,-0.01,-0.014,0.18,0.0061,-0.096,-0.069,0.07,-0.04,-0.02,-0.0014,-0.0057,-9e-05,0.039,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.061,0.013,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.6e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.13 +33890000,0.98,-0.01,-0.014,0.18,0.0027,-0.098,-0.068,0.07,-0.049,-0.027,-0.0014,-0.0057,-9e-05,0.039,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.061,0.014,0.014,0.0051,0.041,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.6e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.16 +33990000,0.98,-0.01,-0.014,0.18,0.00041,-0.092,-0.065,0.072,-0.044,-0.031,-0.0014,-0.0056,-9e-05,0.04,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.013,0.005,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.6e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.18 +34090000,0.98,-0.01,-0.014,0.18,-0.0035,-0.097,-0.063,0.072,-0.053,-0.035,-0.0014,-0.0056,-9e-05,0.04,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.014,0.0051,0.041,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.21 +34190000,0.98,-0.0099,-0.014,0.18,-0.0066,-0.092,-0.06,0.074,-0.047,-0.039,-0.0014,-0.0056,-9e-05,0.042,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.013,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.23 +34290000,0.98,-0.0097,-0.014,0.18,-0.0069,-0.096,-0.059,0.073,-0.057,-0.044,-0.0014,-0.0056,-9e-05,0.042,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.013,0.005,0.041,0.04,0.03,2.4e-07,2.3e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.26 +34390000,0.98,-0.0096,-0.014,0.18,-0.01,-0.09,-0.054,0.074,-0.051,-0.049,-0.0014,-0.0056,-8.9e-05,0.043,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.013,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.28 +34490000,0.98,-0.0096,-0.014,0.18,-0.013,-0.094,-0.053,0.072,-0.06,-0.051,-0.0014,-0.0056,-8.9e-05,0.043,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.013,0.005,0.041,0.04,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.4e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.31 +34590000,0.98,-0.0095,-0.014,0.18,-0.017,-0.085,0.74,0.073,-0.054,-0.023,-0.0014,-0.0056,-8.9e-05,0.045,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.012,0.012,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.4e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.33 +34690000,0.98,-0.0095,-0.013,0.18,-0.022,-0.084,1.7,0.071,-0.062,0.096,-0.0014,-0.0056,-8.9e-05,0.045,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.012,0.0051,0.04,0.04,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.4e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.36 +34790000,0.98,-0.0094,-0.013,0.18,-0.027,-0.074,2.7,0.071,-0.056,0.28,-0.0014,-0.0056,-8.8e-05,0.047,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.012,0.012,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.3e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.38 +34890000,0.98,-0.0094,-0.013,0.18,-0.033,-0.073,3.7,0.068,-0.063,0.57,-0.0014,-0.0056,-8.8e-05,0.047,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.013,0.005,0.04,0.04,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.3e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.41 diff --git a/src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp b/src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp index 3d1649317ed7..4e0592e3bc8d 100644 --- a/src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp +++ b/src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp @@ -103,6 +103,14 @@ void SensorSimulator::loadSensorDataFromFile(std::string file_name) } sensor_sample.sensor_data[i] = std::stod(value_string); + + if (sensor_sample.sensor_type == sensor_info::measurement_t::GPS) { + if (i == 1 || i == 2) { + // GPS lat/lon was previously stored as a scaled integer + sensor_sample.sensor_data[i] = sensor_sample.sensor_data[i] * 1e-7; + } + } + i++; } @@ -257,9 +265,9 @@ void SensorSimulator::setSingleReplaySample(const sensor_info &sample) _baro.setData((float) sample.sensor_data[0]); } else if (sample.sensor_type == sensor_info::measurement_t::GPS) { - _gps.setAltitude((int32_t) sample.sensor_data[0]); - _gps.setLatitude((int32_t) sample.sensor_data[1]); - _gps.setLongitude((int32_t) sample.sensor_data[2]); + _gps.setAltitude(sample.sensor_data[0]); + _gps.setLatitude(sample.sensor_data[1]); + _gps.setLongitude(sample.sensor_data[2]); _gps.setVelocity(Vector3f((float) sample.sensor_data[3], (float) sample.sensor_data[4], (float) sample.sensor_data[5])); From ebbb880e925628fbf9357a7c5f06cc3982d3f3d6 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 23 Aug 2024 17:35:59 -0400 Subject: [PATCH 23/87] ekf2: always use corrected accel/gyro for filtered metrics --- src/modules/ekf2/EKF/ekf_helper.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index e88d3b483a63..9df8fe1da239 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -898,17 +898,21 @@ void Ekf::updateIMUBiasInhibit(const imuSample &imu_delayed) // inhibit learning of imu accel bias if the manoeuvre levels are too high to protect against the effect of sensor nonlinearities or bad accel data is detected // xy accel bias learning is also disabled on ground as those states are poorly observable when perpendicular to the gravity vector { + const Vector3f gyro_corrected = imu_delayed.delta_ang / imu_delayed.delta_ang_dt - _state.gyro_bias; + const float alpha = math::constrain((imu_delayed.delta_ang_dt / _params.acc_bias_learn_tc), 0.f, 1.f); const float beta = 1.f - alpha; - _ang_rate_magnitude_filt = fmaxf(imu_delayed.delta_ang.norm() / imu_delayed.delta_ang_dt, - beta * _ang_rate_magnitude_filt); + + _ang_rate_magnitude_filt = fmaxf(gyro_corrected.norm(), beta * _ang_rate_magnitude_filt); } { + const Vector3f accel_corrected = imu_delayed.delta_vel / imu_delayed.delta_vel_dt - _state.accel_bias; + const float alpha = math::constrain((imu_delayed.delta_vel_dt / _params.acc_bias_learn_tc), 0.f, 1.f); const float beta = 1.f - alpha; - _accel_magnitude_filt = fmaxf(imu_delayed.delta_vel.norm() / imu_delayed.delta_vel_dt, beta * _accel_magnitude_filt); + _accel_magnitude_filt = fmaxf(accel_corrected.norm(), beta * _accel_magnitude_filt); } From 510d3cfb390a65c0a70bd73530a3f631e93e5bcd Mon Sep 17 00:00:00 2001 From: SuddenDeath <65440078+your-sudden-death@users.noreply.github.com> Date: Sat, 24 Aug 2024 17:15:41 +0200 Subject: [PATCH 24/87] gz: Fix endless wait for gazebo on different worlds (#23613) Co-authored-by: your-sudden-death --- src/modules/simulation/gz_bridge/GZBridge.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 7b45600e57fb..29d19fe11177 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -154,7 +154,7 @@ int GZBridge::init() return PX4_ERROR; } - std::string scene_info_service = "/world/default/scene/info"; + std::string scene_info_service = "/world/" + _world_name + "/scene/info"; bool scene_created = false; while (scene_created == false) { From 1a4e8a73414ad99113d6513b2e59e405d0338561 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Mon, 26 Aug 2024 16:09:21 +0200 Subject: [PATCH 25/87] FLOW: PARAM: GCS Parameter readability --- src/modules/sensors/sensor_params_flow.c | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/src/modules/sensors/sensor_params_flow.c b/src/modules/sensors/sensor_params_flow.c index 174cf5ba944c..b8abaab5f6f7 100644 --- a/src/modules/sensors/sensor_params_flow.c +++ b/src/modules/sensors/sensor_params_flow.c @@ -60,7 +60,7 @@ PARAM_DEFINE_INT32(SENS_FLOW_ROT, 0); * @min 0.0 * @max 1.0 * @increment 0.1 - * @decimal 1 + * @decimal 2 * @group Sensor Calibration */ PARAM_DEFINE_FLOAT(SENS_FLOW_MINHGT, 0.08f); @@ -77,7 +77,7 @@ PARAM_DEFINE_FLOAT(SENS_FLOW_MINHGT, 0.08f); * @min 1.0 * @max 100.0 * @increment 0.1 - * @decimal 1 + * @decimal 2 * @group Sensor Calibration */ PARAM_DEFINE_FLOAT(SENS_FLOW_MAXHGT, 100.f); From 9183c479a52dba8a0948eaca0a1225c49896497b Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 26 Aug 2024 16:37:17 +0200 Subject: [PATCH 26/87] ekf2: correctly compute vel variance from flow variance Co-authored-by: Marco Hauswirth --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp index 3299577a2875..95db812faeb5 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp @@ -217,7 +217,9 @@ void Ekf::resetFlowFusion() { ECL_INFO("reset velocity to flow"); _information_events.flags.reset_vel_to_flow = true; - resetHorizontalVelocityTo(_flow_vel_ne, calcOptFlowMeasVar(_flow_sample_delayed)); + + const float flow_vel_var = sq(predictFlowRange()) * calcOptFlowMeasVar(_flow_sample_delayed); + resetHorizontalVelocityTo(_flow_vel_ne, flow_vel_var); // reset position, estimate is relative to initial position in this mode, so we start with zero error if (!_control_status.flags.in_air) { From 8bfd3b0f62866c583b14709676b1aa14e6d751dd Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Mon, 26 Aug 2024 19:13:11 +0200 Subject: [PATCH 27/87] platforms/nuttx/init/stm32f7: rc.board_arch_defaults reduce LOGGER_BUF to 40 To get some breathing space on setups with memory-intensive components (e.g. UAVCAN). Signed-off-by: Silvan Fuhrer --- platforms/nuttx/init/stm32f7/rc.board_arch_defaults | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/platforms/nuttx/init/stm32f7/rc.board_arch_defaults b/platforms/nuttx/init/stm32f7/rc.board_arch_defaults index 2c71f7470c9d..c22d9586e034 100644 --- a/platforms/nuttx/init/stm32f7/rc.board_arch_defaults +++ b/platforms/nuttx/init/stm32f7/rc.board_arch_defaults @@ -13,4 +13,4 @@ param set-default -s MC_AT_EN 1 param set-default -s UAVCAN_ENABLE 2 -set LOGGER_BUF 64 +set LOGGER_BUF 40 From a75db1286dd34cc10ebf32f6694307f30ca28496 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 26 Aug 2024 13:24:39 -0400 Subject: [PATCH 28/87] logger: automatically limit buffer size to largest available free chunk (NuttX only) --- src/modules/logger/log_writer_file.cpp | 40 +++++++++++++++++++++----- src/modules/logger/log_writer_file.h | 6 ++-- 2 files changed, 37 insertions(+), 9 deletions(-) diff --git a/src/modules/logger/log_writer_file.cpp b/src/modules/logger/log_writer_file.cpp index 50d5cf7f45e0..2001baf2f61a 100644 --- a/src/modules/logger/log_writer_file.cpp +++ b/src/modules/logger/log_writer_file.cpp @@ -42,9 +42,11 @@ #include #include #include -#ifdef __PX4_NUTTX -#include -#endif /* __PX4_NUTTX */ + +#if defined(__PX4_NUTTX) +# include +# include +#endif // __PX4_NUTTX using namespace time_literals; @@ -60,11 +62,13 @@ LogWriterFile::LogWriterFile(size_t buffer_size) //We always write larger chunks (orb messages) to the buffer, so the buffer //needs to be larger than the minimum write chunk (300 is somewhat arbitrary) { - math::max(buffer_size, _min_write_chunk + 300), + buffer_size, + _min_write_chunk + 300, perf_alloc(PC_ELAPSED, "logger_sd_write"), perf_alloc(PC_ELAPSED, "logger_sd_fsync")}, { 300, // buffer size for the mission log (can be kept fairly small) + 1, perf_alloc(PC_ELAPSED, "logger_sd_write_mission"), perf_alloc(PC_ELAPSED, "logger_sd_fsync_mission")} } { @@ -590,9 +594,12 @@ const char *log_type_str(LogType type) return "unknown"; } -LogWriterFile::LogFileBuffer::LogFileBuffer(size_t log_buffer_size, perf_counter_t perf_write, - perf_counter_t perf_fsync) - : _buffer_size(log_buffer_size), _perf_write(perf_write), _perf_fsync(perf_fsync) +LogWriterFile::LogFileBuffer::LogFileBuffer(size_t log_buffer_desired_size, size_t log_buffer_min_size, + perf_counter_t perf_write, perf_counter_t perf_fsync) : + _buffer_size(log_buffer_desired_size), + _buffer_size_min(log_buffer_min_size), + _perf_write(perf_write), + _perf_fsync(perf_fsync) { } @@ -660,6 +667,25 @@ bool LogWriterFile::LogFileBuffer::start_log(const char *filename) } if (_buffer == nullptr) { + _buffer_size = math::max(_buffer_size, _buffer_size_min); + +#if defined(__PX4_NUTTX) + struct mallinfo alloc_info = mallinfo(); + + // reduced to largest available free chunk, but leave at least 1 kB available + static constexpr ssize_t one_kb = 1024; + const ssize_t reduced_buffer_size = math::max((alloc_info.mxordblk - one_kb) / one_kb * one_kb, + (ssize_t)_buffer_size_min); + + if ((reduced_buffer_size > 0) && ((ssize_t)_buffer_size > reduced_buffer_size)) { + PX4_WARN("requested buffer size %dB limited to available %dB (available plus 1 kB margin)", + _buffer_size, reduced_buffer_size); + + _buffer_size = reduced_buffer_size; + } + +#endif // __PX4_NUTTX + _buffer = (uint8_t *) px4_cache_aligned_alloc(_buffer_size); if (_buffer == nullptr) { diff --git a/src/modules/logger/log_writer_file.h b/src/modules/logger/log_writer_file.h index 757f69de2505..765487893809 100644 --- a/src/modules/logger/log_writer_file.h +++ b/src/modules/logger/log_writer_file.h @@ -169,7 +169,8 @@ class LogWriterFile class LogFileBuffer { public: - LogFileBuffer(size_t log_buffer_size, perf_counter_t perf_write, perf_counter_t perf_fsync); + LogFileBuffer(size_t log_buffer_desired_size, size_t log_buffer_min_size, + perf_counter_t perf_write, perf_counter_t perf_fsync); ~LogFileBuffer(); @@ -203,7 +204,8 @@ class LogWriterFile bool _should_run = false; px4::atomic_bool _had_write_error{false}; private: - const size_t _buffer_size; + size_t _buffer_size; + const size_t _buffer_size_min; int _fd = -1; uint8_t *_buffer = nullptr; size_t _head = 0; ///< next position to write to From 16c77be7c004b30088d80df8884887813c437884 Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Fri, 23 Aug 2024 08:37:32 -0700 Subject: [PATCH 29/87] tests: loosen radius of vtol rtl landing pos check --- test/mavsdk_tests/test_vtol_rtl.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/test/mavsdk_tests/test_vtol_rtl.cpp b/test/mavsdk_tests/test_vtol_rtl.cpp index 2ce6ef00ff69..c98a3cd3ef62 100644 --- a/test/mavsdk_tests/test_vtol_rtl.cpp +++ b/test/mavsdk_tests/test_vtol_rtl.cpp @@ -74,7 +74,7 @@ TEST_CASE("RTL with Mission Landing", "[vtol]") tester.set_rtl_type(2); tester.arm(); tester.execute_rtl_when_reaching_mission_sequence(2); - tester.check_tracks_mission_raw(35.0f); + tester.check_tracks_mission_raw(40.0f); tester.wait_until_disarmed(std::chrono::seconds(120)); } From ca47f6f01681037ddf440ca0de0ae0bf66e8065b Mon Sep 17 00:00:00 2001 From: LucaS Date: Mon, 26 Aug 2024 13:51:09 -0500 Subject: [PATCH 30/87] lib/mixer_module: added a constant instance start so that when instance start is changed in actuator yaml files they parameters are able to be used (#23616) Co-authored-by: Luca Scheuer --- src/lib/mixer_module/mixer_module.cpp | 16 ++++++++-------- src/lib/mixer_module/mixer_module.hpp | 4 ++-- 2 files changed, 10 insertions(+), 10 deletions(-) diff --git a/src/lib/mixer_module/mixer_module.cpp b/src/lib/mixer_module/mixer_module.cpp index ee75bcf9fa0e..45f56ab54025 100644 --- a/src/lib/mixer_module/mixer_module.cpp +++ b/src/lib/mixer_module/mixer_module.cpp @@ -67,7 +67,7 @@ static const FunctionProvider all_function_providers[] = { }; MixingOutput::MixingOutput(const char *param_prefix, uint8_t max_num_outputs, OutputModuleInterface &interface, - SchedulingPolicy scheduling_policy, bool support_esc_calibration, bool ramp_up) : + SchedulingPolicy scheduling_policy, bool support_esc_calibration, bool ramp_up, const uint8_t instance_start) : ModuleParams(&interface), _output_ramp_up(ramp_up), _scheduling_policy(scheduling_policy), @@ -87,7 +87,7 @@ MixingOutput::MixingOutput(const char *param_prefix, uint8_t max_num_outputs, Ou px4_sem_init(&_lock, 0, 1); - initParamHandles(); + initParamHandles(instance_start); for (unsigned i = 0; i < MAX_ACTUATORS; i++) { _failsafe_value[i] = UINT16_MAX; @@ -108,20 +108,20 @@ MixingOutput::~MixingOutput() _outputs_pub.unadvertise(); } -void MixingOutput::initParamHandles() +void MixingOutput::initParamHandles(const uint8_t instance_start) { char param_name[17]; for (unsigned i = 0; i < _max_num_outputs; ++i) { - snprintf(param_name, sizeof(param_name), "%s_%s%d", _param_prefix, "FUNC", i + 1); + snprintf(param_name, sizeof(param_name), "%s_%s%d", _param_prefix, "FUNC", i + instance_start); _param_handles[i].function = param_find(param_name); - snprintf(param_name, sizeof(param_name), "%s_%s%d", _param_prefix, "DIS", i + 1); + snprintf(param_name, sizeof(param_name), "%s_%s%d", _param_prefix, "DIS", i + instance_start); _param_handles[i].disarmed = param_find(param_name); - snprintf(param_name, sizeof(param_name), "%s_%s%d", _param_prefix, "MIN", i + 1); + snprintf(param_name, sizeof(param_name), "%s_%s%d", _param_prefix, "MIN", i + instance_start); _param_handles[i].min = param_find(param_name); - snprintf(param_name, sizeof(param_name), "%s_%s%d", _param_prefix, "MAX", i + 1); + snprintf(param_name, sizeof(param_name), "%s_%s%d", _param_prefix, "MAX", i + instance_start); _param_handles[i].max = param_find(param_name); - snprintf(param_name, sizeof(param_name), "%s_%s%d", _param_prefix, "FAIL", i + 1); + snprintf(param_name, sizeof(param_name), "%s_%s%d", _param_prefix, "FAIL", i + instance_start); _param_handles[i].failsafe = param_find(param_name); } diff --git a/src/lib/mixer_module/mixer_module.hpp b/src/lib/mixer_module/mixer_module.hpp index 3deaa54aa42f..fa6cd81fcb40 100644 --- a/src/lib/mixer_module/mixer_module.hpp +++ b/src/lib/mixer_module/mixer_module.hpp @@ -120,7 +120,7 @@ class MixingOutput : public ModuleParams */ MixingOutput(const char *param_prefix, uint8_t max_num_outputs, OutputModuleInterface &interface, SchedulingPolicy scheduling_policy, - bool support_esc_calibration, bool ramp_up = true); + bool support_esc_calibration, bool ramp_up = true, const uint8_t instance_start = 1); ~MixingOutput(); @@ -221,7 +221,7 @@ class MixingOutput : public ModuleParams void cleanupFunctions(); - void initParamHandles(); + void initParamHandles(const uint8_t instance_start); void limitAndUpdateOutputs(float outputs[MAX_ACTUATORS], bool has_updates); From f67eb6989d78c0c093fc934ae8a1c2b998846006 Mon Sep 17 00:00:00 2001 From: Jukka Laitinen Date: Fri, 16 Aug 2024 09:42:48 +0300 Subject: [PATCH 31/87] mavlink: Fix ESC_STATUS sending for batches > 1 The indexing was wrong for esc_status sending for ESCs 4-> Signed-off-by: Jukka Laitinen --- src/modules/mavlink/streams/ESC_STATUS.hpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/src/modules/mavlink/streams/ESC_STATUS.hpp b/src/modules/mavlink/streams/ESC_STATUS.hpp index 1e8911577823..54c11cbd8ebb 100644 --- a/src/modules/mavlink/streams/ESC_STATUS.hpp +++ b/src/modules/mavlink/streams/ESC_STATUS.hpp @@ -75,10 +75,11 @@ class MavlinkStreamESCStatus : public MavlinkStream for (int batch_number = 0; batch_number < _number_of_batches; batch_number++) { msg.index = batch_number * batch_size; - for (int esc_index = 0; esc_index < batch_size ; esc_index++) { - msg.rpm[esc_index] = esc_status.esc[esc_index].esc_rpm; - msg.voltage[esc_index] = esc_status.esc[esc_index].esc_voltage; - msg.current[esc_index] = esc_status.esc[esc_index].esc_current; + for (int esc_index = 0; esc_index < batch_size + && msg.index + esc_index < esc_status_s::CONNECTED_ESC_MAX; esc_index++) { + msg.rpm[esc_index] = esc_status.esc[msg.index + esc_index].esc_rpm; + msg.voltage[esc_index] = esc_status.esc[msg.index + esc_index].esc_voltage; + msg.current[esc_index] = esc_status.esc[msg.index + esc_index].esc_current; } mavlink_msg_esc_status_send_struct(_mavlink->get_channel(), &msg); From 5fff1ad6d1c0462ff19657663753bf162201efa5 Mon Sep 17 00:00:00 2001 From: jmackay2 Date: Mon, 26 Aug 2024 22:20:03 -0400 Subject: [PATCH 32/87] Fix spelling of airflow sensor msg comments --- msg/SensorAirflow.msg | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/msg/SensorAirflow.msg b/msg/SensorAirflow.msg index dd55ad0b0c70..f085600489cf 100644 --- a/msg/SensorAirflow.msg +++ b/msg/SensorAirflow.msg @@ -1,5 +1,5 @@ uint64 timestamp # time since system start (microseconds) uint32 device_id # unique device ID for the sensor that does not change between power cycles float32 speed # the speed being reported by the wind / airflow sensor -float32 direction # the direction bein report by the wind / airflow sensor +float32 direction # the direction being reported by the wind / airflow sensor uint8 status # Status code from the sensor From be4d0d351c47dfeb37d1fd760d437cabbcaf0b60 Mon Sep 17 00:00:00 2001 From: sbtjagu <145494402+sbtjagu@users.noreply.github.com> Date: Tue, 27 Aug 2024 13:35:48 +0200 Subject: [PATCH 33/87] ackermann: add speed waypoint support and fix delay detection (#23572) --- .../RoverAckermannGuidance.cpp | 44 +++++++++++-------- .../RoverAckermannGuidance.hpp | 4 ++ 2 files changed, 30 insertions(+), 18 deletions(-) diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp index 1acaebb6386f..48890323bbb4 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.cpp @@ -60,6 +60,14 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c { updateSubscriptions(); + // Distances to waypoints + _distance_to_prev_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _prev_wp(0), _prev_wp(1)); + _distance_to_curr_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _curr_wp(0), _curr_wp(1)); + _distance_to_next_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _next_wp(0), _next_wp(1)); + // Catch return to launch if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { _mission_finished = _distance_to_next_wp < _acceptance_radius; @@ -74,7 +82,8 @@ RoverAckermannGuidance::motor_setpoint RoverAckermannGuidance::computeGuidance(c _desired_speed = 0.f; } else { // Regular guidance algorithm - _desired_speed = calcDesiredSpeed(_param_ra_miss_vel_def.get(), _param_ra_miss_vel_min.get(), + + _desired_speed = calcDesiredSpeed(_wp_max_desired_vel, _param_ra_miss_vel_min.get(), _param_ra_miss_vel_gain.get(), _distance_to_prev_wp, _distance_to_curr_wp, _acceptance_radius, _prev_acceptance_radius, _param_ra_max_accel.get(), _param_ra_max_jerk.get(), nav_state); @@ -156,40 +165,32 @@ void RoverAckermannGuidance::updateWaypointsAndAcceptanceRadius() _position_setpoint_triplet_sub.copy(&position_setpoint_triplet); // Global waypoint coordinates - Vector2d prev_wp = _curr_pos.isAllFinite() ? _curr_pos : Vector2d(0, 0); // Fallback if previous waypoint is invalid - Vector2d curr_wp(0, 0); - Vector2d next_wp = _home_position.isAllFinite() ? _home_position : Vector2d(0, 0); // Enables corner slow down with RTL + _prev_wp = _curr_pos.isAllFinite() ? _curr_pos : Vector2d(0, 0); // Fallback if previous waypoint is invalid + _curr_wp = Vector2d(0, 0); + _next_wp = _home_position.isAllFinite() ? _home_position : Vector2d(0, 0); // Enables corner slow down with RTL if (position_setpoint_triplet.current.valid && PX4_ISFINITE(position_setpoint_triplet.current.lat) && PX4_ISFINITE(position_setpoint_triplet.current.lon)) { - curr_wp = Vector2d(position_setpoint_triplet.current.lat, position_setpoint_triplet.current.lon); + _curr_wp = Vector2d(position_setpoint_triplet.current.lat, position_setpoint_triplet.current.lon); } if (position_setpoint_triplet.previous.valid && PX4_ISFINITE(position_setpoint_triplet.previous.lat) && PX4_ISFINITE(position_setpoint_triplet.previous.lon)) { - prev_wp = Vector2d(position_setpoint_triplet.previous.lat, position_setpoint_triplet.previous.lon); + _prev_wp = Vector2d(position_setpoint_triplet.previous.lat, position_setpoint_triplet.previous.lon); } if (position_setpoint_triplet.next.valid && PX4_ISFINITE(position_setpoint_triplet.next.lat) && PX4_ISFINITE(position_setpoint_triplet.next.lon)) { - next_wp = Vector2d(position_setpoint_triplet.next.lat, position_setpoint_triplet.next.lon); + _next_wp = Vector2d(position_setpoint_triplet.next.lat, position_setpoint_triplet.next.lon); } - // Distances to waypoints - _distance_to_prev_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), - prev_wp(0), prev_wp(1)); - _distance_to_curr_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), - curr_wp(0), curr_wp(1)); - _distance_to_next_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), - next_wp(0), next_wp(1)); - // NED waypoint coordinates - _curr_wp_ned = _global_ned_proj_ref.project(curr_wp(0), curr_wp(1)); - _prev_wp_ned = _global_ned_proj_ref.project(prev_wp(0), prev_wp(1)); - _next_wp_ned = _global_ned_proj_ref.project(next_wp(0), next_wp(1)); + _curr_wp_ned = _global_ned_proj_ref.project(_curr_wp(0), _curr_wp(1)); + _prev_wp_ned = _global_ned_proj_ref.project(_prev_wp(0), _prev_wp(1)); + _next_wp_ned = _global_ned_proj_ref.project(_next_wp(0), _next_wp(1)); // Update acceptance radius _prev_acceptance_radius = _acceptance_radius; @@ -201,6 +202,13 @@ void RoverAckermannGuidance::updateWaypointsAndAcceptanceRadius() } else { _acceptance_radius = _param_nav_acc_rad.get(); } + + if (position_setpoint_triplet.current.cruising_speed > 0.f) { + _wp_max_desired_vel = math::constrain(position_setpoint_triplet.current.cruising_speed, 0.f, _param_ra_max_speed.get()); + + } else { + _wp_max_desired_vel = _param_ra_miss_vel_def.get(); + } } float RoverAckermannGuidance::updateAcceptanceRadius(const Vector2f &curr_wp_ned, const Vector2f &prev_wp_ned, diff --git a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp index 23f63ed9280e..de5ef587807c 100644 --- a/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp +++ b/src/modules/rover_ackermann/RoverAckermannGuidance/RoverAckermannGuidance.hpp @@ -205,11 +205,15 @@ class RoverAckermannGuidance : public ModuleParams Vector2f _curr_wp_ned{}; Vector2f _prev_wp_ned{}; Vector2f _next_wp_ned{}; + Vector2d _curr_wp{}; + Vector2d _prev_wp{}; + Vector2d _next_wp{}; float _distance_to_prev_wp{0.f}; float _distance_to_curr_wp{0.f}; float _distance_to_next_wp{0.f}; float _acceptance_radius{0.5f}; float _prev_acceptance_radius{0.5f}; + float _wp_max_desired_vel{0.f}; bool _mission_finished{false}; // Parameters From bbcf741e9ea8743458df8be9a9317e2913f5b695 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 31 May 2024 15:37:05 -0400 Subject: [PATCH 34/87] ekf2: make mag control responsible for WMM - this further untangles mag control (which requires the WMM) from GPS --- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 18 +-- .../aid_sources/magnetometer/mag_control.cpp | 134 ++++++++++++++---- .../aid_sources/magnetometer/mag_fusion.cpp | 55 +++---- src/modules/ekf2/EKF/ekf.h | 8 +- src/modules/ekf2/EKF/ekf_helper.cpp | 37 +---- src/modules/ekf2/EKF/estimator_interface.h | 21 +-- src/modules/ekf2/test/test_EKF_airspeed.cpp | 2 +- src/modules/ekf2/test/test_EKF_basics.cpp | 1 - 8 files changed, 155 insertions(+), 121 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp index 94fa6f04f381..4467ff9f7e28 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -41,10 +41,6 @@ #include "ekf.h" -#if defined(CONFIG_EKF2_MAGNETOMETER) -# include -#endif // CONFIG_EKF2_MAGNETOMETER - #include // GPS pre-flight check bit locations @@ -89,20 +85,20 @@ void Ekf::collect_gps(const gnssSample &gps) _gpos_origin_eph = gps.hacc; _gpos_origin_epv = gps.vacc; + _earth_rate_NED = calcEarthRateNED(math::radians(static_cast(gps.lat))); + _information_events.flags.gps_checks_passed = true; - ECL_INFO("GPS checks passed"); - } - if ((isTimedOut(_wmm_gps_time_last_checked, 1e6)) || (_wmm_gps_time_last_set == 0)) { - // a rough 2D fix is sufficient to lookup declination + ECL_INFO("GPS origin set to lat=%.6f, lon=%.6f", + _pos_ref.getProjectionReferenceLat(), _pos_ref.getProjectionReferenceLon()); + + } else { + // a rough 2D fix is sufficient to lookup earth spin rate const bool gps_rough_2d_fix = (gps.fix_type >= 2) && (gps.hacc < 1000); if (gps_rough_2d_fix && (_gps_checks_passed || !_NED_origin_initialised)) { - updateWmm(gps.lat, gps.lon); _earth_rate_NED = calcEarthRateNED((float)math::radians(gps.lat)); } - - _wmm_gps_time_last_checked = _time_delayed_us; } } diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index 0e42006b249d..f36eba1dc612 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -39,6 +39,8 @@ #include "ekf.h" #include +#include + #include void Ekf::controlMagFusion(const imuSample &imu_sample) @@ -76,15 +78,43 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) _mag_counter++; } + // check for WMM update periodically or if global origin has changed + bool wmm_updated = false; + + if (global_origin().isInitialized()) { + + bool origin_newer_than_last_mag = (global_origin().getProjectionReferenceTimestamp() > aid_src.time_last_fuse); + + if (global_origin_valid() + && (origin_newer_than_last_mag || (local_position_is_valid() && isTimedOut(_wmm_mag_time_last_checked, 10e6))) + ) { + // position of local NED origin in GPS / WGS84 frame + double latitude_deg; + double longitude_deg; + global_origin().reproject(_state.pos(0), _state.pos(1), latitude_deg, longitude_deg); + + if (updateWorldMagneticModel(latitude_deg, longitude_deg)) { + wmm_updated = true; + } + + _wmm_mag_time_last_checked = _time_delayed_us; + + } else if (origin_newer_than_last_mag) { + // use global origin to update WMM + if (updateWorldMagneticModel(global_origin().getProjectionReferenceLat(), + global_origin().getProjectionReferenceLon()) + ) { + wmm_updated = true; + } + } + } + // if enabled, use knowledge of theoretical magnetic field vector to calculate a synthetic magnetomter Z component value. // this is useful if there is a lot of interference on the sensor measurement. if (_params.synthesize_mag_z && (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) - && (PX4_ISFINITE(_mag_inclination_gps) && PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps)) + && (_wmm_earth_field_gauss.isAllFinite() && _wmm_earth_field_gauss.longerThan(0.f)) ) { - const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps, _mag_declination_gps)) - * Vector3f(_mag_strength_gps, 0, 0); - - mag_sample.mag(2) = calculate_synthetic_mag_z_measurement(mag_sample.mag, mag_earth_pred); + mag_sample.mag(2) = calculate_synthetic_mag_z_measurement(mag_sample.mag, _wmm_earth_field_gauss); _control_status.flags.synthetic_mag_z = true; @@ -140,8 +170,6 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) checkMagHeadingConsistency(mag_sample); - // WMM update can occur on the last epoch, just after mag fusion - const bool wmm_updated = (_wmm_gps_time_last_set >= aid_src.time_last_fuse); const bool using_ne_aiding = _control_status.flags.gps || _control_status.flags.aux_gpos; @@ -203,7 +231,21 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) } if (_control_status.flags.mag_dec) { - fuseDeclination(0.5f); + + if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) + && PX4_ISFINITE(_wmm_declination_rad) + ) { + fuseDeclination(_wmm_declination_rad, 0.5f); + + } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) + && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) + ) { + + fuseDeclination(math::radians(_params.mag_declination_deg), 0.5f); + + } else { + _control_status.flags.mag_dec = false; + } } } @@ -333,24 +375,21 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) resetMagCov(); // if world magnetic model (inclination, declination, strength) available then use it to reset mag states - if (PX4_ISFINITE(_mag_inclination_gps) && PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps)) { - + if (_wmm_earth_field_gauss.longerThan(0.f) && _wmm_earth_field_gauss.isAllFinite()) { // use expected earth field to reset states - const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps, _mag_declination_gps)) - * Vector3f(_mag_strength_gps, 0, 0); // mag_B: reset if (!reset_heading && _control_status.flags.yaw_align) { // mag_B: reset using WMM const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal); - _state.mag_B = mag - (R_to_body * mag_earth_pred); + _state.mag_B = mag - (R_to_body * _wmm_earth_field_gauss); } else { _state.mag_B.zero(); } // mag_I: reset, skipped if no change in state and variance good - _state.mag_I = mag_earth_pred; + _state.mag_I = _wmm_earth_field_gauss; if (reset_heading) { resetMagHeading(mag); @@ -451,8 +490,8 @@ bool Ekf::checkMagField(const Vector3f &mag_sample) _mag_strength = mag_sample.length(); if (_params.mag_check & static_cast(MagCheckMask::STRENGTH)) { - if (PX4_ISFINITE(_mag_strength_gps)) { - if (!isMeasuredMatchingExpected(_mag_strength, _mag_strength_gps, _params.mag_check_strength_tolerance_gs)) { + if (PX4_ISFINITE(_wmm_field_strength_gauss)) { + if (!isMeasuredMatchingExpected(_mag_strength, _wmm_field_strength_gauss, _params.mag_check_strength_tolerance_gs)) { _control_status.flags.mag_field_disturbed = true; is_check_failing = true; } @@ -475,9 +514,9 @@ bool Ekf::checkMagField(const Vector3f &mag_sample) _mag_inclination = asinf(mag_earth(2) / fmaxf(mag_earth.norm(), 1e-4f)); if (_params.mag_check & static_cast(MagCheckMask::INCLINATION)) { - if (PX4_ISFINITE(_mag_inclination_gps)) { + if (PX4_ISFINITE(_wmm_inclination_rad)) { const float inc_tol_rad = radians(_params.mag_check_inclination_tolerance_deg); - const float inc_error_rad = wrap_pi(_mag_inclination - _mag_inclination_gps); + const float inc_error_rad = wrap_pi(_mag_inclination - _wmm_inclination_rad); if (fabsf(inc_error_rad) > inc_tol_rad) { _control_status.flags.mag_field_disturbed = true; @@ -549,13 +588,60 @@ float Ekf::getMagDeclination() // Use value consistent with earth field state return atan2f(_state.mag_I(1), _state.mag_I(0)); - } else if (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) { - // use parameter value until GPS is available, then use value returned by geo library - if (PX4_ISFINITE(_mag_declination_gps)) { - return _mag_declination_gps; + } else if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) + && PX4_ISFINITE(_wmm_declination_rad) + ) { + // if available use value returned by geo library + return _wmm_declination_rad; + + } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) + && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) + ) { + // using saved mag declination + return math::radians(_params.mag_declination_deg); + } + + // otherwise unavailable + return 0.f; +} + +bool Ekf::updateWorldMagneticModel(const double latitude_deg, const double longitude_deg) +{ + // set the magnetic field data returned by the geo library using the current GPS position + const float declination_rad = math::radians(get_mag_declination_degrees(latitude_deg, longitude_deg)); + const float inclination_rad = math::radians(get_mag_inclination_degrees(latitude_deg, longitude_deg)); + const float strength_gauss = get_mag_strength_gauss(latitude_deg, longitude_deg); + + if (PX4_ISFINITE(declination_rad) && PX4_ISFINITE(inclination_rad) && PX4_ISFINITE(strength_gauss)) { + + const bool declination_changed = (fabsf(declination_rad - _wmm_declination_rad) > math::radians(1.f)); + const bool inclination_changed = (fabsf(inclination_rad - _wmm_inclination_rad) > math::radians(1.f)); + const bool strength_changed = (fabsf(strength_gauss - _wmm_field_strength_gauss) > 0.01f); + + if (!PX4_ISFINITE(_wmm_declination_rad) + || !PX4_ISFINITE(_wmm_inclination_rad) + || !PX4_ISFINITE(_wmm_field_strength_gauss) + || !_wmm_earth_field_gauss.longerThan(0.f) + || !_wmm_earth_field_gauss.isAllFinite() + || declination_changed + || inclination_changed + || strength_changed + ) { + + ECL_DEBUG("WMM declination updated %.3f -> %.3f deg (lat=%.6f, lon=%.6f)", + (double)math::degrees(_wmm_declination_rad), (double)math::degrees(declination_rad), + (double)latitude_deg, (double)longitude_deg + ); + + _wmm_declination_rad = declination_rad; + _wmm_inclination_rad = inclination_rad; + _wmm_field_strength_gauss = strength_gauss; + + _wmm_earth_field_gauss = Dcmf(Eulerf(0, -inclination_rad, declination_rad)) * Vector3f(strength_gauss, 0, 0); + + return true; } } - // otherwise use the parameter value - return math::radians(_params.mag_declination_deg); + return false; } diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp index acd16578c54f..887caf20dd15 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -150,51 +150,34 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima return false; } -bool Ekf::fuseDeclination(float decl_sigma) +bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma) { - float decl_measurement = NAN; + // observation variance (rad**2) + const float R_DECL = sq(decl_sigma); - if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) - && PX4_ISFINITE(_mag_declination_gps) - ) { - decl_measurement = _mag_declination_gps; + VectorState H; + float decl_pred; + float innovation_variance; - } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) - && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) - ) { - decl_measurement = math::radians(_params.mag_declination_deg); - } - - if (PX4_ISFINITE(decl_measurement)) { - - // observation variance (rad**2) - const float R_DECL = sq(decl_sigma); - - VectorState H; - float decl_pred; - float innovation_variance; - - sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R_DECL, FLT_EPSILON, &decl_pred, &innovation_variance, - &H); - - const float innovation = wrap_pi(decl_pred - decl_measurement); + sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R_DECL, FLT_EPSILON, + &decl_pred, &innovation_variance, &H); - if (innovation_variance < R_DECL) { - // variance calculation is badly conditioned - return false; - } + const float innovation = wrap_pi(decl_pred - decl_measurement_rad); - // Calculate the Kalman gains - VectorState Kfusion = P * H / innovation_variance; + if (innovation_variance < R_DECL) { + // variance calculation is badly conditioned + _fault_status.flags.bad_mag_decl = true; + return false; + } - const bool is_fused = measurementUpdate(Kfusion, H, R_DECL, innovation); + // Calculate the Kalman gains + VectorState Kfusion = P * H / innovation_variance; - _fault_status.flags.bad_mag_decl = !is_fused; + const bool is_fused = measurementUpdate(Kfusion, H, R_DECL, innovation); - return is_fused; - } + _fault_status.flags.bad_mag_decl = !is_fused; - return false; + return is_fused; } float Ekf::calculate_synthetic_mag_z_measurement(const Vector3f &mag_meas, const Vector3f &mag_earth_predicted) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index e6c182171aff..edf50329bb49 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -259,7 +259,6 @@ class Ekf final : public EstimatorInterface // return true if the origin is valid bool getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &longitude, float &origin_alt) const; bool setEkfGlobalOrigin(double latitude, double longitude, float altitude, float eph = 0.f, float epv = 0.f); - void updateWmm(double lat, double lon); // get the 1-sigma horizontal and vertical position uncertainty of the ekf WGS-84 position void get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv) const; @@ -466,6 +465,9 @@ class Ekf final : public EstimatorInterface #endif // CONFIG_EKF2_GNSS #if defined(CONFIG_EKF2_MAGNETOMETER) + // set the magnetic field data returned by the geo library using position + bool updateWorldMagneticModel(const double latitude_deg, const double longitude_deg); + const auto &aid_src_mag() const { return _aid_src_mag; } #endif // CONFIG_EKF2_MAGNETOMETER @@ -770,8 +772,8 @@ class Ekf final : public EstimatorInterface bool update_all_states = false, bool update_tilt = false); // fuse magnetometer declination measurement - // argument passed in is the declination uncertainty in radians - bool fuseDeclination(float decl_sigma); + // declination uncertainty in radians + bool fuseDeclination(float decl_measurement_rad, float decl_sigma); #endif // CONFIG_EKF2_MAGNETOMETER diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 9df8fe1da239..01821fd97bb8 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -96,13 +96,13 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons _pos_ref.initReference(latitude, longitude, _time_delayed_us); _gps_alt_ref = altitude; - updateWmm(current_lat, current_lon); - _gpos_origin_eph = eph; _gpos_origin_epv = epv; _NED_origin_initialised = true; + _earth_rate_NED = calcEarthRateNED(math::radians(static_cast(latitude))); + if (current_pos_available) { // reset horizontal position if we already have a global origin Vector2f position = _pos_ref.project(current_lat, current_lon); @@ -131,39 +131,6 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons return false; } -void Ekf::updateWmm(const double lat, const double lon) -{ -#if defined(CONFIG_EKF2_MAGNETOMETER) - - // set the magnetic field data returned by the geo library using the current GPS position - const float mag_declination_gps = math::radians(get_mag_declination_degrees(lat, lon)); - const float mag_inclination_gps = math::radians(get_mag_inclination_degrees(lat, lon)); - const float mag_strength_gps = get_mag_strength_gauss(lat, lon); - - if (PX4_ISFINITE(mag_declination_gps) && PX4_ISFINITE(mag_inclination_gps) && PX4_ISFINITE(mag_strength_gps)) { - - const bool mag_declination_changed = (fabsf(mag_declination_gps - _mag_declination_gps) > math::radians(1.f)); - const bool mag_inclination_changed = (fabsf(mag_inclination_gps - _mag_inclination_gps) > math::radians(1.f)); - - if ((_wmm_gps_time_last_set == 0) - || !PX4_ISFINITE(_mag_declination_gps) - || !PX4_ISFINITE(_mag_inclination_gps) - || !PX4_ISFINITE(_mag_strength_gps) - || mag_declination_changed - || mag_inclination_changed - ) { - _mag_declination_gps = mag_declination_gps; - _mag_inclination_gps = mag_inclination_gps; - _mag_strength_gps = mag_strength_gps; - - _wmm_gps_time_last_set = _time_delayed_us; - } - } - -#endif // CONFIG_EKF2_MAGNETOMETER -} - - void Ekf::get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv) const { float eph = INFINITY; diff --git a/src/modules/ekf2/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h index 57e6fc06b029..302d113f8d12 100644 --- a/src/modules/ekf2/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -250,7 +250,7 @@ class EstimatorInterface bool get_mag_decl_deg(float &val) const { if (_NED_origin_initialised && (_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL)) { - val = math::degrees(_mag_declination_gps); + val = math::degrees(_wmm_declination_rad); return true; } else { @@ -261,7 +261,7 @@ class EstimatorInterface bool get_mag_inc_deg(float &val) const { if (_NED_origin_initialised) { - val = math::degrees(_mag_inclination_gps); + val = math::degrees(_wmm_inclination_rad); return true; } else { @@ -272,9 +272,9 @@ class EstimatorInterface void get_mag_checks(float &inc_deg, float &inc_ref_deg, float &strength_gs, float &strength_ref_gs) const { inc_deg = math::degrees(_mag_inclination); - inc_ref_deg = math::degrees(_mag_inclination_gps); + inc_ref_deg = math::degrees(_wmm_inclination_rad); strength_gs = _mag_strength; - strength_ref_gs = _mag_strength_gps; + strength_ref_gs = _wmm_field_strength_gauss; } #endif // CONFIG_EKF2_MAGNETOMETER @@ -451,13 +451,14 @@ class EstimatorInterface // allocate data buffers and initialize interface variables bool initialise_interface(uint64_t timestamp); - uint64_t _wmm_gps_time_last_checked{0}; // time WMM last checked - uint64_t _wmm_gps_time_last_set{0}; // time WMM last set - #if defined(CONFIG_EKF2_MAGNETOMETER) - float _mag_declination_gps {NAN}; // magnetic declination returned by the geo library using the last valid GPS position (rad) - float _mag_inclination_gps{NAN}; // magnetic inclination returned by the geo library using the last valid GPS position (rad) - float _mag_strength_gps{NAN}; // magnetic strength returned by the geo library using the last valid GPS position (T) + uint64_t _wmm_mag_time_last_checked {0}; // time WMM update last checked by mag control + + float _wmm_declination_rad{NAN}; // magnetic declination returned by the geo library using the last valid GPS position (rad) + float _wmm_inclination_rad{NAN}; // magnetic inclination returned by the geo library using the last valid GPS position (rad) + float _wmm_field_strength_gauss{NAN}; // magnetic strength returned by the geo library using the last valid GPS position (Gauss) + + Vector3f _wmm_earth_field_gauss{}; // expected magnetic field vector from the last valid GPS position (Gauss) float _mag_inclination{NAN}; float _mag_strength{NAN}; diff --git a/src/modules/ekf2/test/test_EKF_airspeed.cpp b/src/modules/ekf2/test/test_EKF_airspeed.cpp index 61865dfc7a9a..d1bd54a13b21 100644 --- a/src/modules/ekf2/test/test_EKF_airspeed.cpp +++ b/src/modules/ekf2/test/test_EKF_airspeed.cpp @@ -199,7 +199,7 @@ TEST_F(EkfAirspeedTest, testAirspeedDeadReckoning) EXPECT_TRUE(_ekf_wrapper.isWindVelocityEstimated()); const Vector3f vel = _ekf->getVelocity(); - EXPECT_NEAR(vel.norm(), airspeed_body.norm(), 1e-3f); + EXPECT_NEAR(vel.norm(), airspeed_body.norm(), 1e-2f); const Vector2f vel_wind_earth = _ekf->getWindVelocity(); EXPECT_NEAR(vel_wind_earth(0), 0.f, .1f); EXPECT_NEAR(vel_wind_earth(1), 0.f, .1f); diff --git a/src/modules/ekf2/test/test_EKF_basics.cpp b/src/modules/ekf2/test/test_EKF_basics.cpp index e95443344235..0d34e676cbb9 100644 --- a/src/modules/ekf2/test/test_EKF_basics.cpp +++ b/src/modules/ekf2/test/test_EKF_basics.cpp @@ -108,7 +108,6 @@ TEST_F(EkfBasicsTest, initialControlMode) EXPECT_EQ(1, (int) _ekf->control_status_flags().mag_hdg); EXPECT_EQ(0, (int) _ekf->control_status_flags().mag_3D); EXPECT_EQ(1, (int) _ekf->control_status_flags().mag); - EXPECT_EQ(1, (int) _ekf->control_status_flags().mag_dec); EXPECT_EQ(0, (int) _ekf->control_status_flags().in_air); EXPECT_EQ(0, (int) _ekf->control_status_flags().wind); EXPECT_EQ(1, (int) _ekf->control_status_flags().baro_hgt); From 9d57a3c02f80de3945678a51cb6510e7e2e4ff1f Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 23 Aug 2024 13:33:40 -0400 Subject: [PATCH 35/87] ekf2: split resetMagCov() and skip mag reset if negligible change --- .../aid_sources/magnetometer/mag_control.cpp | 73 +++++++++++-------- .../aid_sources/magnetometer/mag_fusion.cpp | 3 +- src/modules/ekf2/EKF/covariance.cpp | 13 +++- src/modules/ekf2/EKF/ekf.h | 3 +- 4 files changed, 57 insertions(+), 35 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index f36eba1dc612..99da95e5a188 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -68,7 +68,9 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) _control_status.flags.mag_fault = false; _state.mag_B.zero(); - resetMagCov(); + resetMagBiasCov(); + + stopMagFusion(); _mag_lpf.reset(mag_sample.mag); _mag_counter = 1; @@ -210,7 +212,7 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) if (continuing_conditions_passing && _control_status.flags.yaw_align) { - if (mag_sample.reset || checkHaglYawResetReq() || (wmm_updated && no_ne_aiding_or_pre_takeoff)) { + if (checkHaglYawResetReq() || (wmm_updated && no_ne_aiding_or_pre_takeoff)) { ECL_INFO("reset to %s", AID_SRC_NAME); resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); aid_src.time_last_fuse = imu_sample.time_us; @@ -313,6 +315,9 @@ void Ekf::stopMagFusion() if (_control_status.flags.mag) { ECL_INFO("stopping mag fusion"); + resetMagEarthCov(); + resetMagBiasCov(); + if (_control_status.flags.yaw_align && (_control_status.flags.mag_3D || _control_status.flags.mag_hdg)) { // reset yaw alignment from mag unless using GNSS aiding const bool using_ne_aiding = _control_status.flags.gps || _control_status.flags.aux_gpos; @@ -371,26 +376,36 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) const Vector3f mag_I_before_reset = _state.mag_I; const Vector3f mag_B_before_reset = _state.mag_B; - // reset covariances to default - resetMagCov(); + static constexpr float kMagEarthMinGauss = 0.01f; // minimum difference in mag earth field strength for reset (Gauss) // if world magnetic model (inclination, declination, strength) available then use it to reset mag states if (_wmm_earth_field_gauss.longerThan(0.f) && _wmm_earth_field_gauss.isAllFinite()) { // use expected earth field to reset states - // mag_B: reset + // mag_I: reset, skipped if negligible change in state + const Vector3f mag_I = _wmm_earth_field_gauss; + bool mag_I_reset = false; + + if ((_state.mag_I - mag_I).longerThan(kMagEarthMinGauss)) { + _state.mag_I = mag_I; + resetMagEarthCov(); + mag_I_reset = true; + } + + // mag_B: reset, skipped if mag_I didn't change if (!reset_heading && _control_status.flags.yaw_align) { - // mag_B: reset using WMM - const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal); - _state.mag_B = mag - (R_to_body * _wmm_earth_field_gauss); + if (mag_I_reset) { + // mag_B: reset using WMM + const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal); + _state.mag_B = mag - (R_to_body * _wmm_earth_field_gauss); + resetMagBiasCov(); + } // otherwise keep existing mag_B state (!mag_I_reset) } else { _state.mag_B.zero(); + resetMagBiasCov(); } - // mag_I: reset, skipped if no change in state and variance good - _state.mag_I = _wmm_earth_field_gauss; - if (reset_heading) { resetMagHeading(mag); } @@ -398,34 +413,32 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading) } else { // mag_B: reset _state.mag_B.zero(); + resetMagBiasCov(); - // Use the magnetometer measurement to reset the field states + // Use the magnetometer measurement to reset the heading if (reset_heading) { resetMagHeading(mag); } - // mag_I: use the last magnetometer measurements to reset the field states - _state.mag_I = _R_to_earth * mag; - } + // mag_I: use the last magnetometer measurement to reset the field states + const Vector3f mag_I = _R_to_earth * mag; - if (!mag_I_before_reset.longerThan(0.f)) { - ECL_INFO("initializing mag I [%.3f, %.3f, %.3f], mag B [%.3f, %.3f, %.3f]", - (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2), - (double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2) - ); + if ((_state.mag_I - mag_I).longerThan(kMagEarthMinGauss)) { + _state.mag_I = mag_I; + resetMagEarthCov(); + } + } - } else { + if ((_state.mag_I - mag_I_before_reset).longerThan(0.f)) { ECL_INFO("resetting mag I [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f]", (double)mag_I_before_reset(0), (double)mag_I_before_reset(1), (double)mag_I_before_reset(2), - (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2) - ); - - if (mag_B_before_reset.longerThan(0.f) || _state.mag_B.longerThan(0.f)) { - ECL_INFO("resetting mag B [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f]", - (double)mag_B_before_reset(0), (double)mag_B_before_reset(1), (double)mag_B_before_reset(2), - (double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2) - ); - } + (double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2)); + } + + if ((_state.mag_B - mag_B_before_reset).longerThan(0.f)) { + ECL_INFO("resetting mag B [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f]", + (double)mag_B_before_reset(0), (double)mag_B_before_reset(1), (double)mag_B_before_reset(2), + (double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2)); } // record the start time for the magnetic field alignment diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp index 887caf20dd15..18174caad4c0 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -99,7 +99,8 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima resetQuatCov(_params.mag_heading_noise); } - resetMagCov(); + resetMagEarthCov(); + resetMagBiasCov(); return false; } diff --git a/src/modules/ekf2/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp index 787d1636e2ab..f148a99d9124 100644 --- a/src/modules/ekf2/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -96,7 +96,8 @@ void Ekf::initialiseCovariance() resetAccelBiasCov(); #if defined(CONFIG_EKF2_MAGNETOMETER) - resetMagCov(); + resetMagEarthCov(); + resetMagBiasCov(); #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_WIND) @@ -340,11 +341,17 @@ void Ekf::resetAccelBiasCov() } #if defined(CONFIG_EKF2_MAGNETOMETER) -void Ekf::resetMagCov() +void Ekf::resetMagEarthCov() { - ECL_INFO("reset mag covariance"); + ECL_INFO("reset mag earth covariance"); P.uncorrelateCovarianceSetVariance(State::mag_I.idx, sq(_params.mag_noise)); +} + +void Ekf::resetMagBiasCov() +{ + ECL_INFO("reset mag bias covariance"); + P.uncorrelateCovarianceSetVariance(State::mag_B.idx, sq(_params.mag_noise)); } #endif // CONFIG_EKF2_MAGNETOMETER diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index edf50329bb49..dd273aa0e1c0 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -1108,7 +1108,8 @@ class Ekf final : public EstimatorInterface void resetQuatCov(const Vector3f &rot_var_ned); #if defined(CONFIG_EKF2_MAGNETOMETER) - void resetMagCov(); + void resetMagEarthCov(); + void resetMagBiasCov(); #endif // CONFIG_EKF2_MAGNETOMETER #if defined(CONFIG_EKF2_WIND) From 2a9e2054427f0e722b6d20fff3d0bf43fc25dc26 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Fri, 23 Aug 2024 15:30:44 -0400 Subject: [PATCH 36/87] ekf2: fuseDeclination respect mag update_all_states - when both mag_hdg/mag_3d are inactive we should be able to continue updating mag without any possible impact on other states --- .../EKF/aid_sources/magnetometer/mag_control.cpp | 4 ++-- .../EKF/aid_sources/magnetometer/mag_fusion.cpp | 15 ++++++++++++++- src/modules/ekf2/EKF/ekf.h | 2 +- 3 files changed, 17 insertions(+), 4 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index 99da95e5a188..f329dc31e7ae 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -237,13 +237,13 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) && PX4_ISFINITE(_wmm_declination_rad) ) { - fuseDeclination(_wmm_declination_rad, 0.5f); + fuseDeclination(_wmm_declination_rad, 0.5f, update_all_states); } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) ) { - fuseDeclination(math::radians(_params.mag_declination_deg), 0.5f); + fuseDeclination(math::radians(_params.mag_declination_deg), 0.5f, update_all_states); } else { _control_status.flags.mag_dec = false; diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp index 18174caad4c0..c4922322c07f 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -151,7 +151,7 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima return false; } -bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma) +bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma, bool update_all_states) { // observation variance (rad**2) const float R_DECL = sq(decl_sigma); @@ -174,6 +174,19 @@ bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma) // Calculate the Kalman gains VectorState Kfusion = P * H / innovation_variance; + if (!update_all_states) { + // zero non-mag Kalman gains if not updating all states + + // copy mag_I and mag_B Kalman gains + const Vector3f K_mag_I = Kfusion.slice(State::mag_I.idx, 0); + const Vector3f K_mag_B = Kfusion.slice(State::mag_B.idx, 0); + + // zero all Kalman gains, then restore mag + Kfusion.setZero(); + Kfusion.slice(State::mag_I.idx, 0) = K_mag_I; + Kfusion.slice(State::mag_B.idx, 0) = K_mag_B; + } + const bool is_fused = measurementUpdate(Kfusion, H, R_DECL, innovation); _fault_status.flags.bad_mag_decl = !is_fused; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index dd273aa0e1c0..fadbd2256c01 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -773,7 +773,7 @@ class Ekf final : public EstimatorInterface // fuse magnetometer declination measurement // declination uncertainty in radians - bool fuseDeclination(float decl_measurement_rad, float decl_sigma); + bool fuseDeclination(float decl_measurement_rad, float decl_sigma, bool update_all_states = false); #endif // CONFIG_EKF2_MAGNETOMETER From ac48b8b51d52b2e398f39eb1345c510e59c88bf3 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 26 Aug 2024 10:53:17 -0400 Subject: [PATCH 37/87] ekf2: mag declination fusion always if there is no aiding --- .../aid_sources/magnetometer/mag_control.cpp | 21 ++++++++++++------- .../aid_sources/magnetometer/mag_fusion.cpp | 11 ++++------ src/modules/ekf2/EKF/ekf.h | 4 ++-- src/modules/ekf2/test/test_EKF_basics.cpp | 1 + 4 files changed, 21 insertions(+), 16 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp index f329dc31e7ae..13caff5ca2d6 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_control.cpp @@ -205,14 +205,14 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) // if we are using 3-axis magnetometer fusion, but without external NE aiding, // then the declination must be fused as an observation to prevent long term heading drift - const bool no_ne_aiding_or_pre_takeoff = !using_ne_aiding || !_control_status.flags.in_air; - _control_status.flags.mag_dec = _control_status.flags.mag && no_ne_aiding_or_pre_takeoff; + const bool no_ne_aiding_or_not_moving = !using_ne_aiding || _control_status.flags.vehicle_at_rest; + _control_status.flags.mag_dec = _control_status.flags.mag && no_ne_aiding_or_not_moving; if (_control_status.flags.mag) { if (continuing_conditions_passing && _control_status.flags.yaw_align) { - if (checkHaglYawResetReq() || (wmm_updated && no_ne_aiding_or_pre_takeoff)) { + if (checkHaglYawResetReq() || (wmm_updated && no_ne_aiding_or_not_moving)) { ECL_INFO("reset to %s", AID_SRC_NAME); resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); aid_src.time_last_fuse = imu_sample.time_us; @@ -234,19 +234,26 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) if (_control_status.flags.mag_dec) { + // observation variance (rad**2) + const float R_DECL = sq(0.5f); + if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL) && PX4_ISFINITE(_wmm_declination_rad) ) { + // using declination from the world magnetic model fuseDeclination(_wmm_declination_rad, 0.5f, update_all_states); } else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL) && PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f) ) { - - fuseDeclination(math::radians(_params.mag_declination_deg), 0.5f, update_all_states); + // using previously saved declination + fuseDeclination(math::radians(_params.mag_declination_deg), R_DECL, update_all_states); } else { - _control_status.flags.mag_dec = false; + // if there is no aiding coming from an inertial frame we need to fuse some declination + // even if we don't know the value, it's better to fuse 0 than nothing + float declination_rad = 0.f; + fuseDeclination(declination_rad, R_DECL); } } } @@ -254,7 +261,7 @@ void Ekf::controlMagFusion(const imuSample &imu_sample) const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); if (is_fusion_failing) { - if (no_ne_aiding_or_pre_takeoff) { + if (no_ne_aiding_or_not_moving) { ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME); resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D); aid_src.time_last_fuse = imu_sample.time_us; diff --git a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp index c4922322c07f..0bada1b2b60e 100644 --- a/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/aid_sources/magnetometer/mag_fusion.cpp @@ -151,21 +151,18 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima return false; } -bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma, bool update_all_states) +bool Ekf::fuseDeclination(float decl_measurement_rad, float R, bool update_all_states) { - // observation variance (rad**2) - const float R_DECL = sq(decl_sigma); - VectorState H; float decl_pred; float innovation_variance; - sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R_DECL, FLT_EPSILON, + sym::ComputeMagDeclinationPredInnovVarAndH(_state.vector(), P, R, FLT_EPSILON, &decl_pred, &innovation_variance, &H); const float innovation = wrap_pi(decl_pred - decl_measurement_rad); - if (innovation_variance < R_DECL) { + if (innovation_variance < R) { // variance calculation is badly conditioned _fault_status.flags.bad_mag_decl = true; return false; @@ -187,7 +184,7 @@ bool Ekf::fuseDeclination(float decl_measurement_rad, float decl_sigma, bool upd Kfusion.slice(State::mag_B.idx, 0) = K_mag_B; } - const bool is_fused = measurementUpdate(Kfusion, H, R_DECL, innovation); + const bool is_fused = measurementUpdate(Kfusion, H, R, innovation); _fault_status.flags.bad_mag_decl = !is_fused; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index fadbd2256c01..7be3fdf92afb 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -772,8 +772,8 @@ class Ekf final : public EstimatorInterface bool update_all_states = false, bool update_tilt = false); // fuse magnetometer declination measurement - // declination uncertainty in radians - bool fuseDeclination(float decl_measurement_rad, float decl_sigma, bool update_all_states = false); + // R: declination observation variance (rad**2) + bool fuseDeclination(const float decl_measurement_rad, const float R, bool update_all_states = false); #endif // CONFIG_EKF2_MAGNETOMETER diff --git a/src/modules/ekf2/test/test_EKF_basics.cpp b/src/modules/ekf2/test/test_EKF_basics.cpp index 0d34e676cbb9..e95443344235 100644 --- a/src/modules/ekf2/test/test_EKF_basics.cpp +++ b/src/modules/ekf2/test/test_EKF_basics.cpp @@ -108,6 +108,7 @@ TEST_F(EkfBasicsTest, initialControlMode) EXPECT_EQ(1, (int) _ekf->control_status_flags().mag_hdg); EXPECT_EQ(0, (int) _ekf->control_status_flags().mag_3D); EXPECT_EQ(1, (int) _ekf->control_status_flags().mag); + EXPECT_EQ(1, (int) _ekf->control_status_flags().mag_dec); EXPECT_EQ(0, (int) _ekf->control_status_flags().in_air); EXPECT_EQ(0, (int) _ekf->control_status_flags().wind); EXPECT_EQ(1, (int) _ekf->control_status_flags().baro_hgt); From 5ff4eea87091da71115de0775da107c662f65aaf Mon Sep 17 00:00:00 2001 From: dagar Date: Mon, 26 Aug 2024 17:06:27 +0000 Subject: [PATCH 38/87] [AUTO COMMIT] update change indication --- .../test/change_indication/ekf_gsf_reset.csv | 644 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 560 +++++++-------- 2 files changed, 602 insertions(+), 602 deletions(-) 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 357bfb7370d0..f12f21d9dd01 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -67,325 +67,325 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 6490000,1,-0.0093,-0.011,0.00026,0.0049,0.0055,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-7.3e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.0001,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,2.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6590000,1,-0.0093,-0.011,0.00019,0.0037,0.0055,-0.099,0.0018,0.001,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,-3.6e+02,0.0015,0.0015,9.6e-05,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6690000,1,-0.0093,-0.011,0.00012,0.0046,0.0051,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,-3.6e+02,0.0016,0.0016,9.9e-05,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,2.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6790000,0.7,0.0013,-0.014,0.71,0.003,0.0048,-0.11,0.0017,0.0014,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-5.7e-05,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.19,0.19,0.6,0.11,0.11,0.2,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.002,0.0025,0.0025,0.0025,0.0025,1,1,1.7 -6890000,0.7,0.0013,-0.014,0.71,0.0011,0.0051,-0.12,0.0019,0.0019,-3.7e+02,-0.0015,-0.0057,-7.5e-05,0,0,-0.00011,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.21,0.21,0.46,0.14,0.14,0.18,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.0014,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -6990000,0.7,0.0014,-0.014,0.71,0.0012,0.0057,-0.12,0.002,0.0024,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-5.1e-06,4.4e-06,-0.00041,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.25,0.25,0.36,0.17,0.17,0.16,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.001,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7090000,0.7,0.0013,-0.014,0.71,-0.00037,-0.00015,-0.13,0.002,0.0025,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.00077,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.29,1e+02,1e+02,0.16,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.00086,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7190000,0.7,0.0013,-0.014,0.71,-0.0019,-0.00023,-0.15,0.0019,0.0025,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.00055,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.24,1e+02,1e+02,0.15,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.00071,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7290000,0.7,0.0014,-0.014,0.71,-0.0033,-0.00022,-0.15,0.0017,0.0025,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0012,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.2,51,51,0.14,8e-05,8e-05,2.4e-06,0.04,0.04,0.04,0.0025,0.00061,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7390000,0.7,0.0014,-0.014,0.71,-0.0032,0.0011,-0.16,0.0014,0.0026,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0014,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.18,52,52,0.13,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.00054,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7490000,0.71,0.0015,-0.014,0.71,-0.0047,0.0013,-0.16,0.0012,0.0027,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0022,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.15,35,35,0.12,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.00048,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7590000,0.71,0.0015,-0.014,0.71,-0.0064,0.0023,-0.17,0.00071,0.0028,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.003,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,25,25,0.14,37,37,0.12,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.00043,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7690000,0.7,0.0015,-0.014,0.71,-0.0079,0.0029,-0.16,0.00044,0.003,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0051,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,24,24,0.13,28,28,0.11,8e-05,8e-05,2.4e-06,0.04,0.04,0.039,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,1,1,2 -7790000,0.71,0.0016,-0.014,0.71,-0.0091,0.0036,-0.16,-0.0004,0.0033,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0071,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,24,24,0.12,30,30,0.11,8e-05,8e-05,2.4e-06,0.04,0.04,0.038,0.0025,0.00036,0.0025,0.0025,0.0025,0.0025,1,1,2 -7890000,0.71,0.0016,-0.014,0.71,-0.011,0.0052,-0.16,-0.0007,0.0035,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.0096,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,23,23,0.11,25,25,0.1,8e-05,8e-05,2.4e-06,0.04,0.04,0.038,0.0025,0.00033,0.0025,0.0025,0.0025,0.0025,1,1,2 -7990000,0.71,0.0016,-0.014,0.71,-0.013,0.0061,-0.16,-0.0019,0.004,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.011,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,23,23,0.1,27,27,0.099,8e-05,8e-05,2.4e-06,0.04,0.04,0.038,0.0025,0.00031,0.0025,0.0025,0.0025,0.0025,1,1,2 -8090000,0.71,0.0016,-0.014,0.71,-0.014,0.0071,-0.17,-0.0022,0.0043,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.011,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,21,21,0.1,23,23,0.097,8e-05,8e-05,2.4e-06,0.04,0.04,0.037,0.0025,0.00029,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8190000,0.71,0.0016,-0.014,0.71,-0.017,0.0084,-0.18,-0.0037,0.0051,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.013,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0015,0.0015,0.09,21,21,0.099,26,26,0.094,8e-05,8e-05,2.4e-06,0.04,0.04,0.037,0.0025,0.00027,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8290000,0.71,0.0016,-0.014,0.71,-0.017,0.0087,-0.17,-0.0039,0.0053,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.017,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,19,19,0.097,22,22,0.091,8e-05,8e-05,2.4e-06,0.04,0.04,0.036,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8390000,0.71,0.0017,-0.014,0.71,-0.019,0.0097,-0.17,-0.0057,0.0062,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.021,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,19,19,0.097,25,25,0.091,8e-05,8e-05,2.4e-06,0.04,0.04,0.035,0.0025,0.00024,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8490000,0.71,0.0017,-0.014,0.71,-0.02,0.011,-0.17,-0.0056,0.0063,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.025,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,17,17,0.096,22,22,0.089,8e-05,8e-05,2.4e-06,0.04,0.04,0.034,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8590000,0.71,0.0017,-0.014,0.71,-0.022,0.013,-0.17,-0.0077,0.0074,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.029,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,17,17,0.095,25,25,0.088,8e-05,8e-05,2.4e-06,0.04,0.04,0.033,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8690000,0.71,0.0017,-0.014,0.71,-0.023,0.013,-0.16,-0.0074,0.0074,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.035,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0017,0.0017,0.09,15,15,0.096,22,22,0.088,7.9e-05,8e-05,2.4e-06,0.04,0.04,0.033,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8790000,0.71,0.0017,-0.014,0.71,-0.025,0.015,-0.15,-0.0099,0.0088,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.041,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0017,0.0017,0.09,15,15,0.095,25,25,0.087,7.9e-05,8e-05,2.4e-06,0.04,0.04,0.032,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8890000,0.71,0.0017,-0.014,0.71,-0.027,0.015,-0.15,-0.013,0.01,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.045,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0017,0.0017,0.09,15,15,0.095,28,28,0.086,7.9e-05,8e-05,2.4e-06,0.04,0.04,0.03,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -8990000,0.71,0.0018,-0.014,0.71,-0.027,0.015,-0.14,-0.012,0.01,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.051,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,14,14,0.096,24,24,0.087,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.029,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9090000,0.71,0.0018,-0.014,0.71,-0.03,0.016,-0.14,-0.015,0.012,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.053,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,14,14,0.095,27,27,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.028,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9190000,0.71,0.0018,-0.014,0.71,-0.029,0.016,-0.14,-0.014,0.011,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.057,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,12,12,0.094,24,24,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.027,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9290000,0.71,0.0018,-0.014,0.71,-0.031,0.017,-0.14,-0.017,0.013,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.061,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,12,12,0.093,26,26,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.025,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9390000,0.71,0.0018,-0.014,0.71,-0.03,0.017,-0.14,-0.016,0.012,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.065,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,10,10,0.093,23,23,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.024,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9490000,0.71,0.0018,-0.014,0.71,-0.032,0.018,-0.13,-0.019,0.014,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.068,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,10,10,0.091,26,26,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.023,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9590000,0.71,0.0019,-0.014,0.71,-0.032,0.018,-0.13,-0.017,0.013,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.072,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.002,0.002,0.09,8.9,8.9,0.09,22,22,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.021,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9690000,0.71,0.0019,-0.014,0.71,-0.034,0.02,-0.12,-0.021,0.015,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.077,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.002,0.002,0.09,9,9,0.089,25,25,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.02,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9790000,0.71,0.0019,-0.014,0.71,-0.032,0.021,-0.11,-0.019,0.014,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.082,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,7.8,7.8,0.087,22,22,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.019,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9890000,0.71,0.0019,-0.014,0.71,-0.035,0.022,-0.11,-0.022,0.016,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.085,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,7.8,7.8,0.084,24,24,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9990000,0.71,0.002,-0.014,0.71,-0.034,0.021,-0.1,-0.021,0.016,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.089,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.09,6.8,6.8,0.083,21,21,0.086,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -10090000,0.71,0.002,-0.014,0.71,-0.036,0.021,-0.096,-0.024,0.018,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.091,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0022,0.0022,0.09,6.9,6.9,0.08,23,23,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10190000,0.71,0.002,-0.014,0.71,-0.035,0.022,-0.096,-0.022,0.017,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.093,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.09,6,6,0.078,20,20,0.084,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10290000,0.71,0.002,-0.014,0.71,-0.037,0.022,-0.084,-0.026,0.019,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7.8e-06,6.8e-06,-0.098,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.09,6.1,6.1,0.076,22,22,0.085,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10390000,0.71,0.002,-0.013,0.71,0.0092,-0.02,0.0096,0.00086,-0.0018,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-7e-05,5.4e-05,-0.1,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.25,0.25,0.56,0.25,0.25,0.078,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10490000,0.71,0.002,-0.013,0.71,0.0077,-0.018,0.023,0.0017,-0.0036,-3.7e+02,-0.0015,-0.0057,-7.5e-05,-0.00015,0.00012,-0.1,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.26,0.26,0.55,0.26,0.26,0.08,7.9e-05,7.9e-05,2.4e-06,0.04,0.04,0.012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10590000,0.71,0.0021,-0.014,0.71,0.0072,-0.0075,0.026,0.0018,-0.00083,-3.7e+02,-0.0015,-0.0057,-7.4e-05,-0.0004,0.00047,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.13,0.13,0.27,0.13,0.13,0.073,7.8e-05,7.8e-05,2.4e-06,0.04,0.04,0.012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10690000,0.71,0.0022,-0.014,0.71,0.0049,-0.0074,0.03,0.0024,-0.0016,-3.7e+02,-0.0015,-0.0057,-7.4e-05,-0.00043,0.00049,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0025,0.0025,0.09,0.15,0.15,0.26,0.14,0.14,0.078,7.8e-05,7.8e-05,2.4e-06,0.04,0.04,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10790000,0.71,0.0022,-0.014,0.71,0.0043,-0.0046,0.024,0.0027,-0.00079,-3.7e+02,-0.0015,-0.0057,-7.3e-05,-0.00045,0.00085,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.1,0.1,0.17,0.09,0.09,0.072,7.4e-05,7.4e-05,2.4e-06,0.039,0.039,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10890000,0.71,0.0021,-0.014,0.71,0.0028,-0.0039,0.02,0.003,-0.0012,-3.7e+02,-0.0015,-0.0057,-7.3e-05,-0.00044,0.00085,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0025,0.0025,0.09,0.12,0.12,0.16,0.097,0.097,0.075,7.4e-05,7.4e-05,2.4e-06,0.039,0.039,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -10990000,0.71,0.0022,-0.014,0.71,0.0052,0.0011,0.014,0.0046,-0.0024,-3.7e+02,-0.0015,-0.0056,-7.2e-05,-0.00019,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0023,0.0023,0.09,0.095,0.095,0.12,0.072,0.072,0.071,6.9e-05,6.9e-05,2.4e-06,0.038,0.038,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11090000,0.71,0.0022,-0.014,0.71,0.0036,0.0031,0.019,0.0051,-0.0022,-3.7e+02,-0.0015,-0.0056,-7.2e-05,-0.00021,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0024,0.0024,0.09,0.12,0.12,0.11,0.079,0.079,0.074,6.9e-05,6.9e-05,2.4e-06,0.038,0.038,0.011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11190000,0.71,0.0021,-0.014,0.71,0.0084,0.0059,0.0076,0.0065,-0.003,-3.7e+02,-0.0015,-0.0055,-7.2e-05,0.00031,0.0029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,0.094,0.094,0.084,0.062,0.062,0.069,6.2e-05,6.2e-05,2.4e-06,0.037,0.037,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11290000,0.71,0.0022,-0.014,0.71,0.0077,0.0078,0.0073,0.0073,-0.0023,-3.7e+02,-0.0015,-0.0055,-7.2e-05,0.00031,0.0029,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0021,0.0021,0.09,0.12,0.12,0.078,0.069,0.069,0.072,6.2e-05,6.2e-05,2.4e-06,0.037,0.037,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11390000,0.71,0.0022,-0.014,0.71,0.0035,0.0071,0.0017,0.0054,-0.0021,-3.7e+02,-0.0015,-0.0056,-7.2e-05,0.00023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0018,0.0018,0.09,0.094,0.094,0.063,0.057,0.057,0.068,5.4e-05,5.4e-05,2.4e-06,0.035,0.035,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11490000,0.71,0.0023,-0.014,0.71,0.00066,0.0096,0.0025,0.0056,-0.0013,-3.7e+02,-0.0015,-0.0056,-7.2e-05,0.00023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0019,0.0019,0.09,0.12,0.12,0.058,0.064,0.064,0.069,5.4e-05,5.4e-05,2.4e-06,0.035,0.035,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11590000,0.71,0.0021,-0.014,0.71,-0.0032,0.0087,-0.0034,0.0043,-0.0015,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00053,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,0.093,0.093,0.049,0.053,0.053,0.066,4.7e-05,4.7e-05,2.4e-06,0.034,0.034,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11690000,0.71,0.0021,-0.014,0.71,-0.0063,0.012,-0.008,0.0039,-0.00053,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00054,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0016,0.0016,0.09,0.11,0.11,0.046,0.062,0.062,0.066,4.7e-05,4.7e-05,2.4e-06,0.034,0.034,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 -11790000,0.71,0.0022,-0.014,0.71,-0.011,0.012,-0.0098,0.0017,0.00048,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00043,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0013,0.0013,0.09,0.09,0.09,0.039,0.051,0.051,0.063,4.1e-05,4.1e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 -11890000,0.71,0.0022,-0.014,0.71,-0.013,0.013,-0.011,0.00051,0.0017,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00043,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0014,0.0014,0.09,0.11,0.11,0.037,0.06,0.06,0.063,4.1e-05,4.1e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 -11990000,0.71,0.0022,-0.014,0.71,-0.014,0.013,-0.016,-0.00041,0.0023,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00062,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0011,0.0011,0.09,0.085,0.085,0.033,0.05,0.05,0.061,3.6e-05,3.6e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3 -12090000,0.71,0.0022,-0.014,0.71,-0.016,0.015,-0.022,-0.0019,0.0036,-3.7e+02,-0.0015,-0.0056,-7.4e-05,0.00063,0.0016,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0012,0.0012,0.09,0.1,0.1,0.031,0.059,0.059,0.061,3.6e-05,3.6e-05,2.4e-06,0.033,0.033,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12190000,0.71,0.0019,-0.014,0.71,-0.0095,0.013,-0.017,0.0012,0.0019,-3.7e+02,-0.0014,-0.0056,-7.7e-05,0.0016,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00099,0.00099,0.09,0.08,0.08,0.028,0.049,0.049,0.059,3.2e-05,3.2e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12290000,0.71,0.0019,-0.014,0.71,-0.012,0.014,-0.016,0.00011,0.0033,-3.7e+02,-0.0014,-0.0056,-7.7e-05,0.0016,0.0018,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.001,0.001,0.09,0.095,0.095,0.028,0.058,0.058,0.059,3.2e-05,3.2e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12390000,0.71,0.0016,-0.014,0.71,-0.0067,0.011,-0.015,0.0026,0.0017,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0.0023,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00088,0.00088,0.09,0.075,0.075,0.026,0.049,0.049,0.057,2.9e-05,2.9e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12490000,0.71,0.0016,-0.014,0.71,-0.0081,0.013,-0.018,0.0019,0.0029,-3.7e+02,-0.0013,-0.0056,-7.9e-05,0.0023,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0009,0.00089,0.09,0.088,0.088,0.026,0.058,0.058,0.057,2.9e-05,2.9e-05,2.4e-06,0.032,0.032,0.01,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12590000,0.71,0.0016,-0.014,0.71,-0.015,0.011,-0.023,-0.003,0.0016,-3.7e+02,-0.0013,-0.0057,-7.9e-05,0.0023,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00079,0.00079,0.09,0.07,0.07,0.025,0.049,0.049,0.055,2.7e-05,2.7e-05,2.4e-06,0.032,0.032,0.0099,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12690000,0.71,0.0016,-0.014,0.71,-0.016,0.013,-0.027,-0.0046,0.0028,-3.7e+02,-0.0013,-0.0057,-7.9e-05,0.0023,0.0015,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00081,0.00081,0.09,0.081,0.081,0.025,0.057,0.057,0.055,2.7e-05,2.7e-05,2.4e-06,0.032,0.032,0.0098,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12790000,0.71,0.0017,-0.014,0.71,-0.02,0.0098,-0.03,-0.0078,0.0015,-3.7e+02,-0.0013,-0.0057,-8e-05,0.0024,0.0012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00073,0.00073,0.09,0.065,0.065,0.024,0.048,0.048,0.053,2.5e-05,2.5e-05,2.4e-06,0.032,0.032,0.0097,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12890000,0.71,0.0016,-0.014,0.71,-0.021,0.0099,-0.03,-0.0099,0.0025,-3.7e+02,-0.0013,-0.0057,-8e-05,0.0024,0.0012,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00074,0.00074,0.09,0.075,0.075,0.025,0.057,0.057,0.054,2.5e-05,2.5e-05,2.4e-06,0.032,0.032,0.0096,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -12990000,0.71,0.0013,-0.014,0.71,-0.0093,0.0075,-0.03,-0.0014,0.0013,-3.7e+02,-0.0012,-0.0057,-8.2e-05,0.0026,0.0017,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00068,0.00068,0.09,0.061,0.061,0.025,0.048,0.048,0.052,2.3e-05,2.3e-05,2.4e-06,0.032,0.032,0.0094,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13090000,0.71,0.0014,-0.014,0.71,-0.01,0.0079,-0.03,-0.0024,0.002,-3.7e+02,-0.0012,-0.0057,-8.2e-05,0.0026,0.0017,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00069,0.00069,0.09,0.069,0.069,0.025,0.056,0.056,0.052,2.3e-05,2.3e-05,2.4e-06,0.032,0.032,0.0094,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13190000,0.71,0.0011,-0.014,0.71,-0.001,0.0074,-0.027,0.0039,0.0012,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.0026,0.002,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00064,0.00064,0.09,0.057,0.057,0.025,0.048,0.048,0.051,2.2e-05,2.2e-05,2.4e-06,0.032,0.032,0.0091,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13290000,0.71,0.0012,-0.014,0.71,-0.0013,0.0085,-0.024,0.0038,0.002,-3.7e+02,-0.0012,-0.0057,-8.3e-05,0.0026,0.0021,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00066,0.00066,0.09,0.065,0.065,0.027,0.056,0.056,0.051,2.2e-05,2.2e-05,2.4e-06,0.032,0.032,0.0091,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13390000,0.71,0.001,-0.014,0.71,-0.00029,0.0075,-0.02,0.0028,0.0011,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0024,0.0021,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00062,0.00062,0.09,0.053,0.053,0.026,0.048,0.048,0.05,2.1e-05,2.1e-05,2.4e-06,0.032,0.032,0.0088,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13490000,0.71,0.001,-0.014,0.71,-0.0008,0.0078,-0.019,0.0028,0.0019,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0024,0.0022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00063,0.00063,0.09,0.06,0.06,0.028,0.056,0.056,0.05,2.1e-05,2.1e-05,2.4e-06,0.032,0.032,0.0087,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13590000,0.71,0.00099,-0.014,0.71,-0.00037,0.008,-0.021,0.002,0.0011,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0006,0.0006,0.09,0.05,0.05,0.028,0.048,0.048,0.05,2e-05,2e-05,2.4e-06,0.032,0.032,0.0084,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13690000,0.71,0.00098,-0.014,0.71,0.00032,0.01,-0.025,0.002,0.002,-3.7e+02,-0.0011,-0.0057,-8.4e-05,0.0023,0.0022,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00061,0.00061,0.09,0.057,0.057,0.029,0.055,0.055,0.05,2e-05,2e-05,2.4e-06,0.032,0.032,0.0083,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13790000,0.71,0.00089,-0.014,0.71,0.001,0.0061,-0.027,0.003,-0.00046,-3.7e+02,-0.0011,-0.0057,-8.5e-05,0.0021,0.0026,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00058,0.00058,0.066,0.047,0.047,0.029,0.047,0.047,0.049,1.9e-05,1.9e-05,2.4e-06,0.032,0.032,0.0079,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13890000,0.71,0.00086,-0.014,0.71,0.0015,0.0064,-0.031,0.0032,0.00014,-3.7e+02,-0.0011,-0.0057,-8.5e-05,0.0021,0.0026,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00059,0.00059,0.066,0.053,0.053,0.03,0.055,0.055,0.05,1.9e-05,1.9e-05,2.4e-06,0.032,0.032,0.0078,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13990000,0.71,0.00081,-0.014,0.71,0.0019,0.004,-0.03,0.004,-0.0018,-3.7e+02,-0.0011,-0.0058,-8.6e-05,0.0019,0.0029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00057,0.00057,0.066,0.045,0.045,0.03,0.047,0.047,0.05,1.8e-05,1.8e-05,2.4e-06,0.031,0.031,0.0074,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -14090000,0.71,0.0008,-0.014,0.71,0.002,0.0046,-0.031,0.0042,-0.0014,-3.7e+02,-0.0011,-0.0058,-8.6e-05,0.0019,0.0029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00058,0.00058,0.066,0.05,0.05,0.031,0.054,0.054,0.05,1.8e-05,1.8e-05,2.4e-06,0.031,0.031,0.0073,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14190000,0.71,0.0007,-0.014,0.71,0.0053,0.0039,-0.033,0.0063,-0.0014,-3.7e+02,-0.001,-0.0058,-8.7e-05,0.0014,0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00056,0.00056,0.066,0.043,0.043,0.03,0.047,0.047,0.05,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0069,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14290000,0.71,0.00072,-0.014,0.71,0.0061,0.0051,-0.032,0.0069,-0.00095,-3.7e+02,-0.001,-0.0058,-8.7e-05,0.0014,0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00057,0.00057,0.066,0.048,0.048,0.031,0.054,0.054,0.051,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0067,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14390000,0.71,0.00064,-0.014,0.71,0.008,0.0059,-0.034,0.0083,-0.001,-3.7e+02,-0.001,-0.0058,-8.8e-05,0.001,0.0031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00055,0.00055,0.066,0.041,0.041,0.031,0.047,0.047,0.05,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0063,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14490000,0.71,0.00063,-0.014,0.71,0.008,0.0076,-0.037,0.0091,-0.00035,-3.7e+02,-0.001,-0.0058,-8.8e-05,0.001,0.0031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00056,0.00056,0.066,0.046,0.046,0.032,0.054,0.054,0.051,1.7e-05,1.7e-05,2.4e-06,0.031,0.031,0.0062,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14590000,0.71,0.00064,-0.013,0.71,0.005,0.006,-0.037,0.0057,-0.0019,-3.7e+02,-0.0011,-0.0058,-8.8e-05,0.0015,0.0037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00055,0.00055,0.066,0.039,0.039,0.031,0.046,0.046,0.051,1.6e-05,1.6e-05,2.4e-06,0.031,0.031,0.0058,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14690000,0.71,0.00061,-0.013,0.71,0.0064,0.0036,-0.034,0.0063,-0.0014,-3.7e+02,-0.0011,-0.0058,-8.8e-05,0.0015,0.0038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00056,0.00056,0.066,0.044,0.044,0.032,0.053,0.053,0.051,1.6e-05,1.6e-05,2.4e-06,0.031,0.031,0.0056,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14790000,0.71,0.00065,-0.013,0.71,0.0036,0.0019,-0.03,0.0035,-0.0027,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.002,0.0044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00054,0.00054,0.066,0.038,0.038,0.031,0.046,0.046,0.051,1.5e-05,1.5e-05,2.4e-06,0.03,0.03,0.0053,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14890000,0.71,0.00065,-0.013,0.71,0.0052,0.0034,-0.033,0.004,-0.0024,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.002,0.0044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00055,0.00055,0.066,0.042,0.042,0.031,0.053,0.053,0.052,1.5e-05,1.5e-05,2.4e-06,0.03,0.03,0.0051,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -14990000,0.71,0.00064,-0.013,0.71,0.0042,0.0029,-0.029,0.0031,-0.0021,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0022,0.0046,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00053,0.00053,0.066,0.037,0.037,0.03,0.046,0.046,0.051,1.4e-05,1.4e-05,2.4e-06,0.03,0.03,0.0048,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15090000,0.71,0.00057,-0.013,0.71,0.0047,0.0033,-0.032,0.0035,-0.0018,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0022,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00054,0.00054,0.066,0.041,0.041,0.031,0.053,0.053,0.052,1.4e-05,1.4e-05,2.4e-06,0.03,0.03,0.0046,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15190000,0.71,0.00058,-0.013,0.71,0.0042,0.0041,-0.029,0.0028,-0.0015,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0023,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00053,0.00052,0.066,0.036,0.036,0.03,0.046,0.046,0.052,1.4e-05,1.4e-05,2.4e-06,0.029,0.029,0.0043,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15290000,0.71,0.00055,-0.013,0.71,0.005,0.0049,-0.027,0.0032,-0.0011,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0023,0.0048,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00054,0.00054,0.066,0.04,0.04,0.03,0.052,0.052,0.052,1.4e-05,1.4e-05,2.4e-06,0.029,0.029,0.0042,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15390000,0.71,0.00055,-0.013,0.71,0.0043,0.0048,-0.025,0.00066,-0.001,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0026,0.005,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00052,0.00052,0.066,0.035,0.035,0.029,0.046,0.046,0.051,1.3e-05,1.3e-05,2.4e-06,0.029,0.029,0.0039,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15490000,0.71,0.00058,-0.013,0.71,0.0058,0.005,-0.025,0.0012,-0.00055,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0026,0.005,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00053,0.00053,0.066,0.039,0.039,0.029,0.052,0.052,0.053,1.3e-05,1.3e-05,2.4e-06,0.029,0.029,0.0037,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15590000,0.71,0.00059,-0.013,0.71,0.004,0.0046,-0.023,-0.0011,-0.0006,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0029,0.0054,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00051,0.00051,0.066,0.034,0.034,0.028,0.045,0.045,0.052,1.2e-05,1.2e-05,2.4e-06,0.028,0.028,0.0035,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15690000,0.71,0.0006,-0.013,0.71,0.0045,0.005,-0.024,-0.00068,-0.00011,-3.7e+02,-0.0011,-0.0058,-8.7e-05,0.0029,0.0054,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00052,0.00052,0.066,0.038,0.038,0.028,0.052,0.052,0.052,1.2e-05,1.2e-05,2.4e-06,0.028,0.028,0.0033,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 -15790000,0.71,0.00059,-0.013,0.71,0.0049,0.003,-0.026,-0.00071,-0.0015,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.003,0.0061,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0005,0.0005,0.066,0.034,0.034,0.027,0.045,0.045,0.051,1.2e-05,1.2e-05,2.4e-06,0.027,0.027,0.0031,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 -15890000,0.71,0.00055,-0.013,0.71,0.0061,0.0031,-0.024,-0.00013,-0.0012,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.0029,0.0061,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00051,0.00051,0.066,0.037,0.037,0.027,0.051,0.051,0.052,1.2e-05,1.2e-05,2.4e-06,0.027,0.027,0.003,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 -15990000,0.71,0.00052,-0.013,0.71,0.0059,0.0019,-0.02,-0.00031,-0.0024,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.003,0.0069,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00049,0.00049,0.066,0.033,0.033,0.026,0.045,0.045,0.051,1.1e-05,1.1e-05,2.4e-06,0.026,0.026,0.0028,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4 -16090000,0.71,0.00053,-0.013,0.71,0.0079,0.0023,-0.016,0.00036,-0.0022,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.003,0.0069,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0005,0.0005,0.066,0.037,0.037,0.025,0.051,0.051,0.052,1.1e-05,1.1e-05,2.4e-06,0.026,0.026,0.0027,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16190000,0.71,0.00055,-0.013,0.71,0.0079,0.0025,-0.015,5.6e-05,-0.0019,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0034,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00048,0.00048,0.066,0.033,0.033,0.025,0.045,0.045,0.051,1e-05,1e-05,2.4e-06,0.026,0.026,0.0025,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16290000,0.71,0.00057,-0.013,0.71,0.0097,0.0022,-0.016,0.00094,-0.0017,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0034,0.0071,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00049,0.00049,0.066,0.036,0.036,0.024,0.051,0.051,0.052,1e-05,1e-05,2.4e-06,0.026,0.026,0.0024,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16390000,0.71,0.00056,-0.013,0.71,0.0086,0.0014,-0.015,0.00051,-0.0015,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0039,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00046,0.00046,0.066,0.032,0.032,0.023,0.045,0.045,0.051,9.6e-06,9.6e-06,2.4e-06,0.025,0.025,0.0022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16490000,0.71,0.00058,-0.013,0.71,0.0081,0.0023,-0.018,0.0013,-0.0013,-3.7e+02,-0.0012,-0.0059,-8.7e-05,0.0039,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00047,0.00047,0.066,0.036,0.036,0.023,0.051,0.051,0.052,9.6e-06,9.6e-06,2.4e-06,0.025,0.025,0.0021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16590000,0.71,0.00079,-0.013,0.71,0.0048,0.0041,-0.018,-0.0016,0.0014,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0057,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00045,0.00045,0.066,0.032,0.032,0.022,0.045,0.045,0.051,8.9e-06,8.9e-06,2.4e-06,0.024,0.024,0.002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16690000,0.71,0.00078,-0.013,0.71,0.0052,0.005,-0.015,-0.0011,0.0019,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0057,0.0069,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00046,0.00046,0.066,0.035,0.035,0.022,0.051,0.051,0.051,8.9e-06,8.9e-06,2.4e-06,0.024,0.024,0.0019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16790000,0.71,0.0009,-0.013,0.71,0.002,0.0064,-0.014,-0.0035,0.004,-3.7e+02,-0.0012,-0.0058,-8.4e-05,0.0072,0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00043,0.00043,0.066,0.031,0.031,0.021,0.045,0.045,0.05,8.3e-06,8.3e-06,2.4e-06,0.023,0.023,0.0018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16890000,0.71,0.00092,-0.013,0.71,0.002,0.0077,-0.011,-0.0033,0.0046,-3.7e+02,-0.0012,-0.0058,-8.4e-05,0.0072,0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00044,0.00044,0.066,0.035,0.035,0.021,0.05,0.05,0.051,8.3e-06,8.3e-06,2.4e-06,0.023,0.023,0.0017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -16990000,0.71,0.00091,-0.013,0.71,0.0019,0.0054,-0.011,-0.004,0.0025,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0075,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00042,0.00042,0.066,0.031,0.031,0.02,0.044,0.044,0.05,7.7e-06,7.7e-06,2.4e-06,0.022,0.022,0.0016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17090000,0.71,0.00088,-0.013,0.71,0.003,0.0068,-0.01,-0.0038,0.0031,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0075,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00043,0.00043,0.066,0.034,0.034,0.02,0.05,0.05,0.05,7.7e-06,7.7e-06,2.4e-06,0.022,0.022,0.0016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17190000,0.71,0.00093,-0.013,0.71,0.0032,0.0065,-0.011,-0.0044,0.0013,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0078,0.0089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0004,0.0004,0.066,0.031,0.031,0.019,0.044,0.044,0.049,7.2e-06,7.2e-06,2.4e-06,0.021,0.021,0.0015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17290000,0.71,0.00091,-0.013,0.71,0.0056,0.008,-0.0067,-0.004,0.002,-3.7e+02,-0.0013,-0.0059,-8.4e-05,0.0078,0.009,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00041,0.00041,0.066,0.034,0.034,0.019,0.05,0.05,0.049,7.2e-06,7.2e-06,2.4e-06,0.021,0.021,0.0014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17390000,0.71,0.00092,-0.013,0.71,0.0059,0.0068,-0.0047,-0.0034,0.00031,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00039,0.00039,0.066,0.03,0.03,0.018,0.044,0.044,0.048,6.6e-06,6.6e-06,2.4e-06,0.02,0.02,0.0013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17490000,0.71,0.00092,-0.013,0.71,0.0068,0.0068,-0.003,-0.0028,0.00098,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0004,0.0004,0.066,0.034,0.034,0.018,0.05,0.05,0.049,6.6e-06,6.6e-06,2.4e-06,0.02,0.02,0.0013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17590000,0.71,0.00087,-0.013,0.71,0.0077,0.0053,0.0025,-0.0025,-0.00054,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00037,0.00037,0.066,0.03,0.03,0.017,0.044,0.044,0.048,6.1e-06,6.1e-06,2.4e-06,0.019,0.019,0.0012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17690000,0.71,0.00084,-0.013,0.71,0.0089,0.0064,0.0019,-0.0016,1.4e-05,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0076,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00038,0.00038,0.066,0.033,0.033,0.017,0.05,0.05,0.048,6.1e-06,6.1e-06,2.4e-06,0.019,0.019,0.0012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17790000,0.71,0.00076,-0.013,0.71,0.011,0.0055,0.00056,-0.0009,-0.00017,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0071,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00036,0.00036,0.066,0.03,0.03,0.016,0.044,0.044,0.048,5.6e-06,5.6e-06,2.4e-06,0.018,0.018,0.0011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17890000,0.71,0.00077,-0.013,0.71,0.013,0.0052,0.00065,0.00028,0.0004,-3.7e+02,-0.0013,-0.0059,-8.5e-05,0.0071,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00036,0.00036,0.066,0.033,0.033,0.016,0.05,0.05,0.048,5.6e-06,5.7e-06,2.4e-06,0.018,0.018,0.0011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17990000,0.71,0.00071,-0.013,0.71,0.014,0.0029,0.0019,0.00061,0.00014,-3.7e+02,-0.0013,-0.006,-8.6e-05,0.0069,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00034,0.00034,0.066,0.029,0.029,0.016,0.044,0.044,0.047,5.2e-06,5.2e-06,2.4e-06,0.017,0.017,0.00099,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -18090000,0.71,0.00072,-0.013,0.71,0.015,0.003,0.0043,0.0021,0.0004,-3.7e+02,-0.0013,-0.006,-8.6e-05,0.0069,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00035,0.00035,0.066,0.032,0.032,0.016,0.05,0.05,0.047,5.2e-06,5.2e-06,2.4e-06,0.017,0.017,0.00096,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18190000,0.71,0.00069,-0.013,0.71,0.015,0.0036,0.0056,0.0026,0.00033,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0072,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00032,0.00032,0.066,0.029,0.029,0.015,0.044,0.044,0.047,4.8e-06,4.8e-06,2.4e-06,0.016,0.016,0.00091,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18290000,0.71,0.00063,-0.013,0.71,0.016,0.0033,0.0068,0.0042,0.00068,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0071,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00033,0.00033,0.066,0.032,0.032,0.015,0.05,0.05,0.046,4.8e-06,4.8e-06,2.4e-06,0.016,0.016,0.00088,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18390000,0.71,0.00066,-0.013,0.71,0.017,0.0045,0.008,0.0044,0.0006,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0074,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00031,0.00031,0.066,0.028,0.028,0.014,0.044,0.044,0.046,4.4e-06,4.4e-06,2.4e-06,0.015,0.015,0.00083,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18490000,0.71,0.00068,-0.013,0.71,0.018,0.0052,0.0076,0.0062,0.0011,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0074,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00031,0.00031,0.066,0.031,0.031,0.014,0.05,0.05,0.046,4.4e-06,4.4e-06,2.4e-06,0.015,0.015,0.00081,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18590000,0.71,0.00072,-0.013,0.71,0.017,0.0049,0.0057,0.0049,0.00079,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0083,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00029,0.00029,0.066,0.028,0.028,0.014,0.044,0.044,0.045,4e-06,4.1e-06,2.4e-06,0.014,0.014,0.00076,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18690000,0.71,0.00068,-0.013,0.71,0.017,0.0045,0.0038,0.0065,0.0013,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0083,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0003,0.0003,0.066,0.031,0.031,0.013,0.049,0.049,0.045,4e-06,4.1e-06,2.4e-06,0.014,0.014,0.00074,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18790000,0.71,0.00074,-0.013,0.71,0.015,0.0044,0.0035,0.0052,0.001,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0091,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00028,0.00028,0.066,0.027,0.027,0.013,0.044,0.044,0.045,3.7e-06,3.7e-06,2.4e-06,0.014,0.014,0.00071,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18890000,0.71,0.00077,-0.013,0.71,0.016,0.0051,0.0041,0.0068,0.0016,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0091,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00028,0.00028,0.066,0.03,0.03,0.013,0.049,0.049,0.045,3.7e-06,3.7e-06,2.4e-06,0.014,0.014,0.00068,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -18990000,0.71,0.00076,-0.013,0.71,0.017,0.0056,0.0028,0.0077,0.0012,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.009,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00027,0.00027,0.066,0.027,0.027,0.012,0.044,0.044,0.044,3.4e-06,3.4e-06,2.4e-06,0.013,0.013,0.00065,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19090000,0.71,0.00075,-0.013,0.71,0.018,0.0065,0.0058,0.0095,0.0019,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.009,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00027,0.00027,0.066,0.029,0.029,0.012,0.049,0.049,0.044,3.4e-06,3.4e-06,2.4e-06,0.013,0.013,0.00063,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19190000,0.71,0.00077,-0.012,0.71,0.018,0.006,0.0059,0.0099,0.0015,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0089,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00025,0.00025,0.066,0.026,0.026,0.012,0.044,0.044,0.044,3.1e-06,3.2e-06,2.4e-06,0.012,0.012,0.0006,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19290000,0.71,0.00079,-0.012,0.71,0.018,0.0055,0.0086,0.012,0.0021,-3.7e+02,-0.0013,-0.006,-8.5e-05,0.0089,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00026,0.00026,0.066,0.029,0.029,0.012,0.049,0.049,0.044,3.1e-06,3.2e-06,2.4e-06,0.012,0.012,0.00059,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19390000,0.71,0.00084,-0.012,0.71,0.016,0.0042,0.012,0.0095,0.0016,-3.7e+02,-0.0013,-0.006,-8.4e-05,0.0098,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00024,0.00024,0.066,0.026,0.026,0.012,0.043,0.043,0.043,2.9e-06,2.9e-06,2.4e-06,0.012,0.012,0.00056,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19490000,0.71,0.00086,-0.012,0.71,0.015,0.0037,0.0088,0.011,0.002,-3.7e+02,-0.0013,-0.006,-8.4e-05,0.0098,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00025,0.00025,0.066,0.028,0.028,0.011,0.049,0.049,0.043,2.9e-06,2.9e-06,2.4e-06,0.012,0.012,0.00055,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19590000,0.71,0.00094,-0.012,0.71,0.013,0.0023,0.0081,0.009,0.0016,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.01,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00023,0.00023,0.066,0.025,0.025,0.011,0.043,0.043,0.042,2.7e-06,2.7e-06,2.4e-06,0.011,0.011,0.00052,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19690000,0.71,0.00094,-0.012,0.71,0.013,0.00031,0.0096,0.01,0.0017,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.01,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00023,0.00023,0.066,0.028,0.028,0.011,0.049,0.049,0.042,2.7e-06,2.7e-06,2.4e-06,0.011,0.011,0.00051,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 -19790000,0.71,0.001,-0.012,0.71,0.011,-0.00093,0.01,0.0084,0.0014,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.011,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00022,0.00022,0.066,0.025,0.025,0.011,0.043,0.043,0.042,2.5e-06,2.5e-06,2.4e-06,0.011,0.011,0.00049,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 -19890000,0.71,0.00098,-0.012,0.71,0.0097,-0.001,0.011,0.0094,0.0013,-3.7e+02,-0.0014,-0.006,-8.4e-05,0.011,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00022,0.00022,0.066,0.027,0.027,0.011,0.049,0.049,0.042,2.5e-06,2.5e-06,2.4e-06,0.011,0.011,0.00048,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 -19990000,0.71,0.00098,-0.012,0.71,0.007,-0.0021,0.014,0.0077,0.00099,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00021,0.00021,0.066,0.024,0.024,0.01,0.043,0.043,0.041,2.3e-06,2.3e-06,2.4e-06,0.01,0.01,0.00046,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5 -20090000,0.71,0.00098,-0.012,0.71,0.0069,-0.0039,0.014,0.0084,0.00071,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00021,0.00021,0.066,0.026,0.026,0.01,0.048,0.048,0.042,2.3e-06,2.3e-06,2.4e-06,0.01,0.01,0.00045,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 -20190000,0.71,0.0011,-0.012,0.71,0.0044,-0.0049,0.017,0.0059,0.0006,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0002,0.0002,0.066,0.024,0.024,0.01,0.043,0.043,0.041,2.1e-06,2.1e-06,2.4e-06,0.0097,0.0097,0.00043,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 -20290000,0.71,0.0011,-0.012,0.71,0.0034,-0.0063,0.015,0.0063,3.9e-05,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.012,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.0002,0.0002,0.066,0.026,0.026,0.0099,0.048,0.048,0.041,2.1e-06,2.1e-06,2.4e-06,0.0097,0.0097,0.00042,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 -20390000,0.71,0.0011,-0.012,0.71,0.00074,-0.0073,0.017,0.0041,6.5e-05,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00019,0.00019,0.066,0.023,0.023,0.0097,0.043,0.043,0.041,1.9e-06,1.9e-06,2.4e-06,0.0092,0.0093,0.00041,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.1 -20490000,0.71,0.0011,-0.012,0.71,0.00044,-0.0078,0.016,0.0041,-0.00069,-3.7e+02,-0.0014,-0.006,-8.3e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00019,0.00019,0.066,0.025,0.025,0.0096,0.048,0.048,0.041,1.9e-06,1.9e-06,2.4e-06,0.0092,0.0093,0.0004,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 -20590000,0.71,0.0012,-0.012,0.71,0.0005,-0.0081,0.013,0.0035,-0.00055,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00018,0.00018,0.066,0.023,0.023,0.0093,0.043,0.043,0.04,1.8e-06,1.8e-06,2.4e-06,0.0088,0.0089,0.00038,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 -20690000,0.71,0.0012,-0.012,0.71,0.00066,-0.0094,0.015,0.0035,-0.0014,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00018,0.00018,0.066,0.025,0.025,0.0093,0.048,0.048,0.04,1.8e-06,1.8e-06,2.4e-06,0.0088,0.0089,0.00037,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 -20790000,0.71,0.0012,-0.012,0.71,-0.00073,-0.0088,0.015,0.0029,-0.0011,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00017,0.00017,0.066,0.022,0.022,0.0091,0.043,0.043,0.04,1.7e-06,1.7e-06,2.4e-06,0.0085,0.0085,0.00036,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.2 -20890000,0.71,0.0012,-0.012,0.71,-0.001,-0.011,0.014,0.0028,-0.0021,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00018,0.00018,0.066,0.024,0.024,0.009,0.048,0.048,0.04,1.7e-06,1.7e-06,2.5e-06,0.0085,0.0085,0.00035,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 -20990000,0.71,0.0012,-0.012,0.71,-0.0015,-0.012,0.015,0.0041,-0.0018,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00017,0.00017,0.066,0.022,0.022,0.0088,0.042,0.042,0.039,1.6e-06,1.6e-06,2.5e-06,0.0081,0.0082,0.00034,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 -21090000,0.71,0.0012,-0.012,0.71,-0.0016,-0.014,0.015,0.004,-0.0031,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00017,0.00017,0.066,0.024,0.024,0.0088,0.047,0.047,0.039,1.6e-06,1.6e-06,2.5e-06,0.0081,0.0082,0.00033,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 -21190000,0.71,0.0012,-0.012,0.71,-0.001,-0.013,0.014,0.0051,-0.0025,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00016,0.00016,0.066,0.021,0.021,0.0086,0.042,0.042,0.039,1.5e-06,1.5e-06,2.5e-06,0.0078,0.0078,0.00032,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.3 -21290000,0.71,0.0012,-0.012,0.71,-0.0015,-0.016,0.016,0.005,-0.004,-3.7e+02,-0.0014,-0.006,-8.2e-05,0.013,0.014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00016,0.00016,0.066,0.023,0.023,0.0085,0.047,0.047,0.039,1.5e-06,1.5e-06,2.5e-06,0.0078,0.0078,0.00032,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 -21390000,0.71,0.0013,-0.012,0.71,-0.0025,-0.015,0.016,0.0042,-0.0023,-3.7e+02,-0.0014,-0.0059,-8.2e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.021,0.021,0.0084,0.042,0.042,0.039,1.4e-06,1.4e-06,2.5e-06,0.0075,0.0076,0.00031,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 -21490000,0.71,0.0013,-0.012,0.71,-0.0029,-0.016,0.015,0.0039,-0.0038,-3.7e+02,-0.0014,-0.0059,-8.2e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.023,0.023,0.0083,0.047,0.047,0.038,1.4e-06,1.4e-06,2.5e-06,0.0075,0.0076,0.0003,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 -21590000,0.71,0.0013,-0.012,0.71,-0.0037,-0.014,0.015,0.0033,-0.0021,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.02,0.02,0.0081,0.042,0.042,0.038,1.3e-06,1.3e-06,2.5e-06,0.0073,0.0073,0.00029,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.4 -21690000,0.71,0.0013,-0.012,0.71,-0.0035,-0.015,0.017,0.0029,-0.0035,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.014,0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00015,0.00015,0.066,0.022,0.022,0.0081,0.047,0.047,0.038,1.3e-06,1.3e-06,2.5e-06,0.0073,0.0073,0.00029,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.5 -21790000,0.71,0.0012,-0.013,0.71,-0.0043,-0.0098,0.015,0.0014,0.00015,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.015,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00014,0.00014,0.066,0.02,0.02,0.008,0.042,0.042,0.038,1.2e-06,1.2e-06,2.5e-06,0.007,0.007,0.00028,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.5 -21890000,0.71,0.0012,-0.012,0.71,-0.0042,-0.01,0.016,0.00098,-0.00084,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.015,0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.6e+02,0.00014,0.00014,0.066,0.022,0.022,0.0079,0.047,0.047,0.038,1.2e-06,1.2e-06,2.5e-06,0.007,0.007,0.00028,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,5.5 -21990000,0.71,0.0013,-0.013,0.71,-0.0048,-0.0077,0.016,-0.00016,0.0023,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00014,0.00014,0.066,0.02,0.02,0.0078,0.042,0.042,0.038,1.1e-06,1.1e-06,2.5e-06,0.0068,0.0068,0.00027,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22090000,0.71,0.0013,-0.013,0.71,-0.0051,-0.0068,0.015,-0.00065,0.0016,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00014,0.00014,0.066,0.021,0.021,0.0078,0.046,0.046,0.037,1.1e-06,1.1e-06,2.5e-06,0.0068,0.0068,0.00026,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22190000,0.71,0.0012,-0.013,0.71,-0.0051,-0.006,0.015,-0.00055,0.0014,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.019,0.019,0.0076,0.042,0.042,0.037,1e-06,1e-06,2.5e-06,0.0066,0.0066,0.00026,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22290000,0.71,0.0013,-0.013,0.71,-0.0064,-0.0067,0.015,-0.0011,0.00073,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.021,0.021,0.0076,0.046,0.046,0.037,1e-06,1e-06,2.5e-06,0.0066,0.0066,0.00025,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22390000,0.71,0.0013,-0.013,0.71,-0.0071,-0.0063,0.017,-0.00099,0.00058,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.019,0.019,0.0075,0.041,0.041,0.037,9.9e-07,9.9e-07,2.5e-06,0.0064,0.0064,0.00025,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22490000,0.71,0.0013,-0.013,0.71,-0.0077,-0.0061,0.018,-0.0017,-5.8e-05,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00013,0.00013,0.066,0.02,0.02,0.0074,0.046,0.046,0.037,9.9e-07,9.9e-07,2.5e-06,0.0064,0.0064,0.00024,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22590000,0.71,0.0012,-0.013,0.71,-0.0076,-0.0058,0.017,-0.0022,0.00086,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.018,0.019,0.0073,0.041,0.041,0.036,9.3e-07,9.3e-07,2.5e-06,0.0062,0.0062,0.00024,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22690000,0.71,0.0013,-0.013,0.71,-0.0087,-0.0055,0.018,-0.0031,0.0003,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.02,0.02,0.0073,0.046,0.046,0.036,9.3e-07,9.3e-07,2.5e-06,0.0062,0.0062,0.00023,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22790000,0.71,0.0012,-0.013,0.71,-0.0094,-0.0044,0.019,-0.0044,0.00027,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.018,0.018,0.0072,0.041,0.041,0.036,8.8e-07,8.8e-07,2.5e-06,0.0061,0.0061,0.00023,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22890000,0.71,0.0012,-0.013,0.71,-0.011,-0.004,0.021,-0.0054,-0.00015,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.02,0.02,0.0072,0.046,0.046,0.036,8.8e-07,8.8e-07,2.5e-06,0.0061,0.0061,0.00022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22990000,0.71,0.0012,-0.013,0.71,-0.011,-0.0045,0.022,-0.0063,-0.00017,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0099,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.018,0.018,0.0071,0.041,0.041,0.036,8.4e-07,8.3e-07,2.5e-06,0.0059,0.0059,0.00022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23090000,0.71,0.0012,-0.012,0.71,-0.012,-0.0045,0.022,-0.0075,-0.00061,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0099,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00012,0.00012,0.066,0.019,0.019,0.007,0.045,0.045,0.036,8.4e-07,8.4e-07,2.5e-06,0.0059,0.0059,0.00022,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23190000,0.71,0.0013,-0.012,0.71,-0.013,-0.0055,0.024,-0.011,-0.00059,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.018,0.018,0.0069,0.041,0.041,0.035,8e-07,7.9e-07,2.5e-06,0.0058,0.0058,0.00021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23290000,0.71,0.0012,-0.012,0.71,-0.014,-0.0067,0.024,-0.012,-0.0012,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.019,0.019,0.0069,0.045,0.045,0.036,8e-07,7.9e-07,2.5e-06,0.0058,0.0058,0.00021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23390000,0.71,0.0013,-0.012,0.71,-0.015,-0.0071,0.022,-0.015,-0.0011,-3.7e+02,-0.0014,-0.0059,-8e-05,0.016,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.017,0.017,0.0068,0.041,0.041,0.035,7.6e-07,7.5e-07,2.5e-06,0.0056,0.0056,0.00021,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23490000,0.71,0.0037,-0.01,0.71,-0.022,-0.0078,-0.012,-0.017,-0.0019,-3.7e+02,-0.0014,-0.0059,-8e-05,0.016,0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.019,0.019,0.0068,0.045,0.045,0.035,7.6e-07,7.5e-07,2.5e-06,0.0056,0.0056,0.0002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23590000,0.71,0.0089,-0.0022,0.71,-0.032,-0.0067,-0.043,-0.016,-0.00069,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0095,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.017,0.017,0.0067,0.04,0.04,0.035,7.2e-07,7.2e-07,2.5e-06,0.0055,0.0055,0.0002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23690000,0.71,0.0085,0.0036,0.71,-0.063,-0.015,-0.094,-0.02,-0.0017,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0095,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,0.00011,0.066,0.018,0.019,0.0067,0.045,0.045,0.035,7.2e-07,7.2e-07,2.5e-06,0.0055,0.0055,0.0002,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23790000,0.71,0.0055,0.00025,0.71,-0.087,-0.026,-0.15,-0.02,-0.0012,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0086,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.017,0.017,0.0066,0.04,0.04,0.035,6.9e-07,6.9e-07,2.5e-06,0.0054,0.0054,0.00019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23890000,0.71,0.0029,-0.0058,0.71,-0.1,-0.035,-0.2,-0.029,-0.0043,-3.7e+02,-0.0014,-0.0059,-8e-05,0.015,0.0086,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.018,0.019,0.0066,0.045,0.045,0.035,6.9e-07,6.9e-07,2.5e-06,0.0054,0.0054,0.00019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23990000,0.71,0.0015,-0.01,0.71,-0.1,-0.039,-0.25,-0.033,-0.0076,-3.7e+02,-0.0014,-0.0059,-8e-05,0.014,0.0081,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.9e-05,9.9e-05,0.066,0.017,0.018,0.0066,0.04,0.04,0.035,6.6e-07,6.5e-07,2.5e-06,0.0053,0.0053,0.00019,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24090000,0.71,0.0028,-0.0091,0.71,-0.11,-0.039,-0.3,-0.044,-0.011,-3.7e+02,-0.0014,-0.0059,-8e-05,0.014,0.0081,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,0.0001,0.066,0.018,0.019,0.0065,0.044,0.045,0.035,6.6e-07,6.6e-07,2.5e-06,0.0053,0.0053,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24190000,0.71,0.0038,-0.0069,0.71,-0.11,-0.04,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.013,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.7e-05,9.6e-05,0.066,0.017,0.017,0.0065,0.04,0.04,0.034,6.3e-07,6.3e-07,2.5e-06,0.0052,0.0052,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24290000,0.71,0.0043,-0.006,0.71,-0.12,-0.044,-0.41,-0.057,-0.018,-3.7e+02,-0.0014,-0.0059,-8.1e-05,0.013,0.0074,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.8e-05,9.8e-05,0.066,0.018,0.019,0.0065,0.044,0.044,0.034,6.3e-07,6.3e-07,2.5e-06,0.0052,0.0052,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24390000,0.7,0.0043,-0.0062,0.71,-0.13,-0.051,-0.46,-0.063,-0.029,-3.7e+02,-0.0013,-0.0059,-8.1e-05,0.012,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.4e-05,9.4e-05,0.066,0.016,0.017,0.0064,0.04,0.04,0.034,6e-07,6e-07,2.5e-06,0.0051,0.0051,0.00018,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24490000,0.7,0.0052,-0.0021,0.71,-0.14,-0.056,-0.51,-0.076,-0.035,-3.7e+02,-0.0013,-0.0059,-8.1e-05,0.012,0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.5e-05,9.5e-05,0.066,0.018,0.019,0.0064,0.044,0.044,0.034,6e-07,6e-07,2.5e-06,0.0051,0.0051,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24590000,0.7,0.0056,0.0016,0.71,-0.16,-0.068,-0.56,-0.08,-0.044,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.011,0.0075,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.2e-05,9.2e-05,0.065,0.016,0.017,0.0063,0.04,0.04,0.034,5.8e-07,5.8e-07,2.5e-06,0.005,0.005,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24690000,0.7,0.0057,0.0026,0.71,-0.18,-0.081,-0.64,-0.097,-0.052,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.011,0.0075,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,9.3e-05,0.065,0.018,0.019,0.0063,0.044,0.044,0.034,5.8e-07,5.8e-07,2.5e-06,0.005,0.005,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24790000,0.7,0.0053,0.0012,0.71,-0.2,-0.094,-0.73,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.01,0.0068,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,8.9e-05,0.065,0.016,0.018,0.0062,0.04,0.04,0.034,5.6e-07,5.6e-07,2.5e-06,0.005,0.0049,0.00017,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24890000,0.7,0.0071,0.0029,0.71,-0.22,-0.11,-0.75,-0.13,-0.072,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.01,0.0068,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,9e-05,0.065,0.018,0.02,0.0062,0.044,0.044,0.034,5.6e-07,5.6e-07,2.5e-06,0.005,0.0049,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24990000,0.71,0.0088,0.0046,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.0091,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,8.7e-05,0.064,0.016,0.018,0.0062,0.04,0.04,0.034,5.4e-07,5.4e-07,2.5e-06,0.0049,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25090000,0.71,0.0091,0.004,0.71,-0.27,-0.12,-0.86,-0.15,-0.092,-3.7e+02,-0.0013,-0.0059,-8.2e-05,0.0091,0.0053,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.9e-05,8.8e-05,0.064,0.018,0.02,0.0062,0.044,0.044,0.034,5.4e-07,5.4e-07,2.5e-06,0.0049,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25190000,0.7,0.0086,0.0026,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,-8.3e-05,0.0082,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,8.5e-05,0.063,0.016,0.019,0.0061,0.04,0.04,0.033,5.2e-07,5.2e-07,2.5e-06,0.0048,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25290000,0.7,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,-8.3e-05,0.0082,0.0056,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,8.6e-05,0.063,0.017,0.021,0.0061,0.044,0.044,0.033,5.2e-07,5.2e-07,2.5e-06,0.0048,0.0048,0.00016,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25390000,0.7,0.012,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,-8.4e-05,0.0066,0.0048,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,8.3e-05,0.062,0.016,0.02,0.0061,0.039,0.04,0.033,5e-07,5e-07,2.5e-06,0.0048,0.0047,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25490000,0.7,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,-8.4e-05,0.0066,0.0048,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,8.4e-05,0.062,0.018,0.023,0.0061,0.044,0.045,0.033,5e-07,5.1e-07,2.5e-06,0.0048,0.0047,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25590000,0.7,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0053,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,8.1e-05,0.06,0.016,0.022,0.006,0.039,0.04,0.033,4.9e-07,4.9e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25690000,0.7,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,-8.5e-05,0.0053,0.005,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,8.2e-05,0.06,0.018,0.025,0.006,0.043,0.045,0.033,4.9e-07,4.9e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25790000,0.7,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,-8.6e-05,0.003,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.4e-05,8e-05,0.058,0.017,0.024,0.006,0.039,0.04,0.033,4.7e-07,4.8e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25890000,0.7,0.018,0.029,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,-8.6e-05,0.003,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,8e-05,0.058,0.018,0.029,0.006,0.043,0.045,0.033,4.7e-07,4.8e-07,2.5e-06,0.0047,0.0046,0.00015,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25990000,0.7,0.017,0.026,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.0011,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7.8e-05,0.055,0.017,0.028,0.0059,0.039,0.041,0.033,4.6e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26090000,0.7,0.021,0.036,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,-8.7e-05,0.0011,0.0033,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7.9e-05,0.055,0.019,0.032,0.0059,0.043,0.046,0.033,4.6e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,-8.8e-05,-0.0021,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7.6e-05,0.051,0.017,0.031,0.0059,0.039,0.041,0.032,4.5e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,-8.8e-05,-0.0021,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,7.7e-05,0.051,0.019,0.037,0.0059,0.043,0.046,0.033,4.5e-07,4.7e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26390000,0.7,0.023,0.044,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0043,0.0016,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.6e-05,7.5e-05,0.046,0.018,0.035,0.0058,0.039,0.042,0.032,4.4e-07,4.6e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26490000,0.7,0.031,0.06,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,-8.9e-05,-0.0043,0.0016,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,7.6e-05,0.046,0.02,0.042,0.0058,0.043,0.047,0.032,4.4e-07,4.6e-07,2.5e-06,0.0046,0.0045,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26590000,0.7,0.037,0.076,0.71,-1.1,-0.59,-1.3,-0.82,-0.66,-3.7e+02,-0.00096,-0.0059,-8.9e-05,-0.0082,-0.00089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,7.4e-05,0.041,0.019,0.041,0.0058,0.039,0.042,0.032,4.3e-07,4.6e-07,2.5e-06,0.0046,0.0044,0.00014,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26690000,0.7,0.038,0.079,0.71,-1.3,-0.65,-1.3,-0.95,-0.73,-3.7e+02,-0.00096,-0.0059,-8.9e-05,-0.0082,-0.00089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,7.5e-05,0.041,0.021,0.051,0.0058,0.043,0.049,0.032,4.3e-07,4.6e-07,2.5e-06,0.0046,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26790000,0.7,0.036,0.073,0.71,-1.4,-0.74,-1.3,-1,-0.85,-3.7e+02,-0.00092,-0.0059,-9.5e-05,-0.011,-0.00024,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.9e-05,7.3e-05,0.034,0.02,0.048,0.0058,0.039,0.043,0.032,4.2e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26890000,0.7,0.045,0.095,0.71,-1.5,-0.8,-1.3,-1.2,-0.93,-3.7e+02,-0.00092,-0.0059,-9.5e-05,-0.011,-0.00024,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,7.3e-05,0.034,0.022,0.058,0.0058,0.044,0.05,0.032,4.2e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26990000,0.7,0.05,0.12,0.7,-1.7,-0.88,-1.3,-1.2,-1,-3.7e+02,-0.0008,-0.0059,-9.8e-05,-0.017,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,7.2e-05,0.028,0.021,0.054,0.0057,0.039,0.044,0.032,4.1e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27090000,0.7,0.051,0.12,0.7,-1.9,-0.97,-1.3,-1.4,-1.1,-3.7e+02,-0.0008,-0.0059,-9.8e-05,-0.017,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,7.2e-05,0.028,0.024,0.069,0.0058,0.044,0.051,0.032,4.1e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27190000,0.71,0.049,0.11,0.69,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00077,-0.0059,-8.2e-05,-0.019,-0.0039,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,7.2e-05,0.023,0.024,0.065,0.0057,0.046,0.053,0.032,4.1e-07,4.5e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27290000,0.71,0.043,0.095,0.69,-2.3,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00077,-0.0059,-8.2e-05,-0.019,-0.0039,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.2e-05,7.3e-05,0.023,0.026,0.076,0.0058,0.051,0.062,0.032,4.1e-07,4.6e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27390000,0.72,0.037,0.079,0.69,-2.4,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.0007,-0.0059,-7.4e-05,-0.022,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.2e-05,7.2e-05,0.018,0.024,0.064,0.0057,0.053,0.062,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0044,0.00013,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27490000,0.72,0.031,0.064,0.69,-2.5,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.0007,-0.0059,-7.4e-05,-0.022,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,7.3e-05,0.018,0.026,0.069,0.0057,0.059,0.072,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0044,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27590000,0.73,0.026,0.051,0.69,-2.5,-1.1,-1.2,-2.6,-1.6,-3.7e+02,-0.0007,-0.0059,-6.5e-05,-0.022,-0.0056,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,7.2e-05,0.015,0.024,0.056,0.0057,0.061,0.072,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27690000,0.73,0.026,0.05,0.69,-2.6,-1.1,-1.2,-2.8,-1.7,-3.7e+02,-0.0007,-0.0059,-6.5e-05,-0.022,-0.0056,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.4e-05,7.3e-05,0.015,0.025,0.057,0.0057,0.067,0.082,0.032,4e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27790000,0.73,0.026,0.051,0.68,-2.6,-1.1,-1.2,-3.1,-1.8,-3.7e+02,-0.00069,-0.006,-6e-05,-0.023,-0.0055,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.5e-05,7.2e-05,0.012,0.023,0.047,0.0057,0.069,0.081,0.032,3.9e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27890000,0.73,0.025,0.049,0.68,-2.7,-1.1,-1.2,-3.3,-1.9,-3.7e+02,-0.00069,-0.006,-6e-05,-0.023,-0.0055,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.6e-05,7.3e-05,0.012,0.024,0.049,0.0057,0.076,0.092,0.032,3.9e-07,4.5e-07,2.5e-06,0.0045,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27990000,0.73,0.024,0.046,0.68,-2.7,-1.1,-1.2,-3.6,-2,-3.7e+02,-0.00072,-0.006,-5.6e-05,-0.022,-0.0039,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.7e-05,7.2e-05,0.011,0.023,0.042,0.0057,0.078,0.091,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28090000,0.73,0.03,0.059,0.68,-2.7,-1.2,-1.2,-3.9,-2.1,-3.7e+02,-0.00072,-0.006,-5.6e-05,-0.022,-0.0039,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.8e-05,7.3e-05,0.011,0.024,0.043,0.0057,0.085,0.1,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28190000,0.73,0.036,0.072,0.68,-2.8,-1.2,-0.94,-4.2,-2.2,-3.7e+02,-0.00074,-0.006,-5.4e-05,-0.022,-0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.9e-05,7.2e-05,0.01,0.022,0.038,0.0057,0.087,0.1,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28290000,0.73,0.028,0.055,0.68,-2.8,-1.2,-0.08,-4.5,-2.3,-3.7e+02,-0.00074,-0.006,-5.4e-05,-0.022,-0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.01,0.022,0.038,0.0057,0.094,0.11,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28390000,0.73,0.011,0.024,0.68,-2.8,-1.2,0.78,-4.8,-2.5,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.3e-05,0.01,0.023,0.038,0.0057,0.1,0.12,0.032,3.9e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00012,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28490000,0.73,0.001,0.0062,0.68,-2.7,-1.2,1.1,-5,-2.6,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.4e-05,0.01,0.023,0.038,0.0057,0.11,0.13,0.032,3.9e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28590000,0.73,-0.00091,0.0027,0.68,-2.7,-1.2,0.97,-5.3,-2.7,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.5e-05,0.01,0.024,0.036,0.0057,0.12,0.15,0.032,3.9e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28690000,0.73,-0.0017,0.0018,0.68,-2.6,-1.2,0.98,-5.6,-2.8,-3.7e+02,-0.00073,-0.006,-5.4e-05,-0.022,-0.0025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.6e-05,0.01,0.025,0.035,0.0057,0.13,0.16,0.032,3.9e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28790000,0.73,-0.0017,0.0017,0.68,-2.6,-1.1,0.98,-5.9,-2.9,-3.7e+02,-0.00078,-0.006,-5.2e-05,-0.02,-0.0014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0096,0.024,0.03,0.0057,0.13,0.16,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28890000,0.73,-0.0018,0.0019,0.68,-2.5,-1.1,0.97,-6.2,-3,-3.7e+02,-0.00078,-0.006,-5.2e-05,-0.02,-0.0012,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0096,0.025,0.029,0.0057,0.14,0.17,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28990000,0.74,-0.0013,0.0026,0.68,-2.5,-1.1,0.97,-6.5,-3.1,-3.7e+02,-0.00086,-0.006,-5.2e-05,-0.017,0.00024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0094,0.024,0.026,0.0057,0.14,0.17,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29090000,0.74,-0.0011,0.003,0.68,-2.4,-1.1,0.96,-6.7,-3.2,-3.7e+02,-0.00086,-0.006,-5.2e-05,-0.017,0.00044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0094,0.025,0.027,0.0057,0.15,0.18,0.032,3.8e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29190000,0.74,-0.00074,0.0034,0.68,-2.4,-1.1,0.95,-7,-3.3,-3.7e+02,-0.0009,-0.006,-5.4e-05,-0.015,0.0014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0093,0.024,0.025,0.0057,0.15,0.18,0.032,3.7e-07,4.5e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29290000,0.74,-0.00041,0.0042,0.68,-2.3,-1.1,0.98,-7.3,-3.4,-3.7e+02,-0.0009,-0.006,-5.4e-05,-0.015,0.0017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0093,0.025,0.025,0.0057,0.16,0.19,0.032,3.7e-07,4.6e-07,2.5e-06,0.0044,0.0043,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29390000,0.74,0.00042,0.0058,0.67,-2.3,-1.1,0.99,-7.6,-3.6,-3.7e+02,-0.00096,-0.006,-5.7e-05,-0.012,0.003,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0092,0.024,0.024,0.0056,0.16,0.19,0.031,3.7e-07,4.5e-07,2.5e-06,0.0044,0.0042,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29490000,0.74,0.00093,0.0069,0.67,-2.2,-1.1,0.99,-7.8,-3.7,-3.7e+02,-0.00096,-0.006,-5.7e-05,-0.012,0.0032,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.5e-05,0.0093,0.025,0.025,0.0057,0.17,0.2,0.032,3.7e-07,4.5e-07,2.5e-06,0.0044,0.0042,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29590000,0.74,0.0015,0.0079,0.67,-2.2,-1.1,0.98,-8.1,-3.8,-3.7e+02,-0.001,-0.006,-6.4e-05,-0.01,0.0036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0093,0.024,0.024,0.0056,0.17,0.2,0.031,3.6e-07,4.4e-07,2.5e-06,0.0043,0.0042,0.00011,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29690000,0.74,0.0018,0.0085,0.67,-2.2,-1.1,0.98,-8.3,-3.9,-3.7e+02,-0.00099,-0.006,-6.4e-05,-0.011,0.0038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0093,0.026,0.026,0.0056,0.18,0.21,0.031,3.6e-07,4.5e-07,2.5e-06,0.0043,0.0042,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29790000,0.74,0.0023,0.009,0.67,-2.1,-1.1,0.96,-8.6,-4,-3.7e+02,-0.001,-0.006,-7.3e-05,-0.0081,0.0042,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0092,0.024,0.025,0.0056,0.18,0.21,0.031,3.6e-07,4.4e-07,2.5e-06,0.0043,0.0042,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29890000,0.74,0.0023,0.0091,0.67,-2.1,-1.1,0.95,-8.8,-4.1,-3.7e+02,-0.001,-0.006,-7.3e-05,-0.0083,0.0046,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0092,0.026,0.027,0.0056,0.19,0.22,0.031,3.6e-07,4.4e-07,2.5e-06,0.0043,0.0042,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29990000,0.74,0.0026,0.0091,0.67,-2.1,-1.1,0.94,-9,-4.2,-3.7e+02,-0.0011,-0.006,-8.5e-05,-0.0066,0.0044,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0092,0.025,0.026,0.0056,0.19,0.22,0.031,3.5e-07,4.3e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30090000,0.74,0.0025,0.009,0.67,-2.1,-1.1,0.92,-9.2,-4.3,-3.7e+02,-0.0011,-0.006,-8.5e-05,-0.0068,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.4e-05,0.0092,0.026,0.028,0.0056,0.2,0.23,0.031,3.5e-07,4.3e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30190000,0.74,0.0028,0.0088,0.67,-2,-1.1,0.91,-9.5,-4.4,-3.7e+02,-0.0011,-0.006,-9.8e-05,-0.0045,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0091,0.025,0.027,0.0056,0.2,0.23,0.031,3.5e-07,4.2e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30290000,0.74,0.0027,0.0086,0.67,-2,-1.1,0.9,-9.7,-4.5,-3.7e+02,-0.0011,-0.006,-9.8e-05,-0.0046,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0091,0.026,0.03,0.0056,0.21,0.24,0.031,3.5e-07,4.2e-07,2.5e-06,0.0043,0.0041,0.0001,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30390000,0.74,0.0028,0.0083,0.67,-2,-1.1,0.89,-9.9,-4.6,-3.7e+02,-0.0011,-0.006,-0.00011,-0.0031,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.2e-05,0.009,0.025,0.029,0.0055,0.21,0.24,0.031,3.4e-07,4.1e-07,2.5e-06,0.0042,0.0041,9.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30490000,0.74,0.0026,0.008,0.67,-1.9,-1.1,0.87,-10,-4.7,-3.7e+02,-0.0011,-0.006,-0.00011,-0.0032,0.0047,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.009,0.026,0.031,0.0056,0.22,0.25,0.031,3.4e-07,4.1e-07,2.5e-06,0.0042,0.0041,9.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30590000,0.74,0.0027,0.0075,0.68,-1.9,-1.1,0.83,-10,-4.8,-3.7e+02,-0.0012,-0.0059,-0.00012,-0.0012,0.0046,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.0089,0.025,0.03,0.0055,0.22,0.25,0.031,3.4e-07,3.9e-07,2.5e-06,0.0042,0.004,9.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30690000,0.74,0.0025,0.0072,0.68,-1.9,-1.1,0.83,-11,-4.9,-3.7e+02,-0.0012,-0.0059,-0.00012,-0.0014,0.0049,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.00011,7.3e-05,0.0089,0.027,0.032,0.0055,0.23,0.26,0.031,3.4e-07,3.9e-07,2.5e-06,0.0042,0.004,9.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30790000,0.74,0.0026,0.0067,0.68,-1.9,-1,0.82,-11,-4.9,-3.7e+02,-0.0012,-0.0059,-0.00014,0.00039,0.0042,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.1e-05,0.0087,0.025,0.031,0.0055,0.23,0.26,0.031,3.3e-07,3.8e-07,2.5e-06,0.0042,0.004,9.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30890000,0.74,0.0024,0.0062,0.68,-1.8,-1,0.81,-11,-5,-3.7e+02,-0.0012,-0.0059,-0.00014,0.00024,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.0087,0.027,0.033,0.0055,0.24,0.27,0.031,3.3e-07,3.8e-07,2.5e-06,0.0042,0.004,9.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30990000,0.74,0.0026,0.0056,0.68,-1.8,-1,0.8,-11,-5.1,-3.7e+02,-0.0012,-0.0059,-0.00015,0.0024,0.0041,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.9e-05,7.1e-05,0.0085,0.025,0.032,0.0055,0.24,0.27,0.031,3.3e-07,3.7e-07,2.5e-06,0.0041,0.004,9.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31090000,0.74,0.0023,0.0051,0.68,-1.8,-1,0.79,-11,-5.2,-3.7e+02,-0.0012,-0.0059,-0.00015,0.0022,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,0.0001,7.2e-05,0.0085,0.027,0.034,0.0055,0.25,0.28,0.031,3.3e-07,3.7e-07,2.5e-06,0.0041,0.0039,9.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31190000,0.73,0.0023,0.0046,0.68,-1.8,-1,0.78,-12,-5.3,-3.7e+02,-0.0013,-0.0059,-0.00016,0.0034,0.0045,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.6e-05,7.1e-05,0.0083,0.025,0.032,0.0055,0.25,0.28,0.031,3.2e-07,3.6e-07,2.5e-06,0.0041,0.0039,9.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31290000,0.73,0.0021,0.0041,0.68,-1.8,-1,0.78,-12,-5.4,-3.7e+02,-0.0013,-0.0059,-0.00016,0.0032,0.005,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.7e-05,7.1e-05,0.0083,0.027,0.035,0.0055,0.26,0.29,0.031,3.2e-07,3.6e-07,2.5e-06,0.0041,0.0039,9.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31390000,0.73,0.0021,0.0034,0.68,-1.7,-1,0.78,-12,-5.5,-3.7e+02,-0.0013,-0.0058,-0.00018,0.0049,0.0051,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.3e-05,7e-05,0.008,0.026,0.033,0.0054,0.25,0.29,0.031,3.1e-07,3.4e-07,2.5e-06,0.0041,0.0039,9.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31490000,0.73,0.0018,0.0028,0.68,-1.7,-1,0.78,-12,-5.6,-3.7e+02,-0.0013,-0.0058,-0.00018,0.0047,0.0055,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.4e-05,7.1e-05,0.008,0.027,0.035,0.0055,0.27,0.3,0.031,3.2e-07,3.5e-07,2.5e-06,0.0041,0.0039,9.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31590000,0.73,0.0019,0.0022,0.68,-1.7,-0.98,0.77,-12,-5.7,-3.7e+02,-0.0013,-0.0058,-0.00019,0.0062,0.0052,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9e-05,7e-05,0.0078,0.026,0.033,0.0054,0.26,0.3,0.031,3.1e-07,3.3e-07,2.5e-06,0.004,0.0038,9.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31690000,0.73,0.0016,0.0015,0.68,-1.7,-0.98,0.78,-12,-5.8,-3.7e+02,-0.0013,-0.0058,-0.00019,0.006,0.0056,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,9.1e-05,7e-05,0.0078,0.027,0.035,0.0054,0.28,0.31,0.031,3.1e-07,3.3e-07,2.5e-06,0.004,0.0038,9.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31790000,0.73,0.0015,0.00072,0.68,-1.6,-0.96,0.78,-13,-5.9,-3.7e+02,-0.0013,-0.0058,-0.0002,0.0077,0.0056,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.7e-05,6.9e-05,0.0075,0.026,0.033,0.0054,0.27,0.31,0.031,3e-07,3.2e-07,2.5e-06,0.004,0.0038,9.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31890000,0.73,0.0012,-7.5e-06,0.68,-1.6,-0.96,0.77,-13,-6,-3.7e+02,-0.0013,-0.0058,-0.0002,0.0075,0.0061,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.8e-05,7e-05,0.0075,0.027,0.035,0.0054,0.29,0.32,0.031,3.1e-07,3.2e-07,2.5e-06,0.004,0.0038,9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31990000,0.73,0.0012,-0.00065,0.68,-1.6,-0.94,0.77,-13,-6,-3.7e+02,-0.0013,-0.0058,-0.00022,0.0085,0.0059,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.4e-05,6.9e-05,0.0072,0.026,0.033,0.0054,0.28,0.32,0.031,3e-07,3.2e-07,2.5e-06,0.004,0.0038,9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32090000,0.73,0.00088,-0.0014,0.68,-1.5,-0.93,0.78,-13,-6.1,-3.7e+02,-0.0013,-0.0058,-0.00022,0.0083,0.0064,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.5e-05,7e-05,0.0072,0.027,0.035,0.0054,0.29,0.33,0.031,3e-07,3.2e-07,2.5e-06,0.004,0.0038,8.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32190000,0.73,0.00078,-0.0024,0.69,-1.5,-0.91,0.78,-13,-6.2,-3.7e+02,-0.0014,-0.0058,-0.00023,0.0095,0.0067,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.2e-05,6.9e-05,0.007,0.026,0.033,0.0054,0.29,0.33,0.031,3e-07,3.1e-07,2.5e-06,0.0039,0.0038,8.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32290000,0.73,0.0005,-0.0031,0.69,-1.5,-0.91,0.77,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-0.00023,0.0093,0.0072,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8.3e-05,6.9e-05,0.007,0.027,0.035,0.0054,0.3,0.34,0.031,3e-07,3.1e-07,2.5e-06,0.0039,0.0038,8.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32390000,0.73,0.00041,-0.0039,0.69,-1.5,-0.89,0.77,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-0.00024,0.0099,0.0071,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.9e-05,6.8e-05,0.0067,0.025,0.033,0.0054,0.3,0.34,0.031,2.9e-07,3e-07,2.5e-06,0.0039,0.0037,8.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32490000,0.73,0.00026,-0.0041,0.69,-1.4,-0.88,0.78,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-0.00024,0.0097,0.0075,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,8e-05,6.9e-05,0.0067,0.027,0.035,0.0054,0.31,0.35,0.031,2.9e-07,3e-07,2.5e-06,0.0039,0.0037,8.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32590000,0.73,0.00039,-0.0045,0.69,-1.4,-0.87,0.78,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0078,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.7e-05,6.8e-05,0.0065,0.025,0.033,0.0053,0.31,0.35,0.031,2.9e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32690000,0.73,0.00033,-0.0046,0.69,-1.4,-0.86,0.77,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0081,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.8e-05,6.8e-05,0.0065,0.027,0.035,0.0053,0.32,0.35,0.031,2.9e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32790000,0.72,0.00048,-0.0046,0.69,-1.3,-0.84,0.77,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0081,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.5e-05,6.7e-05,0.0063,0.025,0.032,0.0053,0.32,0.35,0.031,2.8e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32890000,0.72,0.00055,-0.0046,0.69,-1.3,-0.84,0.77,-14,-6.8,-3.7e+02,-0.0014,-0.0057,-0.00025,0.011,0.0086,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.6e-05,6.8e-05,0.0063,0.027,0.034,0.0053,0.33,0.36,0.031,2.8e-07,2.9e-07,2.5e-06,0.0039,0.0037,8.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32990000,0.72,0.00079,-0.0046,0.69,-1.3,-0.82,0.77,-15,-6.9,-3.7e+02,-0.0014,-0.0057,-0.00026,0.012,0.009,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.4e-05,6.7e-05,0.0061,0.025,0.032,0.0053,0.33,0.36,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33090000,0.72,0.00074,-0.0047,0.69,-1.3,-0.82,0.76,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00026,0.012,0.0094,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.4e-05,6.8e-05,0.0061,0.027,0.034,0.0053,0.34,0.37,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33190000,0.72,0.0043,-0.0039,0.7,-1.3,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00027,0.012,0.0095,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.2e-05,6.7e-05,0.0059,0.025,0.032,0.0053,0.34,0.37,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,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.00027,0.012,0.0098,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.3e-05,6.7e-05,0.0059,0.027,0.033,0.0053,0.35,0.38,0.031,2.8e-07,2.8e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33390000,0.57,0.014,-0.0037,0.82,-1.2,-0.77,0.88,-15,-7.2,-3.7e+02,-0.0014,-0.0057,-0.00027,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.1e-05,6.6e-05,0.0057,0.025,0.03,0.0053,0.35,0.38,0.031,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33490000,0.43,0.0073,-0.0012,0.9,-1.2,-0.76,0.89,-15,-7.2,-3.7e+02,-0.0014,-0.0057,-0.00027,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7.1e-05,6.7e-05,0.0057,0.026,0.032,0.0053,0.36,0.39,0.031,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33590000,0.27,0.0011,-0.0037,0.96,-1.2,-0.76,0.86,-15,-7.3,-3.7e+02,-0.0014,-0.0057,-0.00028,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.9e-05,6.5e-05,0.0055,0.025,0.03,0.0052,0.35,0.39,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33690000,0.11,-0.0025,-0.0068,0.99,-1.1,-0.75,0.87,-15,-7.4,-3.7e+02,-0.0014,-0.0057,-0.00028,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,7e-05,6.6e-05,0.0055,0.026,0.032,0.0053,0.37,0.4,0.031,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33790000,-0.065,-0.0044,-0.0086,1,-1.1,-0.73,0.85,-16,-7.4,-3.7e+02,-0.0015,-0.0057,-0.00029,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.7e-05,6.4e-05,0.0054,0.025,0.031,0.0052,0.36,0.4,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33890000,-0.23,-0.0059,-0.0092,0.97,-1,-0.7,0.83,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00029,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.7e-05,6.4e-05,0.0054,0.026,0.033,0.0052,0.38,0.41,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33990000,-0.38,-0.0046,-0.013,0.92,-0.95,-0.65,0.81,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.0003,0.012,0.01,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.5e-05,6.2e-05,0.0052,0.026,0.032,0.0052,0.37,0.41,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0037,8.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34090000,-0.49,-0.0038,-0.014,0.87,-0.89,-0.6,0.81,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.0003,0.012,0.011,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.5e-05,6.2e-05,0.0052,0.028,0.035,0.0052,0.39,0.42,0.03,2.7e-07,2.7e-07,2.5e-06,0.0038,0.0036,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34190000,-0.56,-0.0036,-0.013,0.83,-0.86,-0.55,0.81,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00031,0.011,0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.1e-05,5.9e-05,0.005,0.028,0.034,0.0052,0.38,0.42,0.03,2.6e-07,2.6e-07,2.5e-06,0.0038,0.0036,8.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34290000,-0.6,-0.0046,-0.0095,0.8,-0.81,-0.49,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00031,0.011,0.014,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,6.1e-05,5.9e-05,0.005,0.03,0.038,0.0052,0.39,0.43,0.03,2.6e-07,2.6e-07,2.5e-06,0.0038,0.0036,8.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34390000,-0.63,-0.0052,-0.0067,0.78,-0.79,-0.45,0.81,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00032,0.0086,0.019,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.7e-05,5.6e-05,0.0049,0.03,0.036,0.0052,0.39,0.43,0.03,2.6e-07,2.6e-07,2.5e-06,0.0037,0.0036,8.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34490000,-0.64,-0.0061,-0.0045,0.76,-0.73,-0.4,0.81,-16,-7.9,-3.7e+02,-0.0015,-0.0057,-0.00032,0.0084,0.019,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.7e-05,5.6e-05,0.0049,0.033,0.04,0.0052,0.4,0.44,0.03,2.6e-07,2.6e-07,2.5e-06,0.0037,0.0036,8.2e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34590000,-0.65,-0.0061,-0.0032,0.76,-0.72,-0.37,0.8,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00033,0.0041,0.025,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.3e-05,5.2e-05,0.0047,0.032,0.038,0.0052,0.4,0.44,0.03,2.6e-07,2.6e-07,2.5e-06,0.0036,0.0035,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34690000,-0.66,-0.0065,-0.0023,0.75,-0.66,-0.32,0.8,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00033,0.004,0.025,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5.3e-05,5.2e-05,0.0047,0.036,0.042,0.0052,0.41,0.45,0.03,2.6e-07,2.6e-07,2.5e-06,0.0036,0.0035,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34790000,-0.66,-0.0058,-0.0019,0.75,-0.65,-0.3,0.79,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00035,-0.0013,0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.034,0.039,0.0052,0.41,0.45,0.03,2.6e-07,2.6e-07,2.5e-06,0.0034,0.0034,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34890000,-0.67,-0.0059,-0.0018,0.75,-0.6,-0.25,0.79,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00035,-0.0014,0.033,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.038,0.044,0.0052,0.42,0.46,0.03,2.6e-07,2.6e-07,2.5e-06,0.0034,0.0033,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -34990000,-0.67,-0.013,-0.0043,0.74,0.45,0.35,-0.044,-17,-8.2,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.042,0.058,0.0054,0.42,0.46,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35090000,-0.67,-0.013,-0.0043,0.74,0.58,0.38,-0.1,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.046,0.064,0.0055,0.43,0.47,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35190000,-0.67,-0.013,-0.0044,0.74,0.61,0.42,-0.1,-17,-8.1,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.051,0.068,0.0055,0.44,0.47,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35290000,-0.67,-0.013,-0.0044,0.74,0.64,0.46,-0.1,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.055,0.073,0.0055,0.46,0.48,0.03,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35390000,-0.67,-0.013,-0.0044,0.74,0.67,0.51,-0.097,-17,-8,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.06,0.078,0.0055,0.47,0.49,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35490000,-0.67,-0.013,-0.0044,0.74,0.7,0.55,-0.095,-17,-7.9,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.065,0.083,0.0055,0.49,0.51,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35590000,-0.67,-0.013,-0.0044,0.74,0.73,0.59,-0.095,-17,-7.9,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0044,0.07,0.088,0.0056,0.51,0.52,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35690000,-0.67,-0.013,-0.0044,0.74,0.76,0.63,-0.092,-16,-7.8,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.5e-05,4.4e-05,0.0045,0.075,0.094,0.0056,0.53,0.54,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8.1e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -35790000,-0.67,-0.013,-0.0044,0.74,0.79,0.68,-0.09,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.4e-05,0.0045,0.081,0.1,0.0056,0.55,0.56,0.031,2.6e-07,2.6e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.023 -35890000,-0.67,-0.013,-0.0044,0.74,0.82,0.72,-0.086,-16,-7.7,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.4e-05,0.0045,0.087,0.11,0.0056,0.57,0.58,0.031,2.6e-07,2.7e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.048 -35990000,-0.67,-0.013,-0.0044,0.74,0.85,0.76,-0.083,-16,-7.6,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.4e-05,0.0045,0.093,0.11,0.0056,0.6,0.6,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.073 -36090000,-0.67,-0.013,-0.0044,0.74,0.88,0.8,-0.08,-16,-7.5,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0085,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.1,0.12,0.0056,0.62,0.63,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.099 -36190000,-0.67,-0.013,-0.0044,0.74,0.92,0.85,-0.075,-16,-7.4,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0084,0.042,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.11,0.13,0.0056,0.66,0.66,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.12 -36290000,-0.67,-0.013,-0.0044,0.74,0.95,0.89,-0.07,-16,-7.4,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0083,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.11,0.13,0.0057,0.69,0.69,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.15 -36390000,-0.67,-0.013,-0.0044,0.74,0.98,0.93,-0.067,-16,-7.3,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0082,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.12,0.14,0.0057,0.72,0.73,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.17 -36490000,-0.67,-0.013,-0.0044,0.74,1,0.98,-0.063,-16,-7.2,-3.7e+02,-0.0016,-0.0058,-0.00037,-0.0082,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.13,0.15,0.0057,0.76,0.76,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.9e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.2 -36590000,-0.67,-0.013,-0.0044,0.74,1,1,-0.057,-16,-7.1,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0081,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.6e-05,4.5e-05,0.0045,0.14,0.16,0.0057,0.81,0.81,0.031,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.23 -36690000,-0.67,-0.013,-0.0043,0.74,1.1,1.1,-0.053,-16,-7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.008,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.5e-05,0.0045,0.14,0.17,0.0057,0.85,0.86,0.032,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.25 -36790000,-0.67,-0.013,-0.0043,0.74,1.1,1.1,-0.047,-15,-6.9,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0079,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.5e-05,0.0045,0.15,0.17,0.0057,0.9,0.91,0.032,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.8e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.28 -36890000,-0.67,-0.013,-0.0043,0.74,1.1,1.1,-0.042,-15,-6.7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0078,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.5e-05,0.0045,0.16,0.18,0.0057,0.96,0.96,0.032,2.7e-07,2.7e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.3 -36990000,-0.67,-0.013,-0.0043,0.74,1.2,1.2,-0.037,-15,-6.6,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0077,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.17,0.19,0.0057,1,1,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.33 -37090000,-0.67,-0.013,-0.0042,0.74,1.2,1.2,-0.031,-15,-6.5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0076,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.18,0.2,0.0057,1.1,1.1,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.35 -37190000,-0.67,-0.013,-0.0042,0.74,1.2,1.3,-0.025,-15,-6.4,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0076,0.041,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.19,0.21,0.0057,1.1,1.2,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.7e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.38 -37290000,-0.67,-0.013,-0.0042,0.74,1.3,1.3,-0.02,-15,-6.2,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0075,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.7e-05,4.6e-05,0.0045,0.2,0.22,0.0057,1.2,1.2,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.41 -37390000,-0.67,-0.013,-0.0042,0.74,1.3,1.4,-0.015,-15,-6.1,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0075,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.6e-05,0.0045,0.21,0.23,0.0057,1.3,1.3,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.43 -37490000,-0.67,-0.013,-0.0041,0.74,1.3,1.4,-0.009,-15,-6,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0075,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.6e-05,0.0045,0.22,0.24,0.0057,1.4,1.4,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.46 -37590000,-0.67,-0.013,-0.0041,0.74,1.4,1.4,-0.0023,-14,-5.8,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0074,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.6e-05,0.0045,0.23,0.25,0.0057,1.5,1.5,0.032,2.8e-07,2.8e-07,2.5e-06,0.0033,0.0032,7.6e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.48 -37690000,-0.67,-0.013,-0.0041,0.74,1.4,1.5,0.0051,-14,-5.7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0071,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.7e-05,0.0045,0.24,0.26,0.0057,1.6,1.6,0.032,2.8e-07,2.8e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.51 -37790000,-0.67,-0.013,-0.0042,0.74,1.4,1.5,0.012,-14,-5.5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.007,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.7e-05,0.0045,0.25,0.28,0.0057,1.7,1.7,0.032,2.8e-07,2.8e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.54 -37890000,-0.67,-0.013,-0.0042,0.74,1.4,1.6,0.018,-14,-5.4,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.007,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.8e-05,4.7e-05,0.0046,0.26,0.29,0.0057,1.8,1.8,0.032,2.8e-07,2.8e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.56 -37990000,-0.67,-0.013,-0.0042,0.74,1.5,1.6,0.026,-14,-5.2,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0069,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.7e-05,0.0046,0.27,0.3,0.0057,1.9,2,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.5e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.59 -38090000,-0.67,-0.013,-0.0042,0.74,1.5,1.7,0.035,-14,-5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0068,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.7e-05,0.0046,0.28,0.31,0.0057,2,2.1,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.61 -38190000,-0.67,-0.013,-0.0042,0.74,1.5,1.7,0.041,-14,-4.9,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0067,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.7e-05,0.0046,0.29,0.32,0.0056,2.1,2.2,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.64 -38290000,-0.67,-0.013,-0.0041,0.74,1.6,1.8,0.047,-13,-4.7,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0067,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.3,0.33,0.0057,2.3,2.4,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.67 -38390000,-0.67,-0.013,-0.0041,0.74,1.6,1.8,0.053,-13,-4.5,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0066,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,4.9e-05,4.8e-05,0.0046,0.32,0.35,0.0056,2.4,2.5,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.4e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.69 -38490000,-0.67,-0.013,-0.0041,0.74,1.6,1.8,0.059,-13,-4.3,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0066,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.8e-05,0.0046,0.33,0.36,0.0056,2.6,2.7,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.72 -38590000,-0.67,-0.013,-0.004,0.74,1.7,1.9,0.064,-13,-4.1,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0066,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.8e-05,0.0046,0.34,0.37,0.0056,2.8,2.9,0.032,2.9e-07,2.9e-07,2.6e-06,0.0033,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.75 -38690000,-0.67,-0.013,-0.004,0.74,1.7,1.9,0.07,-13,-4,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0068,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.9e-05,0.0046,0.35,0.39,0.0056,2.9,3.1,0.032,2.9e-07,2.9e-07,2.6e-06,0.0032,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.77 -38790000,-0.67,-0.013,-0.004,0.74,1.7,2,0.076,-13,-3.8,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0068,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.9e-05,0.0046,0.37,0.4,0.0056,3.1,3.3,0.032,2.9e-07,2.9e-07,2.6e-06,0.0032,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.8 -38890000,-0.67,-0.014,-0.0041,0.74,1.7,2,0.58,-12,-3.6,-3.7e+02,-0.0016,-0.0058,-0.00036,-0.0067,0.04,-0.11,0.37,0.0037,0.026,0,0,0,0,0,-3.7e+02,5e-05,4.9e-05,0.0046,0.38,0.41,0.0056,3.3,3.5,0.032,2.9e-07,2.9e-07,2.6e-06,0.0032,0.0032,7.3e-05,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,1,1,0.83 +6790000,0.71,0.0012,-0.014,0.71,0.0049,0.0051,-0.11,0.0028,0.0015,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,-6.9e-05,0.21,8e-05,0.43,3.6e-05,0.00032,-0.0024,0,0,-3.6e+02,0.0013,0.0013,0.053,0.18,0.18,0.6,0.11,0.11,0.2,7.8e-05,7.7e-05,2.4e-06,0.04,0.04,0.04,0.0015,0.0012,0.0014,0.0018,0.0015,0.0014,1,1,1.7 +6890000,0.71,0.0013,-0.014,0.7,0.00053,0.0064,-0.12,0.0015,0.0026,-3.7e+02,-0.0015,-0.0057,-7.4e-05,0,0,-9.7e-05,0.21,1.3e-05,0.43,1.3e-06,0.00089,-0.00086,0,0,-3.6e+02,0.0013,0.0013,0.047,0.21,0.21,0.46,0.13,0.14,0.18,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0014,0.00065,0.0013,0.0017,0.0014,0.0013,1,1,1.8 +6990000,0.71,0.0013,-0.014,0.71,-0.00023,0.0046,-0.12,0.0011,0.0017,-3.7e+02,-0.0015,-0.0057,-7.6e-05,-2.8e-05,-0.00025,-0.00041,0.21,-3.9e-05,0.43,-0.00025,0.00056,-0.00042,0,0,-3.6e+02,0.0013,0.0013,0.044,0.23,0.24,0.36,0.17,0.17,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00044,0.0013,0.0017,0.0013,0.0013,1,1,1.8 +7090000,0.71,0.0012,-0.014,0.71,-0.00079,0.0011,-0.13,0.0011,0.00014,-3.7e+02,-0.0014,-0.0057,-7.7e-05,0.0002,-0.00056,-0.00078,0.21,-3.8e-05,0.43,-0.00037,0.00025,-0.00041,0,0,-3.6e+02,0.0013,0.0013,0.043,0.27,0.27,0.29,0.2,0.21,0.16,7.8e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00034,0.0013,0.0017,0.0013,0.0013,1,1,1.8 +7190000,0.71,0.0013,-0.014,0.71,-0.0025,0.0019,-0.15,0.00089,0.0011,-3.7e+02,-0.0015,-0.0057,-7.7e-05,0.00014,-0.0005,-0.00057,0.21,-3.1e-05,0.43,-0.00036,0.00035,-0.00045,0,0,-3.6e+02,0.0013,0.0013,0.042,0.3,0.31,0.24,0.25,0.25,0.15,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00027,0.0013,0.0016,0.0013,0.0013,1,1,1.8 +7290000,0.71,0.0015,-0.014,0.71,-0.0044,0.0099,-0.15,0.00034,0.0079,-3.7e+02,-0.0016,-0.0057,-7.3e-05,-0.00021,-0.0002,-0.0012,0.21,-3.3e-05,0.43,-0.00035,0.00077,-0.00039,0,0,-3.6e+02,0.0013,0.0013,0.042,0.34,0.35,0.2,0.3,0.31,0.14,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.04,0.0013,0.00023,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7390000,0.71,0.0016,-0.014,0.71,-0.0037,0.015,-0.16,0.00062,0.012,-3.7e+02,-0.0016,-0.0057,-7.1e-05,-0.00028,-3.8e-05,-0.0014,0.21,-2.9e-05,0.43,-0.00035,0.00086,-0.00032,0,0,-3.6e+02,0.0013,0.0013,0.041,0.38,0.39,0.18,0.37,0.37,0.13,7.7e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.0002,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7490000,0.71,0.0015,-0.014,0.71,-0.0038,0.011,-0.16,0.0014,0.0094,-3.7e+02,-0.0016,-0.0057,-7.2e-05,-0.00018,-7.3e-05,-0.0022,0.21,-2.2e-05,0.43,-0.00032,0.00078,-0.00043,0,0,-3.6e+02,0.0013,0.0013,0.041,0.43,0.43,0.15,0.44,0.45,0.12,7.6e-05,7.6e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00017,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7590000,0.71,0.0016,-0.014,0.71,-0.0034,0.02,-0.17,0.0033,0.018,-3.7e+02,-0.0017,-0.0057,-6.8e-05,-0.00024,0.00021,-0.003,0.21,-2.1e-05,0.43,-0.00035,0.00087,-0.00026,0,0,-3.6e+02,0.0013,0.0013,0.04,0.48,0.48,0.14,0.53,0.53,0.12,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00015,0.0013,0.0016,0.0013,0.0013,1,1,1.9 +7690000,0.71,0.0016,-0.014,0.71,-0.0046,0.017,-0.16,0.0032,0.016,-3.7e+02,-0.0016,-0.0057,-7e-05,-0.00024,0.00018,-0.0051,0.21,-1.8e-05,0.43,-0.00032,0.00084,-0.00033,0,0,-3.6e+02,0.0014,0.0013,0.04,0.53,0.53,0.13,0.63,0.63,0.11,7.5e-05,7.5e-05,2.4e-06,0.04,0.04,0.039,0.0013,0.00014,0.0013,0.0016,0.0013,0.0013,1,1,2 +7790000,0.71,0.0017,-0.014,0.71,-0.011,0.016,-0.16,-0.0031,0.016,-3.7e+02,-0.0016,-0.0057,-7.3e-05,-0.00036,6.2e-05,-0.0071,0.21,-1.6e-05,0.43,-0.00034,0.00078,-0.00038,0,0,-3.6e+02,0.0014,0.0013,0.04,0.58,0.58,0.12,0.74,0.74,0.11,7.4e-05,7.5e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00013,0.0013,0.0016,0.0013,0.0013,1,1,2 +7890000,0.71,0.0017,-0.014,0.71,-0.011,0.021,-0.16,-0.00066,0.02,-3.7e+02,-0.0016,-0.0057,-7.1e-05,-0.00038,0.0002,-0.0096,0.21,-1.5e-05,0.43,-0.00035,0.00079,-0.0003,0,0,-3.6e+02,0.0014,0.0014,0.04,0.64,0.63,0.11,0.87,0.86,0.1,7.3e-05,7.4e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00012,0.0013,0.0016,0.0013,0.0013,1,1,2 +7990000,0.71,0.0017,-0.014,0.71,-0.0091,0.022,-0.16,0.0022,0.022,-3.7e+02,-0.0016,-0.0056,-6.9e-05,-0.00037,0.00028,-0.011,0.21,-1.4e-05,0.43,-0.00035,0.00085,-0.00038,0,0,-3.6e+02,0.0014,0.0014,0.04,0.7,0.68,0.1,1,0.99,0.099,7.1e-05,7.3e-05,2.4e-06,0.04,0.04,0.038,0.0013,0.00011,0.0013,0.0016,0.0013,0.0013,1,1,2 +8090000,0.71,0.0017,-0.014,0.71,-0.005,0.024,-0.17,0.0082,0.024,-3.7e+02,-0.0016,-0.0056,-6.7e-05,-0.0003,0.00035,-0.011,0.21,-1.2e-05,0.43,-0.00033,0.0009,-0.00035,0,0,-3.6e+02,0.0014,0.0014,0.04,0.76,0.74,0.1,1.2,1.1,0.097,7e-05,7.3e-05,2.4e-06,0.04,0.04,0.037,0.0013,0.0001,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8190000,0.71,0.0017,-0.014,0.71,-0.014,0.028,-0.18,-6.4e-05,0.029,-3.7e+02,-0.0016,-0.0056,-6.9e-05,-0.00043,0.00036,-0.013,0.21,-1.2e-05,0.43,-0.00036,0.00085,-0.00036,0,0,-3.6e+02,0.0014,0.0014,0.04,0.82,0.79,0.099,1.4,1.3,0.094,6.8e-05,7.2e-05,2.4e-06,0.04,0.04,0.037,0.0013,9.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8290000,0.71,0.0017,-0.014,0.71,-0.017,0.021,-0.17,-0.0058,0.022,-3.7e+02,-0.0016,-0.0057,-7.2e-05,-0.00056,0.00031,-0.017,0.21,-1e-05,0.43,-0.00031,0.00079,-0.00035,0,0,-3.6e+02,0.0014,0.0014,0.039,0.88,0.84,0.097,1.6,1.5,0.091,6.6e-05,7.1e-05,2.4e-06,0.04,0.04,0.036,0.0013,8.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8390000,0.71,0.0017,-0.014,0.71,-0.0012,0.00041,-0.17,0.0038,0.023,-3.7e+02,-0.0016,-0.0056,-7e-05,-0.00051,0.00039,-0.021,0.21,-9.3e-06,0.43,-0.0003,0.00084,-0.00031,0,0,-3.6e+02,0.0014,0.0014,0.039,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,7e-05,2.4e-06,0.04,0.04,0.035,0.0013,8.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.1 +8490000,0.71,0.0017,-0.014,0.71,-0.003,0.0023,-0.17,0.0036,0.023,-3.7e+02,-0.0016,-0.0056,-7e-05,-0.00051,0.00039,-0.025,0.21,-9e-06,0.43,-0.00031,0.0008,-0.00028,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.089,6.2e-05,6.9e-05,2.4e-06,0.04,0.04,0.034,0.0013,7.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8590000,0.71,0.0021,-0.014,0.71,-0.00044,0.00093,-0.17,0.0032,0.023,-3.7e+02,-0.0018,-0.0057,-6.8e-05,-0.00051,0.00039,-0.029,0.21,-1.2e-05,0.43,-0.00042,0.00076,-0.00028,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.088,6e-05,6.8e-05,2.4e-06,0.04,0.04,0.033,0.0013,7.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8690000,0.71,0.002,-0.014,0.71,-0.0034,0.0028,-0.16,0.003,0.023,-3.7e+02,-0.0017,-0.0056,-6.6e-05,-0.00051,0.00039,-0.035,0.21,-1e-05,0.43,-0.00039,0.00084,-0.00029,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.088,5.8e-05,6.7e-05,2.4e-06,0.04,0.04,0.033,0.0013,7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8790000,0.71,0.0019,-0.014,0.71,-0.0057,0.0049,-0.15,0.0026,0.024,-3.7e+02,-0.0017,-0.0057,-6.9e-05,-0.0005,0.00043,-0.041,0.21,-9.1e-06,0.43,-0.00037,0.0008,-0.00029,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.087,5.6e-05,6.6e-05,2.4e-06,0.04,0.04,0.032,0.0013,6.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.2 +8890000,0.71,0.0019,-0.014,0.71,-0.0079,0.0055,-0.15,0.0019,0.024,-3.7e+02,-0.0016,-0.0057,-7.1e-05,-0.00063,0.00042,-0.045,0.21,-7.8e-06,0.43,-0.00034,0.00078,-0.00033,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.095,1e+02,1e+02,0.086,5.3e-05,6.4e-05,2.4e-06,0.04,0.04,0.03,0.0013,6.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +8990000,0.71,0.0018,-0.014,0.71,-0.01,0.0049,-0.14,0.00085,0.024,-3.7e+02,-0.0015,-0.0058,-7.5e-05,-0.00087,0.00044,-0.051,0.21,-6.6e-06,0.43,-0.0003,0.00071,-0.00034,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.096,1e+02,1e+02,0.087,5.1e-05,6.3e-05,2.4e-06,0.04,0.04,0.029,0.0013,6.1e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +9090000,0.71,0.002,-0.014,0.71,-0.014,0.006,-0.14,-0.00063,0.025,-3.7e+02,-0.0016,-0.0058,-7.6e-05,-0.00098,0.00054,-0.053,0.21,-6.9e-06,0.43,-0.00033,0.00068,-0.00034,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.095,1.1e+02,1.1e+02,0.086,4.9e-05,6.2e-05,2.4e-06,0.04,0.04,0.028,0.0013,5.9e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +9190000,0.71,0.0019,-0.014,0.71,-0.012,0.0087,-0.14,-0.0008,0.026,-3.7e+02,-0.0015,-0.0056,-7e-05,-0.00086,0.00059,-0.057,0.21,-6.2e-06,0.43,-0.00031,0.00081,-0.00025,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.094,1.1e+02,1.1e+02,0.085,4.6e-05,6e-05,2.4e-06,0.04,0.04,0.027,0.0013,5.6e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.3 +9290000,0.71,0.0017,-0.014,0.71,-0.011,0.0086,-0.14,-0.0015,0.026,-3.7e+02,-0.0015,-0.0056,-7.1e-05,-0.00096,0.00059,-0.061,0.21,-5.1e-06,0.43,-0.00026,0.00082,-0.00024,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.093,1.1e+02,1.1e+02,0.085,4.4e-05,5.8e-05,2.4e-06,0.04,0.04,0.025,0.0013,5.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9390000,0.71,0.0015,-0.014,0.71,-0.011,0.0092,-0.14,-0.0023,0.027,-3.7e+02,-0.0014,-0.0056,-7.3e-05,-0.001,0.00058,-0.065,0.21,-4.3e-06,0.43,-0.00022,0.00082,-0.00022,0,0,-3.6e+02,0.0013,0.0014,0.039,25,25,0.093,1.2e+02,1.2e+02,0.086,4.2e-05,5.7e-05,2.4e-06,0.04,0.04,0.024,0.0013,5.2e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9490000,0.71,0.0014,-0.014,0.71,-0.0078,0.011,-0.13,-0.0012,0.028,-3.7e+02,-0.0014,-0.0055,-6.9e-05,-0.001,0.0006,-0.068,0.21,-3.7e-06,0.43,-0.00018,0.0009,-0.00013,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.091,1.2e+02,1.2e+02,0.085,4e-05,5.5e-05,2.4e-06,0.04,0.04,0.023,0.0013,5e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9590000,0.71,0.0016,-0.014,0.71,-0.01,0.016,-0.13,-0.0026,0.031,-3.7e+02,-0.0015,-0.0054,-6.6e-05,-0.0011,0.00079,-0.072,0.21,-4.5e-06,0.43,-0.00024,0.00091,-0.00012,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.09,1.3e+02,1.3e+02,0.085,3.8e-05,5.4e-05,2.4e-06,0.04,0.04,0.021,0.0013,4.8e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.4 +9690000,0.71,0.0018,-0.014,0.71,-0.017,0.017,-0.12,-0.0071,0.032,-3.7e+02,-0.0015,-0.0056,-7e-05,-0.0013,0.00092,-0.077,0.21,-4.8e-06,0.43,-0.00027,0.0008,-0.00017,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.089,1.3e+02,1.3e+02,0.086,3.6e-05,5.2e-05,2.4e-06,0.04,0.04,0.02,0.0013,4.7e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +9790000,0.71,0.0017,-0.014,0.71,-0.013,0.02,-0.11,-0.0063,0.034,-3.7e+02,-0.0015,-0.0055,-6.8e-05,-0.0014,0.001,-0.082,0.21,-4.4e-06,0.43,-0.00024,0.00085,-9.7e-05,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.087,1.4e+02,1.4e+02,0.085,3.4e-05,5e-05,2.4e-06,0.04,0.04,0.019,0.0013,4.5e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +9890000,0.71,0.0018,-0.014,0.71,-0.016,0.023,-0.11,-0.0088,0.037,-3.7e+02,-0.0015,-0.0055,-6.8e-05,-0.0015,0.0011,-0.085,0.21,-4.5e-06,0.43,-0.00026,0.00083,-0.0001,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.084,1.4e+02,1.4e+02,0.085,3.2e-05,4.9e-05,2.4e-06,0.04,0.04,0.018,0.0013,4.4e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +9990000,0.71,0.0019,-0.014,0.71,-0.02,0.021,-0.1,-0.012,0.037,-3.7e+02,-0.0015,-0.0056,-7.1e-05,-0.0016,0.0011,-0.089,0.21,-4.2e-06,0.43,-0.00025,0.00078,-0.00013,0,0,-3.6e+02,0.0013,0.0013,0.039,25,25,0.083,1.5e+02,1.5e+02,0.086,3e-05,4.7e-05,2.4e-06,0.04,0.04,0.017,0.0013,4.3e-05,0.0013,0.0016,0.0013,0.0013,1,1,2.5 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 +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 91d3fb7de4fe..3c42e668968b 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -69,283 +69,283 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 6690000,1,-0.0088,-0.011,0.00055,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.9e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0016,0.0016,9.9e-05,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,2.6e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6790000,1,-0.0089,-0.011,0.00052,0.003,0.015,-0.042,0.0021,0.006,-0.058,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0014,0.0014,9.3e-05,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.7 6890000,1,-0.0087,-0.011,0.00043,0.0023,0.015,-0.039,0.0024,0.0075,-0.055,-0.0017,-0.0056,-9.1e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.095,0.0015,0.0015,9.6e-05,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,2.4e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -6990000,0.98,-0.0066,-0.012,0.19,0.0013,0.013,-0.037,0.0016,0.0058,-0.055,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0013,0.0013,0.09,0.17,0.17,0.031,0.11,0.11,0.066,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0026,0.0025,0.002,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7090000,0.98,-0.0065,-0.012,0.19,0.00038,0.018,-0.038,0.0017,0.0074,-0.056,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0013,0.0013,0.09,0.19,0.19,0.03,0.13,0.13,0.066,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0024,0.0025,0.0014,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7190000,0.98,-0.0064,-0.012,0.19,0,0,-0.037,0.0016,0.0093,-0.058,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0014,0.0014,0.09,25,25,0.029,1e+02,1e+02,0.065,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0023,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,1,1,1.8 -7290000,0.98,-0.0064,-0.012,0.19,0.00075,0.0036,-0.034,0.0016,0.0094,-0.054,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0014,0.0014,0.09,25,25,0.028,1e+02,1e+02,0.064,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0022,0.0025,0.00086,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7390000,0.98,-0.0063,-0.012,0.19,-0.001,0.006,-0.032,0.0016,0.01,-0.052,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,25,25,0.027,1e+02,1e+02,0.064,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.002,0.0025,0.00073,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7490000,0.98,-0.0063,-0.012,0.19,0.0013,0.0084,-0.026,0.0017,0.01,-0.046,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,25,25,0.026,51,51,0.063,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0019,0.0025,0.00062,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7590000,0.98,-0.0064,-0.012,0.19,0.0022,0.011,-0.023,0.0018,0.011,-0.041,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0016,0.0016,0.09,25,25,0.025,52,52,0.062,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0018,0.0025,0.00054,0.0025,0.0025,0.0025,0.0025,1,1,1.9 -7690000,0.98,-0.0064,-0.013,0.19,0.0019,0.014,-0.022,0.002,0.012,-0.036,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0016,0.0016,0.09,24,24,0.025,35,35,0.062,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0017,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,1,1,2 -7790000,0.98,-0.0063,-0.013,0.19,0.0034,0.016,-0.025,0.0022,0.013,-0.041,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0017,0.0017,0.09,24,24,0.024,37,37,0.061,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0016,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,1,1,2 -7890000,0.98,-0.0063,-0.013,0.19,0.002,0.02,-0.025,0.0022,0.014,-0.045,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0017,0.0017,0.09,24,24,0.023,29,29,0.06,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0015,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,1,1,2 -7990000,0.98,-0.0062,-0.013,0.19,0.0023,0.022,-0.022,0.0024,0.016,-0.042,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0018,0.0018,0.09,24,24,0.022,31,31,0.059,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0015,0.0025,0.00036,0.0025,0.0025,0.0025,0.0025,1,1,2 -8090000,0.98,-0.0061,-0.013,0.19,0.0037,0.025,-0.022,0.0026,0.016,-0.044,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0019,0.0019,0.09,23,23,0.022,25,25,0.059,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0014,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8190000,0.98,-0.0061,-0.012,0.19,0.0043,0.03,-0.018,0.003,0.019,-0.038,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0019,0.0019,0.09,23,23,0.021,28,28,0.058,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0013,0.0025,0.00031,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8290000,0.98,-0.0061,-0.012,0.19,0.0064,0.033,-0.017,0.0032,0.02,-0.038,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.002,0.002,0.09,21,21,0.02,24,24,0.057,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0013,0.0025,0.00029,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8390000,0.98,-0.0061,-0.012,0.19,0.0042,0.035,-0.016,0.0037,0.023,-0.036,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.002,0.002,0.09,21,21,0.02,26,26,0.057,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0012,0.0025,0.00027,0.0025,0.0025,0.0025,0.0025,1,1,2.1 -8490000,0.98,-0.006,-0.012,0.19,0.0037,0.037,-0.017,0.0036,0.023,-0.041,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0021,0.0021,0.09,19,19,0.019,23,23,0.056,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0011,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8590000,0.98,-0.0059,-0.013,0.19,0.0048,0.04,-0.012,0.004,0.027,-0.036,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0022,0.0022,0.09,19,19,0.018,26,26,0.055,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0011,0.0025,0.00024,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8690000,0.98,-0.0059,-0.013,0.19,0.0045,0.04,-0.014,0.0038,0.027,-0.038,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0022,0.0022,0.09,17,17,0.018,23,23,0.055,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.001,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8790000,0.98,-0.0059,-0.013,0.19,0.006,0.043,-0.014,0.0043,0.031,-0.035,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0023,0.0023,0.09,17,17,0.018,25,25,0.055,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00099,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,1,1,2.2 -8890000,0.98,-0.006,-0.013,0.19,0.0056,0.043,-0.0093,0.0042,0.03,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0024,0.0024,0.09,15,15,0.017,22,22,0.054,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00094,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -8990000,0.98,-0.0059,-0.013,0.19,0.0048,0.048,-0.0085,0.0047,0.034,-0.032,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0024,0.0024,0.09,15,15,0.017,25,25,0.054,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00091,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9090000,0.98,-0.0059,-0.013,0.19,0.0047,0.049,-0.0095,0.0044,0.033,-0.032,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0025,0.0025,0.09,13,13,0.016,22,22,0.053,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00087,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9190000,0.98,-0.0058,-0.013,0.19,0.0083,0.052,-0.009,0.0051,0.038,-0.032,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0026,0.0026,0.09,13,13,0.016,25,25,0.052,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00083,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.3 -9290000,0.98,-0.0057,-0.013,0.19,0.01,0.051,-0.0074,0.0051,0.036,-0.03,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0027,0.0027,0.09,12,12,0.015,22,22,0.052,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.0008,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9390000,0.98,-0.0056,-0.013,0.19,0.01,0.054,-0.0063,0.0062,0.041,-0.03,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0027,0.0027,0.09,12,12,0.015,24,24,0.052,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00077,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9490000,0.98,-0.0056,-0.013,0.19,0.01,0.057,-0.0046,0.0072,0.047,-0.027,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0028,0.0028,0.09,12,12,0.015,27,27,0.051,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00074,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9590000,0.98,-0.0056,-0.013,0.19,0.0096,0.054,-0.0045,0.0069,0.044,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0029,0.0029,0.09,10,10,0.014,24,24,0.05,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00071,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,1,1,2.4 -9690000,0.98,-0.0056,-0.013,0.19,0.0096,0.057,-0.0016,0.0079,0.049,-0.027,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,10,10,0.014,26,26,0.05,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00068,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9790000,0.98,-0.0056,-0.013,0.19,0.01,0.057,-0.0029,0.0075,0.046,-0.028,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,8.9,8.9,0.014,23,23,0.05,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00066,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9890000,0.98,-0.0056,-0.013,0.19,0.013,0.059,-0.0016,0.0086,0.052,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0031,0.0031,0.09,8.9,8.9,0.013,25,25,0.049,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00063,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -9990000,0.98,-0.0056,-0.013,0.19,0.014,0.057,-0.0009,0.0084,0.049,-0.031,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0032,0.0032,0.09,7.7,7.7,0.013,22,22,0.049,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00061,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,1,1,2.5 -10090000,0.98,-0.0055,-0.013,0.19,0.012,0.058,0.00032,0.0097,0.054,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0033,0.0033,0.09,7.8,7.8,0.013,24,24,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00059,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10190000,0.98,-0.0055,-0.013,0.19,0.0099,0.057,0.0012,0.0091,0.05,-0.03,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,6.8,6.8,0.012,21,21,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00057,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10290000,0.98,-0.0055,-0.013,0.19,0.011,0.06,0.00014,0.01,0.056,-0.029,-0.0016,-0.0056,-9.2e-05,-2.8e-06,2.4e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,6.9,6.9,0.012,23,23,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00055,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10390000,0.98,-0.0055,-0.013,0.19,0.0071,0.0052,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0056,-9.2e-05,-4.1e-06,3.9e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0035,0.0035,0.09,0.25,0.25,0.56,0.25,0.25,0.048,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00053,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.6 -10490000,0.98,-0.0054,-0.012,0.19,0.0085,0.0076,0.0071,0.0015,0.00075,-0.023,-0.0016,-0.0056,-9.2e-05,-1.1e-05,1.2e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0036,0.0036,0.09,0.26,0.26,0.55,0.26,0.26,0.057,6.6e-05,6.6e-05,2.2e-06,0.04,0.04,0.00052,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10590000,0.98,-0.0053,-0.012,0.19,-0.0012,0.0054,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,-9.3e-05,-4.3e-05,-0.00011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0036,0.0036,0.09,0.13,0.13,0.27,0.13,0.13,0.055,6.4e-05,6.4e-05,2.2e-06,0.04,0.04,0.00051,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10690000,0.98,-0.0053,-0.012,0.19,-5.7e-05,0.0066,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,-9.3e-05,-4.4e-05,-0.00011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0037,0.0037,0.09,0.15,0.15,0.26,0.14,0.14,0.065,6.4e-05,6.4e-05,2.2e-06,0.04,0.04,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10790000,0.98,-0.0055,-0.012,0.19,0.0018,0.0029,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,-9.5e-05,0.00011,-0.00023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0036,0.0036,0.09,0.11,0.11,0.17,0.09,0.09,0.062,6e-05,6e-05,2.2e-06,0.04,0.04,0.00049,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.7 -10890000,0.98,-0.0054,-0.013,0.19,0.0019,0.0063,0.01,-0.00059,-0.0043,-0.018,-0.0016,-0.0057,-9.5e-05,0.00011,-0.00023,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0037,0.0037,0.09,0.13,0.13,0.16,0.097,0.097,0.068,6e-05,6e-05,2.2e-06,0.04,0.04,0.00049,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -10990000,0.98,-0.0055,-0.013,0.19,0.0014,0.012,0.016,-0.00045,-0.0031,-0.012,-0.0015,-0.0057,-9.6e-05,0.00018,-0.00032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,0.099,0.099,0.12,0.072,0.072,0.065,5.3e-05,5.3e-05,2.2e-06,0.04,0.04,0.00048,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11090000,0.98,-0.0056,-0.013,0.19,0.0024,0.017,0.02,-0.0003,-0.0017,-0.0074,-0.0015,-0.0057,-9.6e-05,0.00018,-0.00031,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0034,0.0034,0.09,0.12,0.12,0.11,0.079,0.079,0.069,5.3e-05,5.3e-05,2.2e-06,0.04,0.04,0.00048,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11190000,0.98,-0.006,-0.013,0.19,0.0042,0.016,0.026,0.0011,-0.0019,-0.00041,-0.0015,-0.0057,-9.7e-05,0.00048,-0.0004,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,0.099,0.099,0.083,0.062,0.062,0.066,4.4e-05,4.4e-05,2.2e-06,0.04,0.04,0.00048,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.8 -11290000,0.98,-0.006,-0.013,0.19,0.0045,0.018,0.026,0.0015,-0.00014,-0.00017,-0.0015,-0.0057,-9.7e-05,0.00048,-0.0004,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.003,0.003,0.09,0.12,0.12,0.077,0.07,0.07,0.069,4.4e-05,4.4e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11390000,0.98,-0.0062,-0.013,0.19,0.0027,0.015,0.016,0.00089,-0.00098,-0.0086,-0.0014,-0.0057,-0.0001,0.00067,-0.00066,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0025,0.0025,0.09,0.1,0.1,0.062,0.057,0.057,0.066,3.5e-05,3.5e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11490000,0.98,-0.0061,-0.013,0.19,0.0019,0.016,0.02,0.0011,0.00055,-0.0025,-0.0014,-0.0057,-0.0001,0.00067,-0.00066,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0026,0.0026,0.09,0.12,0.12,0.057,0.065,0.065,0.067,3.5e-05,3.5e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11590000,0.98,-0.0065,-0.012,0.19,0.0036,0.012,0.018,0.00085,-0.00049,-0.0036,-0.0013,-0.0057,-0.0001,0.00084,-0.00084,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0021,0.0021,0.09,0.098,0.098,0.048,0.054,0.054,0.065,2.7e-05,2.7e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,2.9 -11690000,0.98,-0.0065,-0.012,0.19,0.0041,0.016,0.018,0.0012,0.00089,-0.005,-0.0013,-0.0057,-0.0001,0.00084,-0.00084,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0021,0.0021,0.09,0.12,0.12,0.044,0.062,0.062,0.066,2.7e-05,2.7e-05,2.2e-06,0.04,0.04,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 -11790000,0.98,-0.0069,-0.012,0.19,0.0028,0.0099,0.019,0.00069,-0.0019,-0.002,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0017,0.0017,0.09,0.094,0.094,0.037,0.052,0.052,0.063,2.1e-05,2.1e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 -11890000,0.98,-0.007,-0.012,0.19,0.0055,0.011,0.017,0.0011,-0.00093,-0.0013,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0018,0.0018,0.09,0.11,0.11,0.034,0.06,0.06,0.063,2.1e-05,2.1e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 -11990000,0.98,-0.0072,-0.012,0.19,0.0085,0.011,0.015,0.0021,-0.0019,-0.005,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,0.089,0.089,0.03,0.05,0.05,0.061,1.6e-05,1.6e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3 -12090000,0.98,-0.0071,-0.012,0.19,0.01,0.011,0.018,0.0031,-0.00082,0.0011,-0.0012,-0.0058,-0.00011,0.0011,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0015,0.0015,0.09,0.11,0.11,0.027,0.059,0.059,0.06,1.6e-05,1.6e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12190000,0.98,-0.007,-0.012,0.19,0.0082,0.011,0.017,0.0018,0.00029,0.0029,-0.0012,-0.0058,-0.00011,0.0011,-0.0012,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0012,0.0012,0.09,0.083,0.083,0.024,0.05,0.05,0.058,1.2e-05,1.2e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12290000,0.98,-0.0071,-0.012,0.19,0.006,0.01,0.016,0.0025,0.0013,0.0039,-0.0012,-0.0058,-0.00011,0.0011,-0.0012,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0013,0.0013,0.09,0.098,0.098,0.022,0.058,0.058,0.058,1.2e-05,1.2e-05,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12390000,0.98,-0.0072,-0.012,0.19,0.0045,0.0068,0.014,0.0017,0.00041,-0.0021,-0.0012,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0011,0.0011,0.09,0.077,0.077,0.02,0.049,0.049,0.056,9.8e-06,9.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.1 -12490000,0.98,-0.0072,-0.012,0.19,0.0047,0.0078,0.018,0.0022,0.0011,-8.1e-05,-0.0012,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0011,0.0011,0.09,0.09,0.09,0.018,0.058,0.058,0.055,9.8e-06,9.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12590000,0.98,-0.0074,-0.012,0.19,0.0084,0.0013,0.019,0.0033,-0.0014,0.0017,-0.0011,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00094,0.00094,0.09,0.071,0.071,0.017,0.049,0.049,0.054,7.9e-06,7.9e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12690000,0.98,-0.0073,-0.012,0.19,0.009,-0.00085,0.019,0.0041,-0.0014,0.0033,-0.0011,-0.0058,-0.00011,0.0011,-0.0013,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00095,0.00095,0.09,0.083,0.083,0.015,0.057,0.057,0.053,7.9e-06,7.9e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12790000,0.98,-0.0076,-0.012,0.19,0.011,-0.0041,0.021,0.0041,-0.0045,0.0054,-0.0011,-0.0058,-0.00011,0.0012,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00084,0.00084,0.09,0.066,0.066,0.014,0.049,0.049,0.051,6.5e-06,6.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.2 -12890000,0.98,-0.0076,-0.012,0.19,0.011,-0.0049,0.022,0.0052,-0.0049,0.0084,-0.0011,-0.0058,-0.00011,0.0012,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00085,0.00085,0.09,0.076,0.076,0.013,0.057,0.057,0.051,6.5e-06,6.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -12990000,0.98,-0.0075,-0.012,0.19,0.0087,-0.0029,0.022,0.0036,-0.0036,0.0096,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00076,0.00076,0.09,0.061,0.061,0.012,0.048,0.048,0.05,5.4e-06,5.4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13090000,0.98,-0.0076,-0.012,0.19,0.0098,-0.0027,0.02,0.0045,-0.0039,0.0085,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00077,0.00077,0.09,0.07,0.07,0.011,0.057,0.057,0.049,5.4e-06,5.4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13190000,0.98,-0.0076,-0.012,0.19,0.0048,-0.0043,0.019,0.001,-0.0046,0.0091,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00071,0.00071,0.09,0.057,0.057,0.011,0.048,0.048,0.047,4.6e-06,4.6e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.3 -13290000,0.98,-0.0076,-0.012,0.19,0.0047,-0.0052,0.016,0.0015,-0.005,0.0084,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00071,0.00071,0.09,0.065,0.065,0.01,0.056,0.056,0.047,4.6e-06,4.6e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13390000,0.98,-0.0075,-0.012,0.19,0.0037,-0.0033,0.016,0.00095,-0.0038,0.0091,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00066,0.00066,0.09,0.053,0.053,0.0094,0.048,0.048,0.046,4e-06,4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13490000,0.98,-0.0075,-0.012,0.19,0.0044,-0.0015,0.015,0.0014,-0.004,0.0053,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00066,0.00067,0.09,0.06,0.06,0.009,0.056,0.056,0.045,4e-06,4e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13590000,0.98,-0.0075,-0.012,0.19,0.0086,-0.0018,0.017,0.0041,-0.0032,0.0038,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00062,0.00062,0.09,0.049,0.049,0.0085,0.048,0.048,0.044,3.5e-06,3.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.4 -13690000,0.98,-0.0074,-0.012,0.19,0.0088,-0.0031,0.017,0.0049,-0.0035,0.0064,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00063,0.00063,0.09,0.055,0.055,0.0082,0.055,0.055,0.044,3.5e-06,3.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13790000,0.98,-0.0074,-0.012,0.19,0.015,0.00083,0.017,0.0083,-0.001,0.0059,-0.0011,-0.0058,-0.00011,0.0011,-0.0015,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00059,0.00059,0.09,0.046,0.046,0.0078,0.047,0.047,0.042,3.1e-06,3.1e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13890000,0.98,-0.0073,-0.012,0.19,0.017,0.0016,0.018,0.0099,-0.00092,0.0081,-0.0011,-0.0058,-0.00011,0.0011,-0.0015,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0006,0.0006,0.09,0.052,0.051,0.0076,0.055,0.055,0.042,3.1e-06,3.1e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -13990000,0.98,-0.0074,-0.012,0.19,0.016,0.002,0.017,0.0075,-0.0023,0.007,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00057,0.00057,0.066,0.043,0.043,0.0073,0.047,0.047,0.041,2.8e-06,2.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.5 -14090000,0.98,-0.0074,-0.012,0.19,0.014,-0.0024,0.018,0.0091,-0.0024,0.0035,-0.0011,-0.0058,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00057,0.00057,0.066,0.048,0.048,0.0072,0.054,0.054,0.041,2.8e-06,2.8e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14190000,0.98,-0.0073,-0.012,0.19,0.011,-0.0011,0.018,0.0082,-0.0018,0.0037,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00055,0.00055,0.066,0.041,0.041,0.007,0.047,0.047,0.04,2.5e-06,2.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14290000,0.98,-0.0073,-0.012,0.19,0.013,-0.0011,0.016,0.0093,-0.0019,0.0079,-0.0011,-0.0059,-0.00011,0.0011,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00055,0.00055,0.066,0.045,0.045,0.0069,0.054,0.054,0.039,2.5e-06,2.5e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14390000,0.98,-0.0073,-0.011,0.19,0.013,-0.0039,0.018,0.0087,-0.003,0.012,-0.0011,-0.0059,-0.00011,0.001,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00053,0.00053,0.066,0.038,0.038,0.0067,0.047,0.047,0.039,2.3e-06,2.3e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.6 -14490000,0.98,-0.0075,-0.011,0.19,0.012,-0.0036,0.021,0.0099,-0.0034,0.015,-0.0011,-0.0059,-0.00011,0.001,-0.0014,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00054,0.00054,0.066,0.042,0.042,0.0066,0.053,0.053,0.038,2.3e-06,2.3e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14590000,0.98,-0.0075,-0.011,0.19,0.01,-0.0036,0.019,0.0063,-0.0041,0.011,-0.0011,-0.0059,-0.00011,0.00096,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00052,0.00052,0.066,0.036,0.036,0.0065,0.046,0.046,0.038,2.2e-06,2.2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14690000,0.98,-0.0075,-0.011,0.19,0.0097,-0.0034,0.019,0.0073,-0.0044,0.011,-0.0011,-0.0059,-0.00011,0.00095,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00052,0.00052,0.066,0.04,0.04,0.0065,0.053,0.053,0.037,2.2e-06,2.2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14790000,0.98,-0.0075,-0.011,0.19,0.011,0.0023,0.019,0.0059,0.00061,0.014,-0.0011,-0.0059,-0.00011,0.0013,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00051,0.00051,0.066,0.034,0.034,0.0064,0.046,0.046,0.036,2e-06,2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.7 -14890000,0.98,-0.0074,-0.011,0.19,0.01,-8.2e-05,0.023,0.0069,0.00073,0.015,-0.0011,-0.0059,-0.00011,0.0013,-0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00051,0.00051,0.066,0.037,0.037,0.0064,0.052,0.052,0.036,2e-06,2e-06,2.2e-06,0.039,0.039,0.00047,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -14990000,0.98,-0.0075,-0.011,0.19,0.0093,-0.0013,0.026,0.0054,-0.00072,0.017,-0.0011,-0.0059,-0.00011,0.0012,-0.00095,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0005,0.0005,0.066,0.032,0.032,0.0064,0.046,0.046,0.036,1.9e-06,1.9e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15090000,0.98,-0.0075,-0.011,0.19,0.0097,-0.00019,0.03,0.0064,-0.00084,0.019,-0.0011,-0.0059,-0.00011,0.0012,-0.00095,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0005,0.0005,0.066,0.035,0.035,0.0064,0.052,0.052,0.035,1.9e-06,1.9e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15190000,0.98,-0.0076,-0.011,0.19,0.0079,-0.0013,0.03,0.0051,-0.00077,0.021,-0.0011,-0.0059,-0.00011,0.0012,-0.00082,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00049,0.00049,0.066,0.031,0.03,0.0064,0.046,0.046,0.035,1.8e-06,1.8e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.8 -15290000,0.98,-0.0077,-0.011,0.19,0.0089,-0.0023,0.03,0.0059,-0.00092,0.018,-0.0011,-0.0059,-0.00011,0.0012,-0.00081,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.0005,0.0005,0.066,0.033,0.033,0.0065,0.052,0.052,0.035,1.8e-06,1.8e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15390000,0.98,-0.0078,-0.011,0.19,0.0091,1.3e-06,0.03,0.0048,-0.00065,0.018,-0.0011,-0.0059,-0.00011,0.0012,-0.00068,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00049,0.00049,0.066,0.029,0.029,0.0064,0.045,0.045,0.034,1.7e-06,1.7e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15490000,0.98,-0.0078,-0.011,0.19,0.0089,-0.0025,0.03,0.0056,-0.00075,0.019,-0.0011,-0.0059,-0.00011,0.0012,-0.00068,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00049,0.00049,0.066,0.032,0.032,0.0065,0.051,0.051,0.034,1.7e-06,1.7e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15590000,0.98,-0.0079,-0.011,0.19,0.012,-0.005,0.029,0.0071,-0.0042,0.018,-0.0011,-0.0059,-0.00011,0.00078,-0.00072,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.028,0.028,0.0065,0.045,0.045,0.034,1.6e-06,1.6e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,3.9 -15690000,0.98,-0.0079,-0.011,0.19,0.014,-0.008,0.03,0.0083,-0.0049,0.019,-0.0011,-0.0059,-0.00011,0.00077,-0.00071,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.03,0.03,0.0066,0.051,0.051,0.034,1.6e-06,1.6e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 -15790000,0.98,-0.0079,-0.011,0.19,0.011,-0.0079,0.03,0.0066,-0.004,0.021,-0.0011,-0.0059,-0.00011,0.00094,-0.00051,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.026,0.026,0.0066,0.045,0.045,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 -15890000,0.98,-0.0079,-0.011,0.19,0.0098,-0.0062,0.03,0.0076,-0.0047,0.02,-0.0011,-0.0059,-0.00011,0.00092,-0.0005,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00048,0.00048,0.066,0.029,0.029,0.0067,0.05,0.05,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00046,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 -15990000,0.98,-0.0078,-0.011,0.19,0.0079,-0.0052,0.027,0.0061,-0.0038,0.02,-0.0011,-0.0059,-0.00011,0.001,-0.00032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.025,0.025,0.0068,0.044,0.044,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4 -16090000,0.98,-0.0077,-0.011,0.19,0.0076,-0.0064,0.025,0.0069,-0.0043,0.02,-0.0011,-0.0059,-0.00011,0.001,-0.00032,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.027,0.027,0.0069,0.05,0.05,0.033,1.5e-06,1.5e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16190000,0.98,-0.0077,-0.011,0.19,0.0041,-0.0045,0.024,0.0044,-0.0034,0.017,-0.0011,-0.0059,-0.00011,0.0012,-1.1e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.024,0.024,0.0069,0.044,0.044,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16290000,0.98,-0.0077,-0.011,0.19,0.0049,-0.006,0.024,0.0048,-0.0039,0.018,-0.0011,-0.0059,-0.00011,0.0012,-8.5e-06,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.026,0.026,0.007,0.049,0.049,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00045,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16390000,0.98,-0.0077,-0.011,0.19,0.0065,-0.0058,0.024,0.0052,-0.0032,0.018,-0.0011,-0.0059,-0.00011,0.0013,-8.7e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.023,0.023,0.007,0.044,0.044,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.1 -16490000,0.98,-0.0078,-0.011,0.19,0.009,-0.0074,0.027,0.006,-0.0039,0.022,-0.0011,-0.0059,-0.00011,0.0013,-9.1e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00047,0.00047,0.066,0.025,0.025,0.0072,0.049,0.049,0.033,1.4e-06,1.4e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16590000,0.98,-0.0078,-0.011,0.19,0.013,-0.0079,0.03,0.0052,-0.0032,0.022,-0.0011,-0.0059,-0.00011,0.0015,7.7e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.022,0.022,0.0072,0.043,0.043,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16690000,0.98,-0.0078,-0.011,0.19,0.015,-0.013,0.03,0.0066,-0.0042,0.023,-0.0011,-0.0059,-0.00011,0.0015,8.4e-05,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.024,0.024,0.0073,0.048,0.048,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00044,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16790000,0.98,-0.0077,-0.011,0.19,0.016,-0.012,0.029,0.0055,-0.0034,0.023,-0.0012,-0.0059,-0.00011,0.0018,0.00037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.022,0.022,0.0073,0.043,0.043,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00043,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.2 -16890000,0.98,-0.0076,-0.011,0.19,0.016,-0.013,0.03,0.0071,-0.0047,0.022,-0.0012,-0.0059,-0.00011,0.0018,0.00038,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.023,0.023,0.0074,0.048,0.048,0.033,1.3e-06,1.3e-06,2.2e-06,0.039,0.039,0.00043,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -16990000,0.98,-0.0077,-0.011,0.19,0.014,-0.013,0.03,0.0062,-0.0039,0.02,-0.0012,-0.0059,-0.00011,0.002,0.00036,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.021,0.021,0.0074,0.043,0.043,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00043,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17090000,0.98,-0.0078,-0.011,0.19,0.016,-0.016,0.03,0.0077,-0.0053,0.02,-0.0012,-0.0059,-0.00011,0.002,0.00037,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00046,0.00046,0.066,0.023,0.023,0.0075,0.048,0.048,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00042,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17190000,0.98,-0.0079,-0.011,0.19,0.015,-0.02,0.031,0.0057,-0.0083,0.023,-0.0012,-0.0059,-0.00011,0.0019,0.00068,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.02,0.02,0.0076,0.042,0.042,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00042,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.3 -17290000,0.98,-0.0078,-0.011,0.19,0.017,-0.021,0.031,0.0073,-0.01,0.023,-0.0012,-0.0059,-0.00011,0.0019,0.00069,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.022,0.022,0.0076,0.047,0.047,0.033,1.2e-06,1.2e-06,2.2e-06,0.038,0.038,0.00042,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17390000,0.98,-0.0078,-0.011,0.19,0.012,-0.022,0.031,0.008,-0.0077,0.023,-0.0012,-0.0059,-0.00011,0.0026,0.00052,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.02,0.02,0.0076,0.042,0.042,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00041,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17490000,0.98,-0.0078,-0.011,0.19,0.011,-0.023,0.03,0.0091,-0.01,0.025,-0.0012,-0.0059,-0.00011,0.0026,0.00053,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.021,0.021,0.0078,0.047,0.047,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00041,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17590000,0.98,-0.0077,-0.011,0.19,0.0084,-0.02,0.029,0.0057,-0.0083,0.022,-0.0012,-0.0059,-0.00011,0.0034,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.019,0.019,0.0077,0.042,0.042,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.0004,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.4 -17690000,0.98,-0.0078,-0.011,0.19,0.008,-0.021,0.031,0.0065,-0.01,0.025,-0.0012,-0.0059,-0.00011,0.0034,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00045,0.00045,0.066,0.021,0.021,0.0078,0.046,0.046,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.0004,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17790000,0.98,-0.0079,-0.011,0.19,0.0097,-0.021,0.031,0.0066,-0.0096,0.03,-0.0012,-0.0059,-0.00011,0.0041,0.001,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.019,0.019,0.0078,0.042,0.042,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00039,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17890000,0.98,-0.0078,-0.011,0.19,0.012,-0.023,0.031,0.0077,-0.012,0.034,-0.0012,-0.0059,-0.00011,0.0041,0.001,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.02,0.02,0.0079,0.046,0.046,0.033,1.1e-06,1.1e-06,2.2e-06,0.038,0.038,0.00039,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -17990000,0.98,-0.0077,-0.011,0.19,0.012,-0.019,0.03,0.0066,-0.0071,0.035,-0.0012,-0.0059,-0.00011,0.0056,0.0011,-0.14,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.018,0.018,0.0079,0.041,0.041,0.033,1e-06,1e-06,2.2e-06,0.038,0.038,0.00038,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.5 -18090000,0.98,-0.0078,-0.011,0.19,0.012,-0.02,0.03,0.0078,-0.009,0.033,-0.0012,-0.0059,-0.00011,0.0056,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.02,0.02,0.008,0.046,0.046,0.034,1e-06,1e-06,2.2e-06,0.038,0.038,0.00038,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18190000,0.98,-0.0078,-0.011,0.19,0.011,-0.019,0.03,0.0075,-0.0077,0.031,-0.0012,-0.0059,-0.00011,0.0061,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.018,0.018,0.0079,0.041,0.041,0.034,1e-06,1e-06,2.2e-06,0.037,0.037,0.00037,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18290000,0.98,-0.0078,-0.011,0.19,0.012,-0.02,0.029,0.0087,-0.0097,0.03,-0.0012,-0.0059,-0.00011,0.0061,0.0011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.019,0.019,0.008,0.046,0.046,0.034,1e-06,1e-06,2.2e-06,0.037,0.037,0.00037,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18390000,0.98,-0.0078,-0.011,0.19,0.012,-0.019,0.029,0.0092,-0.0083,0.029,-0.0012,-0.0059,-0.00011,0.0067,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.018,0.018,0.0079,0.041,0.041,0.034,9.8e-07,9.9e-07,2.3e-06,0.037,0.037,0.00036,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.6 -18490000,0.98,-0.0078,-0.011,0.19,0.015,-0.02,0.028,0.011,-0.01,0.031,-0.0012,-0.0059,-0.00011,0.0067,0.00093,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00044,0.00044,0.066,0.019,0.019,0.008,0.045,0.045,0.034,9.9e-07,9.9e-07,2.3e-06,0.037,0.037,0.00036,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18590000,0.98,-0.0076,-0.011,0.19,0.014,-0.019,0.028,0.0092,-0.0088,0.033,-0.0012,-0.0059,-0.00011,0.0074,0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.017,0.017,0.0079,0.041,0.041,0.034,9.5e-07,9.6e-07,2.3e-06,0.037,0.037,0.00035,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18690000,0.98,-0.0076,-0.011,0.19,0.014,-0.019,0.026,0.011,-0.011,0.032,-0.0012,-0.0059,-0.00011,0.0074,0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.019,0.019,0.008,0.045,0.045,0.034,9.6e-07,9.6e-07,2.3e-06,0.037,0.037,0.00035,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18790000,0.98,-0.0076,-0.011,0.19,0.013,-0.018,0.026,0.0099,-0.0093,0.03,-0.0012,-0.0059,-0.00011,0.0081,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.017,0.017,0.0079,0.04,0.04,0.034,9.3e-07,9.3e-07,2.3e-06,0.037,0.037,0.00035,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.7 -18890000,0.98,-0.0075,-0.011,0.19,0.012,-0.019,0.024,0.011,-0.011,0.026,-0.0012,-0.0059,-0.00011,0.008,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.018,0.018,0.008,0.045,0.045,0.034,9.3e-07,9.3e-07,2.3e-06,0.037,0.037,0.00034,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -18990000,0.98,-0.0075,-0.011,0.19,0.01,-0.018,0.025,0.0095,-0.0097,0.03,-0.0012,-0.0059,-0.00011,0.0088,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.017,0.017,0.0079,0.04,0.04,0.034,9e-07,9e-07,2.3e-06,0.036,0.036,0.00034,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19090000,0.98,-0.0076,-0.011,0.19,0.0088,-0.02,0.025,0.011,-0.012,0.026,-0.0012,-0.0059,-0.00011,0.0087,0.0019,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00043,0.00043,0.066,0.018,0.018,0.0079,0.045,0.045,0.035,9e-07,9e-07,2.3e-06,0.036,0.036,0.00033,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19190000,0.98,-0.0075,-0.011,0.19,0.007,-0.019,0.025,0.009,-0.01,0.025,-0.0013,-0.0059,-0.00011,0.0095,0.0021,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.017,0.017,0.0079,0.04,0.04,0.034,8.7e-07,8.7e-07,2.3e-06,0.036,0.036,0.00033,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.8 -19290000,0.98,-0.0074,-0.011,0.19,0.0066,-0.02,0.025,0.0097,-0.012,0.024,-0.0013,-0.0059,-0.00011,0.0095,0.0021,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.018,0.018,0.0079,0.044,0.044,0.034,8.7e-07,8.8e-07,2.3e-06,0.036,0.036,0.00032,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19390000,0.98,-0.0075,-0.011,0.19,0.0057,-0.016,0.026,0.0084,-0.0094,0.023,-0.0013,-0.0059,-0.00011,0.011,0.0023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.016,0.016,0.0078,0.04,0.04,0.035,8.5e-07,8.5e-07,2.3e-06,0.036,0.036,0.00032,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19490000,0.98,-0.0075,-0.011,0.19,0.0054,-0.017,0.026,0.009,-0.011,0.023,-0.0013,-0.0059,-0.00011,0.01,0.0023,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00042,0.00042,0.066,0.018,0.018,0.0078,0.044,0.044,0.035,8.5e-07,8.5e-07,2.3e-06,0.036,0.036,0.00031,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19590000,0.98,-0.0075,-0.011,0.19,0.0033,-0.019,0.028,0.0084,-0.011,0.023,-0.0013,-0.0059,-0.00011,0.011,0.0022,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.016,0.016,0.0077,0.04,0.04,0.035,8.2e-07,8.2e-07,2.3e-06,0.035,0.035,0.00031,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,4.9 -19690000,0.98,-0.0075,-0.011,0.19,0.002,-0.018,0.026,0.0087,-0.012,0.023,-0.0013,-0.0059,-0.00011,0.011,0.0022,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00042,0.066,0.018,0.018,0.0078,0.044,0.044,0.035,8.2e-07,8.2e-07,2.3e-06,0.035,0.035,0.0003,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 -19790000,0.98,-0.0076,-0.011,0.19,0.00072,-0.016,0.025,0.0099,-0.011,0.019,-0.0013,-0.0059,-0.00011,0.011,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.016,0.016,0.0077,0.04,0.04,0.035,8e-07,8e-07,2.3e-06,0.035,0.035,0.0003,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 -19890000,0.98,-0.0076,-0.011,0.19,0.0011,-0.017,0.025,0.0099,-0.012,0.017,-0.0013,-0.0059,-0.00011,0.011,0.0018,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.017,0.017,0.0077,0.044,0.044,0.035,8e-07,8e-07,2.3e-06,0.035,0.035,0.00029,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 -19990000,0.98,-0.0076,-0.011,0.19,0.0004,-0.016,0.022,0.0093,-0.0099,0.014,-0.0013,-0.0059,-0.00011,0.012,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.016,0.016,0.0076,0.04,0.04,0.035,7.7e-07,7.7e-07,2.3e-06,0.035,0.035,0.00029,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5 -20090000,0.98,-0.0076,-0.011,0.19,0.0013,-0.019,0.022,0.0094,-0.012,0.018,-0.0013,-0.0059,-0.00011,0.012,0.0015,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.095,0.00041,0.00041,0.066,0.017,0.017,0.0076,0.044,0.044,0.035,7.7e-07,7.8e-07,2.3e-06,0.035,0.035,0.00028,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,5.1 -20190000,0.98,-0.0076,-0.011,0.19,0.0016,-0.016,0.023,0.0097,-0.01,0.017,-0.0013,-0.0059,-0.00011,0.013,0.0014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.016,0.016,0.0075,0.039,0.039,0.035,7.5e-07,7.5e-07,2.3e-06,0.035,0.035,0.00028,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20290000,0.98,-0.0076,-0.011,0.19,-0.0012,-0.018,0.023,0.0097,-0.012,0.018,-0.0013,-0.0059,-0.00011,0.013,0.0014,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.017,0.017,0.0075,0.043,0.043,0.035,7.5e-07,7.5e-07,2.3e-06,0.035,0.035,0.00028,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20390000,0.98,-0.0076,-0.011,0.19,-0.0026,-0.016,0.024,0.0098,-0.01,0.019,-0.0013,-0.0059,-0.00011,0.014,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.016,0.016,0.0075,0.039,0.039,0.035,7.3e-07,7.3e-07,2.3e-06,0.034,0.034,0.00027,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20490000,0.98,-0.0076,-0.011,0.18,-0.007,-0.018,0.024,0.0093,-0.012,0.017,-0.0013,-0.0059,-0.00011,0.014,0.0012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.017,0.017,0.0075,0.043,0.043,0.035,7.3e-07,7.3e-07,2.3e-06,0.034,0.034,0.00027,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20590000,0.98,-0.0075,-0.011,0.18,-0.0069,-0.018,0.023,0.0095,-0.01,0.016,-0.0013,-0.0059,-0.00011,0.014,0.00077,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00039,0.00039,0.066,0.016,0.016,0.0074,0.039,0.039,0.035,7e-07,7.1e-07,2.3e-06,0.034,0.034,0.00026,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20690000,0.98,-0.0075,-0.011,0.18,-0.0084,-0.018,0.024,0.0087,-0.012,0.016,-0.0013,-0.0059,-0.00011,0.014,0.00078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.0004,0.0004,0.066,0.017,0.017,0.0074,0.043,0.043,0.035,7.1e-07,7.1e-07,2.3e-06,0.034,0.034,0.00026,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20790000,0.98,-0.0069,-0.011,0.18,-0.011,-0.014,0.009,0.0072,-0.011,0.015,-0.0013,-0.0059,-0.00011,0.015,0.00054,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.11,0.00039,0.00039,0.066,0.016,0.016,0.0073,0.039,0.039,0.035,6.8e-07,6.9e-07,2.3e-06,0.034,0.034,0.00025,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20890000,0.98,0.0023,-0.0074,0.18,-0.017,-0.0032,-0.11,0.0057,-0.011,0.0085,-0.0013,-0.0059,-0.00011,0.015,0.00055,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.11,0.00039,0.00039,0.066,0.017,0.017,0.0073,0.043,0.043,0.035,6.8e-07,6.9e-07,2.3e-06,0.034,0.034,0.00025,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -20990000,0.98,0.0056,-0.0039,0.18,-0.029,0.016,-0.25,0.0041,-0.009,-0.0065,-0.0013,-0.0059,-0.00011,0.015,5.1e-05,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.093,0.00039,0.00039,0.066,0.016,0.016,0.0072,0.039,0.039,0.034,6.6e-07,6.6e-07,2.3e-06,0.033,0.033,0.00025,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21090000,0.98,0.004,-0.0043,0.18,-0.042,0.031,-0.37,0.00064,-0.0066,-0.037,-0.0013,-0.0059,-0.00011,0.015,5e-05,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.063,0.00039,0.00039,0.066,0.017,0.017,0.0072,0.043,0.043,0.035,6.6e-07,6.7e-07,2.3e-06,0.033,0.033,0.00024,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21190000,0.98,0.0012,-0.0059,0.19,-0.047,0.038,-0.49,-0.00032,-0.0049,-0.074,-0.0013,-0.0059,-0.00011,0.014,-0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,0.026,0.00038,0.00038,0.066,0.016,0.016,0.0071,0.039,0.039,0.035,6.4e-07,6.4e-07,2.3e-06,0.033,0.033,0.00024,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21290000,0.98,-0.001,-0.0072,0.19,-0.047,0.04,-0.62,-0.005,-0.00096,-0.13,-0.0013,-0.0059,-0.00011,0.014,-0.0013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.032,0.00038,0.00038,0.066,0.018,0.018,0.0071,0.043,0.043,0.035,6.4e-07,6.4e-07,2.3e-06,0.033,0.033,0.00024,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21390000,0.98,-0.0025,-0.0079,0.19,-0.043,0.038,-0.75,-0.0049,0.0031,-0.2,-0.0013,-0.0059,-0.00011,0.014,-0.0025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.097,0.00038,0.00038,0.066,0.016,0.016,0.007,0.039,0.039,0.035,6.2e-07,6.2e-07,2.3e-06,0.032,0.032,0.00023,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21490000,0.98,-0.0033,-0.0083,0.19,-0.038,0.034,-0.89,-0.009,0.0067,-0.28,-0.0013,-0.0059,-0.00011,0.014,-0.0025,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.18,0.00038,0.00038,0.066,0.018,0.018,0.007,0.043,0.043,0.035,6.2e-07,6.2e-07,2.3e-06,0.032,0.032,0.00023,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21590000,0.98,-0.0038,-0.0083,0.19,-0.03,0.031,-1,-0.0081,0.0087,-0.37,-0.0013,-0.0059,-0.00011,0.015,-0.0031,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.27,0.00037,0.00037,0.066,0.017,0.017,0.0069,0.039,0.039,0.034,6e-07,6e-07,2.3e-06,0.032,0.032,0.00023,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21690000,0.98,-0.0041,-0.0081,0.19,-0.028,0.026,-1.1,-0.011,0.012,-0.49,-0.0013,-0.0059,-0.00011,0.014,-0.003,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.39,0.00037,0.00037,0.066,0.018,0.018,0.0069,0.043,0.043,0.035,6e-07,6e-07,2.3e-06,0.032,0.032,0.00022,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21790000,0.98,-0.0045,-0.0083,0.19,-0.021,0.021,-1.3,-0.0047,0.01,-0.61,-0.0013,-0.0059,-0.00011,0.015,-0.0043,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.51,0.00036,0.00036,0.066,0.017,0.017,0.0069,0.039,0.039,0.034,5.8e-07,5.8e-07,2.3e-06,0.032,0.032,0.00022,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21890000,0.98,-0.0048,-0.0085,0.19,-0.018,0.016,-1.4,-0.0066,0.012,-0.75,-0.0013,-0.0059,-0.00011,0.015,-0.0042,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.65,0.00036,0.00036,0.066,0.018,0.018,0.0068,0.043,0.043,0.034,5.8e-07,5.8e-07,2.3e-06,0.032,0.032,0.00022,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -21990000,0.98,-0.0055,-0.0087,0.19,-0.014,0.011,-1.4,-0.0012,0.0091,-0.88,-0.0013,-0.0059,-0.00011,0.015,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.78,0.00036,0.00036,0.066,0.017,0.017,0.0068,0.039,0.039,0.034,5.6e-07,5.6e-07,2.3e-06,0.031,0.031,0.00021,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22090000,0.98,-0.0062,-0.0095,0.19,-0.012,0.0068,-1.4,-0.0026,0.0099,-1,-0.0013,-0.0059,-0.00011,0.015,-0.004,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-0.93,0.00036,0.00036,0.066,0.018,0.018,0.0068,0.043,0.043,0.034,5.6e-07,5.6e-07,2.3e-06,0.031,0.031,0.00021,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22190000,0.98,-0.0067,-0.0098,0.19,-0.0041,0.002,-1.4,0.005,0.0053,-1.2,-0.0013,-0.0059,-0.00011,0.015,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.1,0.00035,0.00035,0.066,0.016,0.016,0.0067,0.039,0.039,0.034,5.5e-07,5.4e-07,2.3e-06,0.031,0.031,0.00021,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22290000,0.98,-0.0074,-0.01,0.19,0.00091,-0.0037,-1.4,0.0048,0.0052,-1.3,-0.0013,-0.0059,-0.00011,0.015,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.2,0.00035,0.00035,0.066,0.017,0.017,0.0067,0.043,0.043,0.034,5.5e-07,5.5e-07,2.3e-06,0.031,0.031,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22390000,0.98,-0.0077,-0.01,0.19,0.006,-0.012,-1.4,0.012,-0.003,-1.5,-0.0013,-0.0059,-0.00011,0.014,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.4,0.00034,0.00034,0.066,0.016,0.016,0.0066,0.039,0.039,0.034,5.3e-07,5.3e-07,2.3e-06,0.03,0.03,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22490000,0.98,-0.0078,-0.011,0.19,0.0098,-0.018,-1.4,0.013,-0.0046,-1.6,-0.0013,-0.0059,-0.00011,0.014,-0.0037,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.5,0.00034,0.00034,0.066,0.017,0.017,0.0066,0.043,0.043,0.034,5.3e-07,5.3e-07,2.3e-06,0.03,0.03,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22590000,0.98,-0.0078,-0.011,0.19,0.019,-0.026,-1.4,0.025,-0.012,-1.7,-0.0013,-0.0059,-0.00011,0.014,-0.0044,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.6,0.00034,0.00034,0.066,0.016,0.016,0.0065,0.039,0.039,0.034,5.1e-07,5.1e-07,2.3e-06,0.03,0.03,0.0002,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22690000,0.98,-0.0077,-0.011,0.19,0.021,-0.031,-1.4,0.027,-0.015,-1.9,-0.0013,-0.0059,-0.00011,0.014,-0.0043,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.8,0.00034,0.00034,0.066,0.017,0.017,0.0065,0.043,0.043,0.034,5.1e-07,5.1e-07,2.3e-06,0.03,0.03,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22790000,0.98,-0.0077,-0.012,0.19,0.027,-0.038,-1.4,0.037,-0.024,-2,-0.0013,-0.0059,-0.00011,0.014,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-1.9,0.00033,0.00033,0.066,0.015,0.015,0.0065,0.039,0.039,0.034,5e-07,5e-07,2.3e-06,0.03,0.03,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22890000,0.98,-0.0078,-0.012,0.19,0.03,-0.044,-1.4,0.04,-0.028,-2.2,-0.0013,-0.0059,-0.00011,0.014,-0.0041,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.1,0.00033,0.00033,0.066,0.016,0.016,0.0065,0.043,0.043,0.034,5e-07,5e-07,2.3e-06,0.03,0.03,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -22990000,0.98,-0.0078,-0.013,0.18,0.035,-0.049,-1.4,0.05,-0.038,-2.3,-0.0013,-0.0059,-0.00011,0.015,-0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.2,0.00033,0.00033,0.066,0.015,0.015,0.0064,0.039,0.039,0.034,4.8e-07,4.8e-07,2.3e-06,0.029,0.029,0.00019,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23090000,0.98,-0.0078,-0.013,0.18,0.04,-0.054,-1.4,0.054,-0.043,-2.5,-0.0013,-0.0059,-0.00011,0.014,-0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.4,0.00033,0.00033,0.066,0.016,0.016,0.0064,0.043,0.043,0.034,4.8e-07,4.8e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23190000,0.98,-0.0078,-0.013,0.18,0.046,-0.055,-1.4,0.065,-0.052,-2.6,-0.0013,-0.0059,-0.00011,0.015,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.5,0.00032,0.00032,0.066,0.015,0.015,0.0063,0.039,0.039,0.033,4.7e-07,4.7e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23290000,0.98,-0.0083,-0.013,0.18,0.051,-0.06,-1.4,0.07,-0.058,-2.8,-0.0013,-0.0059,-0.00011,0.015,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.7,0.00032,0.00032,0.066,0.016,0.016,0.0063,0.043,0.043,0.034,4.7e-07,4.7e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23390000,0.98,-0.0082,-0.013,0.18,0.057,-0.062,-1.4,0.081,-0.063,-2.9,-0.0013,-0.0059,-0.00011,0.016,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.8,0.00032,0.00032,0.066,0.015,0.015,0.0063,0.039,0.039,0.033,4.6e-07,4.6e-07,2.3e-06,0.029,0.029,0.00018,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23490000,0.98,-0.0083,-0.014,0.18,0.061,-0.065,-1.4,0.087,-0.069,-3,-0.0013,-0.0059,-0.00011,0.016,-0.0034,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-2.9,0.00032,0.00032,0.066,0.016,0.016,0.0063,0.043,0.043,0.033,4.6e-07,4.6e-07,2.3e-06,0.029,0.029,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23590000,0.98,-0.0085,-0.014,0.18,0.064,-0.067,-1.4,0.095,-0.078,-3.2,-0.0013,-0.0059,-0.00011,0.017,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.1,0.00031,0.00031,0.066,0.014,0.014,0.0062,0.039,0.039,0.033,4.5e-07,4.5e-07,2.3e-06,0.029,0.029,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23690000,0.98,-0.0091,-0.014,0.18,0.062,-0.07,-1.3,0.1,-0.085,-3.3,-0.0013,-0.0059,-0.00011,0.017,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.2,0.00031,0.00031,0.066,0.015,0.015,0.0062,0.042,0.042,0.033,4.5e-07,4.5e-07,2.3e-06,0.029,0.029,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23790000,0.98,-0.011,-0.017,0.18,0.057,-0.067,-0.95,0.11,-0.089,-3.4,-0.0013,-0.0059,-0.00011,0.018,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.3,0.00031,0.00031,0.066,0.014,0.014,0.0061,0.038,0.038,0.033,4.4e-07,4.4e-07,2.3e-06,0.028,0.028,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23890000,0.98,-0.014,-0.021,0.18,0.052,-0.068,-0.52,0.12,-0.096,-3.5,-0.0013,-0.0059,-0.00011,0.018,-0.0026,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00031,0.00031,0.066,0.014,0.014,0.0061,0.042,0.042,0.033,4.4e-07,4.4e-07,2.3e-06,0.028,0.028,0.00017,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -23990000,0.98,-0.016,-0.024,0.18,0.054,-0.066,-0.13,0.13,-0.097,-3.6,-0.0013,-0.0059,-0.00011,0.02,-0.0031,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.013,0.013,0.0061,0.038,0.038,0.033,4.3e-07,4.3e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24090000,0.98,-0.016,-0.023,0.18,0.06,-0.075,0.099,0.13,-0.1,-3.6,-0.0013,-0.0059,-0.00011,0.02,-0.003,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.014,0.014,0.0061,0.042,0.042,0.033,4.3e-07,4.3e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24190000,0.98,-0.013,-0.019,0.18,0.071,-0.08,0.089,0.14,-0.11,-3.6,-0.0013,-0.0059,-0.00011,0.021,-0.0036,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.013,0.013,0.006,0.038,0.038,0.033,4.2e-07,4.2e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24290000,0.98,-0.011,-0.016,0.18,0.075,-0.084,0.067,0.15,-0.12,-3.6,-0.0013,-0.0059,-0.00011,0.021,-0.0035,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.00031,0.00031,0.066,0.014,0.014,0.006,0.042,0.042,0.033,4.2e-07,4.2e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24390000,0.98,-0.0099,-0.015,0.18,0.069,-0.078,0.083,0.15,-0.12,-3.6,-0.0013,-0.0059,-0.00011,0.023,-0.0046,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.0003,0.0003,0.066,0.013,0.013,0.006,0.038,0.038,0.033,4.1e-07,4.1e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24490000,0.98,-0.01,-0.015,0.18,0.064,-0.076,0.081,0.16,-0.12,-3.6,-0.0013,-0.0059,-0.00011,0.023,-0.0046,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.0003,0.0003,0.066,0.014,0.014,0.006,0.041,0.041,0.033,4.1e-07,4.1e-07,2.3e-06,0.028,0.028,0.00016,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24590000,0.98,-0.011,-0.015,0.19,0.061,-0.072,0.077,0.16,-0.12,-3.6,-0.0014,-0.0059,-0.00011,0.024,-0.0058,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.5,0.0003,0.0003,0.066,0.013,0.013,0.0059,0.038,0.038,0.033,4e-07,4e-07,2.3e-06,0.028,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24690000,0.98,-0.011,-0.015,0.19,0.059,-0.072,0.076,0.17,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.024,-0.0058,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0059,0.041,0.041,0.033,4e-07,4e-07,2.3e-06,0.028,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24790000,0.98,-0.011,-0.014,0.19,0.056,-0.069,0.068,0.17,-0.12,-3.5,-0.0014,-0.0059,-0.00011,0.026,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.013,0.013,0.0059,0.038,0.038,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24890000,0.98,-0.011,-0.014,0.19,0.054,-0.073,0.057,0.18,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.026,-0.0066,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0059,0.041,0.041,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -24990000,0.98,-0.011,-0.014,0.19,0.045,-0.069,0.05,0.18,-0.12,-3.5,-0.0014,-0.0059,-0.00011,0.029,-0.0078,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.013,0.013,0.0058,0.037,0.037,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25090000,0.98,-0.011,-0.014,0.19,0.042,-0.068,0.048,0.18,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.029,-0.0077,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0058,0.041,0.041,0.032,3.9e-07,3.9e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25190000,0.98,-0.011,-0.014,0.19,0.037,-0.062,0.048,0.18,-0.12,-3.5,-0.0014,-0.0059,-0.00011,0.031,-0.0089,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0058,0.037,0.037,0.032,3.8e-07,3.8e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25290000,0.98,-0.012,-0.013,0.19,0.032,-0.064,0.042,0.19,-0.13,-3.5,-0.0014,-0.0059,-0.00011,0.031,-0.0088,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.066,0.014,0.014,0.0058,0.041,0.041,0.032,3.8e-07,3.8e-07,2.3e-06,0.027,0.027,0.00015,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25390000,0.98,-0.012,-0.013,0.19,0.024,-0.056,0.041,0.18,-0.11,-3.5,-0.0014,-0.0058,-0.0001,0.033,-0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0058,0.037,0.037,0.032,3.7e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25490000,0.98,-0.012,-0.013,0.19,0.019,-0.057,0.041,0.18,-0.12,-3.5,-0.0014,-0.0058,-0.0001,0.033,-0.01,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0058,0.041,0.041,0.032,3.7e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25590000,0.98,-0.012,-0.013,0.19,0.014,-0.052,0.042,0.18,-0.11,-3.5,-0.0014,-0.0058,-0.0001,0.035,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0057,0.037,0.037,0.032,3.6e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25690000,0.98,-0.011,-0.012,0.19,0.013,-0.052,0.031,0.18,-0.12,-3.5,-0.0014,-0.0058,-0.0001,0.035,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0057,0.041,0.041,0.032,3.7e-07,3.7e-07,2.3e-06,0.027,0.027,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25790000,0.98,-0.011,-0.012,0.19,0.0025,-0.043,0.031,0.17,-0.1,-3.5,-0.0015,-0.0058,-0.0001,0.037,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0057,0.037,0.037,0.032,3.6e-07,3.6e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25890000,0.98,-0.011,-0.012,0.19,-0.0031,-0.042,0.033,0.17,-0.11,-3.5,-0.0015,-0.0058,-0.0001,0.037,-0.011,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0057,0.041,0.041,0.032,3.6e-07,3.6e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -25990000,0.98,-0.011,-0.012,0.19,-0.012,-0.034,0.027,0.16,-0.098,-3.5,-0.0015,-0.0058,-0.0001,0.039,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0057,0.037,0.037,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26090000,0.98,-0.011,-0.012,0.19,-0.017,-0.035,0.025,0.16,-0.1,-3.5,-0.0015,-0.0058,-0.0001,0.039,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0057,0.041,0.041,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00014,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26190000,0.98,-0.011,-0.012,0.19,-0.023,-0.027,0.021,0.15,-0.093,-3.5,-0.0015,-0.0058,-0.0001,0.04,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0056,0.037,0.037,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26290000,0.98,-0.011,-0.013,0.19,-0.024,-0.027,0.015,0.15,-0.096,-3.5,-0.0015,-0.0058,-0.0001,0.04,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.5e-07,3.5e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26390000,0.98,-0.01,-0.013,0.19,-0.03,-0.019,0.019,0.14,-0.086,-3.5,-0.0015,-0.0058,-0.0001,0.041,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0056,0.037,0.037,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26490000,0.98,-0.0099,-0.013,0.19,-0.033,-0.016,0.028,0.13,-0.088,-3.5,-0.0015,-0.0058,-0.0001,0.041,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26590000,0.98,-0.0093,-0.013,0.19,-0.035,-0.0072,0.029,0.12,-0.08,-3.5,-0.0015,-0.0058,-0.0001,0.042,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.013,0.013,0.0056,0.037,0.037,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26690000,0.98,-0.0091,-0.013,0.19,-0.037,-0.0027,0.027,0.12,-0.08,-3.5,-0.0015,-0.0058,-0.0001,0.042,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.4e-07,3.4e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26790000,0.98,-0.0089,-0.012,0.19,-0.044,0.0018,0.027,0.11,-0.073,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26890000,0.98,-0.0083,-0.012,0.19,-0.049,0.0045,0.022,0.1,-0.073,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0056,0.041,0.041,0.032,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -26990000,0.98,-0.0077,-0.013,0.19,-0.056,0.012,0.021,0.089,-0.065,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27090000,0.98,-0.0076,-0.013,0.19,-0.058,0.019,0.025,0.084,-0.064,-3.5,-0.0015,-0.0058,-0.0001,0.043,-0.012,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.0003,0.0003,0.065,0.014,0.014,0.0055,0.041,0.041,0.031,3.3e-07,3.3e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27190000,0.98,-0.0076,-0.013,0.19,-0.064,0.025,0.027,0.073,-0.056,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.026,0.00013,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27290000,0.98,-0.0078,-0.014,0.19,-0.071,0.03,0.14,0.066,-0.053,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.014,0.014,0.0055,0.041,0.041,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.026,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27390000,0.98,-0.0092,-0.016,0.18,-0.077,0.037,0.46,0.056,-0.045,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.013,0.013,0.0055,0.037,0.037,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27490000,0.98,-0.011,-0.018,0.18,-0.081,0.042,0.78,0.048,-0.041,-3.5,-0.0015,-0.0058,-0.0001,0.044,-0.013,-0.13,0.37,0.0037,0.026,0,0,0,0,0,-3.4,0.00029,0.00029,0.065,0.014,0.013,0.0055,0.04,0.04,0.031,3.2e-07,3.2e-07,2.3e-06,0.026,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27590000,0.98,-0.01,-0.017,0.18,-0.076,0.046,0.87,0.04,-0.035,-3.4,-0.0015,-0.0058,-0.0001,0.044,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.3,0.00029,0.00029,0.065,0.013,0.012,0.0055,0.037,0.037,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27690000,0.98,-0.0092,-0.014,0.18,-0.072,0.042,0.78,0.032,-0.03,-3.3,-0.0015,-0.0058,-0.0001,0.044,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.2,0.00029,0.00029,0.065,0.014,0.013,0.0055,0.04,0.04,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27790000,0.98,-0.0079,-0.013,0.18,-0.071,0.04,0.77,0.026,-0.027,-3.2,-0.0015,-0.0058,-0.0001,0.043,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.1,0.00029,0.00029,0.065,0.013,0.012,0.0054,0.037,0.037,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27890000,0.98,-0.0075,-0.013,0.18,-0.078,0.047,0.81,0.018,-0.022,-3.2,-0.0015,-0.0058,-0.0001,0.043,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3.1,0.00029,0.00029,0.065,0.014,0.013,0.0054,0.04,0.04,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -27990000,0.98,-0.008,-0.013,0.18,-0.078,0.049,0.8,0.013,-0.019,-3.1,-0.0015,-0.0058,-0.0001,0.042,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-3,0.00029,0.00029,0.065,0.013,0.012,0.0054,0.037,0.037,0.031,3.1e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28090000,0.98,-0.0083,-0.013,0.18,-0.081,0.05,0.8,0.0049,-0.014,-3,-0.0015,-0.0058,-0.0001,0.042,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.9,0.00029,0.00029,0.065,0.014,0.013,0.0054,0.04,0.04,0.031,3.1e-07,3.1e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28190000,0.98,-0.0078,-0.013,0.18,-0.082,0.047,0.81,-0.0019,-0.012,-2.9,-0.0015,-0.0058,-0.0001,0.041,-0.014,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.8,0.00029,0.00029,0.064,0.013,0.012,0.0054,0.037,0.037,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28290000,0.98,-0.0073,-0.014,0.18,-0.087,0.05,0.81,-0.01,-0.0074,-2.9,-0.0015,-0.0058,-0.0001,0.041,-0.015,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.8,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28390000,0.98,-0.0073,-0.014,0.18,-0.087,0.054,0.81,-0.015,-0.0032,-2.8,-0.0015,-0.0058,-0.0001,0.041,-0.015,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.7,0.00029,0.00029,0.064,0.013,0.012,0.0054,0.037,0.037,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28490000,0.98,-0.0076,-0.015,0.18,-0.089,0.058,0.81,-0.024,0.0024,-2.7,-0.0015,-0.0058,-0.0001,0.041,-0.015,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.6,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,3e-07,3e-07,2.3e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28590000,0.98,-0.0077,-0.015,0.18,-0.082,0.053,0.81,-0.027,0.0014,-2.6,-0.0015,-0.0058,-0.0001,0.039,-0.016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.5,0.00029,0.00029,0.064,0.013,0.012,0.0054,0.037,0.037,0.031,3e-07,2.9e-07,2.4e-06,0.025,0.025,0.00012,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28690000,0.98,-0.0075,-0.014,0.18,-0.082,0.054,0.81,-0.036,0.0069,-2.6,-0.0015,-0.0058,-0.0001,0.039,-0.016,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.5,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,3e-07,3e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28790000,0.98,-0.0068,-0.014,0.18,-0.079,0.055,0.81,-0.038,0.0098,-2.5,-0.0014,-0.0058,-9.9e-05,0.039,-0.017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.4,0.00029,0.00029,0.064,0.013,0.012,0.0053,0.037,0.037,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28890000,0.98,-0.0067,-0.013,0.18,-0.083,0.056,0.81,-0.046,0.015,-2.4,-0.0014,-0.0058,-9.9e-05,0.039,-0.017,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.3,0.00029,0.00029,0.064,0.014,0.013,0.0054,0.04,0.04,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -28990000,0.98,-0.0065,-0.014,0.18,-0.079,0.054,0.81,-0.046,0.016,-2.3,-0.0014,-0.0058,-9.9e-05,0.037,-0.018,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.2,0.00029,0.00029,0.064,0.013,0.012,0.0053,0.037,0.037,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29090000,0.98,-0.0064,-0.014,0.18,-0.081,0.056,0.81,-0.054,0.021,-2.3,-0.0014,-0.0058,-9.9e-05,0.038,-0.018,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.2,0.00029,0.00029,0.064,0.013,0.013,0.0053,0.04,0.04,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29190000,0.98,-0.0064,-0.014,0.18,-0.077,0.055,0.8,-0.051,0.021,-2.2,-0.0014,-0.0058,-9.8e-05,0.036,-0.019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2.1,0.00029,0.00029,0.063,0.013,0.012,0.0053,0.037,0.037,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29290000,0.98,-0.0067,-0.014,0.18,-0.079,0.061,0.81,-0.059,0.027,-2.1,-0.0014,-0.0058,-9.8e-05,0.037,-0.019,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-2,0.00029,0.00029,0.063,0.014,0.013,0.0053,0.04,0.04,0.031,2.9e-07,2.9e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29390000,0.98,-0.0072,-0.013,0.18,-0.074,0.06,0.81,-0.058,0.029,-2,-0.0014,-0.0058,-9.7e-05,0.036,-0.02,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.9,0.00029,0.00029,0.063,0.013,0.012,0.0053,0.037,0.037,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29490000,0.98,-0.0072,-0.013,0.18,-0.077,0.06,0.81,-0.065,0.035,-2,-0.0014,-0.0058,-9.7e-05,0.036,-0.02,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.9,0.00029,0.00029,0.063,0.013,0.013,0.0053,0.04,0.04,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29590000,0.98,-0.0071,-0.013,0.18,-0.073,0.058,0.81,-0.063,0.035,-1.9,-0.0014,-0.0058,-9.7e-05,0.035,-0.021,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.8,0.00029,0.00029,0.063,0.013,0.012,0.0053,0.037,0.037,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29690000,0.98,-0.0072,-0.013,0.18,-0.077,0.057,0.81,-0.07,0.041,-1.8,-0.0014,-0.0058,-9.7e-05,0.035,-0.021,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.7,0.00029,0.00029,0.063,0.013,0.013,0.0053,0.04,0.04,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.025,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29790000,0.98,-0.0071,-0.013,0.18,-0.073,0.051,0.8,-0.065,0.039,-1.7,-0.0014,-0.0058,-9.6e-05,0.034,-0.022,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.6,0.00029,0.00029,0.063,0.012,0.012,0.0053,0.037,0.037,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29890000,0.98,-0.0065,-0.014,0.18,-0.073,0.052,0.8,-0.073,0.044,-1.7,-0.0014,-0.0058,-9.6e-05,0.034,-0.023,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.6,0.00029,0.00029,0.063,0.013,0.013,0.0053,0.04,0.04,0.031,2.8e-07,2.8e-07,2.4e-06,0.025,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -29990000,0.98,-0.0068,-0.014,0.18,-0.068,0.047,0.8,-0.068,0.04,-1.6,-0.0014,-0.0058,-9.6e-05,0.033,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.5,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.8e-07,2.8e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30090000,0.98,-0.0069,-0.014,0.18,-0.068,0.048,0.8,-0.075,0.045,-1.5,-0.0014,-0.0058,-9.6e-05,0.033,-0.024,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.4,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.8e-07,2.8e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30190000,0.98,-0.0069,-0.014,0.18,-0.062,0.045,0.8,-0.068,0.044,-1.5,-0.0014,-0.0058,-9.5e-05,0.032,-0.025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.4,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.031,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30290000,0.98,-0.007,-0.014,0.18,-0.061,0.045,0.8,-0.075,0.048,-1.4,-0.0014,-0.0058,-9.5e-05,0.032,-0.025,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.3,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30390000,0.98,-0.007,-0.014,0.18,-0.054,0.039,0.8,-0.066,0.046,-1.3,-0.0014,-0.0057,-9.4e-05,0.032,-0.027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.2,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30490000,0.98,-0.007,-0.014,0.18,-0.057,0.039,0.8,-0.072,0.05,-1.2,-0.0014,-0.0057,-9.4e-05,0.032,-0.027,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.1,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.031,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30590000,0.98,-0.0074,-0.014,0.18,-0.052,0.036,0.8,-0.065,0.046,-1.2,-0.0014,-0.0057,-9.4e-05,0.031,-0.028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1.1,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.00011,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30690000,0.98,-0.0078,-0.014,0.18,-0.05,0.035,0.8,-0.07,0.05,-1.1,-0.0014,-0.0057,-9.4e-05,0.031,-0.028,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-1,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30790000,0.98,-0.0075,-0.014,0.18,-0.043,0.03,0.8,-0.063,0.049,-1,-0.0013,-0.0057,-9.3e-05,0.031,-0.029,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.92,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30890000,0.98,-0.0069,-0.014,0.18,-0.044,0.026,0.79,-0.067,0.052,-0.95,-0.0013,-0.0057,-9.3e-05,0.031,-0.03,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.85,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.7e-07,2.7e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -30990000,0.98,-0.0071,-0.014,0.18,-0.036,0.021,0.79,-0.057,0.045,-0.88,-0.0013,-0.0057,-9.3e-05,0.03,-0.031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.78,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31090000,0.98,-0.0073,-0.014,0.18,-0.035,0.02,0.79,-0.061,0.047,-0.81,-0.0013,-0.0057,-9.3e-05,0.03,-0.031,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.71,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31190000,0.98,-0.0075,-0.014,0.18,-0.03,0.015,0.8,-0.052,0.042,-0.74,-0.0013,-0.0057,-9.3e-05,0.03,-0.032,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.64,0.00029,0.00029,0.063,0.012,0.012,0.0052,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31290000,0.98,-0.0078,-0.014,0.18,-0.028,0.013,0.8,-0.055,0.044,-0.67,-0.0013,-0.0057,-9.3e-05,0.03,-0.032,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.57,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31390000,0.98,-0.0076,-0.014,0.18,-0.022,0.0066,0.8,-0.047,0.039,-0.59,-0.0013,-0.0057,-9.2e-05,0.03,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.49,0.00029,0.00029,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31490000,0.98,-0.0073,-0.014,0.18,-0.022,0.0035,0.8,-0.049,0.039,-0.52,-0.0013,-0.0057,-9.2e-05,0.03,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.42,0.00029,0.00029,0.063,0.013,0.013,0.0052,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31590000,0.98,-0.0072,-0.015,0.18,-0.018,0.0016,0.8,-0.038,0.035,-0.45,-0.0013,-0.0057,-9.2e-05,0.03,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.35,0.00028,0.00029,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31690000,0.98,-0.0072,-0.015,0.18,-0.02,0.00032,0.8,-0.04,0.035,-0.38,-0.0013,-0.0057,-9.2e-05,0.03,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.28,0.00029,0.00029,0.063,0.013,0.013,0.0051,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31790000,0.98,-0.0075,-0.016,0.18,-0.011,-0.0021,0.8,-0.029,0.034,-0.3,-0.0013,-0.0057,-9.2e-05,0.031,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.2,0.00028,0.00028,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31890000,0.98,-0.0072,-0.016,0.18,-0.008,-0.0047,0.8,-0.029,0.034,-0.24,-0.0013,-0.0057,-9.2e-05,0.031,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.14,0.00028,0.00028,0.063,0.013,0.013,0.0051,0.04,0.04,0.03,2.6e-07,2.6e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -31990000,0.98,-0.0075,-0.015,0.18,-0.00019,-0.0051,0.79,-0.018,0.031,-0.17,-0.0013,-0.0057,-9.2e-05,0.031,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,-0.068,0.00028,0.00028,0.063,0.012,0.012,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,0.0001,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32090000,0.98,-0.0079,-0.015,0.18,-0.00077,-0.0087,0.8,-0.018,0.03,-0.096,-0.0013,-0.0057,-9.2e-05,0.031,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.004,0.00028,0.00028,0.063,0.013,0.013,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32190000,0.98,-0.0081,-0.015,0.18,0.0045,-0.012,0.8,-0.0066,0.029,-0.028,-0.0013,-0.0057,-9.1e-05,0.032,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.072,0.00028,0.00028,0.062,0.012,0.012,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32290000,0.98,-0.008,-0.015,0.18,0.006,-0.015,0.8,-0.0061,0.028,0.042,-0.0013,-0.0057,-9.1e-05,0.032,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.14,0.00028,0.00028,0.062,0.013,0.013,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32390000,0.98,-0.0082,-0.015,0.18,0.012,-0.016,0.79,0.0052,0.026,0.12,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.22,0.00028,0.00028,0.062,0.012,0.012,0.0051,0.036,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32490000,0.98,-0.011,-0.013,0.18,0.039,-0.082,-0.077,0.0084,0.019,0.12,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.22,0.00028,0.00028,0.062,0.015,0.015,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32590000,0.98,-0.011,-0.013,0.18,0.04,-0.083,-0.08,0.02,0.016,0.1,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.2,0.00028,0.00028,0.062,0.014,0.014,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32690000,0.98,-0.011,-0.013,0.18,0.036,-0.088,-0.081,0.024,0.007,0.088,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.19,0.00028,0.00028,0.062,0.015,0.014,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32790000,0.98,-0.011,-0.013,0.18,0.035,-0.087,-0.082,0.034,0.0051,0.072,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.17,0.00028,0.00027,0.062,0.014,0.013,0.0051,0.037,0.037,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32890000,0.98,-0.011,-0.013,0.18,0.035,-0.094,-0.084,0.037,-0.0039,0.058,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.16,0.00028,0.00028,0.062,0.015,0.014,0.0051,0.04,0.04,0.03,2.5e-07,2.5e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -32990000,0.98,-0.011,-0.013,0.18,0.033,-0.093,-0.083,0.045,-0.0074,0.044,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.14,0.00027,0.00027,0.062,0.014,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33090000,0.98,-0.011,-0.013,0.18,0.03,-0.097,-0.08,0.049,-0.017,0.037,-0.0013,-0.0057,-9.1e-05,0.033,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.14,0.00027,0.00027,0.062,0.015,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.9e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33190000,0.98,-0.011,-0.013,0.18,0.027,-0.097,-0.079,0.055,-0.019,0.029,-0.0014,-0.0057,-9.1e-05,0.034,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.13,0.00027,0.00027,0.061,0.014,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33290000,0.98,-0.011,-0.013,0.18,0.024,-0.1,-0.079,0.057,-0.029,0.021,-0.0014,-0.0057,-9.1e-05,0.034,-0.038,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.015,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.024,0.024,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.01 -33390000,0.98,-0.011,-0.014,0.18,0.021,-0.094,-0.077,0.061,-0.026,0.012,-0.0014,-0.0057,-9.1e-05,0.035,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.014,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.8e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.033 -33490000,0.98,-0.01,-0.013,0.18,0.017,-0.097,-0.076,0.063,-0.036,0.0025,-0.0014,-0.0057,-9.1e-05,0.035,-0.037,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.015,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.7e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.058 -33590000,0.98,-0.01,-0.014,0.18,0.014,-0.096,-0.073,0.065,-0.033,-0.0054,-0.0014,-0.0057,-9e-05,0.037,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.014,0.013,0.005,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.7e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.083 -33690000,0.98,-0.01,-0.014,0.18,0.01,-0.099,-0.074,0.066,-0.043,-0.013,-0.0014,-0.0057,-9e-05,0.037,-0.036,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00027,0.00027,0.061,0.014,0.014,0.0051,0.04,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.7e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.11 -33790000,0.98,-0.01,-0.014,0.18,0.0061,-0.096,-0.069,0.07,-0.04,-0.02,-0.0014,-0.0057,-9e-05,0.039,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.061,0.013,0.013,0.0051,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.6e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.13 -33890000,0.98,-0.01,-0.014,0.18,0.0027,-0.098,-0.068,0.07,-0.049,-0.027,-0.0014,-0.0057,-9e-05,0.039,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.061,0.014,0.014,0.0051,0.041,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.6e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.16 -33990000,0.98,-0.01,-0.014,0.18,0.00041,-0.092,-0.065,0.072,-0.044,-0.031,-0.0014,-0.0056,-9e-05,0.04,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.013,0.005,0.037,0.037,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.6e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.18 -34090000,0.98,-0.01,-0.014,0.18,-0.0035,-0.097,-0.063,0.072,-0.053,-0.035,-0.0014,-0.0056,-9e-05,0.04,-0.035,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.014,0.0051,0.041,0.04,0.03,2.4e-07,2.4e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.21 -34190000,0.98,-0.0099,-0.014,0.18,-0.0066,-0.092,-0.06,0.074,-0.047,-0.039,-0.0014,-0.0056,-9e-05,0.042,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.013,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.23 -34290000,0.98,-0.0097,-0.014,0.18,-0.0069,-0.096,-0.059,0.073,-0.057,-0.044,-0.0014,-0.0056,-9e-05,0.042,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.013,0.005,0.041,0.04,0.03,2.4e-07,2.3e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.26 -34390000,0.98,-0.0096,-0.014,0.18,-0.01,-0.09,-0.054,0.074,-0.051,-0.049,-0.0014,-0.0056,-8.9e-05,0.043,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.013,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.5e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.28 -34490000,0.98,-0.0096,-0.014,0.18,-0.013,-0.094,-0.053,0.072,-0.06,-0.051,-0.0014,-0.0056,-8.9e-05,0.043,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.013,0.005,0.041,0.04,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.4e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.31 -34590000,0.98,-0.0095,-0.014,0.18,-0.017,-0.085,0.74,0.073,-0.054,-0.023,-0.0014,-0.0056,-8.9e-05,0.045,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.012,0.012,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.4e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.33 -34690000,0.98,-0.0095,-0.013,0.18,-0.022,-0.084,1.7,0.071,-0.062,0.096,-0.0014,-0.0056,-8.9e-05,0.045,-0.033,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.013,0.012,0.0051,0.04,0.04,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.4e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.36 -34790000,0.98,-0.0094,-0.013,0.18,-0.027,-0.074,2.7,0.071,-0.056,0.28,-0.0014,-0.0056,-8.8e-05,0.047,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.012,0.012,0.005,0.037,0.037,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.3e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.38 -34890000,0.98,-0.0094,-0.013,0.18,-0.033,-0.073,3.7,0.068,-0.063,0.57,-0.0014,-0.0056,-8.8e-05,0.047,-0.034,-0.12,0.37,0.0037,0.026,0,0,0,0,0,0.12,0.00026,0.00026,0.06,0.014,0.013,0.005,0.04,0.04,0.03,2.3e-07,2.3e-07,2.4e-06,0.023,0.023,9.3e-05,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,1,1,0.41 +6990000,0.98,-0.0067,-0.012,0.18,0.0025,0.011,-0.037,0.0023,0.0048,-0.055,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.21,-0.00049,0.44,0.00044,-0.0011,0.00036,0,0,0.095,0.0012,0.0012,0.054,0.16,0.17,0.031,0.1,0.1,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0026,0.0015,0.0012,0.0014,0.0015,0.0018,0.0014,1,1,1.8 +7090000,0.98,-0.0065,-0.012,0.18,0.00012,0.018,-0.038,0.0014,0.0074,-0.056,-0.0016,-0.0056,-9.2e-05,0,0,-0.13,0.2,-0.00015,0.44,-0.00019,-0.00047,0.00017,0,0,0.095,0.0013,0.0013,0.048,0.18,0.19,0.03,0.13,0.13,0.066,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0024,0.0014,0.00067,0.0013,0.0014,0.0016,0.0013,1,1,1.8 +7190000,0.98,-0.0065,-0.012,0.18,-5.8e-05,0.019,-0.037,0.0016,0.0091,-0.058,-0.0016,-0.0056,-9.2e-05,-6.3e-05,3.4e-05,-0.13,0.2,-0.0001,0.43,-0.00018,-0.00052,-3.7e-06,0,0,0.095,0.0013,0.0013,0.046,0.21,0.21,0.029,0.16,0.16,0.065,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0023,0.0013,0.00044,0.0013,0.0014,0.0016,0.0013,1,1,1.8 +7290000,0.98,-0.0064,-0.012,0.18,-0.00067,0.024,-0.034,0.00055,0.012,-0.054,-0.0016,-0.0057,-9.2e-05,-0.0003,0.00019,-0.13,0.2,-7.3e-05,0.43,-0.00037,-0.00044,6.5e-05,0,0,0.095,0.0014,0.0013,0.044,0.24,0.24,0.028,0.19,0.19,0.064,6.5e-05,6.4e-05,2.2e-06,0.04,0.04,0.0022,0.0013,0.00033,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7390000,0.98,-0.0063,-0.012,0.18,-0.0015,0.00094,-0.032,0.00016,0.014,-0.052,-0.0017,-0.0057,-9.2e-05,-0.00036,0.00036,-0.13,0.2,-5.7e-05,0.43,-0.00048,-0.0004,8.8e-05,0,0,0.095,0.0014,0.0014,0.043,25,25,0.027,1e+02,1e+02,0.064,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.002,0.0013,0.00027,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7490000,0.98,-0.0063,-0.012,0.18,0.00097,0.0035,-0.026,0.00016,0.014,-0.046,-0.0017,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-4.5e-05,0.43,-0.00042,-0.00038,-7.9e-05,0,0,0.095,0.0015,0.0014,0.043,25,25,0.026,1e+02,1e+02,0.063,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0019,0.0013,0.00022,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7590000,0.98,-0.0064,-0.012,0.18,0.0021,0.006,-0.023,0.00032,0.014,-0.041,-0.0017,-0.0056,-9e-05,-0.00036,0.00036,-0.13,0.2,-3.8e-05,0.43,-0.00034,-0.00039,-9.5e-06,0,0,0.095,0.0015,0.0015,0.042,25,25,0.025,51,51,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0018,0.0013,0.00019,0.0013,0.0014,0.0016,0.0013,1,1,1.9 +7690000,0.98,-0.0064,-0.013,0.18,0.0021,0.0093,-0.022,0.00055,0.015,-0.036,-0.0017,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-3.4e-05,0.43,-0.00031,-0.0004,2.5e-06,0,0,0.095,0.0016,0.0015,0.042,25,25,0.025,52,52,0.062,6.4e-05,6.3e-05,2.2e-06,0.04,0.04,0.0017,0.0013,0.00017,0.0013,0.0014,0.0016,0.0013,1,1,2 +7790000,0.98,-0.0064,-0.013,0.18,0.0056,0.01,-0.025,0.00093,0.015,-0.041,-0.0016,-0.0055,-9e-05,-0.00036,0.00036,-0.13,0.2,-2.9e-05,0.43,-0.00021,-0.00039,-1.5e-06,0,0,0.095,0.0016,0.0016,0.042,24,24,0.024,35,35,0.061,6.3e-05,6.2e-05,2.2e-06,0.04,0.04,0.0016,0.0013,0.00015,0.0013,0.0014,0.0016,0.0013,1,1,2 +7890000,0.98,-0.0065,-0.013,0.18,0.0046,0.014,-0.025,0.0013,0.017,-0.045,-0.0016,-0.0055,-9e-05,-0.00036,0.00036,-0.13,0.2,-2.6e-05,0.43,-0.00019,-0.0004,4.4e-05,0,0,0.095,0.0016,0.0016,0.042,24,24,0.023,36,36,0.06,6.3e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.00013,0.0013,0.0014,0.0016,0.0013,1,1,2 +7990000,0.98,-0.0063,-0.013,0.18,0.0032,0.017,-0.022,0.00098,0.017,-0.042,-0.0016,-0.0056,-9.1e-05,-0.00036,0.00036,-0.13,0.2,-2.5e-05,0.43,-0.0002,-0.00042,7.4e-05,0,0,0.095,0.0017,0.0016,0.042,24,24,0.022,28,28,0.059,6.2e-05,6.1e-05,2.2e-06,0.04,0.04,0.0015,0.0013,0.00012,0.0013,0.0014,0.0016,0.0013,1,1,2 +8090000,0.98,-0.0063,-0.013,0.18,0.0043,0.019,-0.022,0.0013,0.019,-0.044,-0.0016,-0.0056,-9.4e-05,-0.00036,0.00036,-0.13,0.2,-2.2e-05,0.43,-0.00017,-0.00042,9.9e-05,0,0,0.095,0.0017,0.0017,0.042,24,24,0.022,30,30,0.059,6.2e-05,6e-05,2.2e-06,0.04,0.04,0.0014,0.0013,0.00011,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8190000,0.98,-0.0064,-0.012,0.18,0.0052,0.022,-0.018,0.0015,0.019,-0.038,-0.0016,-0.0056,-9.5e-05,-0.00036,0.00036,-0.13,0.2,-2e-05,0.44,-0.00014,-0.00041,0.00014,0,0,0.095,0.0018,0.0017,0.041,23,23,0.021,24,24,0.058,6.1e-05,5.9e-05,2.2e-06,0.04,0.04,0.0013,0.0013,0.0001,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8290000,0.98,-0.0062,-0.012,0.18,0.002,0.028,-0.017,0.0003,0.022,-0.038,-0.0016,-0.0058,-9.7e-05,-0.00036,0.00036,-0.13,0.2,-2e-05,0.43,-0.00014,-0.00044,6.7e-05,0,0,0.095,0.0018,0.0017,0.041,23,23,0.02,27,27,0.057,6.1e-05,5.8e-05,2.2e-06,0.04,0.04,0.0013,0.0013,9.6e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8390000,0.98,-0.0062,-0.012,0.18,-0.0023,0.028,-0.016,-0.00016,0.022,-0.036,-0.0016,-0.0058,-9.7e-05,-0.00036,0.00036,-0.13,0.2,-1.9e-05,0.43,-0.00014,-0.00044,2.1e-05,0,0,0.095,0.0019,0.0018,0.041,21,21,0.02,23,23,0.057,6e-05,5.7e-05,2.2e-06,0.04,0.04,0.0012,0.0013,9e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.1 +8490000,0.98,-0.0059,-0.012,0.18,-0.0061,0.035,-0.017,-0.0015,0.026,-0.041,-0.0017,-0.0059,-9.6e-05,-0.00036,0.00036,-0.13,0.2,-1.9e-05,0.43,-0.00014,-0.00048,-7.4e-06,0,0,0.095,0.0019,0.0018,0.041,21,21,0.019,25,25,0.056,5.9e-05,5.6e-05,2.2e-06,0.04,0.04,0.0011,0.0013,8.4e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8590000,0.98,-0.006,-0.012,0.18,-0.00034,0.034,-0.012,0.00033,0.026,-0.036,-0.0016,-0.0057,-9.6e-05,-0.00036,0.00036,-0.14,0.2,-1.7e-05,0.43,-0.00018,-0.00043,3.3e-06,0,0,0.095,0.0019,0.0018,0.041,19,19,0.018,22,22,0.055,5.8e-05,5.5e-05,2.2e-06,0.04,0.04,0.0011,0.0013,7.9e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8690000,0.98,-0.006,-0.012,0.18,-0.0022,0.037,-0.014,-0.00034,0.03,-0.038,-0.0016,-0.0058,-9.5e-05,-0.00036,0.00036,-0.14,0.2,-1.6e-05,0.43,-0.00022,-0.00045,-8.7e-05,0,0,0.095,0.002,0.0018,0.041,19,19,0.018,24,24,0.055,5.8e-05,5.3e-05,2.2e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8790000,0.98,-0.006,-0.012,0.18,-0.005,0.039,-0.014,-0.0023,0.033,-0.035,-0.0016,-0.0058,-9.8e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00019,-0.00045,-0.00013,0,0,0.095,0.002,0.0018,0.041,19,19,0.018,27,27,0.055,5.7e-05,5.2e-05,2.2e-06,0.04,0.04,0.00099,0.0013,7.1e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.2 +8890000,0.98,-0.006,-0.012,0.18,0.00054,0.041,-0.0093,0.00054,0.033,-0.029,-0.0016,-0.0057,-9.4e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.00026,-0.00043,-0.00011,0,0,0.095,0.002,0.0018,0.041,17,17,0.017,24,24,0.054,5.6e-05,5e-05,2.2e-06,0.04,0.04,0.00094,0.0013,6.7e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 +8990000,0.98,-0.0059,-0.013,0.18,0.01,0.047,-0.0085,0.0062,0.038,-0.032,-0.0017,-0.0056,-8.9e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.00037,-0.00039,-6.6e-05,0,0,0.095,0.0021,0.0018,0.041,17,17,0.017,27,27,0.054,5.5e-05,4.9e-05,2.2e-06,0.04,0.04,0.00091,0.0013,6.4e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 +9090000,0.98,-0.0055,-0.012,0.18,-0.00032,0.056,-0.0095,0.00069,0.041,-0.032,-0.0018,-0.0057,-8.8e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00028,-0.00049,-8.8e-05,0,0,0.095,0.0021,0.0018,0.041,15,15,0.016,24,24,0.053,5.3e-05,4.7e-05,2.2e-06,0.04,0.04,0.00087,0.0013,6.1e-05,0.0013,0.0014,0.0016,0.0013,1,1,2.3 +9190000,0.98,-0.0053,-0.013,0.18,0.0029,0.064,-0.0089,0.00089,0.049,-0.032,-0.0018,-0.0057,-8.6e-05,-0.00036,0.00036,-0.14,0.2,-1.5e-05,0.43,-0.00031,-0.00053,-0.00011,0,0,0.095,0.0021,0.0018,0.041,15,15,0.016,27,27,0.052,5.2e-05,4.5e-05,2.2e-06,0.04,0.04,0.00083,0.0013,5.9e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.3 +9290000,0.98,-0.0053,-0.013,0.18,0.013,0.062,-0.0074,0.0055,0.046,-0.03,-0.0018,-0.0056,-8.4e-05,-0.00036,0.00036,-0.14,0.2,-1.4e-05,0.43,-0.0004,-0.00049,-8.5e-05,0,0,0.095,0.0021,0.0018,0.041,13,13,0.015,24,24,0.052,5.1e-05,4.4e-05,2.2e-06,0.04,0.04,0.00079,0.0013,5.6e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.4 +9390000,0.98,-0.0054,-0.013,0.18,0.014,0.06,-0.0062,0.0071,0.049,-0.03,-0.0017,-0.0056,-8.7e-05,-0.00036,0.00036,-0.14,0.2,-1.2e-05,0.43,-0.00035,-0.00043,-3.8e-05,0,0,0.095,0.0021,0.0018,0.041,13,13,0.015,26,26,0.052,5e-05,4.2e-05,2.2e-06,0.04,0.04,0.00077,0.0013,5.4e-05,0.0013,0.0013,0.0016,0.0013,1,1,2.4 +9490000,0.98,-0.0053,-0.013,0.18,0.0087,0.061,-0.0045,0.0044,0.048,-0.027,-0.0018,-0.0056,-8.7e-05,-0.00036,0.00036,-0.14,0.2,-1.2e-05,0.43,-0.00033,-0.00048,-7.6e-05,0,0,0.095,0.0021,0.0018,0.041,12,12,0.015,23,23,0.051,4.8e-05,4e-05,2.2e-06,0.04,0.04,0.00074,0.0013,5.2e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.4 +9590000,0.98,-0.0057,-0.013,0.18,0.0078,0.052,-0.0045,0.0046,0.048,-0.029,-0.0016,-0.0057,-9.3e-05,-0.00036,0.00036,-0.14,0.2,-1e-05,0.43,-0.00031,-0.00041,-0.00012,0,0,0.095,0.0022,0.0018,0.041,12,12,0.014,26,26,0.05,4.7e-05,3.9e-05,2.2e-06,0.04,0.04,0.00071,0.0013,5e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.4 +9690000,0.98,-0.0059,-0.013,0.18,0.0096,0.047,-0.0016,0.0057,0.043,-0.027,-0.0016,-0.0056,-9.5e-05,-0.00036,0.00036,-0.14,0.2,-9.2e-06,0.43,-0.00031,-0.00037,-9.9e-05,0,0,0.095,0.0022,0.0018,0.041,10,10,0.014,23,23,0.05,4.6e-05,3.7e-05,2.2e-06,0.04,0.04,0.00068,0.0013,4.8e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +9790000,0.98,-0.0061,-0.012,0.18,0.001,0.041,-0.003,0.00039,0.042,-0.028,-0.0015,-0.0058,-0.0001,-0.00036,0.00036,-0.14,0.2,-7.7e-06,0.43,-0.00018,-0.00036,-0.00015,0,0,0.095,0.0022,0.0017,0.041,10,10,0.014,25,25,0.05,4.4e-05,3.5e-05,2.2e-06,0.04,0.04,0.00066,0.0013,4.7e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +9890000,0.98,-0.0061,-0.012,0.18,0.0086,0.04,-0.0016,0.0039,0.04,-0.029,-0.0015,-0.0057,-0.0001,-0.00036,0.00036,-0.14,0.2,-7.6e-06,0.43,-0.00023,-0.00034,-9.4e-05,0,0,0.095,0.0022,0.0017,0.041,8.6,8.7,0.013,22,22,0.049,4.3e-05,3.4e-05,2.2e-06,0.04,0.04,0.00063,0.0013,4.5e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +9990000,0.98,-0.0063,-0.012,0.18,0.0025,0.034,-0.00096,-0.0002,0.039,-0.031,-0.0014,-0.0058,-0.00011,-0.00036,0.00036,-0.14,0.2,-6.4e-06,0.43,-0.00014,-0.00033,-0.00013,0,0,0.095,0.0022,0.0017,0.041,8.6,8.7,0.013,24,24,0.049,4.2e-05,3.2e-05,2.2e-06,0.04,0.04,0.00061,0.0013,4.4e-05,0.0013,0.0013,0.0015,0.0013,1,1,2.5 +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 From 6c24413888a27bc46c570f09210a13caa59f96aa Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 15 Jul 2024 14:19:33 -0400 Subject: [PATCH 39/87] ekf2: filter flow vel (used for flow velocity reset) - individual flow samples can be quite erratic --- msg/VehicleOpticalFlowVel.msg | 3 +++ .../optical_flow/optical_flow_control.cpp | 15 +++++++++++++-- src/modules/ekf2/EKF/ekf.h | 11 ++++++++--- src/modules/ekf2/EKF2.cpp | 3 +++ src/modules/ekf2/test/test_EKF_flow.cpp | 6 ++---- 5 files changed, 29 insertions(+), 9 deletions(-) diff --git a/msg/VehicleOpticalFlowVel.msg b/msg/VehicleOpticalFlowVel.msg index 947131da4dd1..9d9b0ad87625 100644 --- a/msg/VehicleOpticalFlowVel.msg +++ b/msg/VehicleOpticalFlowVel.msg @@ -4,6 +4,9 @@ uint64 timestamp_sample # the timestamp of the raw data (microsec float32[2] vel_body # velocity obtained from gyro-compensated and distance-scaled optical flow raw measurements in body frame(m/s) float32[2] vel_ne # same as vel_body but in local frame (m/s) +float32[2] vel_body_filtered # filtered velocity obtained from gyro-compensated and distance-scaled optical flow raw measurements in body frame(m/s) +float32[2] vel_ne_filtered # filtered same as vel_body_filtered but in local frame (m/s) + float32[2] flow_rate_uncompensated # integrated optical flow measurement (rad/s) float32[2] flow_rate_compensated # integrated optical flow measurement compensated for angular motion (rad/s) diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp index 95db812faeb5..becece91c188 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp @@ -122,8 +122,16 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) const float range = predictFlowRange(); _flow_vel_body(0) = -flow_compensated(1) * range; _flow_vel_body(1) = flow_compensated(0) * range; - _flow_vel_ne = Vector2f(_R_to_earth * Vector3f(_flow_vel_body(0), _flow_vel_body(1), 0.f)); + if (_flow_counter == 0) { + _flow_vel_body_lpf.reset(_flow_vel_body); + _flow_counter = 1; + + } else { + + _flow_vel_body_lpf.update(_flow_vel_body); + _flow_counter++; + } // Check if we are in-air and require optical flow to control position drift bool is_flow_required = _control_status.flags.in_air @@ -144,6 +152,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) && is_quality_good && is_magnitude_good && is_tilt_good + && (_flow_counter > 10) && (isTerrainEstimateValid() || isHorizontalAidingActive()) && isTimedOut(_aid_src_optical_flow.time_last_fuse, (uint64_t)2e6); // Prevent rapid switching @@ -219,7 +228,7 @@ void Ekf::resetFlowFusion() _information_events.flags.reset_vel_to_flow = true; const float flow_vel_var = sq(predictFlowRange()) * calcOptFlowMeasVar(_flow_sample_delayed); - resetHorizontalVelocityTo(_flow_vel_ne, flow_vel_var); + resetHorizontalVelocityTo(getFilteredFlowVelNE(), flow_vel_var); // reset position, estimate is relative to initial position in this mode, so we start with zero error if (!_control_status.flags.in_air) { @@ -273,6 +282,8 @@ void Ekf::stopFlowFusion() _innov_check_fail_status.flags.reject_optflow_X = false; _innov_check_fail_status.flags.reject_optflow_Y = false; + + _flow_counter = 0; } } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 7be3fdf92afb..4449b2d23318 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -122,7 +122,10 @@ class Ekf final : public EstimatorInterface const auto &aid_src_optical_flow() const { return _aid_src_optical_flow; } const Vector2f &getFlowVelBody() const { return _flow_vel_body; } - const Vector2f &getFlowVelNE() const { return _flow_vel_ne; } + Vector2f getFlowVelNE() const { return Vector2f(_R_to_earth * Vector3f(getFlowVelBody()(0), getFlowVelBody()(1), 0.f)); } + + const Vector2f &getFilteredFlowVelBody() const { return _flow_vel_body_lpf.getState(); } + Vector2f getFilteredFlowVelNE() const { return Vector2f(_R_to_earth * Vector3f(getFilteredFlowVelBody()(0), getFilteredFlowVelBody()(1), 0.f)); } const Vector2f &getFlowCompensated() const { return _flow_rate_compensated; } const Vector2f &getFlowUncompensated() const { return _flow_sample_delayed.flow_rate; } @@ -634,10 +637,12 @@ class Ekf final : public EstimatorInterface // optical flow processing Vector3f _flow_gyro_bias{}; ///< bias errors in optical flow sensor rate gyro outputs (rad/sec) - Vector2f _flow_vel_body{}; ///< velocity from corrected flow measurement (body frame)(m/s) - Vector2f _flow_vel_ne{}; ///< velocity from corrected flow measurement (local frame) (m/s) Vector3f _ref_body_rate{}; + Vector2f _flow_vel_body{}; ///< velocity from corrected flow measurement (body frame)(m/s) + AlphaFilter _flow_vel_body_lpf{0.1f}; ///< filtered velocity from corrected flow measurement (body frame)(m/s) + uint32_t _flow_counter{0}; ///< number of flow samples read for initialization + Vector2f _flow_rate_compensated{}; ///< measured angular rate of the image about the X and Y body axes after removal of body rotation (rad/s), RH rotation is positive #endif // CONFIG_EKF2_OPTICAL_FLOW diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index bb986208de84..c339548b8cef 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -2027,6 +2027,9 @@ void EKF2::PublishOpticalFlowVel(const hrt_abstime ×tamp) _ekf.getFlowVelBody().copyTo(flow_vel.vel_body); _ekf.getFlowVelNE().copyTo(flow_vel.vel_ne); + _ekf.getFilteredFlowVelBody().copyTo(flow_vel.vel_body_filtered); + _ekf.getFilteredFlowVelNE().copyTo(flow_vel.vel_ne_filtered); + _ekf.getFlowUncompensated().copyTo(flow_vel.flow_rate_uncompensated); _ekf.getFlowCompensated().copyTo(flow_vel.flow_rate_compensated); diff --git a/src/modules/ekf2/test/test_EKF_flow.cpp b/src/modules/ekf2/test/test_EKF_flow.cpp index 787560ce1bf6..650d168a98b7 100644 --- a/src/modules/ekf2/test/test_EKF_flow.cpp +++ b/src/modules/ekf2/test/test_EKF_flow.cpp @@ -203,10 +203,8 @@ TEST_F(EkfFlowTest, inAirConvergence) _sensor_simulator.setTrajectoryTargetVelocity(simulated_velocity); _ekf_wrapper.enableFlowFusion(); _sensor_simulator.startFlow(); - // Let it reset but not fuse more measurements. We actually need to send 2 - // samples to get a reset because the first one cannot be used as the gyro - // compensation needs to be accumulated between two samples. - _sensor_simulator.runTrajectorySeconds(0.14); + + _sensor_simulator.runTrajectorySeconds(1.0); // THEN: estimated velocity should match simulated velocity Vector3f estimated_velocity = _ekf->getVelocity(); From f3d58cdf10a31998835fab6076b67cd52644ae5c Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 26 Aug 2024 14:11:30 -0400 Subject: [PATCH 40/87] ekf2: resetFlowFusion() pass flowSample by const ref --- .../EKF/aid_sources/optical_flow/optical_flow_control.cpp | 8 ++++---- src/modules/ekf2/EKF/ekf.h | 2 +- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp index becece91c188..dbbc1a72961b 100644 --- a/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/optical_flow/optical_flow_control.cpp @@ -169,7 +169,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) // handle the case when we have optical flow, are reliant on it, but have not been using it for an extended period if (isTimedOut(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max)) { if (is_flow_required && is_quality_good && is_magnitude_good) { - resetFlowFusion(); + resetFlowFusion(flow_sample); if (_control_status.flags.opt_flow_terrain && !isTerrainEstimateValid()) { resetTerrainToFlow(); @@ -203,7 +203,7 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) } else { if (isTerrainEstimateValid() || (_height_sensor_ref == HeightSensor::RANGE)) { ECL_INFO("starting optical flow, resetting"); - resetFlowFusion(); + resetFlowFusion(flow_sample); _control_status.flags.opt_flow = true; } else if (_control_status.flags.opt_flow_terrain) { @@ -222,12 +222,12 @@ void Ekf::controlOpticalFlowFusion(const imuSample &imu_delayed) } } -void Ekf::resetFlowFusion() +void Ekf::resetFlowFusion(const flowSample &flow_sample) { ECL_INFO("reset velocity to flow"); _information_events.flags.reset_vel_to_flow = true; - const float flow_vel_var = sq(predictFlowRange()) * calcOptFlowMeasVar(_flow_sample_delayed); + const float flow_vel_var = sq(predictFlowRange()) * calcOptFlowMeasVar(flow_sample); resetHorizontalVelocityTo(getFilteredFlowVelNE(), flow_vel_var); // reset position, estimate is relative to initial position in this mode, so we start with zero error diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 4449b2d23318..e9715f3e372c 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -878,7 +878,7 @@ class Ekf final : public EstimatorInterface #if defined(CONFIG_EKF2_OPTICAL_FLOW) // control fusion of optical flow observations void controlOpticalFlowFusion(const imuSample &imu_delayed); - void resetFlowFusion(); + void resetFlowFusion(const flowSample &flow_sample); void stopFlowFusion(); void updateOnGroundMotionForOpticalFlowChecks(); From 9169a7c5fc34bae38d1a86d6eae8fe38162ef83f Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 20 Aug 2024 14:34:25 +0200 Subject: [PATCH 41/87] ekf2: split horizontal and vertical origin reset Allow partial resets (only lat/lon or only altitude) --- src/modules/ekf2/EKF/ekf.h | 5 ++ src/modules/ekf2/EKF/ekf_helper.cpp | 114 ++++++++++++++++++---------- 2 files changed, 78 insertions(+), 41 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index e9715f3e372c..44f635573c04 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -261,6 +261,8 @@ class Ekf final : public EstimatorInterface // get the ekf WGS-84 origin position and height and the system time it was last set // return true if the origin is valid bool getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &longitude, float &origin_alt) const; + bool checkLatLonValidity(double latitude, double longitude, float eph = 0.f); + bool checkAltitudeValidity(float altitude, float epv = 0.f); bool setEkfGlobalOrigin(double latitude, double longitude, float altitude, float eph = 0.f, float epv = 0.f); // get the 1-sigma horizontal and vertical position uncertainty of the ekf WGS-84 position @@ -765,6 +767,9 @@ class Ekf final : public EstimatorInterface P.slice(S.idx, S.idx) = cov; } + bool setLatLonOrigin(double latitude, double longitude, float eph = NAN); + bool setAltOrigin(float altitude, float epv = NAN); + // update quaternion states and covariances using an innovation, observation variance and Jacobian vector bool fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW); void computeYawInnovVarAndH(float variance, float &innovation_variance, VectorState &H_YAW) const; diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 01821fd97bb8..4ba346e1f9a0 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -72,63 +72,95 @@ bool Ekf::getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &lo return _NED_origin_initialised; } +bool Ekf::checkLatLonValidity(const double latitude, const double longitude, const float eph) +{ + const bool lat_valid = (PX4_ISFINITE(latitude) && (abs(latitude) <= 90)); + const bool lon_valid = (PX4_ISFINITE(longitude) && (abs(longitude) <= 180)); + const bool eph_valid = (PX4_ISFINITE(eph) && (eph >= 0.f)); + + return (lat_valid && lon_valid && eph_valid); +} + +bool Ekf::checkAltitudeValidity(const float altitude, const float epv) +{ + // sanity check valid altitude anywhere between the Mariana Trench and edge of Space + const bool alt_valid = (PX4_ISFINITE(altitude) && ((altitude > -12'000.f) && (altitude < 100'000.f))); + const bool epv_valid = (PX4_ISFINITE(epv) && (epv >= 0.f)); + + return alt_valid && epv_valid; +} + bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude, const float eph, const float epv) { - // sanity check valid latitude/longitude and altitude anywhere between the Mariana Trench and edge of Space - if (PX4_ISFINITE(latitude) && (abs(latitude) <= 90) - && PX4_ISFINITE(longitude) && (abs(longitude) <= 180) - && PX4_ISFINITE(altitude) && (altitude > -12'000.f) && (altitude < 100'000.f) - ) { - bool current_pos_available = false; - double current_lat = static_cast(NAN); - double current_lon = static_cast(NAN); - - // if we are already doing aiding, correct for the change in position since the EKF started navigating - if (_pos_ref.isInitialized() && isHorizontalAidingActive()) { - _pos_ref.reproject(_state.pos(0), _state.pos(1), current_lat, current_lon); - current_pos_available = true; - } + if (!setLatLonOrigin(latitude, longitude, eph)) { + return false; + } + + // altitude is optional + setAltOrigin(altitude, epv); + + return true; +} - const float gps_alt_ref_prev = _gps_alt_ref; +bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const float eph) +{ + if (!checkLatLonValidity(latitude, longitude, eph)) { + return false; + } - // reinitialize map projection to latitude, longitude, altitude, and reset position - _pos_ref.initReference(latitude, longitude, _time_delayed_us); - _gps_alt_ref = altitude; + bool current_pos_available = false; + double current_lat = static_cast(NAN); + double current_lon = static_cast(NAN); - _gpos_origin_eph = eph; - _gpos_origin_epv = epv; + // if we are already doing aiding, correct for the change in position since the EKF started navigating + if (_pos_ref.isInitialized() && isHorizontalAidingActive()) { + _pos_ref.reproject(_state.pos(0), _state.pos(1), current_lat, current_lon); + current_pos_available = true; + } - _NED_origin_initialised = true; + // reinitialize map projection to latitude, longitude, altitude, and reset position + _pos_ref.initReference(latitude, longitude, _time_delayed_us); + _gpos_origin_eph = eph; - _earth_rate_NED = calcEarthRateNED(math::radians(static_cast(latitude))); + _NED_origin_initialised = true; - if (current_pos_available) { - // reset horizontal position if we already have a global origin - Vector2f position = _pos_ref.project(current_lat, current_lon); - resetHorizontalPositionTo(position); - } + if (current_pos_available) { + // reset horizontal position if we already have a global origin + Vector2f position = _pos_ref.project(current_lat, current_lon); + resetHorizontalPositionTo(position); + } + + return true; +} - if (PX4_ISFINITE(gps_alt_ref_prev) && isVerticalPositionAidingActive()) { - // determine current z - const float z_prev = _state.pos(2); - const float current_alt = -z_prev + gps_alt_ref_prev; +bool Ekf::setAltOrigin(const float altitude, const float epv) +{ + if (!checkAltitudeValidity(altitude, epv)) { + return false; + } + + const float gps_alt_ref_prev = _gps_alt_ref; + _gps_alt_ref = altitude; + _gpos_origin_epv = epv; + + if (PX4_ISFINITE(gps_alt_ref_prev) && isVerticalPositionAidingActive()) { + // determine current z + const float z_prev = _state.pos(2); + const float current_alt = -z_prev + gps_alt_ref_prev; #if defined(CONFIG_EKF2_GNSS) - const float gps_hgt_bias = _gps_hgt_b_est.getBias(); + const float gps_hgt_bias = _gps_hgt_b_est.getBias(); #endif // CONFIG_EKF2_GNSS - resetVerticalPositionTo(_gps_alt_ref - current_alt); - ECL_DEBUG("EKF global origin updated, resetting vertical position %.1fm -> %.1fm", (double)z_prev, - (double)_state.pos(2)); + resetVerticalPositionTo(_gps_alt_ref - current_alt); + ECL_DEBUG("EKF global origin updated, resetting vertical position %.1fm -> %.1fm", (double)z_prev, + (double)_state.pos(2)); #if defined(CONFIG_EKF2_GNSS) - // adjust existing GPS height bias - _gps_hgt_b_est.setBias(gps_hgt_bias); + // adjust existing GPS height bias + _gps_hgt_b_est.setBias(gps_hgt_bias); #endif // CONFIG_EKF2_GNSS - } - - return true; } - return false; + return true; } void Ekf::get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv) const From af752536b92e3dc88a30a3c90e0d17d05d209b66 Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 21 Aug 2024 16:21:17 +0200 Subject: [PATCH 42/87] ekf2: extract setting origin from current lat/lon/alt This is not only needed when GNSS is available but also for other global sources of position (e.g.: aux global pos and manual pos updates) --- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 23 +----- src/modules/ekf2/EKF/ekf.h | 11 ++- src/modules/ekf2/EKF/ekf_helper.cpp | 79 ++++++++++++++++--- 3 files changed, 77 insertions(+), 36 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp index 4467ff9f7e28..e3c40dda7774 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -59,34 +59,15 @@ void Ekf::collect_gps(const gnssSample &gps) { if (_filter_initialised && !_NED_origin_initialised && _gps_checks_passed) { // If we have good GPS data set the origin's WGS-84 position to the last gps fix - const double lat = gps.lat; - const double lon = gps.lon; - if (!_pos_ref.isInitialized()) { - _pos_ref.initReference(lat, lon, gps.time_us); - - // if we are already doing aiding, correct for the change in position since the EKF started navigating - if (isHorizontalAidingActive()) { - double est_lat; - double est_lon; - _pos_ref.reproject(-_state.pos(0), -_state.pos(1), est_lat, est_lon); - _pos_ref.initReference(est_lat, est_lon, gps.time_us); - } + setLatLonOriginFromCurrentPos(gps.lat, gps.lon, gps.hacc); } // Take the current GPS height and subtract the filter height above origin to estimate the GPS height of the origin if (!PX4_ISFINITE(_gps_alt_ref)) { - _gps_alt_ref = gps.alt + _state.pos(2); + setAltOriginFromCurrentPos(gps.alt, gps.vacc); } - _NED_origin_initialised = true; - - // save the horizontal and vertical position uncertainty of the origin - _gpos_origin_eph = gps.hacc; - _gpos_origin_epv = gps.vacc; - - _earth_rate_NED = calcEarthRateNED(math::radians(static_cast(gps.lat))); - _information_events.flags.gps_checks_passed = true; ECL_INFO("GPS origin set to lat=%.6f, lon=%.6f", diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 44f635573c04..5f2ba8c95fb4 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -261,9 +261,11 @@ class Ekf final : public EstimatorInterface // get the ekf WGS-84 origin position and height and the system time it was last set // return true if the origin is valid bool getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &longitude, float &origin_alt) const; - bool checkLatLonValidity(double latitude, double longitude, float eph = 0.f); - bool checkAltitudeValidity(float altitude, float epv = 0.f); - bool setEkfGlobalOrigin(double latitude, double longitude, float altitude, float eph = 0.f, float epv = 0.f); + bool checkLatLonValidity(double latitude, double longitude); + bool checkAltitudeValidity(float altitude); + bool setEkfGlobalOrigin(double latitude, double longitude, float altitude, float eph = NAN, float epv = NAN); + bool setEkfGlobalOriginFromCurrentPos(double latitude, double longitude, float altitude, float eph = NAN, + float epv = NAN); // get the 1-sigma horizontal and vertical position uncertainty of the ekf WGS-84 position void get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv) const; @@ -770,6 +772,9 @@ class Ekf final : public EstimatorInterface bool setLatLonOrigin(double latitude, double longitude, float eph = NAN); bool setAltOrigin(float altitude, float epv = NAN); + bool setLatLonOriginFromCurrentPos(double latitude, double longitude, float eph = NAN); + bool setAltOriginFromCurrentPos(float altitude, float epv = NAN); + // update quaternion states and covariances using an innovation, observation variance and Jacobian vector bool fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H_YAW); void computeYawInnovVarAndH(float variance, float &innovation_variance, VectorState &H_YAW) const; diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 4ba346e1f9a0..6e3bdf3bab45 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -72,22 +72,18 @@ bool Ekf::getEkfGlobalOrigin(uint64_t &origin_time, double &latitude, double &lo return _NED_origin_initialised; } -bool Ekf::checkLatLonValidity(const double latitude, const double longitude, const float eph) +bool Ekf::checkLatLonValidity(const double latitude, const double longitude) { const bool lat_valid = (PX4_ISFINITE(latitude) && (abs(latitude) <= 90)); const bool lon_valid = (PX4_ISFINITE(longitude) && (abs(longitude) <= 180)); - const bool eph_valid = (PX4_ISFINITE(eph) && (eph >= 0.f)); - return (lat_valid && lon_valid && eph_valid); + return (lat_valid && lon_valid); } -bool Ekf::checkAltitudeValidity(const float altitude, const float epv) +bool Ekf::checkAltitudeValidity(const float altitude) { // sanity check valid altitude anywhere between the Mariana Trench and edge of Space - const bool alt_valid = (PX4_ISFINITE(altitude) && ((altitude > -12'000.f) && (altitude < 100'000.f))); - const bool epv_valid = (PX4_ISFINITE(epv) && (epv >= 0.f)); - - return alt_valid && epv_valid; + return (PX4_ISFINITE(altitude) && ((altitude > -12'000.f) && (altitude < 100'000.f))); } bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, const float altitude, const float eph, @@ -105,7 +101,7 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const float eph) { - if (!checkLatLonValidity(latitude, longitude, eph)) { + if (!checkLatLonValidity(latitude, longitude)) { return false; } @@ -121,7 +117,10 @@ bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const f // reinitialize map projection to latitude, longitude, altitude, and reset position _pos_ref.initReference(latitude, longitude, _time_delayed_us); - _gpos_origin_eph = eph; + + if (PX4_ISFINITE(eph) && (eph >= 0.f)) { + _gpos_origin_eph = eph; + } _NED_origin_initialised = true; @@ -136,13 +135,16 @@ bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const f bool Ekf::setAltOrigin(const float altitude, const float epv) { - if (!checkAltitudeValidity(altitude, epv)) { + if (!checkAltitudeValidity(altitude)) { return false; } const float gps_alt_ref_prev = _gps_alt_ref; _gps_alt_ref = altitude; - _gpos_origin_epv = epv; + + if (PX4_ISFINITE(epv) && (epv >= 0.f)) { + _gpos_origin_epv = epv; + } if (PX4_ISFINITE(gps_alt_ref_prev) && isVerticalPositionAidingActive()) { // determine current z @@ -163,6 +165,59 @@ bool Ekf::setAltOrigin(const float altitude, const float epv) return true; } +bool Ekf::setEkfGlobalOriginFromCurrentPos(const double latitude, const double longitude, const float altitude, + const float eph, const float epv) +{ + if (!setLatLonOriginFromCurrentPos(latitude, longitude, eph)) { + return false; + } + + // altitude is optional + setAltOriginFromCurrentPos(altitude, epv); + + return true; +} + +bool Ekf::setLatLonOriginFromCurrentPos(const double latitude, const double longitude, const float eph) +{ + if (!checkLatLonValidity(latitude, longitude)) { + return false; + } + + _pos_ref.initReference(latitude, longitude, _time_delayed_us); + + // if we are already doing aiding, correct for the change in position since the EKF started navigating + if (isHorizontalAidingActive()) { + double est_lat; + double est_lon; + _pos_ref.reproject(-_state.pos(0), -_state.pos(1), est_lat, est_lon); + _pos_ref.initReference(est_lat, est_lon, _time_delayed_us); + } + + if (PX4_ISFINITE(eph) && (eph >= 0.f)) { + _gpos_origin_eph = eph; + } + + _NED_origin_initialised = true; + + return true; +} + +bool Ekf::setAltOriginFromCurrentPos(const float altitude, const float epv) +{ + if (!checkAltitudeValidity(altitude)) { + return false; + } + + _gps_alt_ref = altitude + _state.pos(2); + + if (PX4_ISFINITE(epv) && (epv >= 0.f)) { + _gpos_origin_epv = epv; + } + + return true; +} + void Ekf::get_ekf_gpos_accuracy(float *ekf_eph, float *ekf_epv) const { float eph = INFINITY; From 130fefb1e7f3fc3d9948cd49adf7ac19ca28fc9d Mon Sep 17 00:00:00 2001 From: bresch Date: Wed, 21 Aug 2024 16:32:29 +0200 Subject: [PATCH 43/87] ekf2: initialize origin from corrent position when possible --- .../aid_sources/aux_global_position/aux_global_position.cpp | 3 ++- src/modules/ekf2/EKF/ekf.cpp | 3 +-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp index 6efd4fabe66b..dc8f318c9778 100644 --- a/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp +++ b/src/modules/ekf2/EKF/aid_sources/aux_global_position/aux_global_position.cpp @@ -113,7 +113,8 @@ void AuxGlobalPosition::update(Ekf &ekf, const estimator::imuSample &imu_delayed } else { // Try to initialize using measurement - if (ekf.setEkfGlobalOrigin(sample.latitude, sample.longitude, sample.altitude_amsl, sample.eph, sample.epv)) { + if (ekf.setEkfGlobalOriginFromCurrentPos(sample.latitude, sample.longitude, sample.altitude_amsl, sample.eph, + sample.epv)) { ekf.enableControlStatusAuxGpos(); _reset_counters.lat_lon = sample.lat_lon_reset_counter; _state = State::active; diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 9f6a0ab40b66..a81cc39d6294 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -280,8 +280,7 @@ bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, fl uint64_t timestamp_observation) { if (!_pos_ref.isInitialized()) { - ECL_WARN("unable to reset global position, position reference not initialized"); - return false; + return setLatLonOriginFromCurrentPos(lat_deg, lon_deg, accuracy); } Vector2f pos_corrected = _pos_ref.project(lat_deg, lon_deg); From cd2170deea5d7b2bb387ddc3ba7a7c3abd58b133 Mon Sep 17 00:00:00 2001 From: bresch Date: Mon, 26 Aug 2024 11:53:40 +0200 Subject: [PATCH 44/87] ekf2-origin: backcompute based on lpos validity --- src/modules/ekf2/EKF/ekf_helper.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index 6e3bdf3bab45..f33cbcd5bc43 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -110,7 +110,7 @@ bool Ekf::setLatLonOrigin(const double latitude, const double longitude, const f double current_lon = static_cast(NAN); // if we are already doing aiding, correct for the change in position since the EKF started navigating - if (_pos_ref.isInitialized() && isHorizontalAidingActive()) { + if (_pos_ref.isInitialized() && local_position_is_valid()) { _pos_ref.reproject(_state.pos(0), _state.pos(1), current_lat, current_lon); current_pos_available = true; } @@ -146,7 +146,7 @@ bool Ekf::setAltOrigin(const float altitude, const float epv) _gpos_origin_epv = epv; } - if (PX4_ISFINITE(gps_alt_ref_prev) && isVerticalPositionAidingActive()) { + if (PX4_ISFINITE(gps_alt_ref_prev) && isLocalVerticalPositionValid()) { // determine current z const float z_prev = _state.pos(2); const float current_alt = -z_prev + gps_alt_ref_prev; @@ -187,7 +187,7 @@ bool Ekf::setLatLonOriginFromCurrentPos(const double latitude, const double long _pos_ref.initReference(latitude, longitude, _time_delayed_us); // if we are already doing aiding, correct for the change in position since the EKF started navigating - if (isHorizontalAidingActive()) { + if (local_position_is_valid()) { double est_lat; double est_lon; _pos_ref.reproject(-_state.pos(0), -_state.pos(1), est_lat, est_lon); From bab256bfe6ae496f1438c685693e0cc90d091ade Mon Sep 17 00:00:00 2001 From: bresch Date: Fri, 23 Aug 2024 15:33:21 +0200 Subject: [PATCH 45/87] ekf2: handle external altitude resets --- src/modules/ekf2/EKF/ekf.cpp | 97 ++++++++++++++------- src/modules/ekf2/EKF/ekf.h | 2 +- src/modules/ekf2/EKF2.cpp | 5 +- src/modules/ekf2/test/CMakeLists.txt | 2 +- src/modules/ekf2/test/test_EKF_airspeed.cpp | 79 ++++++++++++++++- 5 files changed, 147 insertions(+), 38 deletions(-) diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index a81cc39d6294..24734dcfb370 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -276,67 +276,100 @@ void Ekf::predictState(const imuSample &imu_delayed) _height_rate_lpf = _height_rate_lpf * (1.0f - alpha_height_rate_lpf) + _state.vel(2) * alpha_height_rate_lpf; } -bool Ekf::resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, - uint64_t timestamp_observation) +bool Ekf::resetGlobalPosToExternalObservation(const double latitude, const double longitude, const float altitude, + const float eph, + const float epv, uint64_t timestamp_observation) { + if (!checkLatLonValidity(latitude, longitude)) { + return false; + } + if (!_pos_ref.isInitialized()) { - return setLatLonOriginFromCurrentPos(lat_deg, lon_deg, accuracy); + if (!setLatLonOriginFromCurrentPos(latitude, longitude, eph)) { + return false; + } + + if (!PX4_ISFINITE(_gps_alt_ref)) { + setAltOriginFromCurrentPos(altitude, epv); + } + + return true; } - Vector2f pos_corrected = _pos_ref.project(lat_deg, lon_deg); + Vector3f pos_correction; // apply a first order correction using velocity at the delayed time horizon and the delta time - if ((timestamp_observation > 0) && (isHorizontalAidingActive() || !_horizontal_deadreckon_time_exceeded)) { + if ((timestamp_observation > 0) && local_position_is_valid()) { timestamp_observation = math::min(_time_latest_us, timestamp_observation); - float diff_us = 0.f; + float dt_us; if (_time_delayed_us >= timestamp_observation) { - diff_us = static_cast(_time_delayed_us - timestamp_observation); + dt_us = static_cast(_time_delayed_us - timestamp_observation); } else { - diff_us = -static_cast(timestamp_observation - _time_delayed_us); + dt_us = -static_cast(timestamp_observation - _time_delayed_us); } - const float dt_s = diff_us * 1e-6f; - pos_corrected += _state.vel.xy() * dt_s; + const float dt_s = dt_us * 1e-6f; + pos_correction = _state.vel * dt_s; } - const float obs_var = math::max(sq(accuracy), sq(0.01f)); + { + const Vector2f hpos = _pos_ref.project(latitude, longitude) + pos_correction.xy(); - const Vector2f innov = Vector2f(_state.pos.xy()) - pos_corrected; - const Vector2f innov_var = Vector2f(getStateVariance()) + obs_var; + const float obs_var = math::max(sq(eph), sq(0.01f)); - const float sq_gate = sq(5.f); // magic hardcoded gate - const Vector2f test_ratio{sq(innov(0)) / (sq_gate * innov_var(0)), - sq(innov(1)) / (sq_gate * innov_var(1))}; + const Vector2f innov = Vector2f(_state.pos.xy()) - hpos; + const Vector2f innov_var = Vector2f(getStateVariance()) + obs_var; - const bool innov_rejected = (test_ratio.max() > 1.f); + const float sq_gate = sq(5.f); // magic hardcoded gate + const float test_ratio = sq(innov(0)) / (sq_gate * innov_var(0)) + sq(innov(1)) / (sq_gate * innov_var(1)); - if (!_control_status.flags.in_air || (accuracy > 0.f && accuracy < 1.f) || innov_rejected) { - // when on ground or accuracy chosen to be very low, we hard reset position - // this allows the user to still send hard resets at any time - ECL_INFO("reset position to external observation"); - _information_events.flags.reset_pos_to_ext_obs = true; + const bool innov_rejected = (test_ratio > 1.f); - resetHorizontalPositionTo(pos_corrected, obs_var); - _last_known_pos.xy() = _state.pos.xy(); - return true; + if (!_control_status.flags.in_air || (eph > 0.f && eph < 1.f) || innov_rejected) { + // when on ground or accuracy chosen to be very low, we hard reset position + // this allows the user to still send hard resets at any time + ECL_INFO("reset position to external observation"); + _information_events.flags.reset_pos_to_ext_obs = true; - } else { - if (fuseDirectStateMeasurement(innov(0), innov_var(0), obs_var, State::pos.idx + 0) - && fuseDirectStateMeasurement(innov(1), innov_var(1), obs_var, State::pos.idx + 1) - ) { - ECL_INFO("fused external observation as position measurement"); + resetHorizontalPositionTo(hpos, obs_var); + _last_known_pos.xy() = _state.pos.xy(); + + } else { + ECL_INFO("fuse external observation as position measurement"); + fuseDirectStateMeasurement(innov(0), innov_var(0), obs_var, State::pos.idx + 0); + fuseDirectStateMeasurement(innov(1), innov_var(1), obs_var, State::pos.idx + 1); + + // Use the reset counters to inform the controllers about a potential large position jump + // TODO: compute the actual position change _state_reset_status.reset_count.posNE++; + _state_reset_status.posNE_change.zero(); + _time_last_hor_pos_fuse = _time_delayed_us; _last_known_pos.xy() = _state.pos.xy(); - return true; } } - return false; + if (checkAltitudeValidity(altitude)) { + const float altitude_corrected = altitude - pos_correction(2); + + if (!PX4_ISFINITE(_gps_alt_ref)) { + setAltOriginFromCurrentPos(altitude_corrected, epv); + + } else { + const float vpos = -(altitude_corrected - _gps_alt_ref); + const float obs_var = math::max(sq(epv), sq(0.01f)); + + ECL_INFO("reset height to external observation"); + resetVerticalPositionTo(vpos, obs_var); + _last_known_pos(2) = _state.pos(2); + } + } + + return true; } void Ekf::updateParameters() diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 5f2ba8c95fb4..5be5cee3bbad 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -533,7 +533,7 @@ class Ekf final : public EstimatorInterface return true; } - bool resetGlobalPosToExternalObservation(double lat_deg, double lon_deg, float accuracy, + bool resetGlobalPosToExternalObservation(double latitude, double longitude, float altitude, float eph, float epv, uint64_t timestamp_observation); /** diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index c339548b8cef..7769543d2bbd 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -545,9 +545,8 @@ void EKF2::Run() accuracy = vehicle_command.param3; } - // TODO add check for lat and long validity - if (_ekf.resetGlobalPosToExternalObservation(vehicle_command.param5, vehicle_command.param6, - accuracy, timestamp_observation) + if (_ekf.resetGlobalPosToExternalObservation(vehicle_command.param5, vehicle_command.param6, vehicle_command.param7, + accuracy, accuracy, timestamp_observation) ) { command_ack.result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED; diff --git a/src/modules/ekf2/test/CMakeLists.txt b/src/modules/ekf2/test/CMakeLists.txt index c1ecb992b99b..7e200c4c54ab 100644 --- a/src/modules/ekf2/test/CMakeLists.txt +++ b/src/modules/ekf2/test/CMakeLists.txt @@ -37,7 +37,7 @@ add_subdirectory(sensor_simulator) add_subdirectory(test_helper) px4_add_unit_gtest(SRC test_EKF_accelerometer.cpp LINKLIBS ecl_EKF ecl_sensor_sim) -px4_add_unit_gtest(SRC test_EKF_airspeed.cpp LINKLIBS ecl_EKF ecl_sensor_sim) +px4_add_unit_gtest(SRC test_EKF_airspeed.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_basics.cpp LINKLIBS ecl_EKF ecl_sensor_sim) px4_add_unit_gtest(SRC test_EKF_externalVision.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) px4_add_unit_gtest(SRC test_EKF_fake_pos.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) diff --git a/src/modules/ekf2/test/test_EKF_airspeed.cpp b/src/modules/ekf2/test/test_EKF_airspeed.cpp index d1bd54a13b21..b9dc3e367279 100644 --- a/src/modules/ekf2/test/test_EKF_airspeed.cpp +++ b/src/modules/ekf2/test/test_EKF_airspeed.cpp @@ -40,6 +40,7 @@ #include "EKF/ekf.h" #include "sensor_simulator/sensor_simulator.h" #include "sensor_simulator/ekf_wrapper.h" +#include "test_helper/reset_logging_checker.h" class EkfAirspeedTest : public ::testing::Test @@ -182,9 +183,11 @@ TEST_F(EkfAirspeedTest, testAirspeedDeadReckoning) const double latitude_new = -15.0000005; const double longitude_new = -115.0000005; const float altitude_new = 1500.0; + const float eph = 50.f; + const float epv = 10.f; _ekf->setEkfGlobalOrigin(latitude_new, longitude_new, altitude_new); - _ekf->resetGlobalPosToExternalObservation(latitude_new, longitude_new, 50.f, 0); + _ekf->resetGlobalPosToExternalObservation(latitude_new, longitude_new, altitude_new, eph, epv, 0); // Simulate the fact that the sideslip can start immediately, without // waiting for a measurement sample. @@ -203,4 +206,78 @@ TEST_F(EkfAirspeedTest, testAirspeedDeadReckoning) const Vector2f vel_wind_earth = _ekf->getWindVelocity(); EXPECT_NEAR(vel_wind_earth(0), 0.f, .1f); EXPECT_NEAR(vel_wind_earth(1), 0.f, .1f); + + EXPECT_TRUE(_ekf->global_position_is_valid()); +} + +TEST_F(EkfAirspeedTest, testAirspeedDeadReckoningLatLonAltReset) +{ + // GIVEN: a flying fixed-wing dead-reckoning with airspeed and sideslip fusion + const Vector3f simulated_velocity_earth(-3.6f, 8.f, 0.0f); + const Vector2f airspeed_body(15.f, 0.0f); + _sensor_simulator.runSeconds(10); + + _ekf->set_in_air_status(true); + _ekf->set_vehicle_at_rest(false); + _ekf->set_is_fixed_wing(true); + + double latitude = -15.0000005; + double longitude = -115.0000005; + float altitude = 1500.0; + const float eph = 50.f; + const float epv = 1.f; + + _ekf->setEkfGlobalOrigin(latitude, longitude, altitude); + _ekf->resetGlobalPosToExternalObservation(latitude, longitude, altitude, eph, epv, 0); + + _ekf_wrapper.enableBetaFusion(); + _sensor_simulator.runSeconds(1.f); + EXPECT_TRUE(_ekf_wrapper.isIntendingBetaFusion()); + + _sensor_simulator.startAirspeedSensor(); + _sensor_simulator._airspeed.setData(airspeed_body(0), airspeed_body(0)); + _sensor_simulator.runSeconds(10.f); + EXPECT_TRUE(_ekf_wrapper.isIntendingAirspeedFusion()); + + EXPECT_TRUE(_ekf->global_position_is_valid()); + + // WHEN: an external position reset is sent + ResetLoggingChecker reset_logging_checker(_ekf); + reset_logging_checker.capturePreResetState(); + + double latitude_new = -16.0000005; + double longitude_new = -116.0000005; + float altitude_new = 1602.0; + _ekf->resetGlobalPosToExternalObservation(latitude_new, longitude_new, altitude_new, eph, epv, 0); + + const Vector3f pos_new = _ekf->getPosition(); + const float altitude_est = -pos_new(2) + _ekf->getEkfGlobalOriginAltitude(); + + double latitude_est, longitude_est; + _ekf->global_origin().reproject(pos_new(0), pos_new(1), latitude_est, longitude_est); + + // THEN: the global position is adjusted accordingly + EXPECT_NEAR(altitude_est, altitude_new, 0.01f); + EXPECT_NEAR(latitude_est, latitude_new, 1e-3f); + EXPECT_NEAR(longitude_est, longitude_new, 1e-3f); + EXPECT_TRUE(_ekf->global_position_is_valid()); + + reset_logging_checker.capturePostResetState(); + EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0)); + EXPECT_TRUE(reset_logging_checker.isVerticalPositionResetCounterIncreasedBy(1)); + EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(0)); + EXPECT_TRUE(reset_logging_checker.isHorizontalPositionResetCounterIncreasedBy(1)); + + // AND WHEN: only the lat/lon is valid + latitude_new = -16.0000005; + longitude_new = -116.0000005; + altitude_new = NAN; + _ekf->resetGlobalPosToExternalObservation(latitude_new, longitude_new, altitude_new, eph, epv, 0); + + // THEN: lat/lon are reset but not the altitude + reset_logging_checker.capturePostResetState(); + EXPECT_TRUE(reset_logging_checker.isVerticalVelocityResetCounterIncreasedBy(0)); + EXPECT_TRUE(reset_logging_checker.isVerticalPositionResetCounterIncreasedBy(1)); + EXPECT_TRUE(reset_logging_checker.isHorizontalVelocityResetCounterIncreasedBy(0)); + EXPECT_TRUE(reset_logging_checker.isHorizontalPositionResetCounterIncreasedBy(2)); } From 0f1507c24e549f165dd3c7f70ab1b996854276f4 Mon Sep 17 00:00:00 2001 From: Jacob Dahl <37091262+dakejahl@users.noreply.github.com> Date: Wed, 28 Aug 2024 07:23:39 -0800 Subject: [PATCH 46/87] [gz] X500 mono_cam_down and aruco world (#23450) * x500 mono cam down and aruco world * remove duplicate line --- .../init.d-posix/airframes/4014_gz_x500_mono_cam_down | 10 ++++++++++ .../init.d-posix/airframes/CMakeLists.txt | 1 + src/modules/simulation/gz_bridge/CMakeLists.txt | 1 + 3 files changed, 12 insertions(+) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_x500_mono_cam_down diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_x500_mono_cam_down b/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_x500_mono_cam_down new file mode 100644 index 000000000000..199e4ecff380 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_x500_mono_cam_down @@ -0,0 +1,10 @@ +#!/bin/sh +# +# @name Gazebo x500 mono cam +# +# @type Quadrotor +# + +PX4_SIM_MODEL=${PX4_SIM_MODEL:=x500_mono_cam_down} + +. ${R}etc/init.d-posix/airframes/4001_gz_x500 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index 9235b2e66340..d53330cec1b8 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -85,6 +85,7 @@ px4_add_romfs_files( 4011_gz_lawnmower 4012_gz_rover_ackermann 4013_gz_x500_lidar + 4014_gz_x500_mono_cam_down 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post diff --git a/src/modules/simulation/gz_bridge/CMakeLists.txt b/src/modules/simulation/gz_bridge/CMakeLists.txt index c7d36e36a5ad..0d1e8eed66fd 100644 --- a/src/modules/simulation/gz_bridge/CMakeLists.txt +++ b/src/modules/simulation/gz_bridge/CMakeLists.txt @@ -94,6 +94,7 @@ if(gz-transport_FOUND) baylands lawn rover + aruco ) # find corresponding airframes From 2cda0efd84811d8ebdd4bdce45b0f6bb618a081d Mon Sep 17 00:00:00 2001 From: Mathieu Bresciani Date: Wed, 28 Aug 2024 17:33:58 +0200 Subject: [PATCH 47/87] Commander: extend COM_ARM_WO_GPS to disable warning (#23628) --- .../checks/estimatorCheck.cpp | 36 +++++++++++++++---- .../checks/estimatorCheck.hpp | 8 ++++- src/modules/commander/commander_params.c | 9 +++-- 3 files changed, 43 insertions(+), 10 deletions(-) diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp index 2b7c45318301..aa400e27c1ae 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.cpp @@ -273,12 +273,27 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor } if (!context.isArmed() && ekf_gps_check_fail) { - NavModes required_groups_gps = required_groups; - events::Log log_level = events::Log::Error; + NavModes required_groups_gps; + events::Log log_level; - if (_param_com_arm_wo_gps.get()) { + switch (static_cast(_param_com_arm_wo_gps.get())) { + default: + + /* FALLTHROUGH */ + case GnssArmingCheck::DenyArming: + required_groups_gps = required_groups; + log_level = events::Log::Error; + break; + + case GnssArmingCheck::WarningOnly: required_groups_gps = NavModes::None; // optional log_level = events::Log::Warning; + break; + + case GnssArmingCheck::Disabled: + required_groups_gps = NavModes::None; + log_level = events::Log::Disabled; + break; } // Only report the first failure to avoid spamming @@ -438,11 +453,20 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor } if (message && reporter.mavlink_log_pub()) { - if (!_param_com_arm_wo_gps.get()) { + switch (static_cast(_param_com_arm_wo_gps.get())) { + default: + + /* FALLTHROUGH */ + case GnssArmingCheck::DenyArming: mavlink_log_critical(reporter.mavlink_log_pub(), message, " Fail"); + break; - } else { - mavlink_log_critical(reporter.mavlink_log_pub(), message, ""); + case GnssArmingCheck::WarningOnly: + mavlink_log_warning(reporter.mavlink_log_pub(), message, ""); + break; + + case GnssArmingCheck::Disabled: + break; } } } diff --git a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp index 4f61df88670f..d5cb363e1130 100644 --- a/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp +++ b/src/modules/commander/HealthAndArmingChecks/checks/estimatorCheck.hpp @@ -59,6 +59,12 @@ class EstimatorChecks : public HealthAndArmingCheckBase void checkAndReport(const Context &context, Report &reporter) override; private: + enum class GnssArmingCheck : uint8_t { + DenyArming = 0, + WarningOnly = 1, + Disabled = 2 + }; + void checkEstimatorStatus(const Context &context, Report &reporter, const estimator_status_s &estimator_status, NavModes required_groups); void checkSensorBias(const Context &context, Report &reporter, NavModes required_groups); @@ -108,7 +114,7 @@ class EstimatorChecks : public HealthAndArmingCheckBase DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase, (ParamInt) _param_sens_imu_mode, (ParamInt) _param_com_arm_mag_str, - (ParamBool) _param_com_arm_wo_gps, + (ParamInt) _param_com_arm_wo_gps, (ParamBool) _param_sys_has_gps, (ParamFloat) _param_com_pos_fs_eph, (ParamFloat) _param_com_vel_fs_evh, diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index a462c8ae898c..0b20831a6eab 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -225,11 +225,14 @@ PARAM_DEFINE_FLOAT(COM_DISARM_LAND, 2.0f); PARAM_DEFINE_FLOAT(COM_DISARM_PRFLT, 10.0f); /** - * Allow arming without GPS + * GPS preflight check + * + * Measures taken when a check defined by EKF2_GPS_CHECK is failing. * * @group Commander - * @value 0 Require GPS lock to arm - * @value 1 Allow arming without GPS + * @value 0 Deny arming + * @value 1 Warning only + * @value 2 Disabled */ PARAM_DEFINE_INT32(COM_ARM_WO_GPS, 1); From 6b3e3aa363f2cf8425fa06d8e7db4d30422d1886 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 14 Aug 2024 14:45:50 +0200 Subject: [PATCH 48/87] Commander: improve param description of COM_POSCTL_NAVL and rename Manual-->Stabilized Signed-off-by: Silvan Fuhrer --- src/modules/commander/commander_params.c | 28 +++++++++------------ src/modules/commander/failsafe/failsafe.cpp | 2 +- src/modules/commander/failsafe/failsafe.h | 2 +- 3 files changed, 14 insertions(+), 18 deletions(-) diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 0b20831a6eab..72dadca8fa42 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -338,14 +338,14 @@ PARAM_DEFINE_INT32(COM_QC_ACT, 0); * The offboard loss failsafe will only be entered after a timeout, * set by COM_OF_LOSS_T in seconds. * - * @value 0 Position mode - * @value 1 Altitude mode - * @value 2 Manual - * @value 3 Return mode - * @value 4 Land mode - * @value 5 Hold mode - * @value 6 Terminate - * @value 7 Disarm + * @value 0 Position mode + * @value 1 Altitude mode + * @value 2 Stabilized + * @value 3 Return mode + * @value 4 Land mode + * @value 5 Hold mode + * @value 6 Terminate + * @value 7 Disarm * @group Commander */ PARAM_DEFINE_INT32(COM_OBL_RC_ACT, 0); @@ -453,16 +453,12 @@ PARAM_DEFINE_FLOAT(COM_RC_STICK_OV, 30.0f); PARAM_DEFINE_INT32(COM_ARM_MIS_REQ, 0); /** - * Position control navigation loss response. - * - * This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control. - * - * If Altitude/Manual is selected: assume use of remote control after fallback. Switch to Altitude mode if a height estimate is available, else switch to MANUAL. + * Position mode navigation loss response * - * If Land/Descend is selected: assume no use of remote control after fallback. Switch to Land mode if a height estimate is available, else switch to Descend. + * This sets the flight mode that will be used if navigation accuracy is no longer adequate for position control in manual Position mode. * - * @value 0 Altitude/Manual - * @value 1 Land/Descend + * @value 0 Altitude mode + * @value 1 Land mode (descend) * * @group Commander */ diff --git a/src/modules/commander/failsafe/failsafe.cpp b/src/modules/commander/failsafe/failsafe.cpp index f868d6740835..926bdfe44d94 100644 --- a/src/modules/commander/failsafe/failsafe.cpp +++ b/src/modules/commander/failsafe/failsafe.cpp @@ -292,7 +292,7 @@ FailsafeBase::Action Failsafe::fromOffboardLossActParam(int param_value, uint8_t user_intended_mode = vehicle_status_s::NAVIGATION_STATE_ALTCTL; break; - case offboard_loss_failsafe_mode::Manual: + case offboard_loss_failsafe_mode::Stabilized: action = Action::FallbackStab; user_intended_mode = vehicle_status_s::NAVIGATION_STATE_STAB; break; diff --git a/src/modules/commander/failsafe/failsafe.h b/src/modules/commander/failsafe/failsafe.h index 1c1b8bd86562..742b84ce36e5 100644 --- a/src/modules/commander/failsafe/failsafe.h +++ b/src/modules/commander/failsafe/failsafe.h @@ -70,7 +70,7 @@ class Failsafe : public FailsafeBase enum class offboard_loss_failsafe_mode : int32_t { Position_mode = 0, Altitude_mode = 1, - Manual = 2, + Stabilized = 2, Return_mode = 3, Land_mode = 4, Hold_mode = 5, From c86d44f831185ba6013c631fb8528e00e7d64593 Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Wed, 14 Aug 2024 14:46:32 +0200 Subject: [PATCH 49/87] Commander: remove 2 decimals from COM_FAIL_ACT_T Signed-off-by: Silvan Fuhrer --- src/modules/commander/commander_params.c | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/commander/commander_params.c b/src/modules/commander/commander_params.c index 72dadca8fa42..8c947719306a 100644 --- a/src/modules/commander/commander_params.c +++ b/src/modules/commander/commander_params.c @@ -288,7 +288,7 @@ PARAM_DEFINE_INT32(COM_LOW_BAT_ACT, 0); * @unit s * @min 0.0 * @max 25.0 - * @decimal 3 + * @decimal 1 */ PARAM_DEFINE_FLOAT(COM_FAIL_ACT_T, 5.f); From f8188f0981a12bfd576854900c3e160f693ceef6 Mon Sep 17 00:00:00 2001 From: chfriedrich98 <125505139+chfriedrich98@users.noreply.github.com> Date: Thu, 29 Aug 2024 15:27:08 +0200 Subject: [PATCH 50/87] differential: update module (#23629) Improve the slow down effect and add support for speed change in mission mode. Seperate code related to turning setpoints into motor commands into its own folder and refactor code. --- .../init.d-posix/airframes/4009_gz_r1_rover | 12 +- .../init.d-posix/airframes/4011_gz_lawnmower | 4 +- .../airframes/50001_aion_robotics_r1_rover | 22 ++ msg/CMakeLists.txt | 1 + msg/RoverDifferentialGuidanceStatus.msg | 3 - msg/RoverDifferentialSetpoint.msg | 9 + msg/RoverDifferentialStatus.msg | 7 +- src/modules/logger/logged_topics.cpp | 1 + src/modules/rover_differential/CMakeLists.txt | 5 +- .../rover_differential/RoverDifferential.cpp | 172 ++++++-------- .../rover_differential/RoverDifferential.hpp | 43 ++-- .../RoverDifferentialControl/CMakeLists.txt | 39 ++++ .../RoverDifferentialControl.cpp | 176 +++++++++++++++ .../RoverDifferentialControl.hpp | 121 ++++++++++ .../RoverDifferentialGuidance/CMakeLists.txt | 1 - .../RoverDifferentialGuidance.cpp | 209 ++++++++---------- .../RoverDifferentialGuidance.hpp | 55 ++--- src/modules/rover_differential/module.yaml | 49 ++-- 18 files changed, 603 insertions(+), 326 deletions(-) create mode 100644 msg/RoverDifferentialSetpoint.msg create mode 100644 src/modules/rover_differential/RoverDifferentialControl/CMakeLists.txt create mode 100644 src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp create mode 100644 src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp 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 7697e23db769..26429add58e5 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 @@ -14,15 +14,17 @@ param set-default SIM_GZ_EN 1 # Gazebo bridge # Rover parameters param set-default RD_WHEEL_TRACK 0.3 param set-default RD_MAN_YAW_SCALE 0.1 -param set-default RD_YAW_RATE_I 0.1 -param set-default RD_YAW_RATE_P 5 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_HEADING_P 5 -param set-default RD_HEADING_I 0.1 +param set-default RD_YAW_RATE_P 5 +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_SPEED_P 1 +param set-default RD_SPEED_I 0 param set-default RD_MAX_YAW_RATE 180 -param set-default RD_MISS_SPD_DEF 7 +param set-default RD_MISS_SPD_DEF 5 param set-default RD_TRANS_DRV_TRN 0.349066 param set-default RD_TRANS_TRN_DRV 0.174533 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower b/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower index c0d91e222365..8a05e2a15e52 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4011_gz_lawnmower @@ -27,8 +27,8 @@ param set-default RD_YAW_RATE_P 5 param set-default RD_MAX_ACCEL 1 param set-default RD_MAX_JERK 3 param set-default RD_MAX_SPEED 8 -param set-default RD_HEADING_P 5 -param set-default RD_HEADING_I 0.1 +param set-default RD_YAW_P 5 +param set-default RD_YAW_I 0.1 param set-default RD_MAX_YAW_RATE 30 param set-default RD_MISS_SPD_DEF 8 param set-default RD_TRANS_DRV_TRN 0.349066 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 c06b158cf857..1ea26ad6bff0 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 @@ -20,3 +20,25 @@ param set-default RBCLW_ADDRESS 128 param set-default RBCLW_FUNC1 101 param set-default RBCLW_FUNC2 102 param set-default RBCLW_REV 1 # reverse right wheels + +# Rover parameters +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_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_SPEED_P 0.5 +param set-default RD_SPEED_I 0.1 +param set-default RD_MAX_YAW_RATE 300 +param set-default RD_MISS_SPD_DEF 1.8 +param set-default RD_TRANS_DRV_TRN 0.349066 +param set-default RD_TRANS_TRN_DRV 0.174533 + +# Pure pursuit parameters +param set-default PP_LOOKAHD_MAX 10 +param set-default PP_LOOKAHD_MIN 1 +param set-default PP_LOOKAHD_GAIN 1 diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 3b31b7de554d..dce7e851dca9 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -182,6 +182,7 @@ set(msg_files RoverAckermannGuidanceStatus.msg RoverAckermannStatus.msg RoverDifferentialGuidanceStatus.msg + RoverDifferentialSetpoint.msg RoverDifferentialStatus.msg Rpm.msg RtlStatus.msg diff --git a/msg/RoverDifferentialGuidanceStatus.msg b/msg/RoverDifferentialGuidanceStatus.msg index 836546e7ebb7..ce3d37511163 100644 --- a/msg/RoverDifferentialGuidanceStatus.msg +++ b/msg/RoverDifferentialGuidanceStatus.msg @@ -1,10 +1,7 @@ uint64 timestamp # time since system start (microseconds) -float32 desired_speed # [m/s] Desired forward speed for the rover float32 lookahead_distance # [m] Lookahead distance of pure the pursuit controller float32 heading_error_deg # [deg] Heading error of the pure pursuit controller -float32 pid_heading_integral # Integral of the PID for the desired yaw rate during missions -float32 pid_throttle_integral # Integral of the PID for the throttle during missions uint8 state_machine # Driving state of the rover [0: SPOT_TURNING, 1: DRIVING, 2: GOAL_REACHED] # TOPICS rover_differential_guidance_status diff --git a/msg/RoverDifferentialSetpoint.msg b/msg/RoverDifferentialSetpoint.msg new file mode 100644 index 000000000000..b16f712828d8 --- /dev/null +++ b/msg/RoverDifferentialSetpoint.msg @@ -0,0 +1,9 @@ +uint64 timestamp # time since system start (microseconds) + +float32 forward_speed_setpoint # [m/s] Desired forward speed for the rover +float32 forward_speed_setpoint_normalized # [-1, 1] Normalized forward speed for the rover +float32 yaw_rate_setpoint # [rad/s] Desired yaw rate for the rover (Overriden by yaw controller if yaw_setpoint is used) +float32 yaw_rate_setpoint_normalized # [-1, 1] Normalized yaw rate for the rover +float32 yaw_setpoint # [rad] Desired yaw (heading) for the rover + +# TOPICS rover_differential_setpoint diff --git a/msg/RoverDifferentialStatus.msg b/msg/RoverDifferentialStatus.msg index 31907ffa6477..4d3d54eb9909 100644 --- a/msg/RoverDifferentialStatus.msg +++ b/msg/RoverDifferentialStatus.msg @@ -1,8 +1,11 @@ uint64 timestamp # time since system start (microseconds) float32 actual_speed # [m/s] Actual forward speed of the rover -float32 desired_yaw_rate_deg_s # [deg/s] Desired yaw rate +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 pid_yaw_rate_integral # Integral of the PID for the desired yaw rate controller +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 # TOPICS rover_differential_status diff --git a/src/modules/logger/logged_topics.cpp b/src/modules/logger/logged_topics.cpp index 5be39234e34f..f5ce636c23c9 100644 --- a/src/modules/logger/logged_topics.cpp +++ b/src/modules/logger/logged_topics.cpp @@ -105,6 +105,7 @@ void LoggedTopics::add_default_topics() add_optional_topic("rover_ackermann_guidance_status", 100); add_optional_topic("rover_ackermann_status", 100); add_optional_topic("rover_differential_guidance_status", 100); + add_optional_topic("rover_differential_setpoint", 100); add_optional_topic("rover_differential_status", 100); add_topic("rtl_time_estimate", 1000); add_topic("rtl_status", 2000); diff --git a/src/modules/rover_differential/CMakeLists.txt b/src/modules/rover_differential/CMakeLists.txt index beaec32a8776..880589316074 100644 --- a/src/modules/rover_differential/CMakeLists.txt +++ b/src/modules/rover_differential/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2023-2024 PX4 Development Team. All rights reserved. +# 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 @@ -32,6 +32,7 @@ ############################################################################ add_subdirectory(RoverDifferentialGuidance) +add_subdirectory(RoverDifferentialControl) px4_add_module( MODULE modules__rover_differential @@ -41,8 +42,8 @@ px4_add_module( RoverDifferential.hpp DEPENDS RoverDifferentialGuidance + RoverDifferentialControl px4_work_queue - modules__control_allocator # for parameter CA_R_REV pure_pursuit MODULE_CONFIG module.yaml diff --git a/src/modules/rover_differential/RoverDifferential.cpp b/src/modules/rover_differential/RoverDifferential.cpp index ab89392a0ec8..20cbf7d9e3e2 100644 --- a/src/modules/rover_differential/RoverDifferential.cpp +++ b/src/modules/rover_differential/RoverDifferential.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2023-2024 PX4 Development Team. All rights reserved. + * 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 @@ -32,16 +32,13 @@ ****************************************************************************/ #include "RoverDifferential.hpp" -using namespace matrix; -using namespace time_literals; RoverDifferential::RoverDifferential() : ModuleParams(nullptr), ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::rate_ctrl) { updateParams(); - _rover_differential_status_pub.advertise(); - pid_init(&_pid_yaw_rate, PID_MODE_DERIVATIV_NONE, 0.001f); + _rover_differential_setpoint_pub.advertise(); } bool RoverDifferential::init() @@ -53,16 +50,7 @@ bool RoverDifferential::init() void RoverDifferential::updateParams() { ModuleParams::updateParams(); - _max_yaw_rate = _param_rd_max_yaw_rate.get() * M_DEG_TO_RAD_F; - - pid_set_parameters(&_pid_yaw_rate, - _param_rd_p_gain_yaw_rate.get(), // Proportional gain - _param_rd_i_gain_yaw_rate.get(), // Integral gain - 0.f, // Derivative gain - 1.f, // Integral limit - 1.f); // Output limit - } void RoverDifferential::Run() @@ -73,135 +61,99 @@ void RoverDifferential::Run() return; } - hrt_abstime timestamp_prev = _timestamp; - _timestamp = hrt_absolute_time(); - const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - - // uORB subscriber updates - if (_parameter_update_sub.updated()) { - parameter_update_s parameter_update; - _parameter_update_sub.copy(¶meter_update); - updateParams(); - } + updateSubscriptions(); - if (_vehicle_status_sub.updated()) { - vehicle_status_s vehicle_status{}; - _vehicle_status_sub.copy(&vehicle_status); - _nav_state = vehicle_status.nav_state; - } + // Generate and publish attitude and velocity setpoints + hrt_abstime timestamp = hrt_absolute_time(); - if (_vehicle_angular_velocity_sub.updated()) { - vehicle_angular_velocity_s vehicle_angular_velocity{}; - _vehicle_angular_velocity_sub.copy(&vehicle_angular_velocity); - _vehicle_body_yaw_rate = vehicle_angular_velocity.xyz[2]; - } - - if (_vehicle_attitude_sub.updated()) { - vehicle_attitude_s vehicle_attitude{}; - _vehicle_attitude_sub.copy(&vehicle_attitude); - _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); - _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); - } - - if (_vehicle_local_position_sub.updated()) { - vehicle_local_position_s vehicle_local_position{}; - _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); - } - - // Navigation modes switch (_nav_state) { case vehicle_status_s::NAVIGATION_STATE_MANUAL: { manual_control_setpoint_s manual_control_setpoint{}; if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - _differential_setpoint.throttle = manual_control_setpoint.throttle; - _differential_setpoint.yaw_rate = manual_control_setpoint.roll * _param_rd_man_yaw_scale.get(); - + 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_setpoint = NAN; + rover_differential_setpoint.yaw_rate_setpoint_normalized = manual_control_setpoint.roll * _param_rd_man_yaw_scale.get(); + rover_differential_setpoint.yaw_rate_setpoint = NAN; + _rover_differential_setpoint_pub.publish(rover_differential_setpoint); } - - _differential_setpoint.closed_loop_yaw_rate = false; } break; case vehicle_status_s::NAVIGATION_STATE_ACRO: { manual_control_setpoint_s manual_control_setpoint{}; if (_manual_control_setpoint_sub.update(&manual_control_setpoint)) { - _differential_setpoint.throttle = manual_control_setpoint.throttle; - _differential_setpoint.yaw_rate = math::interpolate(manual_control_setpoint.roll, - -1.f, 1.f, - -_max_yaw_rate, _max_yaw_rate); + 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(manual_control_setpoint.roll, + -1.f, 1.f, -_max_yaw_rate, _max_yaw_rate); + rover_differential_setpoint.yaw_rate_setpoint_normalized = NAN; + rover_differential_setpoint.yaw_setpoint = NAN; + _rover_differential_setpoint_pub.publish(rover_differential_setpoint); } - _differential_setpoint.closed_loop_yaw_rate = true; } break; case vehicle_status_s::NAVIGATION_STATE_AUTO_MISSION: case vehicle_status_s::NAVIGATION_STATE_AUTO_RTL: - _differential_setpoint = _rover_differential_guidance.computeGuidance(_vehicle_yaw, _vehicle_forward_speed, - _nav_state); + _rover_differential_guidance.computeGuidance(_vehicle_yaw, _vehicle_forward_speed, _nav_state); break; default: // Unimplemented nav states will stop the rover - _differential_setpoint.throttle = 0.f; - _differential_setpoint.yaw_rate = 0.f; - _differential_setpoint.closed_loop_yaw_rate = false; + rover_differential_setpoint_s rover_differential_setpoint{}; + rover_differential_setpoint.forward_speed_setpoint = NAN; + rover_differential_setpoint.forward_speed_setpoint_normalized = 0.f; + rover_differential_setpoint.yaw_rate_setpoint = NAN; + rover_differential_setpoint.yaw_rate_setpoint_normalized = 0.f; + rover_differential_setpoint.yaw_setpoint = NAN; + _rover_differential_setpoint_pub.publish(rover_differential_setpoint); break; } - float speed_diff_normalized = _differential_setpoint.yaw_rate; - - // Closed loop yaw rate control - if (_differential_setpoint.closed_loop_yaw_rate) { - if (fabsf(_differential_setpoint.yaw_rate - _vehicle_body_yaw_rate) < YAW_RATE_ERROR_THRESHOLD) { - speed_diff_normalized = 0.f; - pid_reset_integral(&_pid_yaw_rate); - - } else { - const float speed_diff = _differential_setpoint.yaw_rate * _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, _differential_setpoint.yaw_rate, _vehicle_body_yaw_rate, 0, dt), - -1.f, 1.f); // Feedback - } - - } else { - pid_reset_integral(&_pid_yaw_rate); - } - - // 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.desired_yaw_rate_deg_s = M_RAD_TO_DEG_F * _differential_setpoint.yaw_rate; - rover_differential_status.actual_yaw_rate_deg_s = M_RAD_TO_DEG_F * _vehicle_body_yaw_rate; - rover_differential_status.pid_yaw_rate_integral = _pid_yaw_rate.integral; - _rover_differential_status_pub.publish(rover_differential_status); - - // Publish to motors - actuator_motors_s actuator_motors{}; - actuator_motors.reversible_flags = _param_r_rev.get(); - computeMotorCommands(_differential_setpoint.throttle, speed_diff_normalized).copyTo(actuator_motors.control); - actuator_motors.timestamp = _timestamp; - _actuator_motors_pub.publish(actuator_motors); + _rover_differential_control.computeMotorCommands(_vehicle_yaw, _vehicle_yaw_rate, _vehicle_forward_speed); } -matrix::Vector2f RoverDifferential::computeMotorCommands(float forward_speed, const float speed_diff) +void RoverDifferential::updateSubscriptions() { - float combined_velocity = fabsf(forward_speed) + fabsf(speed_diff); - if (combined_velocity > 1.0f) { // Prioritize yaw rate - float excess_velocity = fabsf(combined_velocity - 1.0f); - forward_speed -= sign(forward_speed) * excess_velocity; + if (_parameter_update_sub.updated()) { + parameter_update_s parameter_update; + _parameter_update_sub.copy(¶meter_update); + updateParams(); + } + + if (_vehicle_status_sub.updated()) { + vehicle_status_s vehicle_status{}; + _vehicle_status_sub.copy(&vehicle_status); + _nav_state = vehicle_status.nav_state; } - // Calculate the left and right wheel speeds - return Vector2f(forward_speed - speed_diff, - forward_speed + speed_diff); + 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]; + } + + if (_vehicle_attitude_sub.updated()) { + vehicle_attitude_s vehicle_attitude{}; + _vehicle_attitude_sub.copy(&vehicle_attitude); + _vehicle_attitude_quaternion = matrix::Quatf(vehicle_attitude.q); + _vehicle_yaw = matrix::Eulerf(_vehicle_attitude_quaternion).psi(); + } + + if (_vehicle_local_position_sub.updated()) { + vehicle_local_position_s vehicle_local_position{}; + _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); + } } int RoverDifferential::task_spawn(int argc, char *argv[]) diff --git a/src/modules/rover_differential/RoverDifferential.hpp b/src/modules/rover_differential/RoverDifferential.hpp index 3dafe99b0566..897a7199ef4d 100644 --- a/src/modules/rover_differential/RoverDifferential.hpp +++ b/src/modules/rover_differential/RoverDifferential.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2023-2024 PX4 Development Team. All rights reserved. + * 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 @@ -42,23 +42,21 @@ // uORB includes #include -#include #include #include #include #include -#include #include #include #include -#include +#include // Standard libraries -#include #include // Local includes #include "RoverDifferentialGuidance/RoverDifferentialGuidance.hpp" +#include "RoverDifferentialControl/RoverDifferentialControl.hpp" using namespace time_literals; @@ -80,21 +78,17 @@ class RoverDifferential : public ModuleBase, public ModulePar bool init(); - /** - * @brief Computes motor commands for differential drive. - * - * @param forward_speed Linear velocity along the x-axis. - * @param speed_diff Speed difference between left and right wheels. - * @return matrix::Vector2f Motor velocities for the right and left motors. - */ - matrix::Vector2f computeMotorCommands(float forward_speed, const float speed_diff); - protected: void updateParams() override; private: void Run() override; + /** + * @brief Update uORB subscriptions. + */ + void updateSubscriptions(); + // uORB Subscriptions uORB::Subscription _manual_control_setpoint_sub{ORB_ID(manual_control_setpoint)}; uORB::Subscription _parameter_update_sub{ORB_ID(parameter_update)}; @@ -104,33 +98,22 @@ class RoverDifferential : public ModuleBase, public ModulePar uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; // uORB Publications - uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; - uORB::Publication _rover_differential_status_pub{ORB_ID(rover_differential_status)}; + uORB::Publication _rover_differential_setpoint_pub{ORB_ID(rover_differential_setpoint)}; // Instances RoverDifferentialGuidance _rover_differential_guidance{this}; + RoverDifferentialControl _rover_differential_control{this}; // Variables - float _vehicle_body_yaw_rate{0.f}; + matrix::Quatf _vehicle_attitude_quaternion{}; + float _vehicle_yaw_rate{0.f}; float _vehicle_forward_speed{0.f}; float _vehicle_yaw{0.f}; float _max_yaw_rate{0.f}; int _nav_state{0}; - matrix::Quatf _vehicle_attitude_quaternion{}; - hrt_abstime _timestamp{0}; - PID_t _pid_yaw_rate; // The PID controller for yaw rate - RoverDifferentialGuidance::differential_setpoint _differential_setpoint; - - // Constants - static constexpr float YAW_RATE_ERROR_THRESHOLD = 0.1f; // [rad/s] Error threshold for the closed loop yaw rate control DEFINE_PARAMETERS( (ParamFloat) _param_rd_man_yaw_scale, - (ParamFloat) _param_rd_wheel_track, - (ParamFloat) _param_rd_p_gain_yaw_rate, - (ParamFloat) _param_rd_i_gain_yaw_rate, - (ParamFloat) _param_rd_max_speed, - (ParamFloat) _param_rd_max_yaw_rate, - (ParamInt) _param_r_rev + (ParamFloat) _param_rd_max_yaw_rate ) }; diff --git a/src/modules/rover_differential/RoverDifferentialControl/CMakeLists.txt b/src/modules/rover_differential/RoverDifferentialControl/CMakeLists.txt new file mode 100644 index 000000000000..58a5239f8cc7 --- /dev/null +++ b/src/modules/rover_differential/RoverDifferentialControl/CMakeLists.txt @@ -0,0 +1,39 @@ +############################################################################ +# +# 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. +# +############################################################################ + +px4_add_library(RoverDifferentialControl + RoverDifferentialControl.cpp +) + +target_link_libraries(RoverDifferentialControl PUBLIC pid) +target_include_directories(RoverDifferentialControl PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp new file mode 100644 index 000000000000..c1f96c0ce066 --- /dev/null +++ b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.cpp @@ -0,0 +1,176 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#include "RoverDifferentialControl.hpp" + +#include + +using namespace matrix; +using namespace time_literals; + +RoverDifferentialControl::RoverDifferentialControl(ModuleParams *parent) : ModuleParams(parent) +{ + updateParams(); + _rover_differential_status_pub.advertise(); + pid_init(&_pid_yaw_rate, PID_MODE_DERIVATIV_NONE, 0.001f); + pid_init(&_pid_throttle, PID_MODE_DERIVATIV_NONE, 0.001f); + pid_init(&_pid_yaw, PID_MODE_DERIVATIV_NONE, 0.001f); +} + +void RoverDifferentialControl::updateParams() +{ + ModuleParams::updateParams(); + _max_yaw_rate = _param_rd_max_yaw_rate.get() * M_DEG_TO_RAD_F; + pid_set_parameters(&_pid_yaw_rate, + _param_rd_yaw_rate_p.get(), // Proportional gain + _param_rd_yaw_rate_i.get(), // Integral gain + 0.f, // Derivative gain + 1.f, // Integral limit + 1.f); // Output limit + pid_set_parameters(&_pid_throttle, + _param_rd_p_gain_speed.get(), // Proportional gain + _param_rd_i_gain_speed.get(), // Integral gain + 0.f, // Derivative gain + 1.f, // Integral limit + 1.f); // Output limit + pid_set_parameters(&_pid_yaw, + _param_rd_p_gain_yaw.get(), // Proportional gain + _param_rd_i_gain_yaw.get(), // Integral gain + 0.f, // Derivative gain + _max_yaw_rate, // Integral limit + _max_yaw_rate); // Output limit +} + +void RoverDifferentialControl::computeMotorCommands(const float vehicle_yaw, const float vehicle_yaw_rate, + const float vehicle_forward_speed) +{ + // Timestamps + hrt_abstime timestamp_prev = _timestamp; + _timestamp = hrt_absolute_time(); + const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; + + // Update differential setpoint + _rover_differential_setpoint_sub.update(&_rover_differential_setpoint); + + // 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); + } + } + + // 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 + } + + } else { // Use normalized setpoint + speed_diff_normalized = PX4_ISFINITE(_rover_differential_setpoint.yaw_rate_setpoint_normalized) ? + math::constrain(_rover_differential_setpoint.yaw_rate_setpoint_normalized, -1.f, 1.f) : 0.f; + } + + // Speed control + 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); + } + } + + } 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; + } + + // 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.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; + _rover_differential_status_pub.publish(rover_differential_status); + + // 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); + actuator_motors.timestamp = _timestamp; + _actuator_motors_pub.publish(actuator_motors); + +} + +matrix::Vector2f RoverDifferentialControl::computeInverseKinematics(float forward_speed_normalized, + const float speed_diff_normalized) +{ + float max_motor_command = fabsf(forward_speed_normalized) + fabsf(speed_diff_normalized); + + if (max_motor_command > 1.0f) { // Prioritize yaw rate if a normalized motor command exceeds limit of 1 + float excess = fabsf(max_motor_command - 1.0f); + forward_speed_normalized -= sign(forward_speed_normalized) * excess; + } + + // Calculate the left and right wheel speeds + return Vector2f(forward_speed_normalized - speed_diff_normalized, + forward_speed_normalized + speed_diff_normalized); +} diff --git a/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp new file mode 100644 index 000000000000..d3ef7a076fd6 --- /dev/null +++ b/src/modules/rover_differential/RoverDifferentialControl/RoverDifferentialControl.hpp @@ -0,0 +1,121 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#pragma once + +// PX4 includes +#include + +// uORB includes +#include +#include +#include +#include +#include +#include + + +// Standard libraries +#include +#include +#include +#include +#include + +using namespace matrix; + +/** + * @brief Class for differential rover guidance. + */ +class RoverDifferentialControl : public ModuleParams +{ +public: + /** + * @brief Constructor for RoverDifferentialControl. + * @param parent The parent ModuleParams object. + */ + RoverDifferentialControl(ModuleParams *parent); + ~RoverDifferentialControl() = default; + + /** + * @brief Compute motor commands based on setpoints + */ + void computeMotorCommands(float vehicle_yaw, float vehicle_yaw_rate, float vehicle_forward_speed); + +protected: + /** + * @brief Update the parameters of the module. + */ + void updateParams() override; + +private: + /** + * @brief Compute normalized motor commands based on normalized setpoints. + * + * @param forward_speed_normalized Normalized forward speed [-1, 1]. + * @param speed_diff_normalized Speed difference between left and right wheels [-1, 1]. + * @return matrix::Vector2f Motor velocities for the right and left motors [-1, 1]. + */ + matrix::Vector2f computeInverseKinematics(float forward_speed_normalized, const float speed_diff_normalized); + + // uORB subscriptions + uORB::Subscription _rover_differential_setpoint_sub{ORB_ID(rover_differential_setpoint)}; + + // uORB publications + uORB::PublicationMulti _actuator_motors_pub{ORB_ID(actuator_motors)}; + uORB::Publication _rover_differential_status_pub{ORB_ID(rover_differential_status)}; + + // Variables + rover_differential_setpoint_s _rover_differential_setpoint{}; + hrt_abstime _timestamp{0}; + float _max_yaw_rate{0.f}; + + // Controllers + PID_t _pid_throttle; // The PID controller for the closed loop speed control + PID_t _pid_yaw; // The PID controller for the closed loop yaw control + PID_t _pid_yaw_rate; // The PID controller for the closed loop yaw rate control + + // Parameters + DEFINE_PARAMETERS( + (ParamFloat) _param_rd_wheel_track, + (ParamFloat) _param_rd_max_speed, + (ParamFloat) _param_rd_max_yaw_rate, + (ParamFloat) _param_rd_yaw_rate_p, + (ParamFloat) _param_rd_yaw_rate_i, + (ParamFloat) _param_rd_p_gain_speed, + (ParamFloat) _param_rd_i_gain_speed, + (ParamFloat) _param_rd_p_gain_yaw, + (ParamFloat) _param_rd_i_gain_yaw, + (ParamInt) _param_r_rev + ) +}; diff --git a/src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt b/src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt index 0fd7b68c394e..81f350d48403 100644 --- a/src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt +++ b/src/modules/rover_differential/RoverDifferentialGuidance/CMakeLists.txt @@ -35,5 +35,4 @@ px4_add_library(RoverDifferentialGuidance RoverDifferentialGuidance.cpp ) -target_link_libraries(RoverDifferentialGuidance PUBLIC pid) target_include_directories(RoverDifferentialGuidance PUBLIC ${CMAKE_CURRENT_SOURCE_DIR}) diff --git a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp index efad52e7b874..848a7f513acf 100644 --- a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp +++ b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.cpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2023-2024 PX4 Development Team. All rights reserved. + * 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 @@ -36,108 +36,45 @@ #include using namespace matrix; -using namespace time_literals; RoverDifferentialGuidance::RoverDifferentialGuidance(ModuleParams *parent) : ModuleParams(parent) { updateParams(); + _max_forward_speed = _param_rd_miss_spd_def.get(); _rover_differential_guidance_status_pub.advertise(); - pid_init(&_pid_heading, PID_MODE_DERIVATIV_NONE, 0.001f); - pid_init(&_pid_throttle, PID_MODE_DERIVATIV_NONE, 0.001f); - } void RoverDifferentialGuidance::updateParams() { ModuleParams::updateParams(); - - _max_yaw_rate = _param_rd_max_yaw_rate.get() * M_DEG_TO_RAD_F; - pid_set_parameters(&_pid_heading, - _param_rd_p_gain_heading.get(), // Proportional gain - _param_rd_i_gain_heading.get(), // Integral gain - 0.f, // Derivative gain - _max_yaw_rate, // Integral limit - _max_yaw_rate); // Output limit - pid_set_parameters(&_pid_throttle, - _param_rd_p_gain_speed.get(), // Proportional gain - _param_rd_i_gain_speed.get(), // Integral gain - 0.f, // Derivative gain - 1.f, // Integral limit - 1.f); // Output limit } -RoverDifferentialGuidance::differential_setpoint RoverDifferentialGuidance::computeGuidance(const float yaw, - const float actual_speed, const int nav_state) +void RoverDifferentialGuidance::computeGuidance(const float vehicle_yaw, const float forward_speed, const int nav_state) { - // Initializations - bool mission_finished{false}; - float desired_speed{0.f}; - float desired_yaw_rate{0.f}; - hrt_abstime timestamp_prev = _timestamp; - _timestamp = hrt_absolute_time(); - const float dt = math::constrain(_timestamp - timestamp_prev, 1_ms, 5000_ms) * 1e-6f; - - // uORB subscriber updates - if (_vehicle_global_position_sub.updated()) { - vehicle_global_position_s vehicle_global_position{}; - _vehicle_global_position_sub.copy(&vehicle_global_position); - _curr_pos = Vector2d(vehicle_global_position.lat, vehicle_global_position.lon); - } + updateSubscriptions(); - if (_local_position_sub.updated()) { - vehicle_local_position_s local_position{}; - _local_position_sub.copy(&local_position); + // Catch return to launch + const float distance_to_curr_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), + _curr_wp(0), _curr_wp(1)); - if (!_global_ned_proj_ref.isInitialized() - || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != local_position.ref_timestamp)) { - _global_ned_proj_ref.initReference(local_position.ref_lat, local_position.ref_lon, local_position.ref_timestamp); - } - - _curr_pos_ned = Vector2f(local_position.x, local_position.y); - } - - if (_position_setpoint_triplet_sub.updated()) { - updateWaypoints(); - } - - if (_mission_result_sub.updated()) { - mission_result_s mission_result{}; - _mission_result_sub.copy(&mission_result); - mission_finished = mission_result.finished; - } - - if (_home_position_sub.updated()) { - home_position_s home_position{}; - _home_position_sub.copy(&home_position); - _home_position = Vector2d(home_position.lat, home_position.lon); - } - - const float desired_heading = _pure_pursuit.calcDesiredHeading(_curr_wp_ned, _prev_wp_ned, _curr_pos_ned, - math::max(actual_speed, 0.f)); - - const float heading_error = matrix::wrap_pi(desired_heading - yaw); - - const float distance_to_next_wp = get_distance_to_next_waypoint(_curr_pos(0), _curr_pos(1), - _curr_wp(0), - _curr_wp(1)); - - if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL - && distance_to_next_wp < _param_nav_acc_rad.get()) { // Return to launch - mission_finished = true; + if (nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL) { + _mission_finished = distance_to_curr_wp < _param_nav_acc_rad.get(); } // State machine - if (!mission_finished && distance_to_next_wp > _param_nav_acc_rad.get()) { + float desired_yaw = _pure_pursuit.calcDesiredHeading(_curr_wp_ned, _prev_wp_ned, _curr_pos_ned, + math::max(forward_speed, 0.f)); + const float heading_error = matrix::wrap_pi(desired_yaw - vehicle_yaw); + + if (!_mission_finished && distance_to_curr_wp > _param_nav_acc_rad.get()) { if (_currentState == GuidanceState::STOPPED) { _currentState = GuidanceState::DRIVING; } if (_currentState == GuidanceState::DRIVING && fabsf(heading_error) > _param_rd_trans_drv_trn.get()) { - pid_reset_integral(&_pid_heading); _currentState = GuidanceState::SPOT_TURNING; } else if (_currentState == GuidanceState::SPOT_TURNING && fabsf(heading_error) < _param_rd_trans_trn_drv.get()) { - pid_reset_integral(&_pid_heading); _currentState = GuidanceState::DRIVING; } @@ -146,68 +83,93 @@ RoverDifferentialGuidance::differential_setpoint RoverDifferentialGuidance::comp } // Guidance logic + float desired_forward_speed{0.f}; + switch (_currentState) { case GuidanceState::DRIVING: { - desired_speed = _param_rd_miss_spd_def.get(); - - if (_param_rd_max_jerk.get() > FLT_EPSILON && _param_rd_max_accel.get() > FLT_EPSILON) { - desired_speed = math::trajectory::computeMaxSpeedFromDistance(_param_rd_max_jerk.get(), - _param_rd_max_accel.get(), distance_to_next_wp, 0.0f); - desired_speed = math::constrain(desired_speed, -_param_rd_max_speed.get(), _param_rd_max_speed.get()); + // Calculate desired forward speed + desired_forward_speed = _max_forward_speed; + + if (_waypoint_transition_angle < M_PI_F - _param_rd_trans_drv_trn.get()) { + if (_param_rd_max_jerk.get() > FLT_EPSILON && _param_rd_max_accel.get() > FLT_EPSILON) { + desired_forward_speed = math::trajectory::computeMaxSpeedFromDistance(_param_rd_max_jerk.get(), + _param_rd_max_accel.get(), distance_to_curr_wp, 0.0f); + desired_forward_speed = math::constrain(desired_forward_speed, -_max_forward_speed, _max_forward_speed); + } } - desired_yaw_rate = pid_calculate(&_pid_heading, heading_error, 0.f, 0.f, dt); } break; case GuidanceState::SPOT_TURNING: - if (actual_speed < TURN_MAX_VELOCITY) { // Wait for the rover to stop - desired_yaw_rate = pid_calculate(&_pid_heading, heading_error, 0.f, 0.f, dt); // Turn on the spot + if (forward_speed > TURN_MAX_VELOCITY) { + desired_yaw = vehicle_yaw; // Wait for the rover to stop + } break; case GuidanceState::STOPPED: default: - desired_speed = 0.f; - desired_yaw_rate = 0.f; + desired_yaw = vehicle_yaw; break; } - // Closed loop speed control - float throttle{0.f}; + // Publish differential guidance status (logging) + hrt_abstime timestamp = hrt_absolute_time(); + rover_differential_guidance_status_s rover_differential_guidance_status{}; + rover_differential_guidance_status.timestamp = timestamp; + rover_differential_guidance_status.lookahead_distance = _pure_pursuit.getLookaheadDistance(); + rover_differential_guidance_status.heading_error_deg = M_RAD_TO_DEG_F * heading_error; + rover_differential_guidance_status.state_machine = (uint8_t) _currentState; + _rover_differential_guidance_status_pub.publish(rover_differential_guidance_status); + + // Publish setpoints + rover_differential_setpoint_s rover_differential_setpoint{}; + rover_differential_setpoint.timestamp = timestamp; + rover_differential_setpoint.forward_speed_setpoint = desired_forward_speed; + rover_differential_setpoint.forward_speed_setpoint_normalized = NAN; + rover_differential_setpoint.yaw_rate_setpoint = NAN; + rover_differential_setpoint.yaw_rate_setpoint_normalized = NAN; + rover_differential_setpoint.yaw_setpoint = desired_yaw; + _rover_differential_setpoint_pub.publish(rover_differential_setpoint); +} - if (fabsf(desired_speed) < FLT_EPSILON) { - pid_reset_integral(&_pid_throttle); +void RoverDifferentialGuidance::updateSubscriptions() +{ + if (_vehicle_global_position_sub.updated()) { + vehicle_global_position_s vehicle_global_position{}; + _vehicle_global_position_sub.copy(&vehicle_global_position); + _curr_pos = Vector2d(vehicle_global_position.lat, vehicle_global_position.lon); + } - } else { - throttle = pid_calculate(&_pid_throttle, desired_speed, actual_speed, 0, - dt); + if (_local_position_sub.updated()) { + vehicle_local_position_s local_position{}; + _local_position_sub.copy(&local_position); - if (_param_rd_max_speed.get() > FLT_EPSILON) { // Feed-forward term - throttle += math::interpolate(desired_speed, - 0.f, _param_rd_max_speed.get(), - 0.f, 1.f); + if (!_global_ned_proj_ref.isInitialized() + || (_global_ned_proj_ref.getProjectionReferenceTimestamp() != local_position.ref_timestamp)) { + _global_ned_proj_ref.initReference(local_position.ref_lat, local_position.ref_lon, local_position.ref_timestamp); } + + _curr_pos_ned = Vector2f(local_position.x, local_position.y); } - // Publish differential controller status (logging) - _rover_differential_guidance_status.timestamp = _timestamp; - _rover_differential_guidance_status.desired_speed = desired_speed; - _rover_differential_guidance_status.pid_throttle_integral = _pid_throttle.integral; - _rover_differential_guidance_status.lookahead_distance = _pure_pursuit.getLookaheadDistance(); - _rover_differential_guidance_status.pid_heading_integral = _pid_heading.integral; - _rover_differential_guidance_status.heading_error_deg = M_RAD_TO_DEG_F * heading_error; - _rover_differential_guidance_status.state_machine = (uint8_t) _currentState; - _rover_differential_guidance_status_pub.publish(_rover_differential_guidance_status); - - // Return setpoints - differential_setpoint differential_setpoint_temp; - differential_setpoint_temp.throttle = math::constrain(throttle, 0.f, 1.f); - differential_setpoint_temp.yaw_rate = math::constrain(desired_yaw_rate, -_max_yaw_rate, - _max_yaw_rate); - differential_setpoint_temp.closed_loop_yaw_rate = true; - return differential_setpoint_temp; + if (_position_setpoint_triplet_sub.updated()) { + updateWaypoints(); + } + + if (_mission_result_sub.updated()) { + mission_result_s mission_result{}; + _mission_result_sub.copy(&mission_result); + _mission_finished = mission_result.finished; + } + + if (_home_position_sub.updated()) { + home_position_s home_position{}; + _home_position_sub.copy(&home_position); + _home_position = Vector2d(home_position.lat, home_position.lon); + } } void RoverDifferentialGuidance::updateWaypoints() @@ -243,5 +205,20 @@ void RoverDifferentialGuidance::updateWaypoints() // NED waypoint coordinates _curr_wp_ned = _global_ned_proj_ref.project(_curr_wp(0), _curr_wp(1)); _prev_wp_ned = _global_ned_proj_ref.project(_prev_wp(0), _prev_wp(1)); + _next_wp_ned = _global_ned_proj_ref.project(_next_wp(0), _next_wp(1)); + // Distances + const Vector2f curr_to_next_wp_ned = _next_wp_ned - _curr_wp_ned; + const Vector2f curr_to_prev_wp_ned = _prev_wp_ned - _curr_wp_ned; + float cosin = curr_to_prev_wp_ned.unit_or_zero() * curr_to_next_wp_ned.unit_or_zero(); + cosin = math::constrain(cosin, -1.f, 1.f); // Protect against float precision problem + _waypoint_transition_angle = acosf(cosin); + + // 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()); + + } 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 29a131f8d8e2..fd3a9485a04e 100644 --- a/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp +++ b/src/modules/rover_differential/RoverDifferentialGuidance/RoverDifferentialGuidance.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2023-2024 PX4 Development Team. All rights reserved. + * 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 @@ -47,9 +47,9 @@ #include #include #include +#include // Standard libraries -#include #include #include #include @@ -80,26 +80,13 @@ class RoverDifferentialGuidance : public ModuleParams RoverDifferentialGuidance(ModuleParams *parent); ~RoverDifferentialGuidance() = default; - struct differential_setpoint { - float throttle{0.f}; - float yaw_rate{0.f}; - bool closed_loop_yaw_rate{false}; - }; - /** - * @brief Compute guidance for the vehicle. - * @param yaw The yaw orientation of the vehicle in radians. - * @param actual_speed The velocity of the vehicle in m/s. - * @param dt The time step in seconds. + * @brief Compute and publish attitude and velocity setpoints based on the mission plan. + * @param vehicle_yaw The yaw of the vehicle [rad]. + * @param forward_speed The forward speed of the vehicle [m/s]. * @param nav_state Navigation state of the rover. */ - RoverDifferentialGuidance::differential_setpoint computeGuidance(float yaw, float actual_speed, - int nav_state); - - /** - * @brief Update global/ned waypoint coordinates - */ - void updateWaypoints(); + void computeGuidance(float vehicle_yaw, float forward_speed, int nav_state); protected: /** @@ -108,6 +95,16 @@ class RoverDifferentialGuidance : public ModuleParams void updateParams() override; private: + /** + * @brief Update uORB subscriptions. + */ + void updateSubscriptions(); + + /** + * @brief Update global/ned waypoint coordinates + */ + void updateWaypoints(); + // uORB subscriptions uORB::Subscription _position_setpoint_triplet_sub{ORB_ID(position_setpoint_triplet)}; uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)}; @@ -116,16 +113,14 @@ class RoverDifferentialGuidance : public ModuleParams uORB::Subscription _home_position_sub{ORB_ID(home_position)}; // uORB publications + uORB::Publication _rover_differential_setpoint_pub{ORB_ID(rover_differential_setpoint)}; uORB::Publication _rover_differential_guidance_status_pub{ORB_ID(rover_differential_guidance_status)}; - rover_differential_guidance_status_s _rover_differential_guidance_status{}; // Variables MapProjection _global_ned_proj_ref{}; // Transform global to ned coordinates. - GuidanceState _currentState{GuidanceState::DRIVING}; // The current state of guidance. + GuidanceState _currentState{GuidanceState::DRIVING}; // The current state of the guidance. PurePursuit _pure_pursuit{this}; // Pure pursuit library - hrt_abstime _timestamp{0}; - float _max_yaw_rate{0.f}; - + bool _mission_finished{false}; // Waypoints Vector2d _curr_pos{}; @@ -135,27 +130,21 @@ class RoverDifferentialGuidance : public ModuleParams Vector2d _curr_wp{}; Vector2f _curr_wp_ned{}; Vector2d _next_wp{}; + Vector2f _next_wp_ned{}; Vector2d _home_position{}; - - // Controllers - PID_t _pid_heading; // The PID controller for the heading - PID_t _pid_throttle; // The PID controller for velocity + float _max_forward_speed{0.f}; // Maximum forward speed for the rover [m/s] + float _waypoint_transition_angle{0.f}; // Angle between the prevWP-currWP and currWP-nextWP line segments [rad] // Constants static constexpr float TURN_MAX_VELOCITY = 0.2f; // Velocity threshhold for starting the spot turn [m/s] // Parameters DEFINE_PARAMETERS( - (ParamFloat) _param_rd_p_gain_heading, - (ParamFloat) _param_rd_i_gain_heading, - (ParamFloat) _param_rd_p_gain_speed, - (ParamFloat) _param_rd_i_gain_speed, (ParamFloat) _param_rd_max_speed, (ParamFloat) _param_nav_acc_rad, (ParamFloat) _param_rd_max_jerk, (ParamFloat) _param_rd_max_accel, (ParamFloat) _param_rd_miss_spd_def, - (ParamFloat) _param_rd_max_yaw_rate, (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 be0a76c60e9b..edc3f8e5ba7f 100644 --- a/src/modules/rover_differential/module.yaml +++ b/src/modules/rover_differential/module.yaml @@ -23,70 +23,70 @@ parameters: In manual mode the setpoint for the yaw rate received from the rc remote is scaled by this value. type: float - min: 0.01 + min: 0.001 max: 1 increment: 0.01 - decimal: 2 + decimal: 3 default: 1 - RD_HEADING_P: + RD_YAW_P: description: - short: Proportional gain for heading controller + short: Proportional gain for closed loop yaw controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 + decimal: 3 default: 1 - RD_HEADING_I: + RD_YAW_I: description: - short: Integral gain for heading controller + short: Integral gain for closed loop yaw controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 - default: 0.1 + decimal: 3 + default: 0 RD_SPEED_P: description: - short: Proportional gain for speed controller + short: Proportional gain for closed loop forward speed controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 + decimal: 3 default: 1 RD_SPEED_I: description: - short: Integral gain for ground speed controller + short: Integral gain for closed loop forward speed controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 + decimal: 3 default: 0 RD_YAW_RATE_P: description: - short: Proportional gain for angular velocity controller + short: Proportional gain for closed loop yaw rate controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 + decimal: 3 default: 1 RD_YAW_RATE_I: description: - short: Integral gain for angular velocity controller + short: Integral gain for closed loop yaw rate controller type: float min: 0 max: 100 increment: 0.01 - decimal: 2 + decimal: 3 default: 0 RD_MAX_JERK: @@ -123,11 +123,11 @@ parameters: max: 100 increment: 0.01 decimal: 2 - default: 7 + default: 1 RD_MAX_YAW_RATE: description: - short: Maximum allowed yaw rate for the rover. + 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. type: float @@ -140,7 +140,7 @@ parameters: RD_MISS_SPD_DEF: description: - short: Default rover speed during a mission + short: Default forward speed for the rover during auto modes type: float unit: m/s min: 0 @@ -151,7 +151,7 @@ parameters: RD_TRANS_TRN_DRV: description: - short: Heading error threshhold to switch from spot turning to driving + short: Yaw error threshhold to switch from spot turning to driving type: float unit: rad min: 0.001 @@ -162,7 +162,12 @@ parameters: RD_TRANS_DRV_TRN: description: - short: Heading error threshhold to switch from driving to spot turning + short: Yaw error threshhold to switch from driving to spot turning + long: | + This threshold is used for the state machine to switch from driving to turning based on the + error between the desired and actual yaw. It is also used as the threshold whether the rover should come + to a smooth stop at the next waypoint. This slow down effect is active if the angle between the + line segments from prevWP-currWP and currWP-nextWP is smaller then 180 - RD_TRANS_DRV_TRN. type: float unit: rad min: 0.001 From 5b0014cb06eabc0d735d0509487c6e71ea76614a Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Thu, 29 Aug 2024 11:51:27 -0400 Subject: [PATCH 51/87] ekf2: remove legacy accel z bias checks (#23341) Co-authored-by: Mathieu Bresciani --- .../scripts/itcm_functions_includes.ld | 1 - msg/EstimatorStatusFlags.msg | 1 - src/modules/ekf2/EKF/common.h | 2 +- src/modules/ekf2/EKF/ekf.cpp | 2 - src/modules/ekf2/EKF/ekf.h | 3 - src/modules/ekf2/EKF/height_control.cpp | 101 ------------------ src/modules/ekf2/EKF2.cpp | 2 - 7 files changed, 1 insertion(+), 111 deletions(-) diff --git a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld index 9b169ae36005..0a4e0faa6ae7 100644 --- a/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld +++ b/boards/px4/fmu-v6xrt/nuttx-config/scripts/itcm_functions_includes.ld @@ -377,7 +377,6 @@ *(.text._ZN19StickAccelerationXYC1EP12ModuleParams) *(.text.imxrt_epsubmit) *(.text._ZN15PositionControl6updateEf) -*(.text._ZN3Ekf29checkVerticalAccelerationBiasERKN9estimator9imuSampleE) *(.text._ZN23MavlinkStreamScaledIMU24sendEv) *(.text._ZN5PX4IO10io_reg_getEhhPtj) *(.text.imxrt_dma_send) diff --git a/msg/EstimatorStatusFlags.msg b/msg/EstimatorStatusFlags.msg index 79b900f6a8b0..6b17842c2650 100644 --- a/msg/EstimatorStatusFlags.msg +++ b/msg/EstimatorStatusFlags.msg @@ -59,7 +59,6 @@ bool fs_bad_airspeed # 5 - true if fusion of the airspeed has encounte bool fs_bad_sideslip # 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error bool fs_bad_optflow_x # 7 - true if fusion of the optical flow X axis has encountered a numerical error bool fs_bad_optflow_y # 8 - true if fusion of the optical flow Y axis has encountered a numerical error -bool fs_bad_acc_bias # 9 - true if bad delta velocity bias estimates have been detected bool fs_bad_acc_vertical # 10 - true if bad vertical accelerometer data has been detected bool fs_bad_acc_clipping # 11 - true if delta velocity data contains clipping (asymmetric railing) diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 13c2767f754b..6eda8b9cc71f 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -513,7 +513,7 @@ bool bad_sideslip : 1; ///< 6 - true if fusion of the synthetic sideslip constraint has encountered a numerical error bool bad_optflow_X : 1; ///< 7 - true if fusion of the optical flow X axis has encountered a numerical error bool bad_optflow_Y : 1; ///< 8 - true if fusion of the optical flow Y axis has encountered a numerical error - bool bad_acc_bias : 1; ///< 9 - true if bad delta velocity bias estimates have been detected + bool __UNUSED : 1; ///< 9 - bool bad_acc_vertical : 1; ///< 10 - true if bad vertical accelerometer data has been detected bool bad_acc_clipping : 1; ///< 11 - true if delta velocity data contains clipping (asymmetric railing) } flags; diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index 24734dcfb370..c8448daa9b3e 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -114,8 +114,6 @@ void Ekf::reset() _last_known_pos.setZero(); - _time_acc_bias_check = 0; - #if defined(CONFIG_EKF2_BAROMETER) _baro_counter = 0; #endif // CONFIG_EKF2_BAROMETER diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index 5be5cee3bbad..a7d59b47ef5d 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -612,8 +612,6 @@ class Ekf final : public EstimatorInterface Vector3f _last_known_pos{}; ///< last known local position vector (m) - uint64_t _time_acc_bias_check{0}; ///< last time the accel bias check passed (uSec) - Vector3f _earth_rate_NED{}; ///< earth rotation vector (NED) in rad/s Dcmf _R_to_earth{}; ///< transformation matrix from body frame to earth frame from last EKF prediction @@ -1094,7 +1092,6 @@ class Ekf final : public EstimatorInterface void stopAuxVelFusion(); #endif // CONFIG_EKF2_AUXVEL - void checkVerticalAccelerationBias(const imuSample &imu_delayed); void checkVerticalAccelerationHealth(const imuSample &imu_delayed); Likelihood estimateInertialNavFallingLikelihood() const; diff --git a/src/modules/ekf2/EKF/height_control.cpp b/src/modules/ekf2/EKF/height_control.cpp index 4db232ca051f..147e198921cf 100644 --- a/src/modules/ekf2/EKF/height_control.cpp +++ b/src/modules/ekf2/EKF/height_control.cpp @@ -39,7 +39,6 @@ void Ekf::controlHeightFusion(const imuSample &imu_delayed) { - checkVerticalAccelerationBias(imu_delayed); checkVerticalAccelerationHealth(imu_delayed); #if defined(CONFIG_EKF2_BAROMETER) @@ -120,106 +119,6 @@ void Ekf::checkHeightSensorRefFallback() } } -void Ekf::checkVerticalAccelerationBias(const imuSample &imu_delayed) -{ - // Run additional checks to see if the delta velocity bias has hit limits in a direction that is clearly wrong - // calculate accel bias term aligned with the gravity vector - const float dVel_bias_lim = 0.9f * _params.acc_bias_lim * _dt_ekf_avg; - const Vector3f delta_vel_bias = _state.accel_bias * _dt_ekf_avg; - const float down_dvel_bias = delta_vel_bias.dot(Vector3f(_R_to_earth.row(2))); - - // check that the vertical component of accel bias is consistent with both the vertical position and velocity innovation - bool bad_acc_bias = false; - - if (fabsf(down_dvel_bias) > dVel_bias_lim) { - - bool bad_vz = false; - -#if defined(CONFIG_EKF2_EXTERNAL_VISION) - - if (_control_status.flags.ev_hgt) { - if (down_dvel_bias * _aid_src_ev_vel.innovation[2] < 0.f) { - bad_vz = true; - } - } - -#endif // CONFIG_EKF2_EXTERNAL_VISION - -#if defined(CONFIG_EKF2_GNSS) - - if (_control_status.flags.gps) { - if (down_dvel_bias * _aid_src_gnss_vel.innovation[2] < 0.f) { - bad_vz = true; - } - } - -#endif // CONFIG_EKF2_GNSS - - if (bad_vz) { -#if defined(CONFIG_EKF2_BAROMETER) - - if (_control_status.flags.baro_hgt) { - if (down_dvel_bias * _aid_src_baro_hgt.innovation < 0.f) { - bad_acc_bias = true; - } - } - -#endif // CONFIG_EKF2_BAROMETER - -#if defined(CONFIG_EKF2_EXTERNAL_VISION) - - if (_control_status.flags.ev_hgt) { - if (down_dvel_bias * _aid_src_ev_hgt.innovation < 0.f) { - bad_acc_bias = true; - } - } - -#endif // CONFIG_EKF2_EXTERNAL_VISION - -#if defined(CONFIG_EKF2_GNSS) - - if (_control_status.flags.gps_hgt) { - if (down_dvel_bias * _aid_src_gnss_hgt.innovation < 0.f) { - bad_acc_bias = true; - } - } - -#endif // CONFIG_EKF2_GNSS - -#if defined(CONFIG_EKF2_RANGE_FINDER) - - if (_control_status.flags.rng_hgt) { - if (down_dvel_bias * _aid_src_rng_hgt.innovation < 0.f) { - bad_acc_bias = true; - } - } - -#endif // CONFIG_EKF2_RANGE_FINDER - } - } - - // record the pass/fail - if (!bad_acc_bias) { - _fault_status.flags.bad_acc_bias = false; - _time_acc_bias_check = _time_delayed_us; - - } else { - _fault_status.flags.bad_acc_bias = true; - } - - // if we have failed for 7 seconds continuously, reset the accel bias covariances to fix bad conditioning of - // the covariance matrix but preserve the variances (diagonals) to allow bias learning to continue - if (_fault_status.flags.bad_acc_bias && isTimedOut(_time_acc_bias_check, (uint64_t)7e6)) { - - resetAccelBiasCov(); - - _time_acc_bias_check = imu_delayed.time_us; - - _fault_status.flags.bad_acc_bias = false; - ECL_WARN("invalid accel bias - covariance reset"); - } -} - void Ekf::checkVerticalAccelerationHealth(const imuSample &imu_delayed) { // Check for IMU accelerometer vibration induced clipping as evidenced by the vertical diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 7769543d2bbd..97ff93bf2a92 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1937,7 +1937,6 @@ void EKF2::PublishStatusFlags(const hrt_abstime ×tamp) status_flags.fs_bad_sideslip = _ekf.fault_status_flags().bad_sideslip; status_flags.fs_bad_optflow_x = _ekf.fault_status_flags().bad_optflow_X; status_flags.fs_bad_optflow_y = _ekf.fault_status_flags().bad_optflow_Y; - status_flags.fs_bad_acc_bias = _ekf.fault_status_flags().bad_acc_bias; status_flags.fs_bad_acc_vertical = _ekf.fault_status_flags().bad_acc_vertical; status_flags.fs_bad_acc_clipping = _ekf.fault_status_flags().bad_acc_clipping; @@ -2666,7 +2665,6 @@ void EKF2::UpdateAccelCalibration(const hrt_abstime ×tamp) const bool bias_valid = (_param_ekf2_imu_ctrl.get() & static_cast(ImuCtrl::AccelBias)) && _ekf.control_status_flags().tilt_align && (_ekf.fault_status().value == 0) - && !_ekf.fault_status_flags().bad_acc_bias && !_ekf.fault_status_flags().bad_acc_clipping && !_ekf.fault_status_flags().bad_acc_vertical; From 787fe9590d83e2ff4e76d9e3b331edbd3bf9e7d6 Mon Sep 17 00:00:00 2001 From: Benjamin Perseghetti Date: Thu, 29 Aug 2024 14:42:56 -0400 Subject: [PATCH 52/87] Fix typo where 22.04 still says Gz (Garden) (#23632) Signed-off-by: Benjamin Perseghetti --- Tools/setup/ubuntu.sh | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Tools/setup/ubuntu.sh b/Tools/setup/ubuntu.sh index 346e071cdcc1..48e23709fb84 100755 --- a/Tools/setup/ubuntu.sh +++ b/Tools/setup/ubuntu.sh @@ -225,7 +225,7 @@ if [[ $INSTALL_SIM == "true" ]]; then # Gazebo / Gazebo classic installation if [[ "${UBUNTU_RELEASE}" == "22.04" ]]; then - echo "Gazebo (Garden) will be installed" + echo "Gazebo (Harmonic) will be installed" echo "Earlier versions will be removed" # Add Gazebo binary repository sudo wget https://packages.osrfoundation.org/gazebo.gpg -O /usr/share/keyrings/pkgs-osrf-archive-keyring.gpg From 7dcea6b2e498835ba6c656eac7370ba554bec9da Mon Sep 17 00:00:00 2001 From: Marco Hauswirth <58551738+haumarco@users.noreply.github.com> Date: Fri, 30 Aug 2024 17:25:56 +0200 Subject: [PATCH 53/87] EKF2: range measurement rejection in rain/fog (#23579) --- .../range_finder/range_height_control.cpp | 1 + .../range_finder/sensor_range_finder.cpp | 21 +++++- .../range_finder/sensor_range_finder.hpp | 12 ++++ src/modules/ekf2/EKF/common.h | 1 + src/modules/ekf2/EKF/ekf.cpp | 1 + src/modules/ekf2/EKF2.cpp | 1 + src/modules/ekf2/EKF2.hpp | 1 + src/modules/ekf2/params_range_finder.yaml | 13 ++++ .../ekf2/test/test_SensorRangeFinder.cpp | 64 ++++++++++++++++--- 9 files changed, 106 insertions(+), 9 deletions(-) diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp index 0aafe8a1b00d..678b6f282ca1 100644 --- a/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/range_height_control.cpp @@ -54,6 +54,7 @@ void Ekf::controlRangeHaglFusion(const imuSample &imu_sample) _range_sensor.setPitchOffset(_params.rng_sens_pitch); _range_sensor.setCosMaxTilt(_params.range_cos_max_tilt); _range_sensor.setQualityHysteresis(_params.range_valid_quality_s); + _range_sensor.setMaxFogDistance(_params.rng_fog); _range_sensor.runChecks(imu_sample.time_us, _R_to_earth); diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp index 359d10ca5242..c0ae2a71ebf6 100644 --- a/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.cpp @@ -84,8 +84,9 @@ void SensorRangeFinder::updateValidity(uint64_t current_time_us) if (isTiltOk() && isDataInRange()) { updateStuckCheck(); + updateFogCheck(getDistBottom(), _sample.time_us); - if (!_is_stuck) { + if (!_is_stuck && !_is_blocked) { _is_sample_valid = true; _time_last_valid_us = _sample.time_us; } @@ -146,5 +147,23 @@ void SensorRangeFinder::updateStuckCheck() } } +void SensorRangeFinder::updateFogCheck(const float dist_bottom, const uint64_t time_us) +{ + if (_max_fog_dist > 0.f && time_us - _time_last_valid_us < 1e6) { + + const float median_dist = _median_dist.apply(dist_bottom); + const float factor = 2.f; // magic hardcoded factor + + if (!_is_blocked && median_dist < _max_fog_dist && _prev_median_dist - median_dist > factor * _max_fog_dist) { + _is_blocked = true; + + } else if (_is_blocked && median_dist > factor * _max_fog_dist) { + _is_blocked = false; + } + + _prev_median_dist = median_dist; + } +} + } // namespace sensor } // namespace estimator diff --git a/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp index f3c59be54135..fd53407fa871 100644 --- a/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp +++ b/src/modules/ekf2/EKF/aid_sources/range_finder/sensor_range_finder.hpp @@ -44,6 +44,7 @@ #include "Sensor.hpp" #include +#include namespace estimator { @@ -99,6 +100,8 @@ class SensorRangeFinder : public Sensor _rng_valid_max_val = max_distance; } + void setMaxFogDistance(float max_fog_dist) { _max_fog_dist = max_fog_dist; } + void setQualityHysteresis(float valid_quality_threshold_s) { _quality_hyst_us = uint64_t(valid_quality_threshold_s * 1e6f); @@ -129,6 +132,7 @@ class SensorRangeFinder : public Sensor bool isTiltOk() const { return _cos_tilt_rng_to_earth > _range_cos_max_tilt; } bool isDataInRange() const; void updateStuckCheck(); + void updateFogCheck(const float dist_bottom, const uint64_t time_us); rangeSample _sample{}; @@ -172,6 +176,14 @@ class SensorRangeFinder : public Sensor */ uint64_t _time_bad_quality_us{}; ///< timestamp at which range finder signal quality was 0 (used for hysteresis) uint64_t _quality_hyst_us{}; ///< minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (us) + + /* + * Fog check + */ + bool _is_blocked{false}; + float _max_fog_dist{0.f}; //< maximum distance at which the range finder could detect fog (m) + math::MedianFilter _median_dist{}; + float _prev_median_dist{0.f}; }; } // namespace sensor diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 6eda8b9cc71f..cc1d48cf164c 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -421,6 +421,7 @@ struct parameters { float range_valid_quality_s{1.0f}; ///< minimum duration during which the reported range finder signal quality needs to be non-zero in order to be declared valid (s) float range_cos_max_tilt{0.7071f}; ///< cosine of the maximum tilt angle from the vertical that permits use of range finder and flow data float range_kin_consistency_gate{1.0f}; ///< gate size used by the range finder kinematic consistency check + float rng_fog{0.f}; ///< max distance which a blocked range sensor measures (fog, dirt) [m] Vector3f rng_pos_body{}; ///< xyz position of range sensor in body frame (m) #endif // CONFIG_EKF2_RANGE_FINDER diff --git a/src/modules/ekf2/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp index c8448daa9b3e..910eb54dd6c1 100644 --- a/src/modules/ekf2/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -81,6 +81,7 @@ void Ekf::reset() _range_sensor.setPitchOffset(_params.rng_sens_pitch); _range_sensor.setCosMaxTilt(_params.range_cos_max_tilt); _range_sensor.setQualityHysteresis(_params.range_valid_quality_s); + _range_sensor.setMaxFogDistance(_params.rng_fog); #endif // CONFIG_EKF2_RANGE_FINDER _control_status.value = 0; diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 97ff93bf2a92..38e5660e4ff4 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -162,6 +162,7 @@ EKF2::EKF2(bool multi_mode, const px4::wq_config_t &config, bool replay_mode): _param_ekf2_rng_a_igate(_params->range_aid_innov_gate), _param_ekf2_rng_qlty_t(_params->range_valid_quality_s), _param_ekf2_rng_k_gate(_params->range_kin_consistency_gate), + _param_ekf2_rng_fog(_params->rng_fog), _param_ekf2_rng_pos_x(_params->rng_pos_body(0)), _param_ekf2_rng_pos_y(_params->rng_pos_body(1)), _param_ekf2_rng_pos_z(_params->rng_pos_body(2)), diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 867cf9ae5758..489e0bbd5ae0 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -623,6 +623,7 @@ class EKF2 final : public ModuleParams, public px4::ScheduledWorkItem (ParamExtFloat) _param_ekf2_rng_a_igate, (ParamExtFloat) _param_ekf2_rng_qlty_t, (ParamExtFloat) _param_ekf2_rng_k_gate, + (ParamExtFloat) _param_ekf2_rng_fog, (ParamExtFloat) _param_ekf2_rng_pos_x, (ParamExtFloat) _param_ekf2_rng_pos_y, (ParamExtFloat) _param_ekf2_rng_pos_z, diff --git a/src/modules/ekf2/params_range_finder.yaml b/src/modules/ekf2/params_range_finder.yaml index 5baa4fb26775..78c30bbcca85 100644 --- a/src/modules/ekf2/params_range_finder.yaml +++ b/src/modules/ekf2/params_range_finder.yaml @@ -150,3 +150,16 @@ parameters: default: 0.0 unit: m decimal: 3 + EKF2_RNG_FOG: + description: + short: Maximum distance at which the range finder could detect fog (m) + long: Limit for fog detection. If the range finder measures a distance greater + than this value, the measurement is considered to not be blocked by fog or rain. + If there's a jump from larger than RNG_FOG to smaller than EKF2_RNG_FOG, the + measurement may gets rejected. 0 - disabled + type: float + default: 1.0 + min: 0.0 + max: 20.0 + unit: m + decimal: 1 diff --git a/src/modules/ekf2/test/test_SensorRangeFinder.cpp b/src/modules/ekf2/test/test_SensorRangeFinder.cpp index fc515a875768..c2e9d1c667e0 100644 --- a/src/modules/ekf2/test/test_SensorRangeFinder.cpp +++ b/src/modules/ekf2/test/test_SensorRangeFinder.cpp @@ -51,6 +51,7 @@ class SensorRangeFinderTest : public ::testing::Test _range_finder.setPitchOffset(0.f); _range_finder.setCosMaxTilt(0.707f); _range_finder.setLimits(_min_range, _max_range); + _range_finder.setMaxFogDistance(2.f); } // Use this method to clean up any memory, network etc. after each test @@ -60,20 +61,21 @@ class SensorRangeFinderTest : public ::testing::Test protected: SensorRangeFinder _range_finder{}; - const rangeSample _good_sample{(uint64_t)2e6, 1.f, 100}; // {time_us, range, quality} + const rangeSample _good_sample{(uint64_t)2e6, 5.f, 100}; // {time_us, range, quality} const float _min_range{0.5f}; const float _max_range{10.f}; - void updateSensorAtRate(uint64_t duration_us, uint64_t dt_update_us, uint64_t dt_sensor_us); + void updateSensorAtRate(rangeSample sample, uint64_t duration_us, uint64_t dt_update_us, uint64_t dt_sensor_us); void testTilt(const Eulerf &euler, bool should_pass); }; -void SensorRangeFinderTest::updateSensorAtRate(uint64_t duration_us, uint64_t dt_update_us, uint64_t dt_sensor_us) +void SensorRangeFinderTest::updateSensorAtRate(rangeSample sample, uint64_t duration_us, uint64_t dt_update_us, + uint64_t dt_sensor_us) { const Dcmf attitude{Eulerf(0.f, 0.f, 0.f)}; - rangeSample new_sample = _good_sample; - uint64_t t_now_us = _good_sample.time_us; + rangeSample new_sample = sample; + uint64_t t_now_us = sample.time_us; for (int i = 0; i < int(duration_us / dt_update_us); i++) { t_now_us += dt_update_us; @@ -307,7 +309,7 @@ TEST_F(SensorRangeFinderTest, continuity) const uint64_t dt_update_us = 10e3; uint64_t dt_sensor_us = 4e6; uint64_t duration_us = 8e6; - updateSensorAtRate(duration_us, dt_update_us, dt_sensor_us); + updateSensorAtRate(_good_sample, duration_us, dt_update_us, dt_sensor_us); // THEN: the data should be marked as unhealthy // Note that it also fails the out-of-date test here @@ -317,14 +319,14 @@ TEST_F(SensorRangeFinderTest, continuity) // AND WHEN: the data rate is acceptable dt_sensor_us = 3e5; duration_us = 5e5; - updateSensorAtRate(duration_us, dt_update_us, dt_sensor_us); + updateSensorAtRate(_good_sample, duration_us, dt_update_us, dt_sensor_us); // THEN: it should still fail until the filter converge // to the new datarate EXPECT_FALSE(_range_finder.isDataHealthy()); EXPECT_FALSE(_range_finder.isHealthy()); - updateSensorAtRate(duration_us, dt_update_us, dt_sensor_us); + updateSensorAtRate(_good_sample, duration_us, dt_update_us, dt_sensor_us); EXPECT_TRUE(_range_finder.isDataHealthy()); EXPECT_TRUE(_range_finder.isHealthy()); } @@ -345,3 +347,49 @@ TEST_F(SensorRangeFinderTest, distBottom) _range_finder.runChecks(sample.time_us, attitude20); EXPECT_FLOAT_EQ(_range_finder.getDistBottom(), sample.rng * cosf(-0.35)); } + +TEST_F(SensorRangeFinderTest, blockedByFog) +{ + // WHEN: sensor is not blocked by fog + const Dcmf attitude{Eulerf(0.f, 0.f, 0.f)}; + const uint64_t dt_update_us = 10e3; + uint64_t dt_sensor_us = 3e5; + uint64_t duration_us = 5e5; + + updateSensorAtRate(_good_sample, duration_us, dt_update_us, dt_sensor_us); + // THEN: the data should be marked as healthy + EXPECT_TRUE(_range_finder.isDataHealthy()); + EXPECT_TRUE(_range_finder.isHealthy()); + + + // WHEN: sensor is then blocked by fog + // range jumps to value below 2m + uint64_t t_now_us = _range_finder.getSampleAddress()->time_us; + rangeSample sample{t_now_us, 1.f, 100}; + updateSensorAtRate(sample, duration_us, dt_update_us, dt_sensor_us); + + // THEN: the data should be marked as unhealthy + EXPECT_FALSE(_range_finder.isDataHealthy()); + EXPECT_FALSE(_range_finder.isHealthy()); + + // WHEN: the sensor is not blocked by fog anymore + sample.rng = 5.f; + updateSensorAtRate(sample, duration_us, dt_update_us, dt_sensor_us); + + // THEN: the data should be marked as healthy again + EXPECT_TRUE(_range_finder.isDataHealthy()); + EXPECT_TRUE(_range_finder.isHealthy()); + + // WHEN: the sensor is is not jumping to a value below 2m + while (sample.rng > _min_range) { + sample.time_us += dt_update_us; + _range_finder.setSample(sample); + _range_finder.runChecks(sample.time_us, attitude); + sample.rng -= 0.5f; + } + + // THEN: the data should still be marked as healthy + EXPECT_TRUE(_range_finder.isDataHealthy()); + EXPECT_TRUE(_range_finder.isHealthy()); + +} From 4c63e9e4f992824ba05b229bf2506cc7178eda1a Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 May 2024 17:12:26 +1200 Subject: [PATCH 54/87] libuavcan: update DroneCAN submodule Signed-off-by: Julian Oes --- src/drivers/uavcan/libuavcan | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/drivers/uavcan/libuavcan b/src/drivers/uavcan/libuavcan index 9a0fd624c448..dce2d4e7d8f4 160000 --- a/src/drivers/uavcan/libuavcan +++ b/src/drivers/uavcan/libuavcan @@ -1 +1 @@ -Subproject commit 9a0fd624c448cad5633720676233f74846387a9f +Subproject commit dce2d4e7d8f41348e571481cd2e4788ac8af900d From 87a63e75be8d6c00a6787420d7e4a34df239203d Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 9 May 2024 14:30:55 +1200 Subject: [PATCH 55/87] mavlink: extract OpenDroneID function to lib This extracts the function mapping from MAV_TYPE to MAV_ODID_UA_TYPE to the library, so that it can be re-used later by the remote ID implementation over DroneCAN. Signed-off-by: Julian Oes --- src/lib/CMakeLists.txt | 1 + src/lib/open_drone_id/CMakeLists.txt | 41 +++ .../open_drone_id_translations.cpp | 255 ++++++++++++++++++ .../open_drone_id_translations.hpp | 52 ++++ src/modules/mavlink/CMakeLists.txt | 1 + .../streams/OPEN_DRONE_ID_BASIC_ID.hpp | 95 +------ .../streams/OPEN_DRONE_ID_LOCATION.hpp | 64 +---- 7 files changed, 358 insertions(+), 151 deletions(-) create mode 100644 src/lib/open_drone_id/CMakeLists.txt create mode 100644 src/lib/open_drone_id/open_drone_id_translations.cpp create mode 100644 src/lib/open_drone_id/open_drone_id_translations.hpp diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index 7a7b5973fd4a..942c2dcad853 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -60,6 +60,7 @@ add_subdirectory(mathlib EXCLUDE_FROM_ALL) add_subdirectory(mixer_module EXCLUDE_FROM_ALL) add_subdirectory(motion_planning EXCLUDE_FROM_ALL) add_subdirectory(npfg EXCLUDE_FROM_ALL) +add_subdirectory(open_drone_id EXCLUDE_FROM_ALL) add_subdirectory(perf EXCLUDE_FROM_ALL) add_subdirectory(fw_performance_model EXCLUDE_FROM_ALL) add_subdirectory(pid EXCLUDE_FROM_ALL) diff --git a/src/lib/open_drone_id/CMakeLists.txt b/src/lib/open_drone_id/CMakeLists.txt new file mode 100644 index 000000000000..2090d159250e --- /dev/null +++ b/src/lib/open_drone_id/CMakeLists.txt @@ -0,0 +1,41 @@ +############################################################################ +# +# 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. +# +############################################################################ + +px4_add_library(open_drone_id + open_drone_id_translations.cpp + open_drone_id_translations.hpp +) + +add_dependencies(open_drone_id mavlink_c_generate) + +target_compile_options(open_drone_id PRIVATE -Wno-cast-align -Wno-address-of-packed-member) diff --git a/src/lib/open_drone_id/open_drone_id_translations.cpp b/src/lib/open_drone_id/open_drone_id_translations.cpp new file mode 100644 index 000000000000..854e7623043d --- /dev/null +++ b/src/lib/open_drone_id/open_drone_id_translations.cpp @@ -0,0 +1,255 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#include "open_drone_id_translations.hpp" +#include +#include + +using namespace time_literals; + + +namespace open_drone_id_translations +{ + +MAV_ODID_UA_TYPE odidTypeForMavType(uint8_t system_type) +{ + switch (system_type) { + case MAV_TYPE_GENERIC: return MAV_ODID_UA_TYPE_OTHER; + + case MAV_TYPE_FIXED_WING: return MAV_ODID_UA_TYPE_AEROPLANE; + + case MAV_TYPE_QUADROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_COAXIAL: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_HELICOPTER: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_ANTENNA_TRACKER: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_GCS: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_AIRSHIP: return MAV_ODID_UA_TYPE_AIRSHIP; + + case MAV_TYPE_FREE_BALLOON: return MAV_ODID_UA_TYPE_FREE_BALLOON; + + case MAV_TYPE_ROCKET: return MAV_ODID_UA_TYPE_ROCKET; + + case MAV_TYPE_GROUND_ROVER: return MAV_ODID_UA_TYPE_GROUND_OBSTACLE; + + case MAV_TYPE_SURFACE_BOAT: return MAV_ODID_UA_TYPE_OTHER; + + case MAV_TYPE_SUBMARINE: return MAV_ODID_UA_TYPE_OTHER; + + case MAV_TYPE_HEXAROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_OCTOROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_TRICOPTER: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_FLAPPING_WING: return MAV_ODID_UA_TYPE_ORNITHOPTER; + + case MAV_TYPE_KITE: return MAV_ODID_UA_TYPE_KITE; + + case MAV_TYPE_ONBOARD_CONTROLLER: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_TILTROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_FIXEDROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_TAILSITTER: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_TILTWING: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_VTOL_RESERVED5: return MAV_ODID_UA_TYPE_HYBRID_LIFT; + + case MAV_TYPE_GIMBAL: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_ADSB: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_PARAFOIL: return MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE; + + case MAV_TYPE_DODECAROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; + + case MAV_TYPE_CAMERA: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_CHARGING_STATION: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_FLARM: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_SERVO: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_ODID: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_DECAROTOR: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_BATTERY: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_PARACHUTE: return MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE; + + case MAV_TYPE_LOG: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_OSD: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_IMU: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_GPS: return MAV_ODID_UA_TYPE_NONE; + + case MAV_TYPE_WINCH: return MAV_ODID_UA_TYPE_NONE; + + default: return MAV_ODID_UA_TYPE_OTHER; + } +} + +MAV_ODID_SPEED_ACC odidSpeedAccForVariance(float s_variance_m_s) +{ + // TODO: should this be stddev, so square root of variance? + // speed_accuracy + if (s_variance_m_s < 0.3f) { + return MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND; + + } else if (s_variance_m_s < 1.f) { + return MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND; + + } else if (s_variance_m_s < 3.f) { + return MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND; + + } else if (s_variance_m_s < 10.f) { + return MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND; + + } else { + return MAV_ODID_SPEED_ACC_UNKNOWN; + } +} + +MAV_ODID_HOR_ACC odidHorAccForEph(float eph) +{ + if (eph < 1.f) { + return MAV_ODID_HOR_ACC_1_METER; + + } else if (eph < 3.f) { + return MAV_ODID_HOR_ACC_3_METER; + + } else if (eph < 10.f) { + return MAV_ODID_HOR_ACC_10_METER; + + } else if (eph < 30.f) { + return MAV_ODID_HOR_ACC_30_METER; + + } else { + return MAV_ODID_HOR_ACC_UNKNOWN; + } +} + +MAV_ODID_VER_ACC odidVerAccForEpv(float epv) +{ + if (epv < 1.f) { + return MAV_ODID_VER_ACC_1_METER; + + } else if (epv < 3.f) { + return MAV_ODID_VER_ACC_3_METER; + + } else if (epv < 10.f) { + return MAV_ODID_VER_ACC_10_METER; + + } else if (epv < 25.f) { + return MAV_ODID_VER_ACC_25_METER; + + } else if (epv < 45.f) { + return MAV_ODID_VER_ACC_45_METER; + + } else if (epv < 150.f) { + return MAV_ODID_VER_ACC_150_METER; + + } else { + return MAV_ODID_VER_ACC_UNKNOWN; + } +} + + +MAV_ODID_TIME_ACC odidTimeForElapsed(uint64_t elapsed) +{ + if (elapsed < 100_ms) { + return MAV_ODID_TIME_ACC_0_1_SECOND; + + } else if (elapsed < 200_ms) { + return MAV_ODID_TIME_ACC_0_2_SECOND; + + } else if (elapsed < 300_ms) { + return MAV_ODID_TIME_ACC_0_3_SECOND; + + } else if (elapsed < 400_ms) { + return MAV_ODID_TIME_ACC_0_4_SECOND; + + } else if (elapsed < 500_ms) { + return MAV_ODID_TIME_ACC_0_5_SECOND; + + } else if (elapsed < 600_ms) { + return MAV_ODID_TIME_ACC_0_6_SECOND; + + } else if (elapsed < 700_ms) { + return MAV_ODID_TIME_ACC_0_7_SECOND; + + } else if (elapsed < 800_ms) { + return MAV_ODID_TIME_ACC_0_8_SECOND; + + } else if (elapsed < 900_ms) { + return MAV_ODID_TIME_ACC_0_9_SECOND; + + } else if (elapsed < 1000_ms) { + return MAV_ODID_TIME_ACC_1_0_SECOND; + + } else if (elapsed < 1100_ms) { + return MAV_ODID_TIME_ACC_1_1_SECOND; + + } else if (elapsed < 1200_ms) { + return MAV_ODID_TIME_ACC_1_2_SECOND; + + } else if (elapsed < 1300_ms) { + return MAV_ODID_TIME_ACC_1_3_SECOND; + + } else if (elapsed < 1400_ms) { + return MAV_ODID_TIME_ACC_1_4_SECOND; + + } else if (elapsed < 1500_ms) { + return MAV_ODID_TIME_ACC_1_5_SECOND; + + } else { + return MAV_ODID_TIME_ACC_UNKNOWN; + } +} + +} // open_drone_id_translations diff --git a/src/lib/open_drone_id/open_drone_id_translations.hpp b/src/lib/open_drone_id/open_drone_id_translations.hpp new file mode 100644 index 000000000000..4632ed1e14e6 --- /dev/null +++ b/src/lib/open_drone_id/open_drone_id_translations.hpp @@ -0,0 +1,52 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#pragma once + +#include +#include + +namespace open_drone_id_translations +{ + +MAV_ODID_UA_TYPE odidTypeForMavType(uint8_t system_type); + +MAV_ODID_SPEED_ACC odidSpeedAccForVariance(float s_variance_m_s); + +MAV_ODID_HOR_ACC odidHorAccForEph(float eph); + +MAV_ODID_VER_ACC odidVerAccForEpv(float epv); + +MAV_ODID_TIME_ACC odidTimeForElapsed(uint64_t elapsed); + +} // open_drone_id_translations diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index f42dd6fa9b7b..4a29a6eb0b34 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -135,6 +135,7 @@ px4_add_module( sensor_calibration geo mavlink_c + open_drone_id timesync tunes variable_length_ringbuffer diff --git a/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp b/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp index d7869dcbb6c9..dcc77c660a53 100644 --- a/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp +++ b/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp @@ -35,6 +35,7 @@ #define OPEN_DRONE_ID_BASIC_ID_HPP #include +#include class MavlinkStreamOpenDroneIdBasicId : public MavlinkStream { @@ -57,98 +58,6 @@ class MavlinkStreamOpenDroneIdBasicId : public MavlinkStream uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)}; - MAV_ODID_UA_TYPE odidTypeForMavType(uint8_t system_type) - { - switch (system_type) { - case MAV_TYPE_GENERIC: return MAV_ODID_UA_TYPE_OTHER; - - case MAV_TYPE_FIXED_WING: return MAV_ODID_UA_TYPE_AEROPLANE; - - case MAV_TYPE_QUADROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_COAXIAL: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_HELICOPTER: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_ANTENNA_TRACKER: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_GCS: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_AIRSHIP: return MAV_ODID_UA_TYPE_AIRSHIP; - - case MAV_TYPE_FREE_BALLOON: return MAV_ODID_UA_TYPE_FREE_BALLOON; - - case MAV_TYPE_ROCKET: return MAV_ODID_UA_TYPE_ROCKET; - - case MAV_TYPE_GROUND_ROVER: return MAV_ODID_UA_TYPE_GROUND_OBSTACLE; - - case MAV_TYPE_SURFACE_BOAT: return MAV_ODID_UA_TYPE_OTHER; - - case MAV_TYPE_SUBMARINE: return MAV_ODID_UA_TYPE_OTHER; - - case MAV_TYPE_HEXAROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_OCTOROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_TRICOPTER: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_FLAPPING_WING: return MAV_ODID_UA_TYPE_ORNITHOPTER; - - case MAV_TYPE_KITE: return MAV_ODID_UA_TYPE_KITE; - - case MAV_TYPE_ONBOARD_CONTROLLER: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_VTOL_TAILSITTER_DUOROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_TAILSITTER_QUADROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_TILTROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_FIXEDROTOR: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_TAILSITTER: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_TILTWING: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_VTOL_RESERVED5: return MAV_ODID_UA_TYPE_HYBRID_LIFT; - - case MAV_TYPE_GIMBAL: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_ADSB: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_PARAFOIL: return MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE; - - case MAV_TYPE_DODECAROTOR: return MAV_ODID_UA_TYPE_HELICOPTER_OR_MULTIROTOR; - - case MAV_TYPE_CAMERA: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_CHARGING_STATION: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_FLARM: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_SERVO: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_ODID: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_DECAROTOR: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_BATTERY: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_PARACHUTE: return MAV_ODID_UA_TYPE_FREE_FALL_PARACHUTE; - - case MAV_TYPE_LOG: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_OSD: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_IMU: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_GPS: return MAV_ODID_UA_TYPE_NONE; - - case MAV_TYPE_WINCH: return MAV_ODID_UA_TYPE_NONE; - - default: return MAV_ODID_UA_TYPE_OTHER; - } - } bool send() override @@ -167,7 +76,7 @@ class MavlinkStreamOpenDroneIdBasicId : public MavlinkStream msg.id_type = MAV_ODID_ID_TYPE_SERIAL_NUMBER; // ua_type: MAV_ODID_UA_TYPE - msg.ua_type = odidTypeForMavType(vehicle_status.system_type); + msg.ua_type = open_drone_id_translations::odidTypeForMavType(vehicle_status.system_type); // uas_id: UAS (Unmanned Aircraft System) ID following the format specified by id_type // TODO: MAV_ODID_ID_TYPE_SERIAL_NUMBER needs to be ANSI/CTA-2063 format diff --git a/src/modules/mavlink/streams/OPEN_DRONE_ID_LOCATION.hpp b/src/modules/mavlink/streams/OPEN_DRONE_ID_LOCATION.hpp index 3a519c5e909a..1eba926a3531 100644 --- a/src/modules/mavlink/streams/OPEN_DRONE_ID_LOCATION.hpp +++ b/src/modules/mavlink/streams/OPEN_DRONE_ID_LOCATION.hpp @@ -144,22 +144,7 @@ class MavlinkStreamOpenDroneIdLocation : public MavlinkStream const int speed_vertical_cm_s = roundf(-vel_ned(2) * 100.f); msg.speed_vertical = math::constrain(speed_vertical_cm_s, -6200, 6200); - // speed_accuracy - if (vehicle_gps_position.s_variance_m_s < 0.3f) { - msg.speed_accuracy = MAV_ODID_SPEED_ACC_0_3_METERS_PER_SECOND; - - } else if (vehicle_gps_position.s_variance_m_s < 1.f) { - msg.speed_accuracy = MAV_ODID_SPEED_ACC_1_METERS_PER_SECOND; - - } else if (vehicle_gps_position.s_variance_m_s < 3.f) { - msg.speed_accuracy = MAV_ODID_SPEED_ACC_3_METERS_PER_SECOND; - - } else if (vehicle_gps_position.s_variance_m_s < 10.f) { - msg.speed_accuracy = MAV_ODID_SPEED_ACC_10_METERS_PER_SECOND; - - } else { - msg.speed_accuracy = MAV_ODID_SPEED_ACC_UNKNOWN; - } + msg.speed_accuracy = open_drone_id_translations::odidSpeedAccForVariance(vehicle_gps_position.s_variance_m_s); updated = true; } @@ -173,45 +158,9 @@ class MavlinkStreamOpenDroneIdLocation : public MavlinkStream msg.altitude_geodetic = static_cast(round(vehicle_gps_position.altitude_msl_m)); // [m] } - // horizontal_accuracy - if (vehicle_gps_position.eph < 1.f) { - msg.horizontal_accuracy = MAV_ODID_HOR_ACC_1_METER; - - } else if (vehicle_gps_position.eph < 3.f) { - msg.horizontal_accuracy = MAV_ODID_HOR_ACC_3_METER; - - } else if (vehicle_gps_position.eph < 10.f) { - msg.horizontal_accuracy = MAV_ODID_HOR_ACC_10_METER; - - } else if (vehicle_gps_position.eph < 30.f) { - msg.horizontal_accuracy = MAV_ODID_HOR_ACC_30_METER; - - } else { - msg.horizontal_accuracy = MAV_ODID_HOR_ACC_UNKNOWN; - } - - // vertical_accuracy - if (vehicle_gps_position.epv < 1.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_1_METER; - - } else if (vehicle_gps_position.epv < 3.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_3_METER; - - } else if (vehicle_gps_position.epv < 10.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_10_METER; - - } else if (vehicle_gps_position.epv < 25.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_25_METER; + msg.horizontal_accuracy = open_drone_id_translations::odidHorAccForEph(vehicle_gps_position.eph); - } else if (vehicle_gps_position.epv < 45.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_45_METER; - - } else if (vehicle_gps_position.epv < 150.f) { - msg.vertical_accuracy = MAV_ODID_VER_ACC_150_METER; - - } else { - msg.vertical_accuracy = MAV_ODID_VER_ACC_UNKNOWN; - } + msg.vertical_accuracy = open_drone_id_translations::odidVerAccForEpv(vehicle_gps_position.epv); updated = true; } @@ -221,9 +170,8 @@ class MavlinkStreamOpenDroneIdLocation : public MavlinkStream uint64_t utc_time_msec = vehicle_gps_position.time_utc_usec / 1000; msg.timestamp = ((float)(utc_time_msec % (60 * 60 * 1000))) / 1000; - if (hrt_elapsed_time(&vehicle_gps_position.timestamp) < 1_s) { - msg.timestamp_accuracy = MAV_ODID_TIME_ACC_1_0_SECOND; // TODO - } + msg.timestamp_accuracy = open_drone_id_translations::odidTimeForElapsed(hrt_elapsed_time( + &vehicle_gps_position.timestamp)); updated = true; } @@ -236,7 +184,7 @@ class MavlinkStreamOpenDroneIdLocation : public MavlinkStream if (_vehicle_air_data_sub.copy(&vehicle_air_data) && (hrt_elapsed_time(&vehicle_air_data.timestamp) < 10_s)) { msg.altitude_barometric = vehicle_air_data.baro_alt_meter; - msg.barometer_accuracy = MAV_ODID_VER_ACC_150_METER; // TODO + msg.barometer_accuracy = MAV_ODID_VER_ACC_UNKNOWN; // We just don't without calibration. updated = true; } } From cf19764d75250fe2f4e6df64a67738f4e011e69b Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 3 May 2024 17:52:22 +1200 Subject: [PATCH 56/87] uavcan: implement OpenDroneID BasicID Signed-off-by: Julian Oes --- src/drivers/uavcan/CMakeLists.txt | 2 + src/drivers/uavcan/Kconfig | 4 ++ src/drivers/uavcan/remoteid.cpp | 73 ++++++++++++++++++++++++++++++ src/drivers/uavcan/remoteid.hpp | 73 ++++++++++++++++++++++++++++++ src/drivers/uavcan/rgbled.hpp | 2 +- src/drivers/uavcan/uavcan_main.cpp | 13 ++++++ src/drivers/uavcan/uavcan_main.hpp | 7 +++ 7 files changed, 173 insertions(+), 1 deletion(-) create mode 100644 src/drivers/uavcan/remoteid.cpp create mode 100644 src/drivers/uavcan/remoteid.hpp diff --git a/src/drivers/uavcan/CMakeLists.txt b/src/drivers/uavcan/CMakeLists.txt index c70d029ea7e3..f8bc1eea8a6a 100644 --- a/src/drivers/uavcan/CMakeLists.txt +++ b/src/drivers/uavcan/CMakeLists.txt @@ -147,6 +147,8 @@ px4_add_module( arming_status.hpp beep.cpp beep.hpp + remoteid.cpp + remoteid.hpp rgbled.cpp rgbled.hpp safety_state.cpp diff --git a/src/drivers/uavcan/Kconfig b/src/drivers/uavcan/Kconfig index 0076d36568f5..37306dabdfde 100644 --- a/src/drivers/uavcan/Kconfig +++ b/src/drivers/uavcan/Kconfig @@ -26,6 +26,10 @@ if DRIVERS_UAVCAN bool "Include safety state controller" default y + config UAVCAN_REMOTEID_CONTROLLER + bool "Include remote ID controller" + default y + config UAVCAN_RGB_CONTROLLER bool "Include rgb controller" default y diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp new file mode 100644 index 000000000000..7c8bc7f822cc --- /dev/null +++ b/src/drivers/uavcan/remoteid.cpp @@ -0,0 +1,73 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#include "remoteid.hpp" +#include + +UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) : + ModuleParams(nullptr), + _timer(node), + _node(node), + _uavcan_pub_remoteid_basicid(node) +{ +} + +int UavcanRemoteIDController::init() +{ + // Setup timer and call back function for periodic updates + _timer.setCallback(TimerCbBinder(this, &UavcanRemoteIDController::periodic_update)); + _timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ)); + return 0; +} + +void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) +{ + if (!_vehicle_status_sub.update()) { + return; + } + + dronecan::remoteid::BasicID basic_id {}; + // basic_id.id_or_mac // supposedly only used for drone ID data from other UAs + basic_id.id_type = dronecan::remoteid::BasicID::ODID_ID_TYPE_SERIAL_NUMBER; + basic_id.ua_type = static_cast(open_drone_id_translations::odidTypeForMavType( + _vehicle_status_sub.get().system_type)); + + // uas_id: UAS (Unmanned Aircraft System) ID following the format specified by id_type + // TODO: MAV_ODID_ID_TYPE_SERIAL_NUMBER needs to be ANSI/CTA-2063 format + + char uas_id[20] = {}; + board_get_px4_guid_formated((char *)(uas_id), sizeof(uas_id)); + basic_id.uas_id = uas_id; + + _uavcan_pub_remoteid_basicid.broadcast(basic_id); +} diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp new file mode 100644 index 000000000000..839a2f8cf2d5 --- /dev/null +++ b/src/drivers/uavcan/remoteid.hpp @@ -0,0 +1,73 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#pragma once + +#include +#include + +#include +#include + +#include + +class UavcanRemoteIDController : public ModuleParams +{ +public: + UavcanRemoteIDController(uavcan::INode &node); + ~UavcanRemoteIDController() = default; + + int init(); + +private: + typedef uavcan::MethodBinder + TimerCbBinder; + + static constexpr unsigned MAX_RATE_HZ = 1; + uavcan::TimerEventForwarder _timer; + + void periodic_update(const uavcan::TimerEvent &); + + uavcan::INode &_node; + + uORB::SubscriptionData _vehicle_status_sub{ORB_ID(vehicle_status)}; + + uavcan::Publisher _uavcan_pub_remoteid_basicid; + + //DEFINE_PARAMETERS( + // (ParamInt) _param_mode_anti_col, + // (ParamInt) _param_mode_strobe, + // (ParamInt) _param_mode_nav, + // (ParamInt) _param_mode_land + //) +}; diff --git a/src/drivers/uavcan/rgbled.hpp b/src/drivers/uavcan/rgbled.hpp index b1190214b111..be0bc876d38b 100644 --- a/src/drivers/uavcan/rgbled.hpp +++ b/src/drivers/uavcan/rgbled.hpp @@ -51,7 +51,7 @@ class UavcanRGBController : public ModuleParams int init(); private: - // Max update rate to avoid exessive bus traffic + // Max update rate to avoid excessive bus traffic static constexpr unsigned MAX_RATE_HZ = 20; void periodic_update(const uavcan::TimerEvent &); diff --git a/src/drivers/uavcan/uavcan_main.cpp b/src/drivers/uavcan/uavcan_main.cpp index fbdc534a9c30..87f3110cac7d 100644 --- a/src/drivers/uavcan/uavcan_main.cpp +++ b/src/drivers/uavcan/uavcan_main.cpp @@ -96,6 +96,9 @@ UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &sys #if defined(CONFIG_UAVCAN_SAFETY_STATE_CONTROLLER) _safety_state_controller(_node), #endif +#if defined(CONFIG_UAVCAN_REMOTEID_CONTROLLER) + _remoteid_controller(_node), +#endif #if defined(CONFIG_UAVCAN_RGB_CONTROLLER) _rgbled_controller(_node), #endif @@ -558,6 +561,16 @@ UavcanNode::init(uavcan::NodeID node_id, UAVCAN_DRIVER::BusEvent &bus_events) return ret; } +#if defined(CONFIG_UAVCAN_REMOTEID_CONTROLLER) + ret = _remoteid_controller.init(); + + if (ret < 0) { + return ret; + } + +#endif + + #if defined(CONFIG_UAVCAN_RGB_CONTROLLER) ret = _rgbled_controller.init(); diff --git a/src/drivers/uavcan/uavcan_main.hpp b/src/drivers/uavcan/uavcan_main.hpp index 5afa04ef672e..d249e5d838cc 100644 --- a/src/drivers/uavcan/uavcan_main.hpp +++ b/src/drivers/uavcan/uavcan_main.hpp @@ -68,6 +68,10 @@ #include "logmessage.hpp" +#if defined(CONFIG_UAVCAN_REMOTEID_CONTROLLER) +#include "remoteid.hpp" +#endif + #if defined(CONFIG_UAVCAN_RGB_CONTROLLER) #include "rgbled.hpp" #endif @@ -269,6 +273,9 @@ class UavcanNode : public px4::ScheduledWorkItem, public ModuleParams #if defined(CONFIG_UAVCAN_SAFETY_STATE_CONTROLLER) UavcanSafetyState _safety_state_controller; #endif +#if defined(CONFIG_UAVCAN_REMOTEID_CONTROLLER) + UavcanRemoteIDController _remoteid_controller; +#endif #if defined(CONFIG_UAVCAN_RGB_CONTROLLER) UavcanRGBController _rgbled_controller; #endif From de00c23e1935c9811b9d2535c220d7a9db7ed6c8 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Wed, 10 Jul 2024 13:56:19 +1200 Subject: [PATCH 57/87] uavcan: implement OpenDroneID Location --- src/drivers/uavcan/remoteid.cpp | 157 +++++++++++++++++++++++++++++++- src/drivers/uavcan/remoteid.hpp | 24 +++-- 2 files changed, 168 insertions(+), 13 deletions(-) diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 7c8bc7f822cc..987f89a97939 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -33,12 +33,17 @@ #include "remoteid.hpp" #include +#include + +using namespace time_literals; + UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) : ModuleParams(nullptr), _timer(node), _node(node), - _uavcan_pub_remoteid_basicid(node) + _uavcan_pub_remoteid_basicid(node), + _uavcan_pub_remoteid_location(node) { } @@ -52,15 +57,19 @@ int UavcanRemoteIDController::init() void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) { - if (!_vehicle_status_sub.update()) { - return; - } + _vehicle_status.update(); + send_basic_id(); + send_location(); +} + +void UavcanRemoteIDController::send_basic_id() +{ dronecan::remoteid::BasicID basic_id {}; // basic_id.id_or_mac // supposedly only used for drone ID data from other UAs basic_id.id_type = dronecan::remoteid::BasicID::ODID_ID_TYPE_SERIAL_NUMBER; basic_id.ua_type = static_cast(open_drone_id_translations::odidTypeForMavType( - _vehicle_status_sub.get().system_type)); + _vehicle_status.get().system_type)); // uas_id: UAS (Unmanned Aircraft System) ID following the format specified by id_type // TODO: MAV_ODID_ID_TYPE_SERIAL_NUMBER needs to be ANSI/CTA-2063 format @@ -71,3 +80,141 @@ void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) _uavcan_pub_remoteid_basicid.broadcast(basic_id); } + +void UavcanRemoteIDController::send_location() +{ + dronecan::remoteid::Location msg {}; + + // initialize all fields to unknown + msg.status = MAV_ODID_STATUS_UNDECLARED; + msg.direction = 36100; // If unknown: 36100 centi-degrees + msg.speed_horizontal = 25500; // If unknown: 25500 cm/s + msg.speed_vertical = 6300; // If unknown: 6300 cm/s + msg.latitude = 0; // If unknown: 0 + msg.longitude = 0; // If unknown: 0 + msg.altitude_geodetic = -1000; // If unknown: -1000 m + msg.altitude_geodetic = -1000; // If unknown: -1000 m + msg.height = -1000; // If unknown: -1000 m + msg.horizontal_accuracy = MAV_ODID_HOR_ACC_UNKNOWN; + msg.vertical_accuracy = MAV_ODID_VER_ACC_UNKNOWN; + msg.barometer_accuracy = MAV_ODID_VER_ACC_UNKNOWN; + msg.speed_accuracy = MAV_ODID_SPEED_ACC_UNKNOWN; + msg.timestamp = 0xFFFF; // If unknown: 0xFFFF + msg.timestamp_accuracy = MAV_ODID_TIME_ACC_UNKNOWN; + + bool updated = false; + + if (_vehicle_land_detected_sub.advertised()) { + vehicle_land_detected_s vehicle_land_detected{}; + + if (_vehicle_land_detected_sub.copy(&vehicle_land_detected) + && (hrt_elapsed_time(&vehicle_land_detected.timestamp) < 10_s)) { + if (vehicle_land_detected.landed) { + msg.status = MAV_ODID_STATUS_GROUND; + + } else { + msg.status = MAV_ODID_STATUS_AIRBORNE; + } + + updated = true; + } + } + + if (hrt_elapsed_time(&_vehicle_status.get().timestamp) < 10_s) { + if (_vehicle_status.get().failsafe && (_vehicle_status.get().arming_state == vehicle_status_s::ARMING_STATE_ARMED)) { + msg.status = MAV_ODID_STATUS_EMERGENCY; + updated = true; + } + } + + if (_vehicle_gps_position_sub.advertised()) { + sensor_gps_s vehicle_gps_position{}; + + if (_vehicle_gps_position_sub.copy(&vehicle_gps_position) + && (hrt_elapsed_time(&vehicle_gps_position.timestamp) < 10_s)) { + + if (vehicle_gps_position.vel_ned_valid) { + const matrix::Vector3f vel_ned{vehicle_gps_position.vel_n_m_s, vehicle_gps_position.vel_e_m_s, vehicle_gps_position.vel_d_m_s}; + + // direction: calculate GPS course over ground angle + const float course = atan2f(vel_ned(1), vel_ned(0)); + const int course_deg = roundf(math::degrees(matrix::wrap_2pi(course))); + msg.direction = math::constrain(100 * course_deg, 0, 35999); // 0 - 35999 centi-degrees + + // speed_horizontal: If speed is larger than 25425 cm/s, use 25425 cm/s. + const int speed_horizontal_cm_s = matrix::Vector2f(vel_ned).length() * 100.f; + msg.speed_horizontal = math::constrain(speed_horizontal_cm_s, 0, 25425); + + // speed_vertical: Up is positive, If speed is larger than 6200 cm/s, use 6200 cm/s. If lower than -6200 cm/s, use -6200 cm/s. + const int speed_vertical_cm_s = roundf(-vel_ned(2) * 100.f); + msg.speed_vertical = math::constrain(speed_vertical_cm_s, -6200, 6200); + + msg.speed_accuracy = open_drone_id_translations::odidSpeedAccForVariance(vehicle_gps_position.s_variance_m_s); + + updated = true; + } + + if (vehicle_gps_position.fix_type >= 2) { + msg.latitude = static_cast(round(vehicle_gps_position.latitude_deg * 1e7)); + msg.longitude = static_cast(round(vehicle_gps_position.longitude_deg * 1e7)); + + // altitude_geodetic + if (vehicle_gps_position.fix_type >= 3) { + msg.altitude_geodetic = static_cast(round(vehicle_gps_position.altitude_msl_m)); // [m] + } + + msg.horizontal_accuracy = open_drone_id_translations::odidHorAccForEph(vehicle_gps_position.eph); + + msg.vertical_accuracy = open_drone_id_translations::odidVerAccForEpv(vehicle_gps_position.epv); + + updated = true; + } + + if (vehicle_gps_position.time_utc_usec != 0) { + // timestamp: UTC then convert for this field using ((float) (time_week_ms % (60*60*1000))) / 1000 + uint64_t utc_time_msec = vehicle_gps_position.time_utc_usec / 1000; + msg.timestamp = ((float)(utc_time_msec % (60 * 60 * 1000))) / 1000; + + msg.timestamp_accuracy = open_drone_id_translations::odidTimeForElapsed(hrt_elapsed_time( + &vehicle_gps_position.timestamp)); + + updated = true; + } + } + } + + // altitude_barometric: The altitude calculated from the barometric pressue + if (_vehicle_air_data_sub.advertised()) { + vehicle_air_data_s vehicle_air_data{}; + + if (_vehicle_air_data_sub.copy(&vehicle_air_data) && (hrt_elapsed_time(&vehicle_air_data.timestamp) < 10_s)) { + msg.altitude_barometric = vehicle_air_data.baro_alt_meter; + msg.barometer_accuracy = MAV_ODID_VER_ACC_UNKNOWN; // We just don't without calibration. + updated = true; + } + } + + // height: The current height of the unmanned aircraft above the take-off location or the ground as indicated by height_reference + if (_home_position_sub.advertised() && _vehicle_local_position_sub.updated()) { + home_position_s home_position{}; + vehicle_local_position_s vehicle_local_position{}; + + if (_home_position_sub.copy(&home_position) + && _vehicle_local_position_sub.copy(&vehicle_local_position) + && (hrt_elapsed_time(&vehicle_local_position.timestamp) < 1_s) + ) { + + if (home_position.valid_alt && vehicle_local_position.z_valid && vehicle_local_position.z_global) { + float altitude = (-vehicle_local_position.z + vehicle_local_position.ref_alt); + + msg.height = altitude - home_position.alt; + msg.height_reference = MAV_ODID_HEIGHT_REF_OVER_TAKEOFF; + updated = true; + } + } + } + + if (updated) { + _uavcan_pub_remoteid_location.broadcast(msg); + } +} diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp index 839a2f8cf2d5..8657ae476242 100644 --- a/src/drivers/uavcan/remoteid.hpp +++ b/src/drivers/uavcan/remoteid.hpp @@ -33,11 +33,17 @@ #pragma once +#include #include +#include +#include +#include +#include #include #include #include +#include #include @@ -58,16 +64,18 @@ class UavcanRemoteIDController : public ModuleParams void periodic_update(const uavcan::TimerEvent &); + void send_basic_id(); + void send_location(); + uavcan::INode &_node; - uORB::SubscriptionData _vehicle_status_sub{ORB_ID(vehicle_status)}; + uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)}; + uORB::SubscriptionData _vehicle_status{ORB_ID(vehicle_status)}; + uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)}; + uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)}; + uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; + uORB::Subscription _home_position_sub{ORB_ID(home_position)}; uavcan::Publisher _uavcan_pub_remoteid_basicid; - - //DEFINE_PARAMETERS( - // (ParamInt) _param_mode_anti_col, - // (ParamInt) _param_mode_strobe, - // (ParamInt) _param_mode_nav, - // (ParamInt) _param_mode_land - //) + uavcan::Publisher _uavcan_pub_remoteid_location; }; From d999258171d07d14cf2a42cf3b5471f0f0de4197 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 11 Jul 2024 11:06:00 +1200 Subject: [PATCH 58/87] uavcan: implement OpenDroneID System --- src/drivers/uavcan/remoteid.cpp | 38 ++++++++++++++++++++++++++++++++- src/drivers/uavcan/remoteid.hpp | 3 +++ 2 files changed, 40 insertions(+), 1 deletion(-) diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 987f89a97939..6e8bdcebeac8 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -43,7 +43,8 @@ UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) : _timer(node), _node(node), _uavcan_pub_remoteid_basicid(node), - _uavcan_pub_remoteid_location(node) + _uavcan_pub_remoteid_location(node), + _uavcan_pub_remoteid_system(node) { } @@ -61,6 +62,7 @@ void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) send_basic_id(); send_location(); + send_system(); } void UavcanRemoteIDController::send_basic_id() @@ -218,3 +220,37 @@ void UavcanRemoteIDController::send_location() _uavcan_pub_remoteid_location.broadcast(msg); } } + +void UavcanRemoteIDController::send_system() +{ + sensor_gps_s vehicle_gps_position; + home_position_s home_position; + + if (_vehicle_gps_position_sub.copy(&vehicle_gps_position) && _home_position_sub.copy(&home_position)) { + if (vehicle_gps_position.fix_type >= 3 + && home_position.valid_alt && home_position.valid_hpos) { + + dronecan::remoteid::System msg {}; + + // msg.id_or_mac // Only used for drone ID data received from other UAs. + msg.operator_location_type = MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF; + msg.classification_type = MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED; + msg.operator_latitude = home_position.lat * 1e7; + msg.operator_longitude = home_position.lon * 1e7; + msg.area_count = 1; + msg.area_radius = 0; + msg.area_ceiling = -1000; + msg.area_floor = -1000; + msg.category_eu = MAV_ODID_CATEGORY_EU_UNDECLARED; + msg.class_eu = MAV_ODID_CLASS_EU_UNDECLARED; + float wgs84_amsl_offset = vehicle_gps_position.altitude_ellipsoid_m - vehicle_gps_position.altitude_msl_m; + msg.operator_altitude_geo = home_position.alt + wgs84_amsl_offset; + + // timestamp: 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. + static uint64_t utc_offset_s = 1'546'300'800; // UTC seconds since 00:00:00 01/01/2019 + msg.timestamp = vehicle_gps_position.time_utc_usec / 1e6 - utc_offset_s; + + _uavcan_pub_remoteid_system.broadcast(msg); + } + } +} diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp index 8657ae476242..3d35e5095997 100644 --- a/src/drivers/uavcan/remoteid.hpp +++ b/src/drivers/uavcan/remoteid.hpp @@ -44,6 +44,7 @@ #include #include #include +#include #include @@ -66,6 +67,7 @@ class UavcanRemoteIDController : public ModuleParams void send_basic_id(); void send_location(); + void send_system(); uavcan::INode &_node; @@ -78,4 +80,5 @@ class UavcanRemoteIDController : public ModuleParams uavcan::Publisher _uavcan_pub_remoteid_basicid; uavcan::Publisher _uavcan_pub_remoteid_location; + uavcan::Publisher _uavcan_pub_remoteid_system; }; From 04ea4f9b3a92da7c33d044cc02a046929b0f8efa Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 11 Jul 2024 14:36:54 +1200 Subject: [PATCH 59/87] uavcan: add OpenDroneID ArmStatus, operator ID In order to have operator ID be sent by QGC, we need to forward ArmStatus from the remote ID module (here on DroneCAN) to MAVLink. --- msg/CMakeLists.txt | 2 + msg/OpenDroneIdArmStatus.msg | 3 + msg/OpenDroneIdOperatorId.msg | 4 + src/drivers/uavcan/remoteid.cpp | 47 ++++++++- src/drivers/uavcan/remoteid.hpp | 18 +++- src/modules/mavlink/mavlink_main.cpp | 4 + src/modules/mavlink/mavlink_messages.cpp | 4 + src/modules/mavlink/mavlink_receiver.cpp | 21 ++++ src/modules/mavlink/mavlink_receiver.h | 5 + .../streams/OPEN_DRONE_ID_ARM_STATUS.hpp | 99 +++++++++++++++++++ 10 files changed, 205 insertions(+), 2 deletions(-) create mode 100644 msg/OpenDroneIdArmStatus.msg create mode 100644 msg/OpenDroneIdOperatorId.msg create mode 100644 src/modules/mavlink/streams/OPEN_DRONE_ID_ARM_STATUS.hpp diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index dce7e851dca9..0585df1ac54d 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -152,6 +152,8 @@ set(msg_files ObstacleDistance.msg OffboardControlMode.msg OnboardComputerStatus.msg + OpenDroneIdArmStatus.msg + OpenDroneIdOperatorId.msg OrbitStatus.msg OrbTest.msg OrbTestLarge.msg diff --git a/msg/OpenDroneIdArmStatus.msg b/msg/OpenDroneIdArmStatus.msg new file mode 100644 index 000000000000..1fa58c6a1f26 --- /dev/null +++ b/msg/OpenDroneIdArmStatus.msg @@ -0,0 +1,3 @@ +uint64 timestamp +uint8 status +char[50] error diff --git a/msg/OpenDroneIdOperatorId.msg b/msg/OpenDroneIdOperatorId.msg new file mode 100644 index 000000000000..0f78a47e5a8d --- /dev/null +++ b/msg/OpenDroneIdOperatorId.msg @@ -0,0 +1,4 @@ +uint64 timestamp +uint8[20] id_or_mac +uint8 operator_id_type +char[20] operator_id diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 6e8bdcebeac8..01c68aa94427 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -44,7 +44,9 @@ UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) : _node(node), _uavcan_pub_remoteid_basicid(node), _uavcan_pub_remoteid_location(node), - _uavcan_pub_remoteid_system(node) + _uavcan_pub_remoteid_system(node), + _uavcan_pub_remoteid_operator_id(node), + _uavcan_sub_arm_status(node) { } @@ -53,6 +55,14 @@ int UavcanRemoteIDController::init() // Setup timer and call back function for periodic updates _timer.setCallback(TimerCbBinder(this, &UavcanRemoteIDController::periodic_update)); _timer.startPeriodic(uavcan::MonotonicDuration::fromMSec(1000 / MAX_RATE_HZ)); + + int res = _uavcan_sub_arm_status.start(ArmStatusBinder(this, &UavcanRemoteIDController::arm_status_sub_cb)); + + if (res < 0) { + PX4_WARN("ArmStatus sub failed %i", res); + return res; + } + return 0; } @@ -63,6 +73,7 @@ void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) send_basic_id(); send_location(); send_system(); + send_operator_id(); } void UavcanRemoteIDController::send_basic_id() @@ -254,3 +265,37 @@ void UavcanRemoteIDController::send_system() } } } + +void UavcanRemoteIDController::send_operator_id() +{ + open_drone_id_operator_id_s operator_id; + + if (_open_drone_id_operator_id.copy(&operator_id)) { + + dronecan::remoteid::OperatorID msg {}; + + for (unsigned i = 0; i < sizeof(operator_id.id_or_mac); ++i) { + msg.id_or_mac.push_back(operator_id.id_or_mac[i]); + } + + msg.operator_id_type = operator_id.operator_id_type; + + for (unsigned i = 0; i < sizeof(operator_id.operator_id); ++i) { + msg.operator_id.push_back(operator_id.operator_id[i]); + } + + _uavcan_pub_remoteid_operator_id.broadcast(msg); + } +} + +void +UavcanRemoteIDController::arm_status_sub_cb(const uavcan::ReceivedDataStructure &msg) +{ + open_drone_id_arm_status_s arm_status{}; + + arm_status.timestamp = hrt_absolute_time(); + arm_status.status = msg.status; + memcpy(arm_status.error, msg.error.c_str(), sizeof(arm_status.error)); + + _open_drone_id_arm_status_pub.publish(arm_status); +} diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp index 3d35e5095997..d78f365be653 100644 --- a/src/drivers/uavcan/remoteid.hpp +++ b/src/drivers/uavcan/remoteid.hpp @@ -33,18 +33,23 @@ #pragma once +#include +#include #include #include #include #include #include #include -#include +#include +#include #include #include #include #include +#include +#include #include @@ -68,6 +73,9 @@ class UavcanRemoteIDController : public ModuleParams void send_basic_id(); void send_location(); void send_system(); + void send_operator_id(); + + void arm_status_sub_cb(const uavcan::ReceivedDataStructure &msg); uavcan::INode &_node; @@ -77,8 +85,16 @@ class UavcanRemoteIDController : public ModuleParams uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)}; uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _home_position_sub{ORB_ID(home_position)}; + uORB::Subscription _open_drone_id_operator_id{ORB_ID(open_drone_id_operator_id)}; + uORB::Publication _open_drone_id_arm_status_pub{ORB_ID(open_drone_id_arm_status)}; uavcan::Publisher _uavcan_pub_remoteid_basicid; uavcan::Publisher _uavcan_pub_remoteid_location; uavcan::Publisher _uavcan_pub_remoteid_system; + uavcan::Publisher _uavcan_pub_remoteid_operator_id; + + using ArmStatusBinder = uavcan::MethodBinder < UavcanRemoteIDController *, + void (UavcanRemoteIDController::*)(const uavcan::ReceivedDataStructure &) >; + + uavcan::Subscriber _uavcan_sub_arm_status; }; diff --git a/src/modules/mavlink/mavlink_main.cpp b/src/modules/mavlink/mavlink_main.cpp index 54e1a8549eeb..e0a4a9c2baa6 100644 --- a/src/modules/mavlink/mavlink_main.cpp +++ b/src/modules/mavlink/mavlink_main.cpp @@ -1429,6 +1429,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("OBSTACLE_DISTANCE", 1.0f); configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f); configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f); + configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f); configure_stream_local("ORBIT_EXECUTION_STATUS", 2.0f); configure_stream_local("PING", 0.1f); configure_stream_local("POSITION_TARGET_GLOBAL_INT", 1.0f); @@ -1498,6 +1499,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f); configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f); configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f); + configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f); configure_stream_local("OPTICAL_FLOW_RAD", 10.0f); configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f); configure_stream_local("PING", 1.0f); @@ -1666,6 +1668,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("NAV_CONTROLLER_OUTPUT", 10.0f); configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f); configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f); + configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f); configure_stream_local("OPTICAL_FLOW_RAD", 10.0f); configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f); configure_stream_local("PING", 1.0f); @@ -1758,6 +1761,7 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream) configure_stream_local("NAV_CONTROLLER_OUTPUT", 1.5f); configure_stream_local("OPEN_DRONE_ID_LOCATION", 1.f); configure_stream_local("OPEN_DRONE_ID_SYSTEM", 1.f); + configure_stream_local("OPEN_DRONE_ID_ARM_STATUS", 1.f); configure_stream_local("OPTICAL_FLOW_RAD", 1.0f); configure_stream_local("ORBIT_EXECUTION_STATUS", 5.0f); configure_stream_local("PING", 0.1f); diff --git a/src/modules/mavlink/mavlink_messages.cpp b/src/modules/mavlink/mavlink_messages.cpp index 638de9cce5f4..60f021a5b126 100644 --- a/src/modules/mavlink/mavlink_messages.cpp +++ b/src/modules/mavlink/mavlink_messages.cpp @@ -97,6 +97,7 @@ #include "streams/OPEN_DRONE_ID_BASIC_ID.hpp" #include "streams/OPEN_DRONE_ID_LOCATION.hpp" #include "streams/OPEN_DRONE_ID_SYSTEM.hpp" +#include "streams/OPEN_DRONE_ID_ARM_STATUS.hpp" #include "streams/OPTICAL_FLOW_RAD.hpp" #include "streams/ORBIT_EXECUTION_STATUS.hpp" #include "streams/PING.hpp" @@ -457,6 +458,9 @@ static const StreamListItem streams_list[] = { #if defined(OPEN_DRONE_ID_SYSTEM_HPP) create_stream_list_item(), #endif // OPEN_DRONE_ID_SYSTEM_HPP +#if defined(OPEN_DRONE_ID_ARM_STATUS_HPP) + create_stream_list_item(), +#endif // OPEN_DRONE_ID_ARM_STATUS_HPP #if defined(ESC_INFO_HPP) create_stream_list_item(), #endif // ESC_INFO_HPP diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 58d2c044ccd0..f54f9c158c86 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -280,6 +280,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) handle_message_statustext(msg); break; + case MAVLINK_MSG_ID_OPEN_DRONE_ID_OPERATOR_ID: + handle_message_open_drone_id_operator_id(msg); + break; + #if !defined(CONSTRAINED_FLASH) case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: @@ -3084,6 +3088,23 @@ MavlinkReceiver::handle_message_gimbal_device_attitude_status(mavlink_message_t _gimbal_device_attitude_status_pub.publish(gimbal_attitude_status); } +void MavlinkReceiver::handle_message_open_drone_id_operator_id( + mavlink_message_t *msg) +{ + mavlink_open_drone_id_operator_id_t odid_module; + mavlink_msg_open_drone_id_operator_id_decode(msg, &odid_module); + + open_drone_id_operator_id_s odid_operator_id{}; + memset(&odid_operator_id, 0, sizeof(odid_operator_id)); + + odid_operator_id.timestamp = hrt_absolute_time(); + memcpy(odid_operator_id.id_or_mac, odid_module.id_or_mac, sizeof(odid_operator_id.id_or_mac)); + odid_operator_id.operator_id_type = odid_module.operator_id_type; + memcpy(odid_operator_id.operator_id, odid_module.operator_id, sizeof(odid_operator_id.operator_id)); + + _open_drone_id_operator_id_pub.publish(odid_operator_id); +} + void MavlinkReceiver::run() { diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index b95bdca59a72..acea50284124 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -87,6 +87,7 @@ #include #include #include +#include #include #include #include @@ -182,6 +183,9 @@ class MavlinkReceiver : public ModuleParams void handle_message_obstacle_distance(mavlink_message_t *msg); void handle_message_odometry(mavlink_message_t *msg); void handle_message_onboard_computer_status(mavlink_message_t *msg); + void handle_message_open_drone_id_operator_id(mavlink_message_t *msg); + void handle_message_open_drone_id_self_id(mavlink_message_t *msg); + void handle_message_open_drone_id_system(mavlink_message_t *msg); void handle_message_optical_flow_rad(mavlink_message_t *msg); void handle_message_ping(mavlink_message_t *msg); void handle_message_play_tune(mavlink_message_t *msg); @@ -312,6 +316,7 @@ class MavlinkReceiver : public ModuleParams uORB::Publication _offboard_control_mode_pub{ORB_ID(offboard_control_mode)}; uORB::Publication _onboard_computer_status_pub{ORB_ID(onboard_computer_status)}; uORB::Publication _velocity_limits_pub{ORB_ID(velocity_limits)}; + uORB::Publication _open_drone_id_operator_id_pub{ORB_ID(open_drone_id_operator_id)}; uORB::Publication _generator_status_pub{ORB_ID(generator_status)}; uORB::Publication _attitude_pub{ORB_ID(vehicle_attitude)}; uORB::Publication _att_sp_pub{ORB_ID(vehicle_attitude_setpoint)}; diff --git a/src/modules/mavlink/streams/OPEN_DRONE_ID_ARM_STATUS.hpp b/src/modules/mavlink/streams/OPEN_DRONE_ID_ARM_STATUS.hpp new file mode 100644 index 000000000000..691ea3645533 --- /dev/null +++ b/src/modules/mavlink/streams/OPEN_DRONE_ID_ARM_STATUS.hpp @@ -0,0 +1,99 @@ +/**************************************************************************** + * + * 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. + * + ****************************************************************************/ + +#ifndef OPEN_DRONE_ID_ARM_STATUS_HPP +#define OPEN_DRONE_ID_ARM_STATUS_HPP + +#include + +class MavlinkStreamOpenDroneIdArmStatus : public MavlinkStream +{ +public: + static MavlinkStream *new_instance(Mavlink *mavlink) + { + return new MavlinkStreamOpenDroneIdArmStatus(mavlink); + } + + static constexpr const char *get_name_static() + { + return "OPEN_DRONE_ID_ARM_STATUS"; + } + static constexpr uint16_t get_id_static() + { + return MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS; + } + + const char *get_name() const override { return get_name_static(); } + uint16_t get_id() override { return get_id_static(); } + + unsigned get_size() override + { + return _open_drone_id_arm_status_sub.advertised() + ? MAVLINK_MSG_ID_OPEN_DRONE_ID_ARM_STATUS_LEN + + MAVLINK_NUM_NON_PAYLOAD_BYTES + : 0; + } + +private: + explicit MavlinkStreamOpenDroneIdArmStatus(Mavlink *mavlink) + : MavlinkStream(mavlink) {} + + uORB::Subscription _open_drone_id_arm_status_sub{ORB_ID(open_drone_id_arm_status)}; + + bool send() override + { + open_drone_id_arm_status_s drone_id_arm; + + if (_open_drone_id_arm_status_sub.update(&drone_id_arm)) { + + mavlink_open_drone_id_arm_status_t msg{}; + + msg.status = drone_id_arm.status; + + for (uint8_t i = 0; i < sizeof(drone_id_arm.error); ++i) { + + msg.error[i] = drone_id_arm.error[i]; + + } + + mavlink_msg_open_drone_id_arm_status_send_struct(_mavlink->get_channel(), + &msg); + + return true; + } + + return false; + } +}; + +#endif // OPEN_DRONE_ID_ARM_STATUS_HPP From 7d1d3989840fe0219e4d2ec8d8537ec4ad09fddd Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 19 Jul 2024 14:12:22 +1200 Subject: [PATCH 60/87] remoteid: add SelfID message --- msg/CMakeLists.txt | 1 + msg/OpenDroneIdSelfId.msg | 4 ++++ src/drivers/uavcan/remoteid.cpp | 24 ++++++++++++++++++++++++ src/drivers/uavcan/remoteid.hpp | 5 +++++ src/modules/mavlink/mavlink_receiver.cpp | 20 ++++++++++++++++++++ src/modules/mavlink/mavlink_receiver.h | 2 ++ 6 files changed, 56 insertions(+) create mode 100644 msg/OpenDroneIdSelfId.msg diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index 0585df1ac54d..f7465fdc002e 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -154,6 +154,7 @@ set(msg_files OnboardComputerStatus.msg OpenDroneIdArmStatus.msg OpenDroneIdOperatorId.msg + OpenDroneIdSelfId.msg OrbitStatus.msg OrbTest.msg OrbTestLarge.msg diff --git a/msg/OpenDroneIdSelfId.msg b/msg/OpenDroneIdSelfId.msg new file mode 100644 index 000000000000..1ff699ebf142 --- /dev/null +++ b/msg/OpenDroneIdSelfId.msg @@ -0,0 +1,4 @@ +uint64 timestamp +uint8[20] id_or_mac +uint8 description_type +char[23] description diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 01c68aa94427..6f66ba94cece 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -44,6 +44,7 @@ UavcanRemoteIDController::UavcanRemoteIDController(uavcan::INode &node) : _node(node), _uavcan_pub_remoteid_basicid(node), _uavcan_pub_remoteid_location(node), + _uavcan_pub_remoteid_self_id(node), _uavcan_pub_remoteid_system(node), _uavcan_pub_remoteid_operator_id(node), _uavcan_sub_arm_status(node) @@ -72,6 +73,7 @@ void UavcanRemoteIDController::periodic_update(const uavcan::TimerEvent &) send_basic_id(); send_location(); + send_self_id(); send_system(); send_operator_id(); } @@ -266,6 +268,28 @@ void UavcanRemoteIDController::send_system() } } +void UavcanRemoteIDController::send_self_id() +{ + open_drone_id_self_id_s self_id; + + if (_open_drone_id_self_id.copy(&self_id)) { + + dronecan::remoteid::SelfID msg {}; + + for (unsigned i = 0; i < sizeof(self_id.id_or_mac); ++i) { + msg.id_or_mac.push_back(self_id.id_or_mac[i]); + } + + msg.description_type = self_id.description_type; + + for (unsigned i = 0; i < sizeof(self_id.description); ++i) { + msg.description.push_back(self_id.description[i]); + } + + _uavcan_pub_remoteid_self_id.broadcast(msg); + } +} + void UavcanRemoteIDController::send_operator_id() { open_drone_id_operator_id_s operator_id; diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp index d78f365be653..eb9bffd6c0e4 100644 --- a/src/drivers/uavcan/remoteid.hpp +++ b/src/drivers/uavcan/remoteid.hpp @@ -43,10 +43,12 @@ #include #include #include +#include #include #include #include +#include #include #include #include @@ -72,6 +74,7 @@ class UavcanRemoteIDController : public ModuleParams void send_basic_id(); void send_location(); + void send_self_id(); void send_system(); void send_operator_id(); @@ -86,10 +89,12 @@ class UavcanRemoteIDController : public ModuleParams uORB::Subscription _vehicle_local_position_sub{ORB_ID(vehicle_local_position)}; uORB::Subscription _home_position_sub{ORB_ID(home_position)}; uORB::Subscription _open_drone_id_operator_id{ORB_ID(open_drone_id_operator_id)}; + uORB::Subscription _open_drone_id_self_id{ORB_ID(open_drone_id_self_id)}; uORB::Publication _open_drone_id_arm_status_pub{ORB_ID(open_drone_id_arm_status)}; uavcan::Publisher _uavcan_pub_remoteid_basicid; uavcan::Publisher _uavcan_pub_remoteid_location; + uavcan::Publisher _uavcan_pub_remoteid_self_id; uavcan::Publisher _uavcan_pub_remoteid_system; uavcan::Publisher _uavcan_pub_remoteid_operator_id; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index f54f9c158c86..6e13f3c0ea49 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -284,6 +284,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) handle_message_open_drone_id_operator_id(msg); break; + case MAVLINK_MSG_ID_OPEN_DRONE_ID_SELF_ID: + handle_message_open_drone_id_self_id(msg); + break; + #if !defined(CONSTRAINED_FLASH) case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: @@ -3105,6 +3109,22 @@ void MavlinkReceiver::handle_message_open_drone_id_operator_id( _open_drone_id_operator_id_pub.publish(odid_operator_id); } +void MavlinkReceiver::handle_message_open_drone_id_self_id(mavlink_message_t *msg) +{ + mavlink_open_drone_id_self_id_t odid_module; + mavlink_msg_open_drone_id_self_id_decode(msg, &odid_module); + + open_drone_id_self_id_s odid_self_id{}; + memset(&odid_self_id, 0, sizeof(odid_self_id)); + + odid_self_id.timestamp = hrt_absolute_time(); + memcpy(odid_self_id.id_or_mac, odid_module.id_or_mac, sizeof(odid_self_id.id_or_mac)); + odid_self_id.description_type = odid_module.description_type; + memcpy(odid_self_id.description, odid_module.description, sizeof(odid_self_id.description)); + + _open_drone_id_self_id_pub.publish(odid_self_id); +} + void MavlinkReceiver::run() { diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index acea50284124..4fa143475add 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -88,6 +88,7 @@ #include #include #include +#include #include #include #include @@ -317,6 +318,7 @@ class MavlinkReceiver : public ModuleParams uORB::Publication _onboard_computer_status_pub{ORB_ID(onboard_computer_status)}; uORB::Publication _velocity_limits_pub{ORB_ID(velocity_limits)}; uORB::Publication _open_drone_id_operator_id_pub{ORB_ID(open_drone_id_operator_id)}; + uORB::Publication _open_drone_id_self_id_pub{ORB_ID(open_drone_id_self_id)}; uORB::Publication _generator_status_pub{ORB_ID(generator_status)}; uORB::Publication _attitude_pub{ORB_ID(vehicle_attitude)}; uORB::Publication _att_sp_pub{ORB_ID(vehicle_attitude_setpoint)}; From cd63cfed3aaa91799e3ca94b1ecae3efd51b3013 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Fri, 19 Jul 2024 14:14:09 +1200 Subject: [PATCH 61/87] remoteid: implement System as sent from GCS This will send the System message if it is already being sent by a ground station. Otherwise, it will assemble the message itself using the takeoff/home location. --- msg/CMakeLists.txt | 1 + msg/OpenDroneIdSystem.msg | 13 ++++ src/drivers/uavcan/remoteid.cpp | 87 ++++++++++++++++-------- src/drivers/uavcan/remoteid.hpp | 2 + src/modules/mavlink/mavlink_receiver.cpp | 29 ++++++++ src/modules/mavlink/mavlink_receiver.h | 2 + 6 files changed, 106 insertions(+), 28 deletions(-) create mode 100644 msg/OpenDroneIdSystem.msg diff --git a/msg/CMakeLists.txt b/msg/CMakeLists.txt index f7465fdc002e..91c38488f5aa 100644 --- a/msg/CMakeLists.txt +++ b/msg/CMakeLists.txt @@ -155,6 +155,7 @@ set(msg_files OpenDroneIdArmStatus.msg OpenDroneIdOperatorId.msg OpenDroneIdSelfId.msg + OpenDroneIdSystem.msg OrbitStatus.msg OrbTest.msg OrbTestLarge.msg diff --git a/msg/OpenDroneIdSystem.msg b/msg/OpenDroneIdSystem.msg new file mode 100644 index 000000000000..0604d8a42acd --- /dev/null +++ b/msg/OpenDroneIdSystem.msg @@ -0,0 +1,13 @@ +uint64 timestamp +uint8[20] id_or_mac +uint8 operator_location_type +uint8 classification_type +int32 operator_latitude +int32 operator_longitude +uint16 area_count +uint16 area_radius +float32 area_ceiling +float32 area_floor +uint8 category_eu +uint8 class_eu +float32 operator_altitude_geo diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 6f66ba94cece..1b473e8d96fc 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -236,34 +236,65 @@ void UavcanRemoteIDController::send_location() void UavcanRemoteIDController::send_system() { - sensor_gps_s vehicle_gps_position; - home_position_s home_position; - - if (_vehicle_gps_position_sub.copy(&vehicle_gps_position) && _home_position_sub.copy(&home_position)) { - if (vehicle_gps_position.fix_type >= 3 - && home_position.valid_alt && home_position.valid_hpos) { - - dronecan::remoteid::System msg {}; - - // msg.id_or_mac // Only used for drone ID data received from other UAs. - msg.operator_location_type = MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF; - msg.classification_type = MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED; - msg.operator_latitude = home_position.lat * 1e7; - msg.operator_longitude = home_position.lon * 1e7; - msg.area_count = 1; - msg.area_radius = 0; - msg.area_ceiling = -1000; - msg.area_floor = -1000; - msg.category_eu = MAV_ODID_CATEGORY_EU_UNDECLARED; - msg.class_eu = MAV_ODID_CLASS_EU_UNDECLARED; - float wgs84_amsl_offset = vehicle_gps_position.altitude_ellipsoid_m - vehicle_gps_position.altitude_msl_m; - msg.operator_altitude_geo = home_position.alt + wgs84_amsl_offset; - - // timestamp: 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. - static uint64_t utc_offset_s = 1'546'300'800; // UTC seconds since 00:00:00 01/01/2019 - msg.timestamp = vehicle_gps_position.time_utc_usec / 1e6 - utc_offset_s; - - _uavcan_pub_remoteid_system.broadcast(msg); + open_drone_id_system_s system; + + if (_open_drone_id_system.advertised() && _open_drone_id_system.copy(&system)) { + + // Use what ground station sends us. + + dronecan::remoteid::System msg {}; + msg.timestamp = system.timestamp; + + for (unsigned i = 0; i < sizeof(system.id_or_mac); ++i) { + msg.id_or_mac.push_back(system.id_or_mac[i]); + } + + msg.operator_location_type = system.operator_location_type; + msg.classification_type = system.classification_type; + msg.operator_latitude = system.operator_latitude; + msg.operator_longitude = system.operator_longitude; + msg.area_count = system.area_count; + msg.area_radius = system.area_radius; + msg.area_ceiling = system.area_ceiling; + msg.area_floor = system.area_floor; + msg.category_eu = system.category_eu; + msg.class_eu = system.class_eu; + msg.operator_altitude_geo = system.operator_altitude_geo; + + _uavcan_pub_remoteid_system.broadcast(msg); + + } else { + // And otherwise, send our home/takeoff location. + + sensor_gps_s vehicle_gps_position; + home_position_s home_position; + + if (_vehicle_gps_position_sub.copy(&vehicle_gps_position) && _home_position_sub.copy(&home_position)) { + if (vehicle_gps_position.fix_type >= 3 + && home_position.valid_alt && home_position.valid_hpos) { + + dronecan::remoteid::System msg {}; + + // msg.id_or_mac // Only used for drone ID data received from other UAs. + msg.operator_location_type = MAV_ODID_OPERATOR_LOCATION_TYPE_TAKEOFF; + msg.classification_type = MAV_ODID_CLASSIFICATION_TYPE_UNDECLARED; + msg.operator_latitude = home_position.lat * 1e7; + msg.operator_longitude = home_position.lon * 1e7; + msg.area_count = 1; + msg.area_radius = 0; + msg.area_ceiling = -1000; + msg.area_floor = -1000; + msg.category_eu = MAV_ODID_CATEGORY_EU_UNDECLARED; + msg.class_eu = MAV_ODID_CLASS_EU_UNDECLARED; + float wgs84_amsl_offset = vehicle_gps_position.altitude_ellipsoid_m - vehicle_gps_position.altitude_msl_m; + msg.operator_altitude_geo = home_position.alt + wgs84_amsl_offset; + + // timestamp: 32 bit Unix Timestamp in seconds since 00:00:00 01/01/2019. + static uint64_t utc_offset_s = 1'546'300'800; // UTC seconds since 00:00:00 01/01/2019 + msg.timestamp = vehicle_gps_position.time_utc_usec / 1e6 - utc_offset_s; + + _uavcan_pub_remoteid_system.broadcast(msg); + } } } } diff --git a/src/drivers/uavcan/remoteid.hpp b/src/drivers/uavcan/remoteid.hpp index eb9bffd6c0e4..1d1fcaa83cef 100644 --- a/src/drivers/uavcan/remoteid.hpp +++ b/src/drivers/uavcan/remoteid.hpp @@ -44,6 +44,7 @@ #include #include #include +#include #include #include @@ -90,6 +91,7 @@ class UavcanRemoteIDController : public ModuleParams uORB::Subscription _home_position_sub{ORB_ID(home_position)}; uORB::Subscription _open_drone_id_operator_id{ORB_ID(open_drone_id_operator_id)}; uORB::Subscription _open_drone_id_self_id{ORB_ID(open_drone_id_self_id)}; + uORB::Subscription _open_drone_id_system{ORB_ID(open_drone_id_system)}; uORB::Publication _open_drone_id_arm_status_pub{ORB_ID(open_drone_id_arm_status)}; uavcan::Publisher _uavcan_pub_remoteid_basicid; diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index 6e13f3c0ea49..9c53b16f3693 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -288,6 +288,10 @@ MavlinkReceiver::handle_message(mavlink_message_t *msg) handle_message_open_drone_id_self_id(msg); break; + case MAVLINK_MSG_ID_OPEN_DRONE_ID_SYSTEM: + handle_message_open_drone_id_system(msg); + break; + #if !defined(CONSTRAINED_FLASH) case MAVLINK_MSG_ID_NAMED_VALUE_FLOAT: @@ -3125,6 +3129,31 @@ void MavlinkReceiver::handle_message_open_drone_id_self_id(mavlink_message_t *ms _open_drone_id_self_id_pub.publish(odid_self_id); } +void MavlinkReceiver::handle_message_open_drone_id_system( + mavlink_message_t *msg) +{ + mavlink_open_drone_id_system_t odid_module; + mavlink_msg_open_drone_id_system_decode(msg, &odid_module); + + open_drone_id_system_s odid_system{}; + memset(&odid_system, 0, sizeof(odid_system)); + + odid_system.timestamp = hrt_absolute_time(); + memcpy(odid_system.id_or_mac, odid_module.id_or_mac, sizeof(odid_system.id_or_mac)); + odid_system.operator_location_type = odid_module.operator_location_type; + odid_system.classification_type = odid_module.classification_type; + odid_system.operator_latitude = odid_module.operator_latitude; + odid_system.operator_longitude = odid_module.operator_longitude; + odid_system.area_count = odid_module.area_count; + odid_system.area_radius = odid_module.area_radius; + odid_system.area_ceiling = odid_module.area_ceiling; + odid_system.area_floor = odid_module.area_floor; + odid_system.category_eu = odid_module.category_eu; + odid_system.class_eu = odid_module.class_eu; + odid_system.operator_altitude_geo = odid_module.operator_altitude_geo; + + _open_drone_id_system_pub.publish(odid_system); +} void MavlinkReceiver::run() { diff --git a/src/modules/mavlink/mavlink_receiver.h b/src/modules/mavlink/mavlink_receiver.h index 4fa143475add..39fe7c33f9c7 100644 --- a/src/modules/mavlink/mavlink_receiver.h +++ b/src/modules/mavlink/mavlink_receiver.h @@ -89,6 +89,7 @@ #include #include #include +#include #include #include #include @@ -319,6 +320,7 @@ class MavlinkReceiver : public ModuleParams uORB::Publication _velocity_limits_pub{ORB_ID(velocity_limits)}; uORB::Publication _open_drone_id_operator_id_pub{ORB_ID(open_drone_id_operator_id)}; uORB::Publication _open_drone_id_self_id_pub{ORB_ID(open_drone_id_self_id)}; + uORB::Publication _open_drone_id_system_pub{ORB_ID(open_drone_id_system)}; uORB::Publication _generator_status_pub{ORB_ID(generator_status)}; uORB::Publication _attitude_pub{ORB_ID(vehicle_attitude)}; uORB::Publication _att_sp_pub{ORB_ID(vehicle_attitude_setpoint)}; From b7c5ba17522db553a1838779b50e4b0725bc52d7 Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 15 Aug 2024 08:46:15 +1200 Subject: [PATCH 62/87] boards: make flash space for remote ID over DroneCAN --- boards/ark/fmu-v6x/default.px4board | 2 -- boards/cuav/x7pro/default.px4board | 3 --- boards/px4/fmu-v4pro/test.px4board | 2 ++ boards/px4/fmu-v5/cryptotest.px4board | 2 ++ boards/px4/fmu-v5x/default.px4board | 1 - boards/px4/fmu-v6x/default.px4board | 1 - 6 files changed, 4 insertions(+), 7 deletions(-) diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 92bf7cb23895..74d63e4cc33c 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -85,8 +85,6 @@ CONFIG_SYSTEMCMDS_NSHTERM=y CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y -CONFIG_SYSTEMCMDS_SD_BENCH=y -CONFIG_SYSTEMCMDS_SD_STRESS=y CONFIG_SYSTEMCMDS_SYSTEM_TIME=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y diff --git a/boards/cuav/x7pro/default.px4board b/boards/cuav/x7pro/default.px4board index f72610fc65cf..4ba4d4a17754 100644 --- a/boards/cuav/x7pro/default.px4board +++ b/boards/cuav/x7pro/default.px4board @@ -79,7 +79,6 @@ CONFIG_MODULES_VTOL_ATT_CONTROL=y CONFIG_SYSTEMCMDS_ACTUATOR_TEST=y CONFIG_SYSTEMCMDS_BSONDUMP=y CONFIG_SYSTEMCMDS_DMESG=y -CONFIG_SYSTEMCMDS_DUMPFILE=y CONFIG_SYSTEMCMDS_GPIO=y CONFIG_SYSTEMCMDS_HARDFAULT_LOG=y CONFIG_SYSTEMCMDS_I2CDETECT=y @@ -91,7 +90,6 @@ CONFIG_SYSTEMCMDS_PARAM=y CONFIG_SYSTEMCMDS_PERF=y CONFIG_SYSTEMCMDS_REBOOT=y CONFIG_SYSTEMCMDS_SD_BENCH=y -CONFIG_SYSTEMCMDS_SD_STRESS=y CONFIG_SYSTEMCMDS_TOP=y CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y CONFIG_SYSTEMCMDS_TUNE_CONTROL=y @@ -99,4 +97,3 @@ CONFIG_SYSTEMCMDS_UORB=y CONFIG_SYSTEMCMDS_USB_CONNECTED=y CONFIG_SYSTEMCMDS_VER=y CONFIG_SYSTEMCMDS_WORK_QUEUE=y -CONFIG_EXAMPLES_FAKE_GPS=y diff --git a/boards/px4/fmu-v4pro/test.px4board b/boards/px4/fmu-v4pro/test.px4board index 057de060c021..51d1135a96cf 100644 --- a/boards/px4/fmu-v4pro/test.px4board +++ b/boards/px4/fmu-v4pro/test.px4board @@ -3,6 +3,8 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n CONFIG_DRIVERS_IRLOCK=n CONFIG_DRIVERS_PCA9685_PWM_OUT=n CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_MODULES_GYRO_FFT=n CONFIG_MODULES_LOCAL_POSITION_ESTIMATOR=n CONFIG_BOARD_TESTING=y diff --git a/boards/px4/fmu-v5/cryptotest.px4board b/boards/px4/fmu-v5/cryptotest.px4board index 831abbb824ab..cc31ed3c2e50 100644 --- a/boards/px4/fmu-v5/cryptotest.px4board +++ b/boards/px4/fmu-v5/cryptotest.px4board @@ -1,4 +1,6 @@ CONFIG_MODULES_ATTITUDE_ESTIMATOR_Q=n +CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n +CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n CONFIG_BOARD_CRYPTO=y CONFIG_DRIVERS_STUB_KEYSTORE=y CONFIG_DRIVERS_SW_CRYPTO=y diff --git a/boards/px4/fmu-v5x/default.px4board b/boards/px4/fmu-v5x/default.px4board index a48b0956876b..8ba41726c086 100644 --- a/boards/px4/fmu-v5x/default.px4board +++ b/boards/px4/fmu-v5x/default.px4board @@ -29,7 +29,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM20649=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM20948=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y -CONFIG_COMMON_INS=y CONFIG_DRIVERS_IRLOCK=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y diff --git a/boards/px4/fmu-v6x/default.px4board b/boards/px4/fmu-v6x/default.px4board index 7c4bf0b6f6cb..eedfd4c90ecb 100644 --- a/boards/px4/fmu-v6x/default.px4board +++ b/boards/px4/fmu-v6x/default.px4board @@ -30,7 +30,6 @@ CONFIG_DRIVERS_IMU_INVENSENSE_ICM42670P=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM45686=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y -CONFIG_COMMON_INS=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y CONFIG_DRIVERS_OSD_MSP_OSD=y From 8f6ce4edbfd154a9f19c21d7927c865f5955c1ed Mon Sep 17 00:00:00 2001 From: Julian Oes Date: Thu, 29 Aug 2024 13:40:47 +1200 Subject: [PATCH 63/87] mavlink/lib: move open_drone_id helpers to mavlink I could not extract the open_drone_id helpers to a separate lib because it would require the mavlink headers while the mavlink library would also depend on it, so it ended up being a circular dependency. Instead, I'm now just using the headers from within the mavlink module as well as from the uavcan driver. --- src/drivers/uavcan/remoteid.cpp | 2 +- src/lib/CMakeLists.txt | 1 - src/lib/open_drone_id/CMakeLists.txt | 41 ------------------- src/modules/mavlink/CMakeLists.txt | 2 +- .../mavlink}/open_drone_id_translations.cpp | 0 .../mavlink}/open_drone_id_translations.hpp | 0 .../streams/OPEN_DRONE_ID_BASIC_ID.hpp | 2 +- 7 files changed, 3 insertions(+), 45 deletions(-) delete mode 100644 src/lib/open_drone_id/CMakeLists.txt rename src/{lib/open_drone_id => modules/mavlink}/open_drone_id_translations.cpp (100%) rename src/{lib/open_drone_id => modules/mavlink}/open_drone_id_translations.hpp (100%) diff --git a/src/drivers/uavcan/remoteid.cpp b/src/drivers/uavcan/remoteid.cpp index 1b473e8d96fc..a2f373b767b0 100644 --- a/src/drivers/uavcan/remoteid.cpp +++ b/src/drivers/uavcan/remoteid.cpp @@ -32,7 +32,7 @@ ****************************************************************************/ #include "remoteid.hpp" -#include +#include #include using namespace time_literals; diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index 942c2dcad853..7a7b5973fd4a 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -60,7 +60,6 @@ add_subdirectory(mathlib EXCLUDE_FROM_ALL) add_subdirectory(mixer_module EXCLUDE_FROM_ALL) add_subdirectory(motion_planning EXCLUDE_FROM_ALL) add_subdirectory(npfg EXCLUDE_FROM_ALL) -add_subdirectory(open_drone_id EXCLUDE_FROM_ALL) add_subdirectory(perf EXCLUDE_FROM_ALL) add_subdirectory(fw_performance_model EXCLUDE_FROM_ALL) add_subdirectory(pid EXCLUDE_FROM_ALL) diff --git a/src/lib/open_drone_id/CMakeLists.txt b/src/lib/open_drone_id/CMakeLists.txt deleted file mode 100644 index 2090d159250e..000000000000 --- a/src/lib/open_drone_id/CMakeLists.txt +++ /dev/null @@ -1,41 +0,0 @@ -############################################################################ -# -# 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. -# -############################################################################ - -px4_add_library(open_drone_id - open_drone_id_translations.cpp - open_drone_id_translations.hpp -) - -add_dependencies(open_drone_id mavlink_c_generate) - -target_compile_options(open_drone_id PRIVATE -Wno-cast-align -Wno-address-of-packed-member) diff --git a/src/modules/mavlink/CMakeLists.txt b/src/modules/mavlink/CMakeLists.txt index 4a29a6eb0b34..45aa9b1cc82f 100644 --- a/src/modules/mavlink/CMakeLists.txt +++ b/src/modules/mavlink/CMakeLists.txt @@ -120,6 +120,7 @@ px4_add_module( mavlink_timesync.cpp mavlink_ulog.cpp MavlinkStatustextHandler.cpp + open_drone_id_translations.cpp tune_publisher.cpp MODULE_CONFIG module.yaml @@ -135,7 +136,6 @@ px4_add_module( sensor_calibration geo mavlink_c - open_drone_id timesync tunes variable_length_ringbuffer diff --git a/src/lib/open_drone_id/open_drone_id_translations.cpp b/src/modules/mavlink/open_drone_id_translations.cpp similarity index 100% rename from src/lib/open_drone_id/open_drone_id_translations.cpp rename to src/modules/mavlink/open_drone_id_translations.cpp diff --git a/src/lib/open_drone_id/open_drone_id_translations.hpp b/src/modules/mavlink/open_drone_id_translations.hpp similarity index 100% rename from src/lib/open_drone_id/open_drone_id_translations.hpp rename to src/modules/mavlink/open_drone_id_translations.hpp diff --git a/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp b/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp index dcc77c660a53..b51d3e79d148 100644 --- a/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp +++ b/src/modules/mavlink/streams/OPEN_DRONE_ID_BASIC_ID.hpp @@ -35,7 +35,7 @@ #define OPEN_DRONE_ID_BASIC_ID_HPP #include -#include +#include class MavlinkStreamOpenDroneIdBasicId : public MavlinkStream { 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 64/87] 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 65/87] 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 66/87] 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 67/87] 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 68/87] 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 69/87] 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 70/87] 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 71/87] 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 72/87] 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 73/87] 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 74/87] 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 75/87] 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 76/87] 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 77/87] 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 78/87] 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 79/87] 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 80/87] 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 81/87] 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 82/87] 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 83/87] 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 84/87] 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 85/87] 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 86/87] 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 87/87] 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