From 7e45f4915208b2d02e05e5741ff7456cf92120f9 Mon Sep 17 00:00:00 2001 From: jmackay2 <1.732mackay@gmail.com> Date: Mon, 19 Aug 2024 02:54:57 -0400 Subject: [PATCH 01/45] Update GZBridge to be able to use gazebo airspeed. Add quadtailsitter. (#23455) * Update GZBridge to be able to use gazebo airspeed. Add gz quadtailsitter. * Fix formatting --------- Co-authored-by: jmackay2 --- .../1045_gazebo-classic_quadtailsitter | 2 +- .../airframes/4004_gz_standard_vtol | 2 - .../airframes/4014_gz_quadtailsitter | 92 +++++++++++++++++++ .../init.d-posix/airframes/CMakeLists.txt | 1 + src/modules/simulation/gz_bridge/GZBridge.cpp | 16 ++-- src/modules/simulation/gz_bridge/GZBridge.hpp | 4 +- .../sensor_airspeed_sim/SensorAirspeedSim.cpp | 2 +- 7 files changed, 103 insertions(+), 16 deletions(-) create mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter 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 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol index 96bb25d69a52..580b6da368de 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol @@ -14,9 +14,7 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol} param set-default SIM_GZ_EN 1 param set-default SENS_EN_GPSSIM 1 -param set-default SENS_EN_BAROSIM 0 param set-default SENS_EN_MAGSIM 1 -param set-default SENS_EN_ARSPDSIM 1 # TODO: Enable motor failure detection when the # VTOL no longer reports 0A for all ESCs in SITL diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter new file mode 100644 index 000000000000..699d1dacc521 --- /dev/null +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter @@ -0,0 +1,92 @@ +#!/bin/sh +# +# @name Quadrotor + Tailsitter +# +# @type VTOL Quad Tailsitter +# + +. ${R}etc/init.d/rc.vtol_defaults + +PX4_SIMULATOR=${PX4_SIMULATOR:=gz} +PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} +PX4_SIM_MODEL=${PX4_SIM_MODEL:=quadtailsitter} + +param set-default SIM_GZ_EN 1 + +param set-default SENS_EN_GPSSIM 1 +param set-default SENS_EN_BAROSIM 0 +param set-default SENS_EN_MAGSIM 1 +param set-default SENS_EN_ARSPDSIM 0 + +param set-default MAV_TYPE 20 + +param set-default CA_AIRFRAME 4 + +param set-default CA_ROTOR_COUNT 4 +param set-default CA_ROTOR0_PX 0.15 +param set-default CA_ROTOR0_PY 0.23 +param set-default CA_ROTOR0_KM 0.05 +param set-default CA_ROTOR1_PX -0.15 +param set-default CA_ROTOR1_PY -0.23 +param set-default CA_ROTOR1_KM 0.05 +param set-default CA_ROTOR2_PX 0.15 +param set-default CA_ROTOR2_PY -0.23 +param set-default CA_ROTOR2_KM -0.05 +param set-default CA_ROTOR3_PX -0.15 +param set-default CA_ROTOR3_PY 0.23 +param set-default CA_ROTOR3_KM -0.05 + +param set-default CA_SV_CS_COUNT 0 + +param set-default SIM_GZ_EC_FUNC1 101 +param set-default SIM_GZ_EC_MIN1 10 +param set-default SIM_GZ_EC_MAX1 1500 +param set-default SIM_GZ_EC_FUNC2 102 +param set-default SIM_GZ_EC_MIN2 10 +param set-default SIM_GZ_EC_MAX2 1500 +param set-default SIM_GZ_EC_FUNC3 103 +param set-default SIM_GZ_EC_MIN3 10 +param set-default SIM_GZ_EC_MAX3 1500 +param set-default SIM_GZ_EC_FUNC4 104 +param set-default SIM_GZ_EC_MIN4 10 +param set-default SIM_GZ_EC_MAX4 1500 + +param set-default FD_FAIL_R 70 + +param set-default FW_P_TC 0.6 + +param set-default FW_PR_I 0.3 +param set-default FW_PR_P 0.5 +param set-default FW_PSP_OFF 2 +param set-default FW_RR_FF 0.1 +param set-default FW_RR_I 0.1 +param set-default FW_RR_P 0.2 +param set-default FW_YR_FF 0 # make yaw rate controller very weak, only keep default P +param set-default FW_YR_I 0 +param set-default FW_THR_TRIM 0.35 +param set-default FW_THR_MAX 0.8 +param set-default FW_THR_MIN 0.05 +param set-default FW_T_CLMB_MAX 6 +param set-default FW_T_HRATE_FF 0.5 +param set-default FW_T_SINK_MAX 3 +param set-default FW_T_SINK_MIN 1.6 +param set-default FW_AIRSPD_STALL 10 +param set-default FW_AIRSPD_MIN 14 +param set-default FW_AIRSPD_TRIM 18 +param set-default FW_AIRSPD_MAX 22 + +param set-default MC_AIRMODE 2 +param set-default MAN_ARM_GESTURE 0 # required for yaw airmode +param set-default MC_ROLL_P 3 +param set-default MC_PITCH_P 3 +param set-default MC_ROLLRATE_P 0.3 +param set-default MC_PITCHRATE_P 0.3 + +param set-default VT_ARSP_TRANS 15 +param set-default VT_B_TRANS_DUR 5 +param set-default VT_FW_DIFTHR_EN 7 +param set-default VT_FW_DIFTHR_S_Y 1 +param set-default VT_F_TRANS_DUR 1.5 +param set-default VT_TYPE 0 + +param set-default WV_EN 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index 9235b2e66340..badd712b063f 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_quadtailsitter 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 3464c628694c..6b4042da8bb3 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -203,17 +203,15 @@ int GZBridge::init() PX4_WARN("failed to subscribe to %s", laser_scan_topic.c_str()); } -#if 0 - // Airspeed: /world/$WORLD/model/$MODEL/link/airspeed_link/sensor/air_speed/air_speed - std::string airpressure_topic = "/world/" + _world_name + "/model/" + _model_name + - "/link/airspeed_link/sensor/air_speed/air_speed"; + // Airspeed: /world/$WORLD/model/$MODEL/link/base_link/sensor/airspeed_sensor/air_speed + std::string airspeed_topic = "/world/" + _world_name + "/model/" + _model_name + + "/link/base_link/sensor/airspeed_sensor/air_speed"; - if (!_node.Subscribe(airpressure_topic, &GZBridge::airspeedCallback, this)) { - PX4_ERR("failed to subscribe to %s", airpressure_topic.c_str()); + if (!_node.Subscribe(airspeed_topic, &GZBridge::airspeedCallback, this)) { + PX4_ERR("failed to subscribe to %s", airspeed_topic.c_str()); return PX4_ERROR; } -#endif // Air pressure: /world/$WORLD/model/$MODEL/link/base_link/sensor/air_pressure_sensor/air_pressure std::string air_pressure_topic = "/world/" + _world_name + "/model/" + _model_name + "/link/base_link/sensor/air_pressure_sensor/air_pressure"; @@ -426,8 +424,7 @@ void GZBridge::barometerCallback(const gz::msgs::FluidPressure &air_pressure) pthread_mutex_unlock(&_node_mutex); } -#if 0 -void GZBridge::airspeedCallback(const gz::msgs::AirSpeedSensor &air_speed) +void GZBridge::airspeedCallback(const gz::msgs::AirSpeed &air_speed) { if (hrt_absolute_time() == 0) { return; @@ -452,7 +449,6 @@ void GZBridge::airspeedCallback(const gz::msgs::AirSpeedSensor &air_speed) pthread_mutex_unlock(&_node_mutex); } -#endif void GZBridge::imuCallback(const gz::msgs::IMU &imu) { diff --git a/src/modules/simulation/gz_bridge/GZBridge.hpp b/src/modules/simulation/gz_bridge/GZBridge.hpp index 8a832f7961b2..824c7d471633 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.hpp +++ b/src/modules/simulation/gz_bridge/GZBridge.hpp @@ -102,7 +102,7 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S void clockCallback(const gz::msgs::Clock &clock); - // void airspeedCallback(const gz::msgs::AirSpeedSensor &air_pressure); + void airspeedCallback(const gz::msgs::AirSpeed &air_speed); void barometerCallback(const gz::msgs::FluidPressure &air_pressure); void imuCallback(const gz::msgs::IMU &imu); void poseInfoCallback(const gz::msgs::Pose_V &pose); @@ -123,7 +123,7 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S // Subscriptions uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; - //uORB::Publication _differential_pressure_pub{ORB_ID(differential_pressure)}; + uORB::Publication _differential_pressure_pub{ORB_ID(differential_pressure)}; uORB::Publication _obstacle_distance_pub{ORB_ID(obstacle_distance)}; uORB::Publication _angular_velocity_ground_truth_pub{ORB_ID(vehicle_angular_velocity_groundtruth)}; uORB::Publication _attitude_ground_truth_pub{ORB_ID(vehicle_attitude_groundtruth)}; diff --git a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp index 7b0d9556cadf..86fbbf29cd4c 100644 --- a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp +++ b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp @@ -195,7 +195,7 @@ int SensorAirspeedSim::print_usage(const char *reason) )DESCR_STR"); - PRINT_MODULE_USAGE_NAME("sensor_arispeed_sim", "system"); + PRINT_MODULE_USAGE_NAME("sensor_airspeed_sim", "system"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); From 4d21110cfb938455b21ad16c8463291094e9ec39 Mon Sep 17 00:00:00 2001 From: Claudio Chies <61051109+Claudio-Chies@users.noreply.github.com> Date: Mon, 19 Aug 2024 13:36:04 +0200 Subject: [PATCH 02/45] Documentation - improved GCS parameter readablity (#23376) improved GCS parameter description Co-authored-by: Hamish Willee Co-authored-by: Silvan Fuhrer --- .../mc_pos_control/multicopter_altitude_mode_params.c | 2 +- .../mc_pos_control/multicopter_autonomous_params.c | 2 +- .../mc_pos_control/multicopter_position_mode_params.c | 11 +++++++---- 3 files changed, 9 insertions(+), 6 deletions(-) diff --git a/src/modules/mc_pos_control/multicopter_altitude_mode_params.c b/src/modules/mc_pos_control/multicopter_altitude_mode_params.c index 3f654fade71a..9174b1ef0d83 100644 --- a/src/modules/mc_pos_control/multicopter_altitude_mode_params.c +++ b/src/modules/mc_pos_control/multicopter_altitude_mode_params.c @@ -95,7 +95,7 @@ PARAM_DEFINE_INT32(MPC_ALT_MODE, 2); /** * Maximum horizontal velocity for which position hold is enabled (use 0 to disable check) * - * Only used with MPC_POS_MODE 0 or MPC_ALT_MODE 2 + * Only used with MPC_POS_MODE Direct velocity or MPC_ALT_MODE 2 * * @unit m/s * @min 0 diff --git a/src/modules/mc_pos_control/multicopter_autonomous_params.c b/src/modules/mc_pos_control/multicopter_autonomous_params.c index 8c97e779be32..e2e453d975ed 100644 --- a/src/modules/mc_pos_control/multicopter_autonomous_params.c +++ b/src/modules/mc_pos_control/multicopter_autonomous_params.c @@ -76,7 +76,7 @@ PARAM_DEFINE_FLOAT(MPC_Z_V_AUTO_DN, 1.5f); /** * Acceleration for autonomous and for manual modes * - * When piloting manually, this parameter is only used in MPC_POS_MODE 4. + * When piloting manually, this parameter is only used in MPC_POS_MODE Acceleration based. * * @unit m/s^2 * @min 2 diff --git a/src/modules/mc_pos_control/multicopter_position_mode_params.c b/src/modules/mc_pos_control/multicopter_position_mode_params.c index 56adad1144bf..a65ef4f5713d 100644 --- a/src/modules/mc_pos_control/multicopter_position_mode_params.c +++ b/src/modules/mc_pos_control/multicopter_position_mode_params.c @@ -35,12 +35,15 @@ * Position/Altitude mode variant * * The supported sub-modes are: - * 0 Sticks directly map to velocity setpoints without smoothing. + * - "Direct velocity": + * Sticks directly map to velocity setpoints without smoothing. * Also applies to vertical direction and Altitude mode. * Useful for velocity control tuning. - * 3 Sticks map to velocity but with maximum acceleration and jerk limits based on + * - "Smoothed velocity": + * Sticks map to velocity but with maximum acceleration and jerk limits based on * jerk optimized trajectory generator (different algorithm than 1). - * 4 Sticks map to acceleration and there's a virtual brake drag + * - "Acceleration based": + * Sticks map to acceleration and there's a virtual brake drag * * @value 0 Direct velocity * @value 3 Smoothed velocity @@ -122,7 +125,7 @@ PARAM_DEFINE_FLOAT(MPC_ACC_HOR_MAX, 5.f); * * Setting this to the maximum value essentially disables the limit. * - * Only used with smooth MPC_POS_MODE 3 and 4. + * Only used with smooth MPC_POS_MODE Smoothed velocity and Acceleration based. * * @unit m/s^3 * @min 0.5 From 0481c04b2b274306d9505c00207c36ab26733dd9 Mon Sep 17 00:00:00 2001 From: Alexis Guijarro Date: Thu, 15 Aug 2024 12:51:24 -0600 Subject: [PATCH 03/45] Nuttx with backport (stm32h7x3x): Add External Power Supply option --- 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 5d74bc138955..39bb38d82b12 160000 --- a/platforms/nuttx/NuttX/nuttx +++ b/platforms/nuttx/NuttX/nuttx @@ -1 +1 @@ -Subproject commit 5d74bc138955e6f010a38e0f87f34e9a9019aecc +Subproject commit 39bb38d82b128a57d0ca40c25ba3ad6601ec0a83 From 746ae257689610f7d244e8c7c791450f9394a47d Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Mon, 19 Aug 2024 07:41:25 -0700 Subject: [PATCH 04/45] ci: replace build workflows (#23550) --- .editorconfig | 2 +- .github/workflows/build_all_targets.yml | 83 +++++++++++ .github/workflows/compile_linux.yml | 58 -------- .github/workflows/compile_linux_arm64.yml | 54 ------- .github/workflows/compile_nuttx.yml | 137 ----------------- Tools/ci_build_all_runner.sh | 19 +++ Tools/generate_board_targets_json.py | 170 +++++++++++++++++++++- 7 files changed, 268 insertions(+), 255 deletions(-) create mode 100644 .github/workflows/build_all_targets.yml delete mode 100644 .github/workflows/compile_linux.yml delete mode 100644 .github/workflows/compile_linux_arm64.yml delete mode 100644 .github/workflows/compile_nuttx.yml create mode 100755 Tools/ci_build_all_runner.sh diff --git a/.editorconfig b/.editorconfig index 683f0fdc5159..1ac25a4f5860 100644 --- a/.editorconfig +++ b/.editorconfig @@ -9,6 +9,6 @@ tab_width = 8 # Not in the official standard, but supported by many editors max_line_length = 120 -[*.yaml] +[*.yaml, *.yml] indent_style = space indent_size = 2 diff --git a/.github/workflows/build_all_targets.yml b/.github/workflows/build_all_targets.yml new file mode 100644 index 000000000000..119236b3198e --- /dev/null +++ b/.github/workflows/build_all_targets.yml @@ -0,0 +1,83 @@ +name: Build all targets + +on: + push: + branches: + - 'main' + - 'stable' + - 'beta' + - 'release/*' + pull_request: + branches: + - '*' + +jobs: + group_targets: + name: Scan for Board Targets + runs-on: ubuntu-latest + outputs: + matrix: ${{ steps.set-matrix.outputs.matrix }} + timestamp: ${{ steps.set-timestamp.outputs.timestamp }} + steps: + - uses: actions/checkout@v4 + + - name: Install Python Dependencies + uses: py-actions/py-dependency-install@v4 + with: + path: "./Tools/setup/requirements.txt" + + - id: set-matrix + run: echo "::set-output name=matrix::$(./Tools/generate_board_targets_json.py --group)" + + - id: set-timestamp + run: echo "::set-output name=timestamp::$(date +"%Y%m%d%H%M%S")" + + setup: + name: ${{ matrix.group }} + runs-on: ubuntu-latest + needs: group_targets + strategy: + matrix: ${{ fromJson(needs.group_targets.outputs.matrix) }} + container: + image: ${{ matrix.container }} + steps: + - uses: actions/checkout@v4 + with: + fetch-depth: 0 + + - name: ownership workaround + run: git config --system --add safe.directory '*' + + - name: ccache setup keys + uses: actions/cache@v4 + with: + path: ~/.ccache + key: ${{ matrix.group }}-ccache-${{ needs.group_targets.outputs.timestamp }} + restore-keys: ${{ matrix.group }}-ccache-${{ needs.group_targets.outputs.timestamp }} + + - 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 = 120M" >> ~/.ccache/ccache.conf + echo "hash_dir = false" >> ~/.ccache/ccache.conf + ccache -s + ccache -z + + - name: build target group + run: | + ./Tools/ci_build_all_runner.sh ${{matrix.targets}} + + - name: Upload px4 package + uses: actions/upload-artifact@v4 + with: + name: px4_${{matrix.group}}_build_artifacts + path: | + build/**/*.px4 + build/**/*.bin + compression-level: 0 + + - name: ccache post-run + run: ccache -s diff --git a/.github/workflows/compile_linux.yml b/.github/workflows/compile_linux.yml deleted file mode 100644 index 23e46deab7f3..000000000000 --- a/.github/workflows/compile_linux.yml +++ /dev/null @@ -1,58 +0,0 @@ -name: Compile Linux Targets - -on: - push: - branches: - - 'main' - - 'stable' - - 'beta' - - 'release/*' - pull_request: - branches: - - '*' - -jobs: - build: - runs-on: ubuntu-latest - container: px4io/px4-dev-armhf:2023-06-26 - strategy: - matrix: - config: [ - beaglebone_blue_default, - emlid_navio2_default, - px4_raspberrypi_default, - scumaker_pilotpi_default, - ] - steps: - - uses: actions/checkout@v1 - with: - token: ${{secrets.ACCESS_TOKEN}} - - name: ownership workaround - run: git config --system --add safe.directory '*' - - 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: ${{matrix.config}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} - restore-keys: ${{matrix.config}}-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: make ${{matrix.config}} - run: make ${{matrix.config}} - - name: ccache post-run - run: ccache -s diff --git a/.github/workflows/compile_linux_arm64.yml b/.github/workflows/compile_linux_arm64.yml deleted file mode 100644 index 5c1c318b411e..000000000000 --- a/.github/workflows/compile_linux_arm64.yml +++ /dev/null @@ -1,54 +0,0 @@ -name: Compile Linux ARM64 Targets - -on: - push: - branches: - - 'main' - - 'stable' - - 'beta' - - 'release/*' - pull_request: - branches: - - '*' - -jobs: - build: - runs-on: ubuntu-latest - container: px4io/px4-dev-aarch64:2022-08-12 - strategy: - matrix: - config: [ - scumaker_pilotpi_arm64, - ] - steps: - - uses: actions/checkout@v1 - with: - token: ${{secrets.ACCESS_TOKEN}} - - - 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: ${{matrix.config}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} - restore-keys: ${{matrix.config}}-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: make ${{matrix.config}} - run: make ${{matrix.config}} - - name: ccache post-run - run: ccache -s diff --git a/.github/workflows/compile_nuttx.yml b/.github/workflows/compile_nuttx.yml deleted file mode 100644 index cc44c55ea252..000000000000 --- a/.github/workflows/compile_nuttx.yml +++ /dev/null @@ -1,137 +0,0 @@ -name: Compile Nuttx Targets - -on: - push: - branches: - - 'main' - - 'stable' - - 'beta' - - 'release/*' - pull_request: - branches: - - '*' - -jobs: - build: - runs-on: ubuntu-latest - container: px4io/px4-dev-nuttx-focal:2022-08-12 - strategy: - fail-fast: false - matrix: - config: [ - 3dr_ctrl-zero-h7-oem-revg, - airmind_mindpx-v2, - ark_can-flow, - ark_can-gps, - ark_can-rtk-gps, - ark_cannode, - ark_fmu-v6x, - ark_pi6x, - ark_septentrio-gps, - atl_mantis-edu, - av_x-v1, - bitcraze_crazyflie, - bitcraze_crazyflie21, - cuav_can-gps-v1, - cuav_nora, - cuav_x7pro, - cubepilot_cubeorange, - cubepilot_cubeorangeplus, - cubepilot_cubeyellow, - diatone_mamba-f405-mk2, - freefly_can-rtk-gps, - holybro_can-gps-v1, - holybro_durandal-v1, - holybro_kakutef7, - holybro_kakuteh7, - holybro_pix32v5, - matek_gnss-m9n-f4, - matek_h743, - matek_h743-mini, - matek_h743-slim, - modalai_fc-v1, - modalai_fc-v2, - mro_ctrl-zero-classic, - mro_ctrl-zero-f7, - mro_ctrl-zero-f7-oem, - mro_ctrl-zero-h7, - mro_ctrl-zero-h7-oem, - mro_pixracerpro, - mro_x21, - mro_x21-777, - nxp_fmuk66-e, - nxp_fmuk66-v3, - nxp_mr-canhubk3, - nxp_ucans32k146, - omnibus_f4sd, - px4_fmu-v2, - px4_fmu-v3, - px4_fmu-v4, - px4_fmu-v4pro, - px4_fmu-v5, - px4_fmu-v5x, - px4_fmu-v6c, - px4_fmu-v6u, - px4_fmu-v6x, - px4_fmu-v6xrt, - raspberrypi_pico, - sky-drones_smartap-airlink, - spracing_h7extreme, - uvify_core, - siyi_n7 - ] - steps: - - uses: actions/checkout@v1 - with: - token: ${{secrets.ACCESS_TOKEN}} - - - 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: ${{matrix.config}}-ccache-${{steps.ccache_cache_timestamp.outputs.timestamp}} - restore-keys: ${{matrix.config}}-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 = 120M" >> ~/.ccache/ccache.conf - echo "hash_dir = false" >> ~/.ccache/ccache.conf - ccache -s - ccache -z - - - name: make all_variants_${{matrix.config}} - run: make all_variants_${{matrix.config}} - timeout-minutes: 45 - - name: make ${{matrix.config}} bloaty_compileunits - run: make ${{matrix.config}} bloaty_compileunits || true - - name: make ${{matrix.config}} bloaty_inlines - run: make ${{matrix.config}} bloaty_inlines || true - - name: make ${{matrix.config}} bloaty_segments - run: make ${{matrix.config}} bloaty_segments || true - - name: make ${{matrix.config}} bloaty_symbols - run: make ${{matrix.config}} bloaty_symbols || true - - name: make ${{matrix.config}} bloaty_templates - run: make ${{matrix.config}} bloaty_templates || true - - name: make ${{matrix.config}} bloaty_ram - run: make ${{matrix.config}} bloaty_ram || true - - name: make ${{matrix.config}} bloaty_compare_master - run: make ${{matrix.config}} bloaty_compare_master || true - - name: ccache post-run - run: ccache -s - - - name: Upload px4 package - uses: actions/upload-artifact@v2 - with: - name: px4_package_${{matrix.config}} - path: | - build/**/*.px4 - build/**/*.bin diff --git a/Tools/ci_build_all_runner.sh b/Tools/ci_build_all_runner.sh new file mode 100755 index 000000000000..bfb77e2623a9 --- /dev/null +++ b/Tools/ci_build_all_runner.sh @@ -0,0 +1,19 @@ +#!/bin/bash +# This script is meant to be used by the build_all.yml workflow in a github runner +# Please only modify if you know what you are doing +set -e + +echo "### :clock1: Build Times" >> $GITHUB_STEP_SUMMARY +targets=$1 +for target in ${targets//,/ } +do + echo "::group::Building: [${target}]" + start=$(date +%s) + make $target + stop=$(date +%s) + diff=$(($stop-$start)) + build_time="$(($diff /60/60))h $(($diff /60))m $(($diff % 60))s elapsed" + echo -e "\033[0;32mBuild Time: [$build_time]" + echo "* **$target** - $build_time" >> $GITHUB_STEP_SUMMARY + echo "::endgroup::" +done diff --git a/Tools/generate_board_targets_json.py b/Tools/generate_board_targets_json.py index 931d5c14776f..649b3fceefa6 100755 --- a/Tools/generate_board_targets_json.py +++ b/Tools/generate_board_targets_json.py @@ -23,11 +23,14 @@ help='Verbose Output') parser.add_argument('-p', '--pretty', dest='pretty', action='store_true', help='Pretty output instead of a single line') +parser.add_argument('-g', '--groups', dest='group', action='store_true', + help='Groups targets') args = parser.parse_args() verbose = args.verbose build_configs = [] +grouped_targets = {} excluded_boards = ['modalai_voxl2', 'px4_ros2'] # TODO: fix and enable excluded_manufacturers = ['atlflight'] excluded_platforms = ['qurt'] @@ -37,10 +40,27 @@ 'uavcanv1', # TODO: fix and enable ] +github_action_config = { 'include': build_configs } +extra_args = {} +if args.pretty: + extra_args['indent'] = 2 + +def chunks(arr, size): + # splits array into parts + for i in range(0, len(arr), size): + yield arr[i:i + size] + +def comma_targets(targets): + # turns array of targets into a comma split string + return ",".join(targets) + def process_target(px4board_file, target_name): + # reads through the board file and grabs + # useful information for building ret = None platform = None toolchain = None + group = None if px4board_file.endswith("default.px4board") or \ px4board_file.endswith("recovery.px4board") or \ @@ -63,22 +83,34 @@ def process_target(px4board_file, target_name): # get the container based on the platform and toolchain if platform == 'posix': container = 'px4io/px4-dev-base-focal:2021-09-08' + group = 'base' if toolchain: if toolchain.startswith('aarch64'): container = 'px4io/px4-dev-aarch64:2022-08-12' + group = 'aarch64' elif toolchain == 'arm-linux-gnueabihf': container = 'px4io/px4-dev-armhf:2023-06-26' + group = 'armhf' else: if verbose: print(f'unmatched toolchain: {toolchain}') elif platform == 'nuttx': container = 'px4io/px4-dev-nuttx-focal:2022-08-12' + group = 'nuttx' else: if verbose: print(f'unmatched platform: {platform}') ret = {'target': target_name, 'container': container} + if(args.group): + ret['arch'] = group return ret +# Look for board targets in the ./boards directory +if(verbose): + print("=======================") + print("= scanning for boards =") + print("=======================") + for manufacturer in os.scandir(os.path.join(source_dir, 'boards')): if not manufacturer.is_dir(): continue @@ -105,12 +137,140 @@ def process_target(px4board_file, target_name): if verbose: print(f'excluding label {label} ({target_name})') continue target = process_target(files.path, target_name) + if (args.group and target is not None): + if (target['arch'] not in grouped_targets): + grouped_targets[target['arch']] = {} + grouped_targets[target['arch']]['container'] = target['container'] + grouped_targets[target['arch']]['manufacturers'] = {} + if(manufacturer.name not in grouped_targets[target['arch']]['manufacturers']): + grouped_targets[target['arch']]['manufacturers'][manufacturer.name] = {} + grouped_targets[target['arch']]['manufacturers'][manufacturer.name] = [] + grouped_targets[target['arch']]['manufacturers'][manufacturer.name].append(target_name) if target is not None: build_configs.append(target) +if(verbose): + import pprint + print("============================") + print("= Boards found in ./boards =") + print("============================") + pprint.pp(grouped_targets) -github_action_config = { 'include': build_configs } -extra_args = {} -if args.pretty: - extra_args['indent'] = 2 -print(json.dumps(github_action_config, **extra_args)) +if (args.group): + # if we are using this script for grouping builds + # we loop trough the manufacturers list and split their targets + # if a manufacturer has more than a LIMIT of boards then we split that + # into sub groups such as "arch-manufacturer name-index" + # example: + # nuttx-px4-0 + # nuttx-px4-1 + # nuttx-px4-2 + # nuttx-ark-0 + # nuttx-ark-1 + # if the manufacturer doesn't have more targets than LIMIT then we add + # them to a generic group with the following structure "arch-index" + # example: + # nuttx-0 + # nuttx-1 + final_groups = [] + temp_group = [] + group_number = {} + last_man = '' + last_arch = '' + SPLIT_LIMIT = 10 + LOWER_LIMIT = 5 + for arch in grouped_targets: + if(last_arch == ''): + last_arch = arch + if(arch not in group_number): + group_number[arch] = 0 + + if(last_arch != arch and len(temp_group) > 0): + group_name = last_arch + "-" + str(group_number[last_arch]) + group_number[last_arch] += 1 + targets = comma_targets(temp_group) + final_groups.append({ + "container": grouped_targets[last_arch]['container'], + "targets": targets, + "arch": last_arch, + "group": group_name, + "len": len(temp_group) + }) + last_arch = arch + temp_group = [] + for man in grouped_targets[arch]['manufacturers']: + for tar in grouped_targets[arch]['manufacturers'][man]: + if(last_man != man): + man_len = len(grouped_targets[arch]['manufacturers'][man]) + if(man_len > LOWER_LIMIT and man_len < (SPLIT_LIMIT + 1)): + # Manufacturers can have their own group + group_name = arch + "-" + man + targets = comma_targets(grouped_targets[arch]['manufacturers'][man]) + last_man = man + final_groups.append({ + "container": grouped_targets[arch]['container'], + "targets": targets, + "arch": arch, + "group": group_name, + "len": len(grouped_targets[arch]['manufacturers'][man]) + }) + elif(man_len >= (SPLIT_LIMIT + 1)): + # Split big man groups into subgroups + # example: Pixhawk + chunk_limit = SPLIT_LIMIT + chunk_counter = 0 + for chunk in chunks(grouped_targets[arch]['manufacturers'][man], chunk_limit): + group_name = arch + "-" + man + "-" + str(chunk_counter) + targets = comma_targets(chunk) + last_man = man + final_groups.append({ + "container": grouped_targets[arch]['container'], + "targets": targets, + "arch": arch, + "group": group_name, + "len": len(chunk), + }) + chunk_counter += 1 + else: + temp_group.append(tar) + + if(last_arch != arch and len(temp_group) > 0): + group_name = last_arch + "-" + str(group_number[last_arch]) + group_number[last_arch] += 1 + targets = comma_targets(temp_group) + final_groups.append({ + "container": grouped_targets[last_arch]['container'], + "targets": targets, + "arch": last_arch, + "group": group_name, + "len": len(temp_group) + }) + last_arch = arch + temp_group = [] + if(len(temp_group) > (LOWER_LIMIT - 1)): + group_name = arch + "-" + str(group_number[arch]) + last_arch = arch + group_number[arch] += 1 + targets = comma_targets(temp_group) + final_groups.append({ + "container": grouped_targets[arch]['container'], + "targets": targets, + "arch": arch, + "group": group_name, + "len": len(temp_group) + }) + temp_group = [] + if(verbose): + import pprint + print("================") + print("= final_groups =") + print("================") + pprint.pp(final_groups) + + print("===============") + print("= JSON output =") + print("===============") + + print(json.dumps({ "include": final_groups }, **extra_args)) +else: + print(json.dumps(github_action_config, **extra_args)) From 072892fbefc1f4b3e4a3ef71f01f4b33316d5d1f Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 22 Apr 2024 10:53:09 -0700 Subject: [PATCH 05/45] romfs: rcS: support storage on other then SD card --- ROMFS/px4fmu_common/init.d/rcS | 36 ++++++++++++++++++++-------------- 1 file changed, 21 insertions(+), 15 deletions(-) diff --git a/ROMFS/px4fmu_common/init.d/rcS b/ROMFS/px4fmu_common/init.d/rcS index 39eed1bcab4d..28804361d1ed 100644 --- a/ROMFS/px4fmu_common/init.d/rcS +++ b/ROMFS/px4fmu_common/init.d/rcS @@ -30,7 +30,7 @@ set LOGGER_BUF 8 set PARAM_FILE "" set PARAM_BACKUP_FILE "" set RC_INPUT_ARGS "" -set SDCARD_AVAILABLE no +set STORAGE_AVAILABLE no set SDCARD_EXT_PATH /fs/microsd/ext_autostart set SDCARD_FORMAT no set STARTUP_TUNE 1 @@ -62,11 +62,11 @@ then umount /fs/microsd else - set SDCARD_AVAILABLE yes + set STORAGE_AVAILABLE yes fi fi - if [ $SDCARD_AVAILABLE = no -o $SDCARD_FORMAT = yes ] + if [ $STORAGE_AVAILABLE = no -o $SDCARD_FORMAT = yes ] then echo "INFO [init] formatting /dev/mmcsd0" set STARTUP_TUNE 15 # tune 15 = SD_ERROR (overridden to SD_INIT if format + mount succeeds) @@ -77,7 +77,7 @@ then if mount -t vfat /dev/mmcsd0 /fs/microsd then - set SDCARD_AVAILABLE yes + set STORAGE_AVAILABLE yes set STARTUP_TUNE 14 # tune 14 = SD_INIT else echo "ERROR [init] card mount failed" @@ -86,16 +86,22 @@ then echo "ERROR [init] format failed" fi fi +else + # Is there a device mounted for storage + if mft query -q -k MTD -s MTD_PARAMETERS -v /mnt/microsd + then + set STORAGE_AVAILABLE yes + fi +fi - if [ $SDCARD_AVAILABLE = yes ] +if [ $STORAGE_AVAILABLE = yes ] +then + if hardfault_log check then - if hardfault_log check + set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE + if hardfault_log commit then - set STARTUP_TUNE 2 # tune 2 = ERROR_TUNE - if hardfault_log commit - then - hardfault_log reset - fi + hardfault_log reset fi fi @@ -172,7 +178,7 @@ else fi fi - if [ $SDCARD_AVAILABLE = yes ] + if [ $STORAGE_AVAILABLE = yes ] then param select-backup $PARAM_BACKUP_FILE fi @@ -220,8 +226,8 @@ else if [ ${VEHICLE_TYPE} == none ] then - # Look for airframe on SD card - if [ $SDCARD_AVAILABLE = yes ] + # Use external startup file + if [ $STORAGE_AVAILABLE = yes ] then . ${R}etc/init.d/rc.autostart_ext else @@ -615,7 +621,7 @@ unset PARAM_FILE unset PARAM_BACKUP_FILE unset PARAM_DEFAULTS_VER unset RC_INPUT_ARGS -unset SDCARD_AVAILABLE +unset STORAGE_AVAILABLE unset SDCARD_EXT_PATH unset SDCARD_FORMAT unset STARTUP_TUNE From 07734c243ff74b6e5191471858fb32300879262e Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Mon, 5 Aug 2024 15:15:03 +0200 Subject: [PATCH 06/45] mtd: Initialized the RAMTRON speed with 30MHz --- platforms/nuttx/src/px4/common/px4_mtd.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/platforms/nuttx/src/px4/common/px4_mtd.cpp b/platforms/nuttx/src/px4/common/px4_mtd.cpp index 24d88ed3d89a..6723c35ecadb 100644 --- a/platforms/nuttx/src/px4/common/px4_mtd.cpp +++ b/platforms/nuttx/src/px4/common/px4_mtd.cpp @@ -75,11 +75,11 @@ static int ramtron_attach(mtd_instance_s &instance) return ENXIO; #else - /* start the RAMTRON driver, attempt 10 times */ + /* start the RAMTRON driver at 30MHz */ - int spi_speed_mhz = 10; + unsigned long spi_speed_hz = 30'000'000; - for (int i = 0; i < 10; i++) { + for (int i = 0; spi_speed_hz > 0; i++) { /* initialize the right spi */ struct spi_dev_s *spi = px4_spibus_initialize(px4_find_spi_bus(instance.devid)); @@ -90,7 +90,7 @@ static int ramtron_attach(mtd_instance_s &instance) /* this resets the spi bus, set correct bus speed again */ SPI_LOCK(spi, true); - SPI_SETFREQUENCY(spi, spi_speed_mhz * 1000 * 1000); + SPI_SETFREQUENCY(spi, spi_speed_hz); SPI_SETBITS(spi, 8); SPI_SETMODE(spi, SPIDEV_MODE3); SPI_SELECT(spi, instance.devid, false); @@ -108,7 +108,7 @@ static int ramtron_attach(mtd_instance_s &instance) } // try reducing speed for next attempt - spi_speed_mhz--; + spi_speed_hz -= 1'000'000; px4_usleep(10000); } @@ -118,7 +118,7 @@ static int ramtron_attach(mtd_instance_s &instance) return -EIO; } - int ret = instance.mtd_dev->ioctl(instance.mtd_dev, MTDIOC_SETSPEED, (unsigned long)spi_speed_mhz * 1000 * 1000); + int ret = instance.mtd_dev->ioctl(instance.mtd_dev, MTDIOC_SETSPEED, spi_speed_hz); if (ret != OK) { // FIXME: From the previous warning call, it looked like this should have been fatal error instead. Tried From c60b1d1a5f2b675bc6724642f038997a8d3921e0 Mon Sep 17 00:00:00 2001 From: David Sidrane Date: Mon, 15 Jul 2024 15:04:26 +0200 Subject: [PATCH 07/45] board_hw_rev_ver: Support EEPROM-only HW IDs --- .../stm32_common/board_hw_info/board_hw_rev_ver.c | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/platforms/nuttx/src/px4/stm/stm32_common/board_hw_info/board_hw_rev_ver.c b/platforms/nuttx/src/px4/stm/stm32_common/board_hw_info/board_hw_rev_ver.c index 6d484c0a826f..1a505e98217f 100644 --- a/platforms/nuttx/src/px4/stm/stm32_common/board_hw_info/board_hw_rev_ver.c +++ b/platforms/nuttx/src/px4/stm/stm32_common/board_hw_info/board_hw_rev_ver.c @@ -73,7 +73,7 @@ static char hw_base_info[HW_INFO_SIZE] = {0}; /**************************************************************************** * Protected Functions ****************************************************************************/ - +#if !defined(BOARD_HAS_ONLY_EEPROM_VERSIONING) static int dn_to_ordinal(uint16_t dn) { /* Table is scaled for 12, so if ADC is in 16 bit mode @@ -111,6 +111,7 @@ static int dn_to_ordinal(uint16_t dn) return -1; } +#endif /* BOARD_HAS_ONLY_EEPROM_VERSIONING */ /************************************************************************************ * Name: read_id_dn @@ -143,7 +144,7 @@ static int dn_to_ordinal(uint16_t dn) * -EIO - FAiled to init or read the ADC * ************************************************************************************/ - +#if !defined(BOARD_HAS_ONLY_EEPROM_VERSIONING) static int read_id_dn(int *id, uint32_t gpio_drive, uint32_t gpio_sense, int adc_channel) { int rv = -EIO; @@ -328,9 +329,15 @@ static int read_id_dn(int *id, uint32_t gpio_drive, uint32_t gpio_sense, int adc stm32_configgpio(gpio_drive); return rv; } +#endif /* BOARD_HAS_ONLY_EEPROM_VERSIONING */ static int determine_hw_info(int *revision, int *version) { +#if defined(BOARD_HAS_ONLY_EEPROM_VERSIONING) + *revision = HW_ID_EEPROM; + *version = HW_ID_EEPROM; + return OK; +#else int dn; int rv = read_id_dn(&dn, GPIO_HW_REV_DRIVE, GPIO_HW_REV_SENSE, ADC_HW_REV_SENSE_CHANNEL); @@ -344,6 +351,7 @@ static int determine_hw_info(int *revision, int *version) } return rv; +#endif } /**************************************************************************** From ecfdbd2e60660a373c158544d4580b21d4f4059b Mon Sep 17 00:00:00 2001 From: Niklas Hauser Date: Wed, 31 Jul 2024 14:36:49 +0200 Subject: [PATCH 08/45] littlefs: needs more stack when used --- .../px4_work_queue/WorkQueueManager.hpp | 2 +- src/modules/logger/Kconfig | 8 ++++++++ src/modules/logger/logger.cpp | 2 +- src/systemcmds/hardfault_log/CMakeLists.txt | 1 + src/systemcmds/param/CMakeLists.txt | 1 + 5 files changed, 12 insertions(+), 2 deletions(-) diff --git a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp index 761041fa0e83..68ac3f1ffea9 100644 --- a/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp +++ b/platforms/common/include/px4_platform_common/px4_work_queue/WorkQueueManager.hpp @@ -89,7 +89,7 @@ static constexpr wq_config_t ttyS9{"wq:ttyS9", 1728, -30}; static constexpr wq_config_t ttyACM0{"wq:ttyACM0", 1728, -31}; static constexpr wq_config_t ttyUnknown{"wq:ttyUnknown", 1728, -32}; -static constexpr wq_config_t lp_default{"wq:lp_default", 2000, -50}; +static constexpr wq_config_t lp_default{"wq:lp_default", 2350, -50}; static constexpr wq_config_t test1{"wq:test1", 2000, 0}; static constexpr wq_config_t test2{"wq:test2", 2000, 0}; diff --git a/src/modules/logger/Kconfig b/src/modules/logger/Kconfig index db2c5a75460e..985fd3d56ed1 100644 --- a/src/modules/logger/Kconfig +++ b/src/modules/logger/Kconfig @@ -10,3 +10,11 @@ menuconfig USER_LOGGER depends on BOARD_PROTECTED && MODULES_LOGGER ---help--- Put logger in userspace memory + +menuconfig LOGGER_STACK_SIZE + int "stack size of logger task" + default 3700 + depends on MODULES_LOGGER + ---help--- + Stack size of the logger task. Some configurations require more stack + than the default. diff --git a/src/modules/logger/logger.cpp b/src/modules/logger/logger.cpp index be66d5465c95..8d897a103a4d 100644 --- a/src/modules/logger/logger.cpp +++ b/src/modules/logger/logger.cpp @@ -176,7 +176,7 @@ int Logger::task_spawn(int argc, char *argv[]) _task_id = px4_task_spawn_cmd("logger", SCHED_DEFAULT, SCHED_PRIORITY_LOG_CAPTURE, - PX4_STACK_ADJUSTED(3700), + PX4_STACK_ADJUSTED(CONFIG_LOGGER_STACK_SIZE), (px4_main_t)&run_trampoline, (char *const *)argv); diff --git a/src/systemcmds/hardfault_log/CMakeLists.txt b/src/systemcmds/hardfault_log/CMakeLists.txt index fca7fc683929..8cd4ca9fea86 100644 --- a/src/systemcmds/hardfault_log/CMakeLists.txt +++ b/src/systemcmds/hardfault_log/CMakeLists.txt @@ -35,6 +35,7 @@ px4_add_module( MAIN hardfault_log COMPILE_FLAGS -Wno-cast-align # TODO: fix and enable + STACK_MAIN 4096 SRCS hardfault_log.c DEPENDS diff --git a/src/systemcmds/param/CMakeLists.txt b/src/systemcmds/param/CMakeLists.txt index 0a27cf958949..056401daf75e 100644 --- a/src/systemcmds/param/CMakeLists.txt +++ b/src/systemcmds/param/CMakeLists.txt @@ -35,6 +35,7 @@ px4_add_module( MAIN param COMPILE_FLAGS -Wno-array-bounds + STACK_MAIN 4096 SRCS param.cpp DEPENDS From f2f4488594f21b83ed9d717a250fd61b93a356ca Mon Sep 17 00:00:00 2001 From: Thomas Stauber <48206725+ThomasRigi@users.noreply.github.com> Date: Mon, 19 Aug 2024 17:14:12 +0200 Subject: [PATCH 09/45] drivers/gps: publish secondary instance satellite_info if main instance is advertised --- src/drivers/gps/gps.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/drivers/gps/gps.cpp b/src/drivers/gps/gps.cpp index c1dd783be029..004be4cc8b90 100644 --- a/src/drivers/gps/gps.cpp +++ b/src/drivers/gps/gps.cpp @@ -1214,11 +1214,13 @@ GPS::publish() void GPS::publishSatelliteInfo() { - if (_instance == Instance::Main) { + if (_instance == Instance::Main || _is_gps_main_advertised.load()) { if (_p_report_sat_info != nullptr) { _report_sat_info_pub.publish(*_p_report_sat_info); } + _is_gps_main_advertised.store(true); + } else { //we don't publish satellite info for the secondary gps } From 98eae3cd4cc1fef11f12d50563d5bbfc5141d833 Mon Sep 17 00:00:00 2001 From: Beniamino Pozzan Date: Sun, 18 Aug 2024 10:09:29 +0100 Subject: [PATCH 10/45] fix: `make help` on Ubuntu 22.04 Ubuntu 22.04 uses make 4.3 which broke the current `make help` target Reference: https://stackoverflow.com/a/26339924 Signed-off-by: Beniamino Pozzan --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index 37c61db1c0b3..5de475d79074 100644 --- a/Makefile +++ b/Makefile @@ -557,7 +557,7 @@ help: @echo "Usage: $(MAKE) " @echo "Where is one of:" @$(MAKE) -pRrq -f $(lastword $(MAKEFILE_LIST)) : 2>/dev/null | \ - awk -v RS= -F: '/^# File/,/^# Finished Make data base/ {if ($$1 !~ "^[#.]") {print $$1}}' | sort | \ + awk -v RS= -F: '/(^|\n)# Files(\n|$$)/,/(^|\n)# Finished Make data base/ {if ($$1 !~ "^[#.]") {print $$1}}' | sort | \ egrep -v -e '^[^[:alnum:]]' -e '^($(subst $(space),|,$(ALL_CONFIG_TARGETS)))$$' -e '_default$$' -e '^(Makefile)' @echo @echo "Or, $(MAKE) []" From 093117957948556b1e10808b942ea456a4b0526b Mon Sep 17 00:00:00 2001 From: bresch Date: Tue, 20 Aug 2024 13:27:12 +0200 Subject: [PATCH 11/45] ekf2: extract WMM update logic --- .../ekf2/EKF/aid_sources/gnss/gps_checks.cpp | 32 +------------ src/modules/ekf2/EKF/ekf.h | 1 + src/modules/ekf2/EKF/ekf_helper.cpp | 48 +++++++++++++------ 3 files changed, 36 insertions(+), 45 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 da7fc4e16060..94fa6f04f381 100644 --- a/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp +++ b/src/modules/ekf2/EKF/aid_sources/gnss/gps_checks.cpp @@ -98,37 +98,7 @@ void Ekf::collect_gps(const gnssSample &gps) const bool gps_rough_2d_fix = (gps.fix_type >= 2) && (gps.hacc < 1000); if (gps_rough_2d_fix && (_gps_checks_passed || !_NED_origin_initialised)) { - - // If we have good GPS data set the origin's WGS-84 position to the last gps fix -#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(gps.lat, gps.lon)); - const float mag_inclination_gps = math::radians(get_mag_inclination_degrees(gps.lat, gps.lon)); - const float mag_strength_gps = get_mag_strength_gauss(gps.lat, gps.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 - + updateWmm(gps.lat, gps.lon); _earth_rate_NED = calcEarthRateNED((float)math::radians(gps.lat)); } diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index f3f055434e62..a7c43567df52 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -259,6 +259,7 @@ 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; diff --git a/src/modules/ekf2/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp index d88f7c400d92..ae3e9e355e0a 100644 --- a/src/modules/ekf2/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -96,20 +96,7 @@ bool Ekf::setEkfGlobalOrigin(const double latitude, const double longitude, cons _pos_ref.initReference(latitude, longitude, _time_delayed_us); _gps_alt_ref = altitude; -#if defined(CONFIG_EKF2_MAGNETOMETER) - const float mag_declination_gps = math::radians(get_mag_declination_degrees(latitude, longitude)); - const float mag_inclination_gps = math::radians(get_mag_inclination_degrees(latitude, longitude)); - const float mag_strength_gps = get_mag_strength_gauss(latitude, longitude); - - if (PX4_ISFINITE(mag_declination_gps) && PX4_ISFINITE(mag_inclination_gps) && PX4_ISFINITE(mag_strength_gps)) { - _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 + updateWmm(current_lat, current_lon); _gpos_origin_eph = eph; _gpos_origin_epv = epv; @@ -144,6 +131,39 @@ 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; From f252e20eaec78972ff0723af26c922c3015aa6a6 Mon Sep 17 00:00:00 2001 From: Jaeyoung Lim Date: Wed, 21 Aug 2024 01:36:08 +0200 Subject: [PATCH 12/45] Revert "Update GZBridge to be able to use gazebo airspeed. Add quadtailsitter. (#23455)" (#23583) This reverts commit 7e45f4915208b2d02e05e5741ff7456cf92120f9. Co-authored-by: jmackay2 <1.732mackay@gmail.com> --- .../1045_gazebo-classic_quadtailsitter | 2 +- .../airframes/4004_gz_standard_vtol | 2 + .../airframes/4014_gz_quadtailsitter | 92 ------------------- .../init.d-posix/airframes/CMakeLists.txt | 1 - src/modules/simulation/gz_bridge/GZBridge.cpp | 16 ++-- src/modules/simulation/gz_bridge/GZBridge.hpp | 4 +- .../sensor_airspeed_sim/SensorAirspeedSim.cpp | 2 +- 7 files changed, 16 insertions(+), 103 deletions(-) delete mode 100644 ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter 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 9539ba6d7402..87afb523b1a7 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 -param set-default FD_FAIL_R 70 +parm set-default FD_FAIL_R 70 param set-default FW_P_TC 0.6 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol index 580b6da368de..96bb25d69a52 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/4004_gz_standard_vtol @@ -14,7 +14,9 @@ PX4_SIM_MODEL=${PX4_SIM_MODEL:=standard_vtol} param set-default SIM_GZ_EN 1 param set-default SENS_EN_GPSSIM 1 +param set-default SENS_EN_BAROSIM 0 param set-default SENS_EN_MAGSIM 1 +param set-default SENS_EN_ARSPDSIM 1 # TODO: Enable motor failure detection when the # VTOL no longer reports 0A for all ESCs in SITL diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter b/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter deleted file mode 100644 index 699d1dacc521..000000000000 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/4014_gz_quadtailsitter +++ /dev/null @@ -1,92 +0,0 @@ -#!/bin/sh -# -# @name Quadrotor + Tailsitter -# -# @type VTOL Quad Tailsitter -# - -. ${R}etc/init.d/rc.vtol_defaults - -PX4_SIMULATOR=${PX4_SIMULATOR:=gz} -PX4_GZ_WORLD=${PX4_GZ_WORLD:=default} -PX4_SIM_MODEL=${PX4_SIM_MODEL:=quadtailsitter} - -param set-default SIM_GZ_EN 1 - -param set-default SENS_EN_GPSSIM 1 -param set-default SENS_EN_BAROSIM 0 -param set-default SENS_EN_MAGSIM 1 -param set-default SENS_EN_ARSPDSIM 0 - -param set-default MAV_TYPE 20 - -param set-default CA_AIRFRAME 4 - -param set-default CA_ROTOR_COUNT 4 -param set-default CA_ROTOR0_PX 0.15 -param set-default CA_ROTOR0_PY 0.23 -param set-default CA_ROTOR0_KM 0.05 -param set-default CA_ROTOR1_PX -0.15 -param set-default CA_ROTOR1_PY -0.23 -param set-default CA_ROTOR1_KM 0.05 -param set-default CA_ROTOR2_PX 0.15 -param set-default CA_ROTOR2_PY -0.23 -param set-default CA_ROTOR2_KM -0.05 -param set-default CA_ROTOR3_PX -0.15 -param set-default CA_ROTOR3_PY 0.23 -param set-default CA_ROTOR3_KM -0.05 - -param set-default CA_SV_CS_COUNT 0 - -param set-default SIM_GZ_EC_FUNC1 101 -param set-default SIM_GZ_EC_MIN1 10 -param set-default SIM_GZ_EC_MAX1 1500 -param set-default SIM_GZ_EC_FUNC2 102 -param set-default SIM_GZ_EC_MIN2 10 -param set-default SIM_GZ_EC_MAX2 1500 -param set-default SIM_GZ_EC_FUNC3 103 -param set-default SIM_GZ_EC_MIN3 10 -param set-default SIM_GZ_EC_MAX3 1500 -param set-default SIM_GZ_EC_FUNC4 104 -param set-default SIM_GZ_EC_MIN4 10 -param set-default SIM_GZ_EC_MAX4 1500 - -param set-default FD_FAIL_R 70 - -param set-default FW_P_TC 0.6 - -param set-default FW_PR_I 0.3 -param set-default FW_PR_P 0.5 -param set-default FW_PSP_OFF 2 -param set-default FW_RR_FF 0.1 -param set-default FW_RR_I 0.1 -param set-default FW_RR_P 0.2 -param set-default FW_YR_FF 0 # make yaw rate controller very weak, only keep default P -param set-default FW_YR_I 0 -param set-default FW_THR_TRIM 0.35 -param set-default FW_THR_MAX 0.8 -param set-default FW_THR_MIN 0.05 -param set-default FW_T_CLMB_MAX 6 -param set-default FW_T_HRATE_FF 0.5 -param set-default FW_T_SINK_MAX 3 -param set-default FW_T_SINK_MIN 1.6 -param set-default FW_AIRSPD_STALL 10 -param set-default FW_AIRSPD_MIN 14 -param set-default FW_AIRSPD_TRIM 18 -param set-default FW_AIRSPD_MAX 22 - -param set-default MC_AIRMODE 2 -param set-default MAN_ARM_GESTURE 0 # required for yaw airmode -param set-default MC_ROLL_P 3 -param set-default MC_PITCH_P 3 -param set-default MC_ROLLRATE_P 0.3 -param set-default MC_PITCHRATE_P 0.3 - -param set-default VT_ARSP_TRANS 15 -param set-default VT_B_TRANS_DUR 5 -param set-default VT_FW_DIFTHR_EN 7 -param set-default VT_FW_DIFTHR_S_Y 1 -param set-default VT_F_TRANS_DUR 1.5 -param set-default VT_TYPE 0 - -param set-default WV_EN 0 diff --git a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt index badd712b063f..9235b2e66340 100644 --- a/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt +++ b/ROMFS/px4fmu_common/init.d-posix/airframes/CMakeLists.txt @@ -85,7 +85,6 @@ px4_add_romfs_files( 4011_gz_lawnmower 4012_gz_rover_ackermann 4013_gz_x500_lidar - 4014_gz_quadtailsitter 6011_gazebo-classic_typhoon_h480 6011_gazebo-classic_typhoon_h480.post diff --git a/src/modules/simulation/gz_bridge/GZBridge.cpp b/src/modules/simulation/gz_bridge/GZBridge.cpp index 6b4042da8bb3..3464c628694c 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.cpp +++ b/src/modules/simulation/gz_bridge/GZBridge.cpp @@ -203,15 +203,17 @@ int GZBridge::init() PX4_WARN("failed to subscribe to %s", laser_scan_topic.c_str()); } - // Airspeed: /world/$WORLD/model/$MODEL/link/base_link/sensor/airspeed_sensor/air_speed - std::string airspeed_topic = "/world/" + _world_name + "/model/" + _model_name + - "/link/base_link/sensor/airspeed_sensor/air_speed"; +#if 0 + // Airspeed: /world/$WORLD/model/$MODEL/link/airspeed_link/sensor/air_speed/air_speed + std::string airpressure_topic = "/world/" + _world_name + "/model/" + _model_name + + "/link/airspeed_link/sensor/air_speed/air_speed"; - if (!_node.Subscribe(airspeed_topic, &GZBridge::airspeedCallback, this)) { - PX4_ERR("failed to subscribe to %s", airspeed_topic.c_str()); + if (!_node.Subscribe(airpressure_topic, &GZBridge::airspeedCallback, this)) { + PX4_ERR("failed to subscribe to %s", airpressure_topic.c_str()); return PX4_ERROR; } +#endif // Air pressure: /world/$WORLD/model/$MODEL/link/base_link/sensor/air_pressure_sensor/air_pressure std::string air_pressure_topic = "/world/" + _world_name + "/model/" + _model_name + "/link/base_link/sensor/air_pressure_sensor/air_pressure"; @@ -424,7 +426,8 @@ void GZBridge::barometerCallback(const gz::msgs::FluidPressure &air_pressure) pthread_mutex_unlock(&_node_mutex); } -void GZBridge::airspeedCallback(const gz::msgs::AirSpeed &air_speed) +#if 0 +void GZBridge::airspeedCallback(const gz::msgs::AirSpeedSensor &air_speed) { if (hrt_absolute_time() == 0) { return; @@ -449,6 +452,7 @@ void GZBridge::airspeedCallback(const gz::msgs::AirSpeed &air_speed) pthread_mutex_unlock(&_node_mutex); } +#endif void GZBridge::imuCallback(const gz::msgs::IMU &imu) { diff --git a/src/modules/simulation/gz_bridge/GZBridge.hpp b/src/modules/simulation/gz_bridge/GZBridge.hpp index 824c7d471633..8a832f7961b2 100644 --- a/src/modules/simulation/gz_bridge/GZBridge.hpp +++ b/src/modules/simulation/gz_bridge/GZBridge.hpp @@ -102,7 +102,7 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S void clockCallback(const gz::msgs::Clock &clock); - void airspeedCallback(const gz::msgs::AirSpeed &air_speed); + // void airspeedCallback(const gz::msgs::AirSpeedSensor &air_pressure); void barometerCallback(const gz::msgs::FluidPressure &air_pressure); void imuCallback(const gz::msgs::IMU &imu); void poseInfoCallback(const gz::msgs::Pose_V &pose); @@ -123,7 +123,7 @@ class GZBridge : public ModuleBase, public ModuleParams, public px4::S // Subscriptions uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s}; - uORB::Publication _differential_pressure_pub{ORB_ID(differential_pressure)}; + //uORB::Publication _differential_pressure_pub{ORB_ID(differential_pressure)}; uORB::Publication _obstacle_distance_pub{ORB_ID(obstacle_distance)}; uORB::Publication _angular_velocity_ground_truth_pub{ORB_ID(vehicle_angular_velocity_groundtruth)}; uORB::Publication _attitude_ground_truth_pub{ORB_ID(vehicle_attitude_groundtruth)}; diff --git a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp index 86fbbf29cd4c..7b0d9556cadf 100644 --- a/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp +++ b/src/modules/simulation/sensor_airspeed_sim/SensorAirspeedSim.cpp @@ -195,7 +195,7 @@ int SensorAirspeedSim::print_usage(const char *reason) )DESCR_STR"); - PRINT_MODULE_USAGE_NAME("sensor_airspeed_sim", "system"); + PRINT_MODULE_USAGE_NAME("sensor_arispeed_sim", "system"); PRINT_MODULE_USAGE_COMMAND("start"); PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); From 3478765c310d3d34fc139dbf62594c41da6f85a9 Mon Sep 17 00:00:00 2001 From: KonradRudin <98741601+KonradRudin@users.noreply.github.com> Date: Wed, 21 Aug 2024 09:08:36 +0200 Subject: [PATCH 13/45] Navigator: MissionFeasibilityCheck: Rework 1st waypoint check (#23568) * FeasibilityChecker: only warn when first waypoint is too far, but still accept mission as valid * feasiblityChecker: make distance to first waypoint check against home position instead of current position, so it is more constant during a flight * Apply suggestions from code review Co-authored-by: Silvan Fuhrer * feasibilityCheckerTest: update tests to not fail for first waypoint check * feasibilityChecker: make comment for 1stwaypointcheck event * Feasibility check unit test: fix comment Signed-off-by: Silvan Fuhrer --------- Signed-off-by: Silvan Fuhrer Co-authored-by: Silvan Fuhrer --- .../MissionFeasibility/FeasibilityChecker.cpp | 40 ++++++++----------- .../MissionFeasibility/FeasibilityChecker.hpp | 4 -- .../FeasibilityCheckerTest.cpp | 4 +- .../navigator/mission_feasibility_checker.cpp | 1 - 4 files changed, 19 insertions(+), 30 deletions(-) diff --git a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp index c684f0119d9b..c2b3a8119807 100644 --- a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp +++ b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.cpp @@ -49,7 +49,6 @@ void FeasibilityChecker::reset() _mission_validity_failed = false; _takeoff_failed = false; _land_pattern_validity_failed = false; - _distance_first_waypoint_failed = false; _distance_between_waypoints_failed = false; _fixed_wing_land_approach_failed = false; _takeoff_land_available_failed = false; @@ -118,12 +117,6 @@ void FeasibilityChecker::updateData() _is_landed = land_detected.landed; } - if (_vehicle_global_position_sub.updated()) { - vehicle_global_position_s vehicle_global_position = {}; - _vehicle_global_position_sub.copy(&vehicle_global_position); - _current_position_lat_lon = matrix::Vector2d(vehicle_global_position.lat, vehicle_global_position.lon); - } - if (_rtl_status_sub.updated()) { rtl_status_s rtl_status = {}; _rtl_status_sub.copy(&rtl_status); @@ -199,8 +192,8 @@ void FeasibilityChecker::doCommonChecks(mission_item_s &mission_item, const int _distance_between_waypoints_failed = !checkDistancesBetweenWaypoints(mission_item); } - if (!_distance_first_waypoint_failed) { - _distance_first_waypoint_failed = !checkHorizontalDistanceToFirstWaypoint(mission_item); + if (!_first_waypoint_found) { + checkHorizontalDistanceToFirstWaypoint(mission_item); } if (!_takeoff_failed) { @@ -631,31 +624,32 @@ bool FeasibilityChecker::hasMissionBothOrNeitherTakeoffAndLanding() bool FeasibilityChecker::checkHorizontalDistanceToFirstWaypoint(mission_item_s &mission_item) { if (_param_mis_dist_1wp > FLT_EPSILON && - (_current_position_lat_lon.isAllFinite()) && !_first_waypoint_found && + (_home_lat_lon.isAllFinite()) && MissionBlock::item_contains_position(mission_item)) { _first_waypoint_found = true; - float dist_to_1wp_from_current_pos = 1e6f; - - if (_current_position_lat_lon.isAllFinite()) { - dist_to_1wp_from_current_pos = get_distance_to_next_waypoint( - mission_item.lat, mission_item.lon, - _current_position_lat_lon(0), _current_position_lat_lon(1)); - } + const float dist_to_1wp_from_home_pos = get_distance_to_next_waypoint( + mission_item.lat, mission_item.lon, + _home_lat_lon(0), _home_lat_lon(1)); - if (dist_to_1wp_from_current_pos < _param_mis_dist_1wp) { + if (dist_to_1wp_from_home_pos < _param_mis_dist_1wp) { return true; } else { /* item is too far from current position */ mavlink_log_critical(_mavlink_log_pub, - "First waypoint too far away: %dm, %d max\t", - (int)dist_to_1wp_from_current_pos, (int)_param_mis_dist_1wp); - events::send(events::ID("navigator_mis_first_wp_too_far"), {events::Log::Error, events::LogInternal::Info}, - "First waypoint too far away: {1m} (maximum: {2m})", (uint32_t)dist_to_1wp_from_current_pos, - (uint32_t)_param_mis_dist_1wp); + "First waypoint far away from home: %dm. Correct mission loaded?\t", + (int)dist_to_1wp_from_home_pos); + /* EVENT + * @description + * + * This check can be configured via MIS_DIST_1WP parameter. + * + */ + events::send(events::ID("navigator_mis_first_wp_far"), {events::Log::Warning, events::LogInternal::Info}, + "First waypoint far away from Home: {1m} Correct mission loaded?", (uint32_t)dist_to_1wp_from_home_pos); return false; } diff --git a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.hpp b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.hpp index fd18cbcfb68e..d0905d363545 100644 --- a/src/modules/navigator/MissionFeasibility/FeasibilityChecker.hpp +++ b/src/modules/navigator/MissionFeasibility/FeasibilityChecker.hpp @@ -78,7 +78,6 @@ class FeasibilityChecker : public ModuleParams bool someCheckFailed() { return _takeoff_failed || - _distance_first_waypoint_failed || _distance_between_waypoints_failed || _land_pattern_validity_failed || _fixed_wing_land_approach_failed || @@ -97,7 +96,6 @@ class FeasibilityChecker : public ModuleParams uORB::Subscription _home_pos_sub{ORB_ID(home_position)}; uORB::Subscription _status_sub{ORB_ID(vehicle_status)}; uORB::Subscription _land_detector_sub{ORB_ID(vehicle_land_detected)}; - uORB::Subscription _vehicle_global_position_sub{ORB_ID(vehicle_global_position)}; uORB::Subscription _rtl_status_sub{ORB_ID(rtl_status)}; // parameters @@ -110,14 +108,12 @@ class FeasibilityChecker : public ModuleParams float _home_alt_msl{NAN}; bool _has_vtol_approach{false}; matrix::Vector2d _home_lat_lon = matrix::Vector2d((double)NAN, (double)NAN); - matrix::Vector2d _current_position_lat_lon = matrix::Vector2d((double)NAN, (double)NAN); VehicleType _vehicle_type{VehicleType::RotaryWing}; // internal flags to keep track of which checks failed bool _mission_validity_failed{false}; bool _takeoff_failed{false}; bool _land_pattern_validity_failed{false}; - bool _distance_first_waypoint_failed{false}; bool _distance_between_waypoints_failed{false}; bool _fixed_wing_land_approach_failed{false}; bool _takeoff_land_available_failed{false}; diff --git a/src/modules/navigator/MissionFeasibility/FeasibilityCheckerTest.cpp b/src/modules/navigator/MissionFeasibility/FeasibilityCheckerTest.cpp index 0de54f33766c..43662441488a 100644 --- a/src/modules/navigator/MissionFeasibility/FeasibilityCheckerTest.cpp +++ b/src/modules/navigator/MissionFeasibility/FeasibilityCheckerTest.cpp @@ -170,9 +170,9 @@ TEST_F(FeasibilityCheckerTest, check_dist_first_waypoint) mission_item.lat = lat_new; mission_item.lon = lon_new; - // THEN: fail + // THEN: pass checker.processNextItem(mission_item, 0, 1); - ASSERT_EQ(checker.someCheckFailed(), true); + ASSERT_EQ(checker.someCheckFailed(), false); // BUT WHEN: valid current position fist WP 499m away from current checker.reset(); diff --git a/src/modules/navigator/mission_feasibility_checker.cpp b/src/modules/navigator/mission_feasibility_checker.cpp index dc2420d55bf5..8049df1236cf 100644 --- a/src/modules/navigator/mission_feasibility_checker.cpp +++ b/src/modules/navigator/mission_feasibility_checker.cpp @@ -41,7 +41,6 @@ */ #include "mission_feasibility_checker.h" -#include "MissionFeasibility/FeasibilityChecker.hpp" #include "mission_block.h" #include "navigator.h" From b2f663648e9858c0f63e50a87faa347431a12e8c Mon Sep 17 00:00:00 2001 From: Ramon Roche Date: Wed, 21 Aug 2024 07:56:37 -0700 Subject: [PATCH 14/45] 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 15/45] 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 16/45] 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 17/45] 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 18/45] 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 19/45] 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 20/45] 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 21/45] 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 22/45] 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 23/45] 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 24/45] 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 25/45] 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 26/45] 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 27/45] 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 28/45] 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 29/45] 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 30/45] 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 31/45] 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 32/45] 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 33/45] 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 34/45] 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 35/45] 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 36/45] 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 37/45] 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 38/45] 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 39/45] 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 40/45] 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 41/45] 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 42/45] 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 43/45] 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 44/45] 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 45/45] 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