From 76af175668c38ab71750d4c54f6c1012d0b02007 Mon Sep 17 00:00:00 2001 From: Roy Ratcliffe Date: Fri, 18 Aug 2023 12:10:57 +0000 Subject: [PATCH 01/11] refactor: devcontainer customisations --- .devcontainer/devcontainer.json | 50 +++++++++++++++++---------------- 1 file changed, 26 insertions(+), 24 deletions(-) diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json index c53467ab8cad..ac053b3e3d2a 100644 --- a/.devcontainer/devcontainer.json +++ b/.devcontainer/devcontainer.json @@ -6,31 +6,33 @@ "runArgs": [ "--cap-add=SYS_PTRACE", "--security-opt", "seccomp=unconfined" ], - // Set *default* container specific settings.json values on container create. - "settings": { - "terminal.integrated.shell.linux": "/bin/bash" - }, + "customizations": { + // Set *default* container specific settings.json values on container create. + "settings": { + "terminal.integrated.shell.linux": "/bin/bash" + }, - // Add the IDs of extensions you want installed when the container is created. - "extensions": [ - "chiehyu.vscode-astyle", - "dan-c-underwood.arm", - "fredericbonnet.cmake-test-adapter", - "github.vscode-pull-request-github", - "marus25.cortex-debug", - "ms-azuretools.vscode-docker", - "ms-iot.vscode-ros", - "ms-python.python", - "ms-vscode.cmake-tools", - "ms-vscode.cpptools", - "ms-vscode.cpptools-extension-pack", - "redhat.vscode-yaml", - "streetsidesoftware.code-spell-checker", - "twxs.cmake", - "uavcan.dsdl", - "wholroyd.jinja", - "zixuanwang.linkerscript" - ], + // Add the IDs of extensions you want installed when the container is created. + "extensions": [ + "chiehyu.vscode-astyle", + "dan-c-underwood.arm", + "fredericbonnet.cmake-test-adapter", + "github.vscode-pull-request-github", + "marus25.cortex-debug", + "ms-azuretools.vscode-docker", + "ms-iot.vscode-ros", + "ms-python.python", + "ms-vscode.cmake-tools", + "ms-vscode.cpptools", + "ms-vscode.cpptools-extension-pack", + "redhat.vscode-yaml", + "streetsidesoftware.code-spell-checker", + "twxs.cmake", + "uavcan.dsdl", + "wholroyd.jinja", + "zixuanwang.linkerscript" + ] + }, "containerUser": "user", "containerEnv": { From fe5ba92896e651ef6f93a67e1d0355e7ddd61e1c Mon Sep 17 00:00:00 2001 From: Roy Ratcliffe Date: Fri, 18 Aug 2023 12:49:13 +0000 Subject: [PATCH 02/11] fix: trailing comma --- .devcontainer/devcontainer.json | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json index ac053b3e3d2a..1ee2d0abef29 100644 --- a/.devcontainer/devcontainer.json +++ b/.devcontainer/devcontainer.json @@ -18,6 +18,7 @@ "dan-c-underwood.arm", "fredericbonnet.cmake-test-adapter", "github.vscode-pull-request-github", + "debug-tracker-vscode", "marus25.cortex-debug", "ms-azuretools.vscode-docker", "ms-iot.vscode-ros", @@ -40,5 +41,5 @@ }, // Use 'forwardPorts' to make a list of ports inside the container available locally. - "forwardPorts": [14556], + "forwardPorts": [14556] } From 4df60a2fc2c024909b280c2869f8391694894bcd Mon Sep 17 00:00:00 2001 From: Roy Ratcliffe Date: Fri, 18 Aug 2023 13:00:13 +0000 Subject: [PATCH 03/11] feat: add mhutchie.git-graph to recommendations --- .vscode/extensions.json | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.vscode/extensions.json b/.vscode/extensions.json index b49f65908330..66f37294bea1 100644 --- a/.vscode/extensions.json +++ b/.vscode/extensions.json @@ -18,6 +18,7 @@ "twxs.cmake", "uavcan.dsdl", "wholroyd.jinja", - "zixuanwang.linkerscript" + "zixuanwang.linkerscript", + "mhutchie.git-graph" ] } From 1b5d2124fc05175e2bce27510543246017636b6f Mon Sep 17 00:00:00 2001 From: Roy Ratcliffe Date: Fri, 18 Aug 2023 16:01:54 +0100 Subject: [PATCH 04/11] fix: C_Cpp settings, lowercase --- .vscode/settings.json | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index 35c3146dcf78..e90b01e013ab 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -7,8 +7,8 @@ "C_Cpp.default.browse.limitSymbolsToIncludedHeaders": true, "C_Cpp.default.cppStandard": "c++14", "C_Cpp.default.cStandard": "c11", - "C_Cpp.formatting": "Disabled", - "C_Cpp.intelliSenseEngine": "Default", + "C_Cpp.formatting": "disabled", + "C_Cpp.intelliSenseEngine": "default", "C_Cpp.vcpkg.enabled": false, "C_Cpp.workspaceParsingPriority": "low", "cmake.buildBeforeRun": true, From 61a20ffd1deaa05a34283d5a3260a6dcaa3a05fb Mon Sep 17 00:00:00 2001 From: Roy Ratcliffe Date: Fri, 18 Aug 2023 16:12:30 +0100 Subject: [PATCH 05/11] fix: explorer open editors visible=1 --- .vscode/settings.json | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.vscode/settings.json b/.vscode/settings.json index e90b01e013ab..74a49c08d990 100644 --- a/.vscode/settings.json +++ b/.vscode/settings.json @@ -36,7 +36,7 @@ "editor.suggest.localityBonus": true, "editor.tabSize": 8, "editor.wordWrapColumn": 120, - "explorer.openEditors.visible": 0, + "explorer.openEditors.visible": 1, "files.insertFinalNewline": true, "files.trimTrailingWhitespace": true, "files.watcherExclude": { From 974a5bd585552aa24fa238c3ac98eba27527b87b Mon Sep 17 00:00:00 2001 From: Ludovic Vanasse Date: Tue, 25 Apr 2023 17:48:42 -0400 Subject: [PATCH 06/11] Add condition for Iridium mode to not send params change after a time In the mavlink_receiver code, after a while it will try to resend some parameter update through the MAVLink instance. But for Iridium links those are not a good idea. So this adds a condition that prevent the sending if the MAVLink instance is in Iridium mode. Related to issue #21496 --- src/modules/mavlink/mavlink_receiver.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/src/modules/mavlink/mavlink_receiver.cpp b/src/modules/mavlink/mavlink_receiver.cpp index d0a0791d12d3..767ec7d02fcf 100644 --- a/src/modules/mavlink/mavlink_receiver.cpp +++ b/src/modules/mavlink/mavlink_receiver.cpp @@ -3267,7 +3267,9 @@ MavlinkReceiver::run() _mission_manager.check_active_mission(); _mission_manager.send(); - _parameters_manager.send(); + if (_mavlink->get_mode() != Mavlink::MAVLINK_MODE::MAVLINK_MODE_IRIDIUM) { + _parameters_manager.send(); + } if (_mavlink->ftp_enabled()) { _mavlink_ftp.send(); From 054c6b9af823333824d108cc076d3431c3684808 Mon Sep 17 00:00:00 2001 From: Alex Klimaj Date: Wed, 16 Aug 2023 14:20:14 -0600 Subject: [PATCH 07/11] new TDK IIM42653 IMU driver and ARKV6X Rev 2 --- boards/ark/fmu-v6x/default.px4board | 1 + boards/ark/fmu-v6x/init/rc.board_sensors | 27 +- boards/ark/fmu-v6x/src/board_config.h | 27 +- boards/ark/fmu-v6x/src/manifest.c | 23 +- boards/ark/fmu-v6x/src/spi.cpp | 140 ++- src/drivers/drv_sensor.h | 1 + .../imu/invensense/iim42653/CMakeLists.txt | 48 + .../imu/invensense/iim42653/IIM42653.cpp | 861 ++++++++++++++++++ .../imu/invensense/iim42653/IIM42653.hpp | 227 +++++ .../InvenSense_IIM42653_registers.hpp | 453 +++++++++ src/drivers/imu/invensense/iim42653/Kconfig | 5 + .../imu/invensense/iim42653/iim42653_main.cpp | 92 ++ 12 files changed, 1867 insertions(+), 38 deletions(-) create mode 100644 src/drivers/imu/invensense/iim42653/CMakeLists.txt create mode 100644 src/drivers/imu/invensense/iim42653/IIM42653.cpp create mode 100644 src/drivers/imu/invensense/iim42653/IIM42653.hpp create mode 100644 src/drivers/imu/invensense/iim42653/InvenSense_IIM42653_registers.hpp create mode 100644 src/drivers/imu/invensense/iim42653/Kconfig create mode 100644 src/drivers/imu/invensense/iim42653/iim42653_main.cpp diff --git a/boards/ark/fmu-v6x/default.px4board b/boards/ark/fmu-v6x/default.px4board index 4a6af4f6d8be..4018e493a2ad 100644 --- a/boards/ark/fmu-v6x/default.px4board +++ b/boards/ark/fmu-v6x/default.px4board @@ -20,6 +20,7 @@ CONFIG_DRIVERS_HEATER=y CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16507=y CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y CONFIG_DRIVERS_IMU_INVENSENSE_IIM42652=y +CONFIG_DRIVERS_IMU_INVENSENSE_IIM42653=y CONFIG_COMMON_LIGHT=y CONFIG_COMMON_MAGNETOMETER=y CONFIG_COMMON_OPTICAL_FLOW=y diff --git a/boards/ark/fmu-v6x/init/rc.board_sensors b/boards/ark/fmu-v6x/init/rc.board_sensors index b87dd9a014f6..0e04ed41cb57 100644 --- a/boards/ark/fmu-v6x/init/rc.board_sensors +++ b/boards/ark/fmu-v6x/init/rc.board_sensors @@ -66,14 +66,29 @@ then fi fi -# Internal SPI bus IIM42652 with SPIX measured frequency of 32.051kHz -iim42652 -R 3 -s -b 1 -C 32051 start +if ver hwtypecmp ARKV6X000000 ARKV6X001000 ARKV6X002000 ARKV6X003000 ARKV6X004000 ARKV6X005000 ARKV6X006000 ARKV6X007000 +then + # Internal SPI bus IIM42652 with SPIX measured frequency of 32.051kHz + iim42652 -R 3 -s -b 1 -C 32051 start + + # Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz + icm42688p -R 9 -s -b 2 -C 32051 start -# Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz -icm42688p -R 9 -s -b 2 -C 32051 start + # Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz + icm42688p -R 6 -s -b 3 -C 32051 start +fi -# Internal SPI bus ICM42688p with SPIX measured frequency of 32.051kHz -icm42688p -R 6 -s -b 3 -C 32051 start +if ver hwtypecmp ARKV6X000001 ARKV6X001001 ARKV6X002001 ARKV6X003001 ARKV6X004001 ARKV6X005001 ARKV6X006001 ARKV6X007001 +then + # Internal SPI bus IIM42653 with SPIX measured frequency of 32.051kHz + iim42653 -R 3 -s -b 1 -C 32051 start + + # Internal SPI bus IIM42653 with SPIX measured frequency of 32.051kHz + iim42653 -R 9 -s -b 2 -C 32051 start + + # Internal SPI bus IIM42653 with SPIX measured frequency of 32.051kHz + iim42653 -R 6 -s -b 3 -C 32051 start +fi # Internal magnetometer on I2C bmm150 -I start diff --git a/boards/ark/fmu-v6x/src/board_config.h b/boards/ark/fmu-v6x/src/board_config.h index 1317d426680e..001a31ae73c5 100644 --- a/boards/ark/fmu-v6x/src/board_config.h +++ b/boards/ark/fmu-v6x/src/board_config.h @@ -211,23 +211,18 @@ #define GPIO_HW_VER_SENSE /* PH3 */ GPIO_ADC3_INP14 #define HW_INFO_INIT_PREFIX "ARKV6X" -#define BOARD_NUM_SPI_CFG_HW_VERSIONS 2 // Rev 0 and Rev 3,4 Sensor sets +#define BOARD_NUM_SPI_CFG_HW_VERSIONS 8 // Rev 0 and Rev 1 // Base/FMUM -#define ARKV6X00 HW_VER_REV(0x0,0x0) // ARKV6X, Rev 0 -#define ARKV6X01 HW_VER_REV(0x0,0x1) // ARKV6X, BMI388 I2C2 Rev 1 -#define ARKV6X03 HW_VER_REV(0x0,0x3) // ARKV6X, Sensor Set Rev 3 -#define ARKV6X04 HW_VER_REV(0x0,0x4) // ARKV6X, Sensor Set Rev 4 -#define ARKV6X10 HW_VER_REV(0x1,0x0) // NO PX4IO, Rev 0 -#define ARKV6X13 HW_VER_REV(0x1,0x3) // NO PX4IO, Sensor Set Rev 3 -#define ARKV6X14 HW_VER_REV(0x1,0x4) // NO PX4IO, Sensor Set Rev 4 -//#define ARKV6X40 HW_VER_REV(0x4,0x0) // ARKV6X, HB CM4 base Rev 0 // never shipped -//#define ARKV6X41 HW_VER_REV(0x4,0x1) // ARKV6X, BMI388 I2C2 HB CM4 base Rev 1 // never shipped -#define ARKV6X43 HW_VER_REV(0x4,0x3) // ARKV6X, Sensor Set HB CM4 base Rev 3 -#define ARKV6X44 HW_VER_REV(0x4,0x4) // ARKV6X, Sensor Set HB CM4 base Rev 4 -#define ARKV6X50 HW_VER_REV(0x5,0x0) // ARKV6X, ARKV6X Rev 0 with HB Mini Rev 5 -//#define ARKV6X51 HW_VER_REV(0x5,0x1) // ARKV6X, BMI388 I2C2 HB Mini Rev 1 // never shipped -#define ARKV6X53 HW_VER_REV(0x5,0x3) // ARKV6X, Sensor Set HB Mini Rev 3 -#define ARKV6X54 HW_VER_REV(0x5,0x4) // ARKV6X, Sensor Set HB Mini Rev 4 +#define ARKV6X00 HW_VER_REV(0x0,0x0) // ARKV6X, Sensor Set Rev 0 +#define ARKV6X01 HW_VER_REV(0x0,0x1) // ARKV6X, Sensor Set Rev 1 +//#define ARKV6X03 HW_VER_REV(0x0,0x3) // ARKV6X, Sensor Set Rev 3 +//#define ARKV6X04 HW_VER_REV(0x0,0x4) // ARKV6X, Sensor Set Rev 4 +#define ARKV6X10 HW_VER_REV(0x1,0x0) // NO PX4IO, Sensor Set Rev 0 +#define ARKV6X11 HW_VER_REV(0x1,0x1) // NO PX4IO, Sensor Set Rev 1 +#define ARKV6X40 HW_VER_REV(0x4,0x0) // ARKV6X, Sensor Set Rev 0 HB CM4 base Rev 3 +#define ARKV6X41 HW_VER_REV(0x4,0x1) // ARKV6X, Sensor Set Rev 1 HB CM4 base Rev 4 +#define ARKV6X50 HW_VER_REV(0x5,0x0) // ARKV6X, Sensor Set Rev 0 HB Mini Rev 5 +#define ARKV6X51 HW_VER_REV(0x5,0x1) // ARKV6X, Sensor Set Rev 1 HB Mini Rev 1 // never shipped #define UAVCAN_NUM_IFACES_RUNTIME 1 diff --git a/boards/ark/fmu-v6x/src/manifest.c b/boards/ark/fmu-v6x/src/manifest.c index 6b8405bcf5d3..f4e012bfb068 100644 --- a/boards/ark/fmu-v6x/src/manifest.c +++ b/boards/ark/fmu-v6x/src/manifest.c @@ -160,21 +160,14 @@ static const px4_hw_mft_item_t hw_mft_list_v0650[] = { static px4_hw_mft_list_entry_t mft_lists[] = { // ver_rev - {ARKV6X00, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, - {ARKV6X01, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2 - {ARKV6X03, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 3 - //{ARKV6X40, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // HB CM4 base // never shipped - //{ARKV6X41, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // BMP388 moved to I2C2 HB CM4 base // never shipped - {ARKV6X43, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // BMP388 moved to I2C2, HB CM4 base Sensor Set 3 - {ARKV6X44, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // BMP388 moved to I2C2, HB CM4 base Sensor Set 4 - {ARKV6X50, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // ARKV6X Rev 0 with HB Mini Rev 5 - //{ARKV6X51, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2 HB Mini // never shipped - {ARKV6X53, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 3 - {ARKV6X54, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // BMP388 moved to I2C2, HB Mini Sensor Set 4 - {ARKV6X10, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO - {ARKV6X13, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 3 - {ARKV6X04, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // BMP388 moved to I2C2, Sensor Set 4 - {ARKV6X14, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // No PX4IO BMP388 moved to I2C2, Sensor Set 4 + {ARKV6X00, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // ARKV6X, Sensor Set Rev 0 + {ARKV6X01, hw_mft_list_v0600, arraySize(hw_mft_list_v0600)}, // ARKV6X, Sensor Set Rev 1 + {ARKV6X10, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // NO PX4IO, Sensor Set Rev 0 + {ARKV6X11, hw_mft_list_v0610, arraySize(hw_mft_list_v0610)}, // NO PX4IO, Sensor Set Rev 1 + {ARKV6X40, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // ARKV6X, Sensor Set Rev 0 HB CM4 base Rev 3 + {ARKV6X41, hw_mft_list_v0640, arraySize(hw_mft_list_v0640)}, // ARKV6X, Sensor Set Rev 1 HB CM4 base Rev 4 + {ARKV6X50, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // ARKV6X, Sensor Set Rev 0 HB Mini Rev 5 + {ARKV6X51, hw_mft_list_v0650, arraySize(hw_mft_list_v0650)}, // ARKV6X, Sensor Set Rev 1 HB Mini Rev 1 // never shipped }; /************************************************************************************ diff --git a/boards/ark/fmu-v6x/src/spi.cpp b/boards/ark/fmu-v6x/src/spi.cpp index 2d047cff1d57..f83a5a91cd4b 100644 --- a/boards/ark/fmu-v6x/src/spi.cpp +++ b/boards/ark/fmu-v6x/src/spi.cpp @@ -59,7 +59,76 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION }), }), - initSPIHWVersion(ARKV6X01, { // Placeholder + initSPIHWVersion(ARKV6X01, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), + }), + + initSPIHWVersion(ARKV6X10, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), + }), + + initSPIHWVersion(ARKV6X11, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), + }), + + initSPIHWVersion(ARKV6X40, { initSPIBus(SPI::Bus::SPI1, { initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), }, {GPIO::PortI, GPIO::Pin11}), @@ -81,6 +150,75 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), }), }), + + initSPIHWVersion(ARKV6X41, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), + }), + + initSPIHWVersion(ARKV6X50, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42652, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_ICM42688P, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), + }), + + initSPIHWVersion(ARKV6X51, { + initSPIBus(SPI::Bus::SPI1, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin9}, SPI::DRDY{GPIO::PortF, GPIO::Pin2}), + }, {GPIO::PortI, GPIO::Pin11}), + initSPIBus(SPI::Bus::SPI2, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortH, GPIO::Pin5}, SPI::DRDY{GPIO::PortA, GPIO::Pin10}), + }, {GPIO::PortF, GPIO::Pin4}), + initSPIBus(SPI::Bus::SPI3, { + initSPIDevice(DRV_IMU_DEVTYPE_IIM42653, SPI::CS{GPIO::PortI, GPIO::Pin4}, SPI::DRDY{GPIO::PortI, GPIO::Pin6}), + }, {GPIO::PortE, GPIO::Pin7}), + // initSPIBus(SPI::Bus::SPI4, { + // // no devices + // TODO: if enabled, remove GPIO_VDD_3V3_SENSORS4_EN from board_config.h + // }, {GPIO::PortG, GPIO::Pin8}), + initSPIBus(SPI::Bus::SPI5, { + initSPIDevice(SPIDEV_FLASH(0), SPI::CS{GPIO::PortG, GPIO::Pin7}) + }), + initSPIBusExternal(SPI::Bus::SPI6, { + initSPIConfigExternal(SPI::CS{GPIO::PortI, GPIO::Pin10}, SPI::DRDY{GPIO::PortD, GPIO::Pin11}), + initSPIConfigExternal(SPI::CS{GPIO::PortA, GPIO::Pin15}, SPI::DRDY{GPIO::PortD, GPIO::Pin12}), + }), + }), }; static constexpr bool unused = validateSPIConfig(px4_spi_buses_all_hw); diff --git a/src/drivers/drv_sensor.h b/src/drivers/drv_sensor.h index fa64e1d7d3d6..182021be3d3d 100644 --- a/src/drivers/drv_sensor.h +++ b/src/drivers/drv_sensor.h @@ -82,6 +82,7 @@ #define DRV_IMU_DEVTYPE_IIM42652 0x2B #define DRV_IMU_DEVTYPE_IAM20680HP 0x2C #define DRV_IMU_DEVTYPE_ICM42686P 0x2D +#define DRV_IMU_DEVTYPE_IIM42653 0x2E #define DRV_RNG_DEVTYPE_MB12XX 0x31 #define DRV_RNG_DEVTYPE_LL40LS 0x32 diff --git a/src/drivers/imu/invensense/iim42653/CMakeLists.txt b/src/drivers/imu/invensense/iim42653/CMakeLists.txt new file mode 100644 index 000000000000..4f0e7a798662 --- /dev/null +++ b/src/drivers/imu/invensense/iim42653/CMakeLists.txt @@ -0,0 +1,48 @@ +############################################################################ +# +# Copyright (c) 2022 PX4 Development Team. All rights reserved. +# +# Redistribution and use in source and binary forms, with or without +# modification, are permitted provided that the following conditions +# are met: +# +# 1. Redistributions of source code must retain the above copyright +# notice, this list of conditions and the following disclaimer. +# 2. Redistributions in binary form must reproduce the above copyright +# notice, this list of conditions and the following disclaimer in +# the documentation and/or other materials provided with the +# distribution. +# 3. Neither the name PX4 nor the names of its contributors may be +# used to endorse or promote products derived from this software +# without specific prior written permission. +# +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS +# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT +# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS +# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE +# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, +# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, +# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS +# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED +# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT +# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN +# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE +# POSSIBILITY OF SUCH DAMAGE. +# +############################################################################ +px4_add_module( + MODULE drivers__imu__invensense__iim42653 + MAIN iim42653 + COMPILE_FLAGS + ${MAX_CUSTOM_OPT_LEVEL} + #-DDEBUG_BUILD + SRCS + iim42653_main.cpp + IIM42653.cpp + IIM42653.hpp + InvenSense_IIM42653_registers.hpp + DEPENDS + px4_work_queue + drivers_accelerometer + drivers_gyroscope + ) diff --git a/src/drivers/imu/invensense/iim42653/IIM42653.cpp b/src/drivers/imu/invensense/iim42653/IIM42653.cpp new file mode 100644 index 000000000000..d5f1f57c0c6c --- /dev/null +++ b/src/drivers/imu/invensense/iim42653/IIM42653.cpp @@ -0,0 +1,861 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * 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 "IIM42653.hpp" + +using namespace time_literals; + +static constexpr int16_t combine(uint8_t msb, uint8_t lsb) +{ + return (msb << 8u) | lsb; +} + +static constexpr uint16_t combine_uint(uint8_t msb, uint8_t lsb) +{ + return (msb << 8u) | lsb; +} + +IIM42653::IIM42653(const I2CSPIDriverConfig &config) : + SPI(config), + I2CSPIDriver(config), + _drdy_gpio(config.drdy_gpio), + _px4_accel(get_device_id(), config.rotation), + _px4_gyro(get_device_id(), config.rotation) +{ + if (config.drdy_gpio != 0) { + _drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed"); + } + + if (config.custom1 != 0) { + _enable_clock_input = true; + _input_clock_freq = config.custom1; + ConfigureCLKIN(); + + } else { + _enable_clock_input = false; + } + + ConfigureSampleRate(_px4_gyro.get_max_rate_hz()); +} + +IIM42653::~IIM42653() +{ + perf_free(_bad_register_perf); + perf_free(_bad_transfer_perf); + perf_free(_fifo_empty_perf); + perf_free(_fifo_overflow_perf); + perf_free(_fifo_reset_perf); + perf_free(_drdy_missed_perf); +} + +int IIM42653::init() +{ + int ret = SPI::init(); + + if (ret != PX4_OK) { + DEVICE_DEBUG("SPI::init failed (%i)", ret); + return ret; + } + + return Reset() ? 0 : -1; +} + +bool IIM42653::Reset() +{ + _state = STATE::RESET; + DataReadyInterruptDisable(); + ScheduleClear(); + ScheduleNow(); + return true; +} + +void IIM42653::exit_and_cleanup() +{ + DataReadyInterruptDisable(); + I2CSPIDriverBase::exit_and_cleanup(); +} + +void IIM42653::print_status() +{ + I2CSPIDriverBase::print_status(); + + PX4_INFO("FIFO empty interval: %d us (%.1f Hz)", _fifo_empty_interval_us, 1e6 / _fifo_empty_interval_us); + PX4_INFO("Clock input: %s", _enable_clock_input ? "enabled" : "disabled"); + + perf_print_counter(_bad_register_perf); + perf_print_counter(_bad_transfer_perf); + perf_print_counter(_fifo_empty_perf); + perf_print_counter(_fifo_overflow_perf); + perf_print_counter(_fifo_reset_perf); + perf_print_counter(_drdy_missed_perf); +} + +int IIM42653::probe() +{ + for (int i = 0; i < 3; i++) { + uint8_t whoami = RegisterRead(Register::BANK_0::WHO_AM_I); + + if (whoami == WHOAMI) { + return PX4_OK; + + } else { + DEVICE_DEBUG("unexpected WHO_AM_I 0x%02x", whoami); + + uint8_t reg_bank_sel = RegisterRead(Register::BANK_0::REG_BANK_SEL); + int bank = reg_bank_sel >> 4; + + if (bank >= 1 && bank <= 3) { + DEVICE_DEBUG("incorrect register bank for WHO_AM_I REG_BANK_SEL:0x%02x, bank:%d", reg_bank_sel, bank); + // force bank selection and retry + SelectRegisterBank(REG_BANK_SEL_BIT::BANK_SEL_0, true); + } + } + } + + return PX4_ERROR; +} + +void IIM42653::RunImpl() +{ + const hrt_abstime now = hrt_absolute_time(); + + switch (_state) { + case STATE::RESET: + // DEVICE_CONFIG: Software reset configuration + RegisterWrite(Register::BANK_0::DEVICE_CONFIG, DEVICE_CONFIG_BIT::SOFT_RESET_CONFIG); + _reset_timestamp = now; + _failure_count = 0; + _state = STATE::WAIT_FOR_RESET; + ScheduleDelayed(1_ms); // wait 1 ms for soft reset to be effective + break; + + case STATE::WAIT_FOR_RESET: + if ((RegisterRead(Register::BANK_0::WHO_AM_I) == WHOAMI) + && (RegisterRead(Register::BANK_0::DEVICE_CONFIG) == 0x00) + && (RegisterRead(Register::BANK_0::INT_STATUS) & INT_STATUS_BIT::RESET_DONE_INT)) { + + // Wakeup accel and gyro and schedule remaining configuration + RegisterWrite(Register::BANK_0::PWR_MGMT0, PWR_MGMT0_BIT::GYRO_MODE_LOW_NOISE | PWR_MGMT0_BIT::ACCEL_MODE_LOW_NOISE); + _state = STATE::CONFIGURE; + ScheduleDelayed(30_ms); // 30 ms gyro startup time, 10 ms accel from sleep to valid data + + } else { + // RESET not complete + if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) { + PX4_DEBUG("Reset failed, retrying"); + _state = STATE::RESET; + ScheduleDelayed(100_ms); + + } else { + PX4_DEBUG("Reset not complete, check again in 10 ms"); + ScheduleDelayed(10_ms); + } + } + + break; + + case STATE::CONFIGURE: + if (Configure()) { + // if configure succeeded then reset the FIFO + _state = STATE::FIFO_RESET; + ScheduleDelayed(1_ms); + + } else { + // CONFIGURE not complete + if (hrt_elapsed_time(&_reset_timestamp) > 1000_ms) { + PX4_DEBUG("Configure failed, resetting"); + _state = STATE::RESET; + + } else { + PX4_DEBUG("Configure failed, retrying"); + } + + ScheduleDelayed(100_ms); + } + + break; + + case STATE::FIFO_RESET: + + _state = STATE::FIFO_READ; + FIFOReset(); + + if (DataReadyInterruptConfigure()) { + _data_ready_interrupt_enabled = true; + + // backup schedule as a watchdog timeout + ScheduleDelayed(100_ms); + + } else { + _data_ready_interrupt_enabled = false; + ScheduleOnInterval(_fifo_empty_interval_us, _fifo_empty_interval_us); + } + + break; + + case STATE::FIFO_READ: { + hrt_abstime timestamp_sample = now; + uint8_t samples = 0; + + if (_data_ready_interrupt_enabled) { + // scheduled from interrupt if _drdy_timestamp_sample was set as expected + const hrt_abstime drdy_timestamp_sample = _drdy_timestamp_sample.fetch_and(0); + + if ((now - drdy_timestamp_sample) < _fifo_empty_interval_us) { + timestamp_sample = drdy_timestamp_sample; + samples = _fifo_gyro_samples; + + } else { + perf_count(_drdy_missed_perf); + } + + // push backup schedule back + ScheduleDelayed(_fifo_empty_interval_us * 2); + } + + if (samples == 0) { + // check current FIFO count + const uint16_t fifo_count = FIFOReadCount(); + + if (fifo_count >= FIFO::SIZE) { + FIFOReset(); + perf_count(_fifo_overflow_perf); + + } else if (fifo_count == 0) { + perf_count(_fifo_empty_perf); + + } else { + // FIFO count (size in bytes) + samples = (fifo_count / sizeof(FIFO::DATA)); + + // tolerate minor jitter, leave sample to next iteration if behind by only 1 + if (samples == _fifo_gyro_samples + 1) { + timestamp_sample -= static_cast(FIFO_SAMPLE_DT); + samples--; + } + + if (samples > FIFO_MAX_SAMPLES) { + // not technically an overflow, but more samples than we expected or can publish + FIFOReset(); + perf_count(_fifo_overflow_perf); + samples = 0; + } + } + } + + bool success = false; + + if (samples >= 1) { + if (FIFORead(timestamp_sample, samples)) { + success = true; + + if (_failure_count > 0) { + _failure_count--; + } + } + } + + if (!success) { + _failure_count++; + + // full reset if things are failing consistently + if (_failure_count > 10) { + Reset(); + return; + } + } + + if (!success || hrt_elapsed_time(&_last_config_check_timestamp) > 100_ms) { + // check configuration registers periodically or immediately following any failure + if (RegisterCheck(_register_bank0_cfg[_checked_register_bank0]) + && RegisterCheck(_register_bank1_cfg[_checked_register_bank1]) + && RegisterCheck(_register_bank2_cfg[_checked_register_bank2]) + ) { + _last_config_check_timestamp = now; + _checked_register_bank0 = (_checked_register_bank0 + 1) % size_register_bank0_cfg; + _checked_register_bank1 = (_checked_register_bank1 + 1) % size_register_bank1_cfg; + _checked_register_bank2 = (_checked_register_bank2 + 1) % size_register_bank2_cfg; + + } else { + // register check failed, force reset + perf_count(_bad_register_perf); + Reset(); + } + } + } + + break; + } +} + +void IIM42653::ConfigureSampleRate(int sample_rate) +{ + // round down to nearest FIFO sample dt + const float min_interval = FIFO_SAMPLE_DT; + _fifo_empty_interval_us = math::max(roundf((1e6f / (float)sample_rate) / min_interval) * min_interval, min_interval); + + _fifo_gyro_samples = roundf(math::min((float)_fifo_empty_interval_us / (1e6f / GYRO_RATE), (float)FIFO_MAX_SAMPLES)); + + // recompute FIFO empty interval (us) with actual gyro sample limit + _fifo_empty_interval_us = _fifo_gyro_samples * (1e6f / GYRO_RATE); + + ConfigureFIFOWatermark(_fifo_gyro_samples); +} + +void IIM42653::ConfigureFIFOWatermark(uint8_t samples) +{ + // FIFO watermark threshold in number of bytes + const uint16_t fifo_watermark_threshold = samples * sizeof(FIFO::DATA); + + for (auto &r : _register_bank0_cfg) { + if (r.reg == Register::BANK_0::FIFO_CONFIG2) { + // FIFO_WM[7:0] FIFO_CONFIG2 + r.set_bits = fifo_watermark_threshold & 0xFF; + + } else if (r.reg == Register::BANK_0::FIFO_CONFIG3) { + // FIFO_WM[11:8] FIFO_CONFIG3 + r.set_bits = (fifo_watermark_threshold >> 8) & 0x0F; + } + } +} + +void IIM42653::ConfigureCLKIN() +{ + for (auto &r0 : _register_bank0_cfg) { + if (r0.reg == Register::BANK_0::INTF_CONFIG1) { + r0.set_bits = INTF_CONFIG1_BIT::RTC_MODE; + r0.set_bits = INTF_CONFIG1_BIT::CLKSEL; + r0.clear_bits = INTF_CONFIG1_BIT::CLKSEL_CLEAR; + } + } + + for (auto &r1 : _register_bank1_cfg) { + if (r1.reg == Register::BANK_1::INTF_CONFIG5) { + r1.set_bits = INTF_CONFIG5_BIT::PIN9_FUNCTION_CLKIN_SET; + r1.clear_bits = INTF_CONFIG5_BIT::PIN9_FUNCTION_CLKIN_CLEAR; + } + } +} + +void IIM42653::SelectRegisterBank(enum REG_BANK_SEL_BIT bank, bool force) +{ + if (bank != _last_register_bank || force) { + // select BANK_0 + uint8_t cmd_bank_sel[2] {}; + cmd_bank_sel[0] = static_cast(Register::BANK_0::REG_BANK_SEL); + cmd_bank_sel[1] = bank; + transfer(cmd_bank_sel, cmd_bank_sel, sizeof(cmd_bank_sel)); + + _last_register_bank = bank; + } +} + +bool IIM42653::Configure() +{ + // first set and clear all configured register bits + for (const auto ®_cfg : _register_bank0_cfg) { + RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits); + } + + for (const auto ®_cfg : _register_bank1_cfg) { + RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits); + } + + for (const auto ®_cfg : _register_bank2_cfg) { + RegisterSetAndClearBits(reg_cfg.reg, reg_cfg.set_bits, reg_cfg.clear_bits); + } + + // now check that all are configured + bool success = true; + + for (const auto ®_cfg : _register_bank0_cfg) { + if (!RegisterCheck(reg_cfg)) { + success = false; + } + } + + for (const auto ®_cfg : _register_bank1_cfg) { + if (!RegisterCheck(reg_cfg)) { + success = false; + } + } + + for (const auto ®_cfg : _register_bank2_cfg) { + if (!RegisterCheck(reg_cfg)) { + success = false; + } + } + + // 20-bits data format used + // the only FSR settings that are operational are ±2000dps for gyroscope and ±16g for accelerometer + _px4_accel.set_range(16.f * CONSTANTS_ONE_G); + _px4_gyro.set_range(math::radians(2000.f)); + + return success; +} + +int IIM42653::DataReadyInterruptCallback(int irq, void *context, void *arg) +{ + static_cast(arg)->DataReady(); + return 0; +} + +void IIM42653::DataReady() +{ + _drdy_timestamp_sample.store(hrt_absolute_time()); + ScheduleNow(); +} + +bool IIM42653::DataReadyInterruptConfigure() +{ + if (_drdy_gpio == 0) { + return false; + } + + // Setup data ready on falling edge + return px4_arch_gpiosetevent(_drdy_gpio, false, true, true, &DataReadyInterruptCallback, this) == 0; +} + +bool IIM42653::DataReadyInterruptDisable() +{ + if (_drdy_gpio == 0) { + return false; + } + + return px4_arch_gpiosetevent(_drdy_gpio, false, false, false, nullptr, nullptr) == 0; +} + +template +bool IIM42653::RegisterCheck(const T ®_cfg) +{ + bool success = true; + + const uint8_t reg_value = RegisterRead(reg_cfg.reg); + + if (reg_cfg.set_bits && ((reg_value & reg_cfg.set_bits) != reg_cfg.set_bits)) { + PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not set)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.set_bits); + success = false; + } + + if (reg_cfg.clear_bits && ((reg_value & reg_cfg.clear_bits) != 0)) { + PX4_DEBUG("0x%02hhX: 0x%02hhX (0x%02hhX not cleared)", (uint8_t)reg_cfg.reg, reg_value, reg_cfg.clear_bits); + success = false; + } + + return success; +} + +template +uint8_t IIM42653::RegisterRead(T reg) +{ + uint8_t cmd[2] {}; + cmd[0] = static_cast(reg) | DIR_READ; + SelectRegisterBank(reg); + transfer(cmd, cmd, sizeof(cmd)); + return cmd[1]; +} + +template +void IIM42653::RegisterWrite(T reg, uint8_t value) +{ + uint8_t cmd[2] { (uint8_t)reg, value }; + SelectRegisterBank(reg); + transfer(cmd, cmd, sizeof(cmd)); +} + +template +void IIM42653::RegisterSetAndClearBits(T reg, uint8_t setbits, uint8_t clearbits) +{ + const uint8_t orig_val = RegisterRead(reg); + + uint8_t val = (orig_val & ~clearbits) | setbits; + + if (orig_val != val) { + RegisterWrite(reg, val); + } +} + +uint16_t IIM42653::FIFOReadCount() +{ + // read FIFO count + uint8_t fifo_count_buf[3] {}; + fifo_count_buf[0] = static_cast(Register::BANK_0::FIFO_COUNTH) | DIR_READ; + SelectRegisterBank(REG_BANK_SEL_BIT::BANK_SEL_0); + + if (transfer(fifo_count_buf, fifo_count_buf, sizeof(fifo_count_buf)) != PX4_OK) { + perf_count(_bad_transfer_perf); + return 0; + } + + return combine(fifo_count_buf[1], fifo_count_buf[2]); +} + +bool IIM42653::FIFORead(const hrt_abstime ×tamp_sample, uint8_t samples) +{ + FIFOTransferBuffer buffer{}; + const size_t transfer_size = math::min(samples * sizeof(FIFO::DATA) + 4, FIFO::SIZE); + SelectRegisterBank(REG_BANK_SEL_BIT::BANK_SEL_0); + + if (transfer((uint8_t *)&buffer, (uint8_t *)&buffer, transfer_size) != PX4_OK) { + perf_count(_bad_transfer_perf); + return false; + } + + if (buffer.INT_STATUS & INT_STATUS_BIT::FIFO_FULL_INT) { + perf_count(_fifo_overflow_perf); + FIFOReset(); + return false; + } + + const uint16_t fifo_count_bytes = combine(buffer.FIFO_COUNTH, buffer.FIFO_COUNTL); + + if (fifo_count_bytes >= FIFO::SIZE) { + perf_count(_fifo_overflow_perf); + FIFOReset(); + return false; + } + + const uint8_t fifo_count_samples = fifo_count_bytes / sizeof(FIFO::DATA); + + if (fifo_count_samples == 0) { + perf_count(_fifo_empty_perf); + return false; + } + + // check FIFO header in every sample + uint8_t valid_samples = 0; + + for (int i = 0; i < math::min(samples, fifo_count_samples); i++) { + bool valid = true; + + // With FIFO_ACCEL_EN and FIFO_GYRO_EN header should be 8’b_0110_10xx + const uint8_t FIFO_HEADER = buffer.f[i].FIFO_Header; + + if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_MSG) { + // FIFO sample empty if HEADER_MSG set + valid = false; + + } else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ACCEL)) { + // accel bit not set + valid = false; + + } else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_GYRO)) { + // gyro bit not set + valid = false; + + } else if (!(FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_20)) { + // Packet does not contain a new and valid extended 20-bit data + valid = false; + + } else if ((FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_TIMESTAMP_FSYNC) != Bit3) { + // Packet does not contain ODR timestamp + valid = false; + + } else if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ODR_ACCEL) { + // accel ODR changed + valid = false; + + } else if (FIFO_HEADER & FIFO::FIFO_HEADER_BIT::HEADER_ODR_GYRO) { + // gyro ODR changed + valid = false; + } + + if (valid) { + valid_samples++; + + } else { + perf_count(_bad_transfer_perf); + break; + } + } + + if (valid_samples > 0) { + if (ProcessTemperature(buffer.f, valid_samples)) { + ProcessGyro(timestamp_sample, buffer.f, valid_samples); + ProcessAccel(timestamp_sample, buffer.f, valid_samples); + return true; + } + } + + return false; +} + +void IIM42653::FIFOReset() +{ + perf_count(_fifo_reset_perf); + + // SIGNAL_PATH_RESET: FIFO flush + RegisterSetBits(Register::BANK_0::SIGNAL_PATH_RESET, SIGNAL_PATH_RESET_BIT::FIFO_FLUSH); + + // reset while FIFO is disabled + _drdy_timestamp_sample.store(0); +} + +static constexpr int32_t reassemble_20bit(const uint32_t a, const uint32_t b, const uint32_t c) +{ + // 0xXXXAABBC + uint32_t high = ((a << 12) & 0x000FF000); + uint32_t low = ((b << 4) & 0x00000FF0); + uint32_t lowest = (c & 0x0000000F); + + uint32_t x = high | low | lowest; + + if (a & Bit7) { + // sign extend + x |= 0xFFF00000u; + } + + return static_cast(x); +} + +void IIM42653::ProcessAccel(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples) +{ + sensor_accel_fifo_s accel{}; + accel.timestamp_sample = timestamp_sample; + accel.samples = 0; + + // 18-bits of accelerometer data + bool scale_20bit = false; + + // first pass + for (int i = 0; i < samples; i++) { + + uint16_t timestamp_fifo = combine_uint(fifo[i].TimeStamp_h, fifo[i].TimeStamp_l); + + if (_enable_clock_input) { + accel.dt = (float)timestamp_fifo * ((1.f / _input_clock_freq) * 1e6f); + + } else { + accel.dt = (float)timestamp_fifo * FIFO_TIMESTAMP_SCALING; + } + + // 20 bit hires mode + // Sign extension + Accel [19:12] + Accel [11:4] + Accel [3:2] (20 bit extension byte) + // Accel data is 18 bit () + int32_t accel_x = reassemble_20bit(fifo[i].ACCEL_DATA_X1, fifo[i].ACCEL_DATA_X0, + fifo[i].Ext_Accel_X_Gyro_X & 0xF0 >> 4); + int32_t accel_y = reassemble_20bit(fifo[i].ACCEL_DATA_Y1, fifo[i].ACCEL_DATA_Y0, + fifo[i].Ext_Accel_Y_Gyro_Y & 0xF0 >> 4); + int32_t accel_z = reassemble_20bit(fifo[i].ACCEL_DATA_Z1, fifo[i].ACCEL_DATA_Z0, + fifo[i].Ext_Accel_Z_Gyro_Z & 0xF0 >> 4); + + // sample invalid if -524288 + if (accel_x != -524288 && accel_y != -524288 && accel_z != -524288) { + // check if any values are going to exceed int16 limits + static constexpr int16_t max_accel = INT16_MAX; + static constexpr int16_t min_accel = INT16_MIN; + + if (accel_x >= max_accel || accel_x <= min_accel) { + scale_20bit = true; + } + + if (accel_y >= max_accel || accel_y <= min_accel) { + scale_20bit = true; + } + + if (accel_z >= max_accel || accel_z <= min_accel) { + scale_20bit = true; + } + + // shift by 2 (2 least significant bits are always 0) + accel.x[accel.samples] = accel_x / 4; + accel.y[accel.samples] = accel_y / 4; + accel.z[accel.samples] = accel_z / 4; + accel.samples++; + } + } + + if (!scale_20bit) { + // if highres enabled accel data is always 4096 LSB/g + _px4_accel.set_scale(CONSTANTS_ONE_G / 4096.f); + + } else { + // 20 bit data scaled to 16 bit (2^4) + for (int i = 0; i < samples; i++) { + // 20 bit hires mode + // Sign extension + Accel [19:12] + Accel [11:4] + Accel [3:2] (20 bit extension byte) + // Accel data is 18 bit () + int16_t accel_x = combine(fifo[i].ACCEL_DATA_X1, fifo[i].ACCEL_DATA_X0); + int16_t accel_y = combine(fifo[i].ACCEL_DATA_Y1, fifo[i].ACCEL_DATA_Y0); + int16_t accel_z = combine(fifo[i].ACCEL_DATA_Z1, fifo[i].ACCEL_DATA_Z0); + + accel.x[i] = accel_x; + accel.y[i] = accel_y; + accel.z[i] = accel_z; + } + + _px4_accel.set_scale(CONSTANTS_ONE_G / 1024.f); + } + + // correct frame for publication + for (int i = 0; i < accel.samples; i++) { + // sensor's frame is +x forward, +y left, +z up + // flip y & z to publish right handed with z down (x forward, y right, z down) + accel.x[i] = accel.x[i]; + accel.y[i] = (accel.y[i] == INT16_MIN) ? INT16_MAX : -accel.y[i]; + accel.z[i] = (accel.z[i] == INT16_MIN) ? INT16_MAX : -accel.z[i]; + } + + _px4_accel.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf) + + perf_event_count(_fifo_empty_perf) + perf_event_count(_fifo_overflow_perf)); + + if (accel.samples > 0) { + _px4_accel.updateFIFO(accel); + } +} + +void IIM42653::ProcessGyro(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples) +{ + sensor_gyro_fifo_s gyro{}; + gyro.timestamp_sample = timestamp_sample; + gyro.samples = 0; + + // 20-bits of gyroscope data + bool scale_20bit = false; + + // first pass + for (int i = 0; i < samples; i++) { + + uint16_t timestamp_fifo = combine_uint(fifo[i].TimeStamp_h, fifo[i].TimeStamp_l); + + if (_enable_clock_input) { + gyro.dt = (float)timestamp_fifo * ((1.f / _input_clock_freq) * 1e6f); + + } else { + gyro.dt = (float)timestamp_fifo * FIFO_TIMESTAMP_SCALING; + } + + // 20 bit hires mode + // Gyro [19:12] + Gyro [11:4] + Gyro [3:0] (bottom 4 bits of 20 bit extension byte) + int32_t gyro_x = reassemble_20bit(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0, fifo[i].Ext_Accel_X_Gyro_X & 0x0F); + int32_t gyro_y = reassemble_20bit(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0, fifo[i].Ext_Accel_Y_Gyro_Y & 0x0F); + int32_t gyro_z = reassemble_20bit(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0, fifo[i].Ext_Accel_Z_Gyro_Z & 0x0F); + + // check if any values are going to exceed int16 limits + static constexpr int16_t max_gyro = INT16_MAX; + static constexpr int16_t min_gyro = INT16_MIN; + + if (gyro_x >= max_gyro || gyro_x <= min_gyro) { + scale_20bit = true; + } + + if (gyro_y >= max_gyro || gyro_y <= min_gyro) { + scale_20bit = true; + } + + if (gyro_z >= max_gyro || gyro_z <= min_gyro) { + scale_20bit = true; + } + + gyro.x[gyro.samples] = gyro_x / 2; + gyro.y[gyro.samples] = gyro_y / 2; + gyro.z[gyro.samples] = gyro_z / 2; + gyro.samples++; + } + + if (!scale_20bit) { + // if highres enabled gyro data is always 65.5 LSB/dps + _px4_gyro.set_scale(math::radians(1.f / 65.5f)); + + } else { + // 20 bit data scaled to 16 bit (2^4) + for (int i = 0; i < samples; i++) { + gyro.x[i] = combine(fifo[i].GYRO_DATA_X1, fifo[i].GYRO_DATA_X0); + gyro.y[i] = combine(fifo[i].GYRO_DATA_Y1, fifo[i].GYRO_DATA_Y0); + gyro.z[i] = combine(fifo[i].GYRO_DATA_Z1, fifo[i].GYRO_DATA_Z0); + } + + _px4_gyro.set_scale(math::radians(4000.f / 32768.f)); + } + + // correct frame for publication + for (int i = 0; i < gyro.samples; i++) { + // sensor's frame is +x forward, +y left, +z up + // flip y & z to publish right handed with z down (x forward, y right, z down) + gyro.x[i] = gyro.x[i]; + gyro.y[i] = (gyro.y[i] == INT16_MIN) ? INT16_MAX : -gyro.y[i]; + gyro.z[i] = (gyro.z[i] == INT16_MIN) ? INT16_MAX : -gyro.z[i]; + } + + _px4_gyro.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf) + + perf_event_count(_fifo_empty_perf) + perf_event_count(_fifo_overflow_perf)); + + if (gyro.samples > 0) { + _px4_gyro.updateFIFO(gyro); + } +} + +bool IIM42653::ProcessTemperature(const FIFO::DATA fifo[], const uint8_t samples) +{ + int16_t temperature[FIFO_MAX_SAMPLES]; + float temperature_sum{0}; + + int valid_samples = 0; + + for (int i = 0; i < samples; i++) { + const int16_t t = combine(fifo[i].TEMP_DATA1, fifo[i].TEMP_DATA0); + + // sample invalid if -32768 + if (t != -32768) { + temperature_sum += t; + temperature[valid_samples] = t; + valid_samples++; + } + } + + if (valid_samples > 0) { + const float temperature_avg = temperature_sum / valid_samples; + + for (int i = 0; i < valid_samples; i++) { + // temperature changing wildly is an indication of a transfer error + if (fabsf(temperature[i] - temperature_avg) > 1000) { + perf_count(_bad_transfer_perf); + return false; + } + } + + // use average temperature reading + const float TEMP_degC = (temperature_avg / TEMPERATURE_SENSITIVITY) + TEMPERATURE_OFFSET; + + if (PX4_ISFINITE(TEMP_degC)) { + _px4_accel.set_temperature(TEMP_degC); + _px4_gyro.set_temperature(TEMP_degC); + return true; + + } else { + perf_count(_bad_transfer_perf); + } + } + + return false; +} diff --git a/src/drivers/imu/invensense/iim42653/IIM42653.hpp b/src/drivers/imu/invensense/iim42653/IIM42653.hpp new file mode 100644 index 000000000000..ab9c551a7a93 --- /dev/null +++ b/src/drivers/imu/invensense/iim42653/IIM42653.hpp @@ -0,0 +1,227 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * 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. + * + ****************************************************************************/ + +/** + * @file IIM42653.hpp + * + * Driver for the Invensense IIM42653 connected via SPI. + * + */ + +#pragma once + +#include "InvenSense_IIM42653_registers.hpp" + +#include +#include +#include +#include +#include +#include +#include +#include + +using namespace InvenSense_IIM42653; + +class IIM42653 : public device::SPI, public I2CSPIDriver +{ +public: + IIM42653(const I2CSPIDriverConfig &config); + ~IIM42653() override; + + static void print_usage(); + + void RunImpl(); + + int init() override; + void print_status() override; + +private: + void exit_and_cleanup() override; + + // Sensor Configuration + static constexpr float FIFO_SAMPLE_DT{1e6f / 8000.f}; // 8000 Hz accel & gyro ODR configured + static constexpr float GYRO_RATE{1e6f / FIFO_SAMPLE_DT}; + static constexpr float ACCEL_RATE{1e6f / FIFO_SAMPLE_DT}; + + static constexpr float FIFO_TIMESTAMP_SCALING{16.f *(32.f / 30.f)}; // Used when not using clock input + + // maximum FIFO samples per transfer is limited to the size of sensor_accel_fifo/sensor_gyro_fifo + static constexpr int32_t FIFO_MAX_SAMPLES{math::min(FIFO::SIZE / sizeof(FIFO::DATA), sizeof(sensor_gyro_fifo_s::x) / sizeof(sensor_gyro_fifo_s::x[0]), sizeof(sensor_accel_fifo_s::x) / sizeof(sensor_accel_fifo_s::x[0]) * (int)(GYRO_RATE / ACCEL_RATE))}; + + // Transfer data + struct FIFOTransferBuffer { + uint8_t cmd{static_cast(Register::BANK_0::INT_STATUS) | DIR_READ}; + uint8_t INT_STATUS{0}; + uint8_t FIFO_COUNTH{0}; + uint8_t FIFO_COUNTL{0}; + FIFO::DATA f[FIFO_MAX_SAMPLES] {}; + }; + // ensure no struct padding + static_assert(sizeof(FIFOTransferBuffer) == (4 + FIFO_MAX_SAMPLES *sizeof(FIFO::DATA))); + + struct register_bank0_config_t { + Register::BANK_0 reg; + uint8_t set_bits{0}; + uint8_t clear_bits{0}; + }; + + struct register_bank1_config_t { + Register::BANK_1 reg; + uint8_t set_bits{0}; + uint8_t clear_bits{0}; + }; + + struct register_bank2_config_t { + Register::BANK_2 reg; + uint8_t set_bits{0}; + uint8_t clear_bits{0}; + }; + + int probe() override; + + bool Reset(); + + bool Configure(); + void ConfigureSampleRate(int sample_rate); + void ConfigureFIFOWatermark(uint8_t samples); + void ConfigureCLKIN(); + + void SelectRegisterBank(enum REG_BANK_SEL_BIT bank, bool force = false); + void SelectRegisterBank(Register::BANK_0 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::BANK_SEL_0); } + void SelectRegisterBank(Register::BANK_1 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::BANK_SEL_1); } + void SelectRegisterBank(Register::BANK_2 reg) { SelectRegisterBank(REG_BANK_SEL_BIT::BANK_SEL_2); } + + static int DataReadyInterruptCallback(int irq, void *context, void *arg); + void DataReady(); + bool DataReadyInterruptConfigure(); + bool DataReadyInterruptDisable(); + + template bool RegisterCheck(const T ®_cfg); + template uint8_t RegisterRead(T reg); + template void RegisterWrite(T reg, uint8_t value); + template void RegisterSetAndClearBits(T reg, uint8_t setbits, uint8_t clearbits); + template void RegisterSetBits(T reg, uint8_t setbits) { RegisterSetAndClearBits(reg, setbits, 0); } + template void RegisterClearBits(T reg, uint8_t clearbits) { RegisterSetAndClearBits(reg, 0, clearbits); } + + uint16_t FIFOReadCount(); + bool FIFORead(const hrt_abstime ×tamp_sample, uint8_t samples); + void FIFOReset(); + + void ProcessAccel(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples); + void ProcessGyro(const hrt_abstime ×tamp_sample, const FIFO::DATA fifo[], const uint8_t samples); + bool ProcessTemperature(const FIFO::DATA fifo[], const uint8_t samples); + + const spi_drdy_gpio_t _drdy_gpio; + + PX4Accelerometer _px4_accel; + PX4Gyroscope _px4_gyro; + + perf_counter_t _bad_register_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad register")}; + perf_counter_t _bad_transfer_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad transfer")}; + perf_counter_t _fifo_empty_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO empty")}; + perf_counter_t _fifo_overflow_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO overflow")}; + perf_counter_t _fifo_reset_perf{perf_alloc(PC_COUNT, MODULE_NAME": FIFO reset")}; + perf_counter_t _drdy_missed_perf{nullptr}; + + hrt_abstime _reset_timestamp{0}; + hrt_abstime _last_config_check_timestamp{0}; + hrt_abstime _temperature_update_timestamp{0}; + int _failure_count{0}; + + bool _enable_clock_input{false}; + float _input_clock_freq{0.f}; + + enum REG_BANK_SEL_BIT _last_register_bank {REG_BANK_SEL_BIT::BANK_SEL_0}; + + px4::atomic _drdy_timestamp_sample{0}; + bool _data_ready_interrupt_enabled{false}; + + enum class STATE : uint8_t { + RESET, + WAIT_FOR_RESET, + CONFIGURE, + FIFO_RESET, + FIFO_READ, + } _state{STATE::RESET}; + + uint16_t _fifo_empty_interval_us{1250}; // default 1250 us / 800 Hz transfer interval + int32_t _fifo_gyro_samples{static_cast(_fifo_empty_interval_us / (1000000 / GYRO_RATE))}; + + uint8_t _checked_register_bank0{0}; + static constexpr uint8_t size_register_bank0_cfg{16}; + register_bank0_config_t _register_bank0_cfg[size_register_bank0_cfg] { + // Register | Set bits, Clear bits + { Register::BANK_0::INT_CONFIG, INT_CONFIG_BIT::INT1_MODE | INT_CONFIG_BIT::INT1_DRIVE_CIRCUIT, INT_CONFIG_BIT::INT1_POLARITY }, + { Register::BANK_0::FIFO_CONFIG, FIFO_CONFIG_BIT::FIFO_MODE_STOP_ON_FULL, 0 }, + { Register::BANK_0::INTF_CONFIG1, 0, 0}, // RTC_MODE[2] set at runtime + { Register::BANK_0::PWR_MGMT0, PWR_MGMT0_BIT::GYRO_MODE_LOW_NOISE | PWR_MGMT0_BIT::ACCEL_MODE_LOW_NOISE, 0 }, + { Register::BANK_0::GYRO_CONFIG0, GYRO_CONFIG0_BIT::GYRO_FS_SEL_4000_DPS | GYRO_CONFIG0_BIT::GYRO_ODR_8KHZ_SET, GYRO_CONFIG0_BIT::GYRO_ODR_8KHZ_CLEAR }, + { Register::BANK_0::ACCEL_CONFIG0, ACCEL_CONFIG0_BIT::ACCEL_FS_SEL_32G | ACCEL_CONFIG0_BIT::ACCEL_ODR_8KHZ_SET, ACCEL_CONFIG0_BIT::ACCEL_ODR_8KHZ_CLEAR }, + { Register::BANK_0::GYRO_CONFIG1, 0, GYRO_CONFIG1_BIT::GYRO_UI_FILT_ORD }, + { Register::BANK_0::GYRO_ACCEL_CONFIG0, 0, GYRO_ACCEL_CONFIG0_BIT::ACCEL_UI_FILT_BW | GYRO_ACCEL_CONFIG0_BIT::GYRO_UI_FILT_BW }, + { Register::BANK_0::ACCEL_CONFIG1, 0, ACCEL_CONFIG1_BIT::ACCEL_UI_FILT_ORD }, + { Register::BANK_0::TMST_CONFIG, TMST_CONFIG_BIT::TMST_EN | TMST_CONFIG_BIT::TMST_DELTA_EN | TMST_CONFIG_BIT::TMST_TO_REGS_EN | TMST_CONFIG_BIT::TMST_RES, TMST_CONFIG_BIT::TMST_FSYNC_EN }, + { Register::BANK_0::FIFO_CONFIG1, FIFO_CONFIG1_BIT::FIFO_WM_GT_TH | FIFO_CONFIG1_BIT::FIFO_HIRES_EN | FIFO_CONFIG1_BIT::FIFO_TEMP_EN | FIFO_CONFIG1_BIT::FIFO_GYRO_EN | FIFO_CONFIG1_BIT::FIFO_ACCEL_EN, FIFO_CONFIG1_BIT::FIFO_TMST_FSYNC_EN }, + { Register::BANK_0::FIFO_CONFIG2, 0, 0 }, // FIFO_WM[7:0] set at runtime + { Register::BANK_0::FIFO_CONFIG3, 0, 0 }, // FIFO_WM[11:8] set at runtime + { Register::BANK_0::INT_CONFIG0, INT_CONFIG0_BIT::CLEAR_ON_FIFO_READ, 0 }, + { Register::BANK_0::INT_CONFIG1, 0, INT_CONFIG1_BIT::INT_ASYNC_RESET }, + { Register::BANK_0::INT_SOURCE0, INT_SOURCE0_BIT::FIFO_THS_INT1_EN, 0 }, + }; + + uint8_t _checked_register_bank1{0}; + static constexpr uint8_t size_register_bank1_cfg{5}; + register_bank1_config_t _register_bank1_cfg[size_register_bank1_cfg] { + // Register | Set bits, Clear bits + { Register::BANK_1::GYRO_CONFIG_STATIC2, 0, GYRO_CONFIG_STATIC2_BIT::GYRO_NF_DIS | GYRO_CONFIG_STATIC2_BIT::GYRO_AAF_DIS }, + { Register::BANK_1::GYRO_CONFIG_STATIC3, GYRO_CONFIG_STATIC3_BIT::GYRO_AAF_DELT_585HZ_SET, GYRO_CONFIG_STATIC3_BIT::GYRO_AAF_DELT_585HZ_CLEAR}, + { Register::BANK_1::GYRO_CONFIG_STATIC4, GYRO_CONFIG_STATIC4_BIT::GYRO_AAF_DELTSQR_LSB_585HZ_SET, GYRO_CONFIG_STATIC4_BIT::GYRO_AAF_DELTSQR_LSB_585HZ_CLEAR}, + { Register::BANK_1::GYRO_CONFIG_STATIC5, GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_BITSHIFT_585HZ_SET | GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_DELTSQR_MSB_585HZ_SET, GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_BITSHIFT_585HZ_CLEAR | GYRO_CONFIG_STATIC5_BIT::GYRO_AAF_DELTSQR_MSB_585HZ_CLEAR}, + { Register::BANK_1::INTF_CONFIG5, 0, 0 }, + }; + + uint8_t _checked_register_bank2{0}; + static constexpr uint8_t size_register_bank2_cfg{8}; + register_bank2_config_t _register_bank2_cfg[size_register_bank2_cfg] { + // Register | Set bits, Clear bits + { Register::BANK_2::ACCEL_CONFIG_STATIC2, ACCEL_CONFIG_STATIC2_BIT::ACCEL_AAF_DELT_585HZ_SET, ACCEL_CONFIG_STATIC2_BIT::ACCEL_AAF_DELT_585HZ_CLEAR | ACCEL_CONFIG_STATIC2_BIT::ACCEL_AAF_DIS }, + { Register::BANK_2::ACCEL_CONFIG_STATIC3, ACCEL_CONFIG_STATIC3_BIT::ACCEL_AAF_DELTSQR_LSB_585HZ_SET, ACCEL_CONFIG_STATIC3_BIT::ACCEL_AAF_DELTSQR_LSB_585HZ_CLEAR }, + { Register::BANK_2::ACCEL_CONFIG_STATIC4, ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_BITSHIFT_585HZ_SET | ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_DELTSQR_MSB_SET, ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_BITSHIFT_585HZ_CLEAR | ACCEL_CONFIG_STATIC4_BIT::ACCEL_AAF_DELTSQR_MSB_CLEAR }, + { Register::BANK_2::AUX1_CONFIG1, 0, AUX1_CONFIG1_BIT::AUX1_ACCEL_LP_CLK_SEL | AUX1_CONFIG1_BIT::GYRO_AUX1_EN | AUX1_CONFIG1_BIT::ACCEL_AUX1_EN}, + { Register::BANK_2::AUX1_CONFIG2, AUX1_CONFIG2_BIT::GYRO_AUX1_HPF_DIS, 0}, + { Register::BANK_2::AUX1_SPI_REG1, AUX1_SPI_REG1_BIT::AUX1_SPI_REG1_SET, AUX1_SPI_REG1_BIT::AUX1_SPI_REG1_CLEAR }, + { Register::BANK_2::AUX1_SPI_REG2, AUX1_SPI_REG2_BIT::AUX1_SPI_REG2_SET, AUX1_SPI_REG2_BIT::AUX1_SPI_REG2_CLEAR }, + { Register::BANK_2::AUX1_SPI_REG3, AUX1_SPI_REG3_BIT::AUX1_SPI_REG3_SET, AUX1_SPI_REG3_BIT::AUX1_SPI_REG3_CLEAR }, + }; +}; diff --git a/src/drivers/imu/invensense/iim42653/InvenSense_IIM42653_registers.hpp b/src/drivers/imu/invensense/iim42653/InvenSense_IIM42653_registers.hpp new file mode 100644 index 000000000000..7bd183787fc6 --- /dev/null +++ b/src/drivers/imu/invensense/iim42653/InvenSense_IIM42653_registers.hpp @@ -0,0 +1,453 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * 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. + * + ****************************************************************************/ + +/** + * @file InvenSense_IIM42653_registers.hpp + * + * Invensense IIM-42653 registers. + * + */ + +#pragma once + +#include +#include + +namespace InvenSense_IIM42653 +{ +// TODO: move to a central header +static constexpr uint8_t Bit0 = (1 << 0); +static constexpr uint8_t Bit1 = (1 << 1); +static constexpr uint8_t Bit2 = (1 << 2); +static constexpr uint8_t Bit3 = (1 << 3); +static constexpr uint8_t Bit4 = (1 << 4); +static constexpr uint8_t Bit5 = (1 << 5); +static constexpr uint8_t Bit6 = (1 << 6); +static constexpr uint8_t Bit7 = (1 << 7); + +static constexpr uint32_t SPI_SPEED = 24 * 1000 * 1000; // 24 MHz SPI +static constexpr uint8_t DIR_READ = 0x80; + +static constexpr uint8_t WHOAMI = 0x56; + +static constexpr float TEMPERATURE_SENSITIVITY = 132.48f; // LSB/C +static constexpr float TEMPERATURE_OFFSET = 25.f; // C + +namespace Register +{ + +enum class BANK_0 : uint8_t { + DEVICE_CONFIG = 0x11, + + INT_CONFIG = 0x14, + + FIFO_CONFIG = 0x16, + + TEMP_DATA1 = 0x1D, + TEMP_DATA0 = 0x1E, + + INT_STATUS = 0x2D, + FIFO_COUNTH = 0x2E, + FIFO_COUNTL = 0x2F, + FIFO_DATA = 0x30, + + SIGNAL_PATH_RESET = 0x4B, + INTF_CONFIG0 = 0x4C, + INTF_CONFIG1 = 0x4D, + PWR_MGMT0 = 0x4E, + GYRO_CONFIG0 = 0x4F, + ACCEL_CONFIG0 = 0x50, + GYRO_CONFIG1 = 0x51, + GYRO_ACCEL_CONFIG0 = 0x52, + ACCEL_CONFIG1 = 0x53, + TMST_CONFIG = 0x54, + + FIFO_CONFIG1 = 0x5F, + FIFO_CONFIG2 = 0x60, + FIFO_CONFIG3 = 0x61, + + INT_CONFIG0 = 0x63, + INT_CONFIG1 = 0x64, + + INT_SOURCE0 = 0x65, + + SELF_TEST_CONFIG = 0x70, + + WHO_AM_I = 0x75, + REG_BANK_SEL = 0x76, +}; + +enum class BANK_1 : uint8_t { + GYRO_CONFIG_STATIC2 = 0x0B, + GYRO_CONFIG_STATIC3 = 0x0C, + GYRO_CONFIG_STATIC4 = 0x0D, + GYRO_CONFIG_STATIC5 = 0x0E, + + INTF_CONFIG5 = 0x7B, +}; + +enum class BANK_2 : uint8_t { + ACCEL_CONFIG_STATIC2 = 0x03, + ACCEL_CONFIG_STATIC3 = 0x04, + ACCEL_CONFIG_STATIC4 = 0x05, + AUX1_CONFIG1 = 0x44, + AUX1_CONFIG2 = 0x45, + AUX1_CONFIG3 = 0x46, + AUX1_SPI_REG1 = 0x71, + AUX1_SPI_REG2 = 0x72, + AUX1_SPI_REG3 = 0x73, +}; + +}; + +//---------------- BANK0 Register bits + +// DEVICE_CONFIG +enum DEVICE_CONFIG_BIT : uint8_t { + SOFT_RESET_CONFIG = Bit0, // +}; + +// INT_CONFIG +enum INT_CONFIG_BIT : uint8_t { + INT1_MODE = Bit2, + INT1_DRIVE_CIRCUIT = Bit1, + INT1_POLARITY = Bit0, +}; + +// FIFO_CONFIG +enum FIFO_CONFIG_BIT : uint8_t { + // 7:6 FIFO_MODE + FIFO_MODE_STOP_ON_FULL = Bit7 | Bit6, // 11: STOP-on-FULL Mode +}; + +// INT_STATUS +enum INT_STATUS_BIT : uint8_t { + RESET_DONE_INT = Bit4, + DATA_RDY_INT = Bit3, + FIFO_THS_INT = Bit2, + FIFO_FULL_INT = Bit1, +}; + +// SIGNAL_PATH_RESET +enum SIGNAL_PATH_RESET_BIT : uint8_t { + ABORT_AND_RESET = Bit3, + FIFO_FLUSH = Bit1, +}; + +enum INTF_CONFIG1_BIT : uint8_t { + RTC_MODE = Bit2, // 0: No input RTC clock is required, 1: RTC clock input is required + CLKSEL = Bit0, + CLKSEL_CLEAR = Bit1, +}; + +// PWR_MGMT0 +enum PWR_MGMT0_BIT : uint8_t { + GYRO_MODE_LOW_NOISE = Bit3 | Bit2, // 11: Places gyroscope in Low Noise (LN) Mode + ACCEL_MODE_LOW_NOISE = Bit1 | Bit0, // 11: Places accelerometer in Low Noise (LN) Mode +}; + +// GYRO_CONFIG0 +enum GYRO_CONFIG0_BIT : uint8_t { + // 7:5 GYRO_FS_SEL + GYRO_FS_SEL_4000_DPS = 0, // 0b000 = ±4000dps (default) + GYRO_FS_SEL_2000_DPS = Bit5, + GYRO_FS_SEL_1000_DPS = Bit6, + GYRO_FS_SEL_500_DPS = Bit6 | Bit5, + GYRO_FS_SEL_250_DPS = Bit7, + + + // 3:0 GYRO_ODR + // 0001: 32kHz + GYRO_ODR_32KHZ_SET = Bit0, + GYRO_ODR_32KHZ_CLEAR = Bit3 | Bit2 | Bit0, + // 0010: 16kHz + GYRO_ODR_16KHZ_SET = Bit1, + GYRO_ODR_16KHZ_CLEAR = Bit3 | Bit2 | Bit0, + // 0011: 8kHz + GYRO_ODR_8KHZ_SET = Bit1 | Bit0, + GYRO_ODR_8KHZ_CLEAR = Bit3 | Bit2, + // 0110: 1kHz (default) + GYRO_ODR_1KHZ_SET = Bit2 | Bit1, + GYRO_ODR_1KHZ_CLEAR = Bit3 | Bit0, +}; + +// ACCEL_CONFIG0 +enum ACCEL_CONFIG0_BIT : uint8_t { + // 7:5 ACCEL_FS_SEL + ACCEL_FS_SEL_32G = 0, // 000: ±32g (default) + ACCEL_FS_SEL_16G = Bit5, + ACCEL_FS_SEL_8G = Bit6, + ACCEL_FS_SEL_4G = Bit6 | Bit5, + + + // 3:0 ACCEL_ODR + // 0001: 32kHz + ACCEL_ODR_32KHZ_SET = Bit0, + ACCEL_ODR_32KHZ_CLEAR = Bit3 | Bit2 | Bit0, + // 0010: 16kHz + ACCEL_ODR_16KHZ_SET = Bit1, + ACCEL_ODR_16KHZ_CLEAR = Bit3 | Bit2 | Bit0, + // 0011: 8kHz + ACCEL_ODR_8KHZ_SET = Bit1 | Bit0, + ACCEL_ODR_8KHZ_CLEAR = Bit3 | Bit2, + // 0110: 1kHz (default) + ACCEL_ODR_1KHZ_SET = Bit2 | Bit1, + ACCEL_ODR_1KHZ_CLEAR = Bit3 | Bit0, +}; + +// GYRO_CONFIG1 +enum GYRO_CONFIG1_BIT : uint8_t { + GYRO_UI_FILT_ORD = Bit3 | Bit2, // 00: 1st Order +}; + +// GYRO_ACCEL_CONFIG0 +enum GYRO_ACCEL_CONFIG0_BIT : uint8_t { + // 7:4 ACCEL_UI_FILT_BW + ACCEL_UI_FILT_BW = Bit7 | Bit6 | Bit5 | Bit4, // 0: BW=ODR/2 + + // 3:0 GYRO_UI_FILT_BW + GYRO_UI_FILT_BW = Bit3 | Bit2 | Bit1 | Bit0, // 0: BW=ODR/2 +}; + +// ACCEL_CONFIG1 +enum ACCEL_CONFIG1_BIT : uint8_t { + ACCEL_UI_FILT_ORD = Bit4 | Bit3, // 00: 1st Order +}; + +// TMST_CONFIG +enum TMST_CONFIG_BIT : uint8_t { + TMST_TO_REGS_EN = Bit4, // 1: TMST_VALUE[19:0] read returns timestamp value + TMST_RES = Bit3, // 0: 1us resolution, 1: 16us resolution + TMST_DELTA_EN = Bit2, // 1: Time Stamp delta enable + TMST_FSYNC_EN = Bit1, // 1: The contents of the Timestamp feature of FSYNC is enabled + TMST_EN = Bit0, // 1: Time Stamp register enable (default) +}; + +// FIFO_CONFIG1 +enum FIFO_CONFIG1_BIT : uint8_t { + FIFO_RESUME_PARTIAL_RD = Bit6, + FIFO_WM_GT_TH = Bit5, + FIFO_HIRES_EN = Bit4, + FIFO_TMST_FSYNC_EN = Bit3, + FIFO_TEMP_EN = Bit2, + FIFO_GYRO_EN = Bit1, + FIFO_ACCEL_EN = Bit0, +}; + +// INT_CONFIG0 +enum INT_CONFIG0_BIT : uint8_t { + // 3:2 FIFO_THS_INT_CLEAR + CLEAR_ON_FIFO_READ = Bit3, +}; + +// INT_CONFIG1 +enum INT_CONFIG1_BIT : uint8_t { + INT_ASYNC_RESET = Bit4, +}; + +// INT_SOURCE0 +enum INT_SOURCE0_BIT : uint8_t { + UI_FSYNC_INT1_EN = Bit6, + PLL_RDY_INT1_EN = Bit5, + RESET_DONE_INT1_EN = Bit4, + UI_DRDY_INT1_EN = Bit3, + FIFO_THS_INT1_EN = Bit2, // FIFO threshold interrupt routed to INT1 + FIFO_FULL_INT1_EN = Bit1, + UI_AGC_RDY_INT1_EN = Bit0, +}; + +// REG_BANK_SEL +enum REG_BANK_SEL_BIT : uint8_t { + // 2:0 BANK_SEL + BANK_SEL_0 = 0, // 000: Bank 0 (default) + BANK_SEL_1 = Bit0, // 001: Bank 1 + BANK_SEL_2 = Bit1, // 010: Bank 2 + BANK_SEL_3 = Bit1 | Bit0, // 011: Bank 3 + BANK_SEL_4 = Bit2, // 100: Bank 4 +}; + + +//---------------- BANK1 Register bits + +// GYRO_CONFIG_STATIC2 +enum GYRO_CONFIG_STATIC2_BIT : uint8_t { + GYRO_AAF_DIS = Bit1, // 1: Disable gyroscope anti-aliasing filter + GYRO_NF_DIS = Bit0, // 1: Disable Notch Filter +}; + +// GYRO_CONFIG_STATIC3 +enum GYRO_CONFIG_STATIC3_BIT : uint8_t { + // 5:0 GYRO_AAF_DELT + // 585 Hz = 13 (0b00'1101) + GYRO_AAF_DELT_585HZ_SET = Bit3 | Bit2 | Bit0, + GYRO_AAF_DELT_585HZ_CLEAR = Bit5 | Bit4 | Bit1, +}; + +// GYRO_CONFIG_STATIC4 +enum GYRO_CONFIG_STATIC4_BIT : uint8_t { + // 7:0 GYRO_AAF_DELTSQR + // 585 Hz = 170 (0b1010'1010) + GYRO_AAF_DELTSQR_LSB_585HZ_SET = Bit7 | Bit5 | Bit3 | Bit1, + GYRO_AAF_DELTSQR_LSB_585HZ_CLEAR = Bit6 | Bit4 | Bit2 | Bit0, +}; + +// GYRO_CONFIG_STATIC5 +enum GYRO_CONFIG_STATIC5_BIT : uint8_t { + // 7:4 GYRO_AAF_BITSHIFT + // 585 Hz = 8 (0b1000) + GYRO_AAF_BITSHIFT_585HZ_SET = Bit7, + GYRO_AAF_BITSHIFT_585HZ_CLEAR = Bit6 | Bit5 | Bit4, + + // 3:0 GYRO_AAF_DELTSQR[11:8] + // 585 Hz = 170 (0b0000'1010'1010) + GYRO_AAF_DELTSQR_MSB_585HZ_SET = 0, + GYRO_AAF_DELTSQR_MSB_585HZ_CLEAR = Bit3 | Bit2 | Bit1 | Bit0, +}; + +// INTF_CONFIG5 +enum INTF_CONFIG5_BIT : uint8_t { + // 2:1 PIN9_FUNCTION + PIN9_FUNCTION_CLKIN_SET = Bit2, // 0b10: CLKIN + PIN9_FUNCTION_CLKIN_CLEAR = Bit1, + + PIN9_FUNCTION_RESET_SET = 0, + PIN9_FUNCTION_RESET_CLEAR = Bit2 | Bit1, +}; + +//---------------- BANK2 Register bits + +// ACCEL_CONFIG_STATIC2 +enum ACCEL_CONFIG_STATIC2_BIT : uint8_t { + // 6:1 ACCEL_AAF_DELT + // 585 Hz = 13 (0b00'1101) + ACCEL_AAF_DELT_585HZ_SET = Bit4 | Bit3 | Bit1, + ACCEL_AAF_DELT_585HZ_CLEAR = Bit6 | Bit5 | Bit2, + + // 0 ACCEL_AAF_DIS + ACCEL_AAF_DIS = Bit0, // 0: Enable accelerometer anti-aliasing filter (default) +}; + +// ACCEL_CONFIG_STATIC3 +enum ACCEL_CONFIG_STATIC3_BIT : uint8_t { + // 7:0 ACCEL_AAF_DELTSQR[7:0] + // 585 Hz = 170 (0b0000'1010'1010) + ACCEL_AAF_DELTSQR_LSB_585HZ_SET = Bit7 | Bit5 | Bit3 | Bit1, + ACCEL_AAF_DELTSQR_LSB_585HZ_CLEAR = Bit6 | Bit4 | Bit2 | Bit0, +}; + +// ACCEL_CONFIG_STATIC4 +enum ACCEL_CONFIG_STATIC4_BIT : uint8_t { + // 7:4 ACCEL_AAF_BITSHIFT + // 585 Hz = 8 (0b1000) + ACCEL_AAF_BITSHIFT_585HZ_SET = Bit7, + ACCEL_AAF_BITSHIFT_585HZ_CLEAR = Bit6 | Bit5 | Bit4, + + // 3:0 ACCEL_AAF_DELTSQR[11:8] + // 585 Hz = 170 (0b0000'1010'1010) + ACCEL_AAF_DELTSQR_MSB_SET = 0, + ACCEL_AAF_DELTSQR_MSB_CLEAR = Bit3 | Bit2 | Bit1 | Bit0, +}; + +// AUX1_CONFIG1 +enum AUX1_CONFIG1_BIT : uint8_t { + AUX1_ACCEL_LP_CLK_SEL = Bit5, + GYRO_AUX1_EN = Bit1, + ACCEL_AUX1_EN = Bit0, +}; + +// AUX1_CONFIG2 +enum AUX1_CONFIG2_BIT : uint8_t { + GYRO_AUX1_HPF_DIS = Bit6, +}; + +// AUX1_SPI_REG1 +enum AUX1_SPI_REG1_BIT : uint8_t { + AUX1_SPI_REG1_CLEAR = Bit1, + AUX1_SPI_REG1_SET = Bit0, +}; + +// AUX1_SPI_REG2 +enum AUX1_SPI_REG2_BIT : uint8_t { + AUX1_SPI_REG2_CLEAR = Bit1, + AUX1_SPI_REG2_SET = Bit0, +}; + +// AUX1_SPI_REG3 +enum AUX1_SPI_REG3_BIT : uint8_t { + AUX1_SPI_REG3_CLEAR = Bit1, + AUX1_SPI_REG3_SET = Bit0, +}; + +namespace FIFO +{ +static constexpr size_t SIZE = 2048; + +// FIFO_DATA layout when FIFO_CONFIG1 has FIFO_GYRO_EN and FIFO_ACCEL_EN set + +// Packet 4 +struct DATA { + uint8_t FIFO_Header; + uint8_t ACCEL_DATA_X1; // Accel X [19:12] + uint8_t ACCEL_DATA_X0; // Accel X [11:4] + uint8_t ACCEL_DATA_Y1; // Accel Y [19:12] + uint8_t ACCEL_DATA_Y0; // Accel Y [11:4] + uint8_t ACCEL_DATA_Z1; // Accel Z [19:12] + uint8_t ACCEL_DATA_Z0; // Accel Z [11:4] + uint8_t GYRO_DATA_X1; // Gyro X [19:12] + uint8_t GYRO_DATA_X0; // Gyro X [11:4] + uint8_t GYRO_DATA_Y1; // Gyro Y [19:12] + uint8_t GYRO_DATA_Y0; // Gyro Y [11:4] + uint8_t GYRO_DATA_Z1; // Gyro Z [19:12] + uint8_t GYRO_DATA_Z0; // Gyro Z [11:4] + uint8_t TEMP_DATA1; // Temperature[15:8] + uint8_t TEMP_DATA0; // Temperature[7:0] + uint8_t TimeStamp_h; // TimeStamp[15:8] + uint8_t TimeStamp_l; // TimeStamp[7:0] + uint8_t Ext_Accel_X_Gyro_X; // Accel X [3:0] Gyro X [3:0] + uint8_t Ext_Accel_Y_Gyro_Y; // Accel Y [3:0] Gyro Y [3:0] + uint8_t Ext_Accel_Z_Gyro_Z; // Accel Z [3:0] Gyro Z [3:0] +}; + +// With FIFO_ACCEL_EN and FIFO_GYRO_EN header should be 8’b_0110_10xx +enum FIFO_HEADER_BIT : uint8_t { + HEADER_MSG = Bit7, // 1: FIFO is empty + HEADER_ACCEL = Bit6, // 1: Packet is sized so that accel data have location in the packet, FIFO_ACCEL_EN must be 1 + HEADER_GYRO = Bit5, // 1: Packet is sized so that gyro data have location in the packet, FIFO_GYRO_EN must be1 + HEADER_20 = Bit4, // 1: Packet has a new and valid sample of extended 20-bit data for gyro and/or accel + HEADER_TIMESTAMP_FSYNC = Bit3 | Bit2, // 10: Packet contains ODR Timestamp + HEADER_ODR_ACCEL = Bit1, // 1: The ODR for accel is different for this accel data packet compared to the previous accel packet + HEADER_ODR_GYRO = Bit0, // 1: The ODR for gyro is different for this gyro data packet compared to the previous gyro packet +}; + +} +} // namespace InvenSense_IIM42653 diff --git a/src/drivers/imu/invensense/iim42653/Kconfig b/src/drivers/imu/invensense/iim42653/Kconfig new file mode 100644 index 000000000000..903f3d3cb9ae --- /dev/null +++ b/src/drivers/imu/invensense/iim42653/Kconfig @@ -0,0 +1,5 @@ +menuconfig DRIVERS_IMU_INVENSENSE_IIM42653 + bool "iim42653" + default n + ---help--- + Enable support for iim42653 diff --git a/src/drivers/imu/invensense/iim42653/iim42653_main.cpp b/src/drivers/imu/invensense/iim42653/iim42653_main.cpp new file mode 100644 index 000000000000..655fdd2e19b1 --- /dev/null +++ b/src/drivers/imu/invensense/iim42653/iim42653_main.cpp @@ -0,0 +1,92 @@ +/**************************************************************************** + * + * Copyright (c) 2023 PX4 Development Team. All rights reserved. + * + * Redistribution and use in source and binary forms, with or without + * modification, are permitted provided that the following conditions + * 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 "IIM42653.hpp" + +#include +#include + +void IIM42653::print_usage() +{ + PRINT_MODULE_USAGE_NAME("iim42653", "driver"); + PRINT_MODULE_USAGE_SUBCATEGORY("imu"); + PRINT_MODULE_USAGE_COMMAND("start"); + PRINT_MODULE_USAGE_PARAMS_I2C_SPI_DRIVER(false, true); + PRINT_MODULE_USAGE_PARAM_INT('R', 0, 0, 35, "Rotation", true); + PRINT_MODULE_USAGE_PARAM_INT('C', 0, 0, 35000, "Input clock frequency (Hz)", true); + PRINT_MODULE_USAGE_DEFAULT_COMMANDS(); +} + +extern "C" int iim42653_main(int argc, char *argv[]) +{ + int ch; + using ThisDriver = IIM42653; + BusCLIArguments cli{false, true}; + cli.default_spi_frequency = SPI_SPEED; + + while ((ch = cli.getOpt(argc, argv, "C:R:")) != EOF) { + switch (ch) { + case 'C': + cli.custom1 = atoi(cli.optArg()); + break; + + case 'R': + cli.rotation = (enum Rotation)atoi(cli.optArg()); + break; + } + } + + const char *verb = cli.optArg(); + + if (!verb) { + ThisDriver::print_usage(); + return -1; + } + + BusInstanceIterator iterator(MODULE_NAME, cli, DRV_IMU_DEVTYPE_IIM42653); + + if (!strcmp(verb, "start")) { + return ThisDriver::module_start(cli, iterator); + } + + if (!strcmp(verb, "stop")) { + return ThisDriver::module_stop(iterator); + } + + if (!strcmp(verb, "status")) { + return ThisDriver::module_status(iterator); + } + + ThisDriver::print_usage(); + return -1; +} From da60618d858698d5201801963c565d2d9a76c3df Mon Sep 17 00:00:00 2001 From: Silvan Fuhrer Date: Thu, 17 Aug 2023 10:02:48 +0200 Subject: [PATCH 08/11] ActuatorEffectiveness: add comment for 2% magic number to stop motors Signed-off-by: Silvan Fuhrer --- .../ActuatorEffectiveness/ActuatorEffectiveness.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectiveness.cpp b/src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectiveness.cpp index 099adb3120c5..901c469746e6 100644 --- a/src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectiveness.cpp +++ b/src/modules/control_allocator/ActuatorEffectiveness/ActuatorEffectiveness.cpp @@ -91,6 +91,8 @@ void ActuatorEffectiveness::stopMaskedMotorsWithZeroThrust(uint32_t stoppable_mo const uint32_t motor_mask = (1u << actuator_idx); if (stoppable_motors_mask & motor_mask) { + + // Stop motor if its setpoint is below 2%. This value was determined empirically (RC stick inaccuracy) if (fabsf(actuator_sp(actuator_idx)) < .02f) { _stopped_motors_mask |= motor_mask; From 550bd7c18917639e34b83eb06c539e2e98dc8104 Mon Sep 17 00:00:00 2001 From: Mathieu Bresciani Date: Thu, 17 Aug 2023 15:55:15 +0200 Subject: [PATCH 09/11] EKF2: improve resilience against incorrect mag data - when GNSS is used require low mag heading innovations during horizontal acceleration (yaw observable) to validate the mag - only fuse mag heading just enough to constrain the yaw estimate variance to a sane value. Leave enough uncertainty to allow for a correction when the yaw is observable through GNSS fusion --- msg/EstimatorStatusFlags.msg | 1 + src/modules/ekf2/EKF/common.h | 1 + src/modules/ekf2/EKF/ekf.h | 2 + src/modules/ekf2/EKF/mag_3d_control.cpp | 1 + src/modules/ekf2/EKF/mag_control.cpp | 17 + src/modules/ekf2/EKF/mag_heading_control.cpp | 23 +- src/modules/ekf2/EKF2.cpp | 1 + .../test/change_indication/ekf_gsf_reset.csv | 656 +++++++++--------- .../ekf2/test/change_indication/iris_gps.csv | 576 +++++++-------- .../test/sensor_simulator/ekf_wrapper.cpp | 5 + .../ekf2/test/sensor_simulator/ekf_wrapper.h | 1 + .../ekf2/test/test_EKF_externalVision.cpp | 3 +- src/modules/ekf2/test/test_EKF_gps_yaw.cpp | 10 +- src/modules/ekf2/test/test_EKF_gyroscope.cpp | 21 +- src/modules/ekf2/test/test_EKF_mag.cpp | 3 +- 15 files changed, 685 insertions(+), 636 deletions(-) diff --git a/msg/EstimatorStatusFlags.msg b/msg/EstimatorStatusFlags.msg index 92aef646eca0..4d747d826880 100644 --- a/msg/EstimatorStatusFlags.msg +++ b/msg/EstimatorStatusFlags.msg @@ -41,6 +41,7 @@ bool cs_fake_hgt # 33 - true when fake height measurements are be bool cs_gravity_vector # 34 - true when gravity vector measurements are being fused bool cs_mag # 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended bool cs_ev_yaw_fault # 36 - true when the EV heading has been declared faulty and is no longer being used +bool cs_mag_heading_consistent # 37 - true when the heading obtained from mag data is declared consistent with the filter # fault status uint32 fault_status_changes # number of filter fault status (fs) changes diff --git a/src/modules/ekf2/EKF/common.h b/src/modules/ekf2/EKF/common.h index 15de4bebd5db..c7f75b35e292 100644 --- a/src/modules/ekf2/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -600,6 +600,7 @@ union filter_control_status_u { uint64_t gravity_vector : 1; ///< 34 - true when gravity vector measurements are being fused uint64_t mag : 1; ///< 35 - true if 3-axis magnetometer measurement fusion (mag states only) is intended uint64_t ev_yaw_fault : 1; ///< 36 - true when the EV heading has been declared faulty and is no longer being used + uint64_t mag_heading_consistent : 1; ///< 37 - true when the heading obtained from mag data is declared consistent with the filter } flags; uint64_t value; diff --git a/src/modules/ekf2/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h index cb47f0c2057e..a42ea5bceed7 100644 --- a/src/modules/ekf2/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -581,6 +581,7 @@ class Ekf final : public EstimatorInterface bool _mag_bias_observable{false}; ///< true when there is enough rotation to make magnetometer bias errors observable bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable uint64_t _time_yaw_started{0}; ///< last system time in usec that a yaw rotation manoeuvre was detected + AlphaFilter _mag_heading_innov_lpf{0.1f}; float _mag_heading_last_declination{}; ///< last magnetic field declination used for heading fusion (rad) bool _mag_decl_cov_reset{false}; ///< true after the fuseDeclination() function has been used to modify the earth field covariances after a magnetic field reset event. uint8_t _nb_mag_heading_reset_available{0}; @@ -1029,6 +1030,7 @@ class Ekf final : public EstimatorInterface void checkYawAngleObservability(); void checkMagBiasObservability(); + void checkMagHeadingConsistency(); bool checkMagField(const Vector3f &mag); static bool isMeasuredMatchingExpected(float measured, float expected, float gate); diff --git a/src/modules/ekf2/EKF/mag_3d_control.cpp b/src/modules/ekf2/EKF/mag_3d_control.cpp index 541e3454e30e..4d0e53983fde 100644 --- a/src/modules/ekf2/EKF/mag_3d_control.cpp +++ b/src/modules/ekf2/EKF/mag_3d_control.cpp @@ -63,6 +63,7 @@ void Ekf::controlMag3DFusion(const magSample &mag_sample, const bool common_star _control_status.flags.mag_3D = (_params.mag_fusion_type == MagFuseType::AUTO) && _control_status.flags.mag && _control_status.flags.mag_aligned_in_flight + && (_control_status.flags.mag_heading_consistent || !_control_status.flags.gps) && !_control_status.flags.mag_fault && isRecent(aid_src.time_last_fuse, 500'000) && getMagBiasVariance().longerThan(0.f) && !getMagBiasVariance().longerThan(sq(0.02f)) diff --git a/src/modules/ekf2/EKF/mag_control.cpp b/src/modules/ekf2/EKF/mag_control.cpp index 38599c359e55..7822a4198043 100644 --- a/src/modules/ekf2/EKF/mag_control.cpp +++ b/src/modules/ekf2/EKF/mag_control.cpp @@ -50,6 +50,7 @@ void Ekf::controlMagFusion() // check mag state observability checkYawAngleObservability(); checkMagBiasObservability(); + checkMagHeadingConsistency(); if (_mag_bias_observable || _yaw_angle_observable) { _time_last_mov_3d_mag_suitable = _time_delayed_us; @@ -257,6 +258,19 @@ void Ekf::checkMagBiasObservability() _time_yaw_started = _time_delayed_us; } +void Ekf::checkMagHeadingConsistency() +{ + if (fabsf(_mag_heading_innov_lpf.getState()) < _params.mag_heading_noise) { + if (_yaw_angle_observable) { + // yaw angle must be observable to consider consistency + _control_status.flags.mag_heading_consistent = true; + } + + } else { + _control_status.flags.mag_heading_consistent = false; + } +} + bool Ekf::checkMagField(const Vector3f &mag_sample) { _control_status.flags.mag_field_disturbed = false; @@ -357,6 +371,9 @@ void Ekf::resetMagHeading(const Vector3f &mag) _mag_heading_last_declination = declination; _time_last_heading_fuse = _time_delayed_us; + + _mag_heading_innov_lpf.reset(0.f); + _control_status.flags.mag_heading_consistent = true; } float Ekf::getMagDeclination() diff --git a/src/modules/ekf2/EKF/mag_heading_control.cpp b/src/modules/ekf2/EKF/mag_heading_control.cpp index 9c00d013122f..b54a879f0ea6 100644 --- a/src/modules/ekf2/EKF/mag_heading_control.cpp +++ b/src/modules/ekf2/EKF/mag_heading_control.cpp @@ -68,18 +68,23 @@ void Ekf::controlMagHeadingFusion(const magSample &mag_sample, const bool common if (_control_status.flags.yaw_align) { // mag heading aid_src.innovation = wrap_pi(getEulerYaw(_R_to_earth) - aid_src.observation); + _mag_heading_innov_lpf.update(aid_src.innovation); } else { // mag heading delta (logging only) aid_src.innovation = wrap_pi(wrap_pi(getEulerYaw(_R_to_earth) - _mag_heading_pred_prev) - wrap_pi(measured_hdg - _mag_heading_prev)); + _mag_heading_innov_lpf.reset(0.f); } // determine if we should use mag heading aiding + const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps; + bool continuing_conditions_passing = ((_params.mag_fusion_type == MagFuseType::HEADING) || (_params.mag_fusion_type == MagFuseType::AUTO && !_control_status.flags.mag_3D)) && _control_status.flags.tilt_align - && (_control_status.flags.yaw_align || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) + && ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss) + || (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align)) && !_control_status.flags.mag_fault && !_control_status.flags.mag_field_disturbed && !_control_status.flags.ev_yaw @@ -99,6 +104,7 @@ void Ekf::controlMagHeadingFusion(const magSample &mag_sample, const bool common const bool declination_changed = _control_status_prev.flags.mag_hdg && (fabsf(declination - _mag_heading_last_declination) > math::radians(3.f)); + bool skip_timeout_check = false; if (mag_sample.reset || declination_changed) { if (declination_changed) { @@ -113,10 +119,21 @@ void Ekf::controlMagHeadingFusion(const magSample &mag_sample, const bool common aid_src.time_last_fuse = _time_delayed_us; } else { - fuseYaw(aid_src); + Vector24f H_YAW; + computeYawInnovVarAndH(aid_src.observation_variance, aid_src.innovation_variance, H_YAW); + + if ((aid_src.innovation_variance - aid_src.observation_variance) > sq(_params.mag_heading_noise / 2.f)) { + // Only fuse mag to constrain the yaw variance to a safe value + fuseYaw(aid_src, H_YAW); + + } else { + // Yaw variance is low enough, stay in mag heading mode but don't fuse the data and skip the fusion timeout check + skip_timeout_check = true; + aid_src.test_ratio = 0.f; // required for preflight checks to pass + } } - const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max); + const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max) && !skip_timeout_check; if (is_fusion_failing) { if (_nb_mag_heading_reset_available > 0) { diff --git a/src/modules/ekf2/EKF2.cpp b/src/modules/ekf2/EKF2.cpp index 4b27a5bf2c3c..ef337739982a 100644 --- a/src/modules/ekf2/EKF2.cpp +++ b/src/modules/ekf2/EKF2.cpp @@ -1771,6 +1771,7 @@ void EKF2::PublishStatusFlags(const hrt_abstime ×tamp) status_flags.cs_gravity_vector = _ekf.control_status_flags().gravity_vector; status_flags.cs_mag = _ekf.control_status_flags().mag; status_flags.cs_ev_yaw_fault = _ekf.control_status_flags().ev_yaw_fault; + status_flags.cs_mag_heading_consistent = _ekf.control_status_flags().mag_heading_consistent; status_flags.fault_status_changes = _filter_fault_status_changes; status_flags.fs_bad_mag_x = _ekf.fault_status_flags().bad_mag_x; 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 7211ac4cd99c..321b7bc14db7 100644 --- a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -61,331 +61,331 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 5890000,1,-0.0095,-0.011,-5.9e-06,0.0045,-0.0011,0.0028,0.0022,-0.0017,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,9e-08,0.00038,0.00038,3.3e-05,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,1.2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 5990000,1,-0.0094,-0.011,1.2e-05,0.0048,0.00032,0.015,0.0026,-0.0017,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-7.3e-05,0,0,0,0,0,0,0,0,9.6e-08,0.00041,0.00041,3.5e-05,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,1.2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 6090000,1,-0.0094,-0.011,-7.2e-06,0.0059,0.0015,-0.011,0.0031,-0.0016,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-6.4e-05,0,0,0,0,0,0,0,0,1e-07,0.00044,0.00044,3.7e-05,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,1.2e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6190000,0.71,0.0013,-0.015,0.71,0.0035,0.0029,-0.005,0.0023,-0.00066,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-8.8e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0016,0.00034,0.00034,0.0016,0.22,0.22,4.9,0.13,0.13,0.32,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6290000,0.71,0.0013,-0.015,0.71,0.0034,0.0043,-0.012,0.0026,-0.00028,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-9.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00078,0.00034,0.00034,0.00075,0.22,0.22,3.2,0.16,0.16,0.3,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6390000,0.71,0.0013,-0.014,0.71,0.0024,0.0048,-0.05,0.0029,0.00018,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-3.7e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00054,0.00034,0.00034,0.00051,0.23,0.23,2.3,0.19,0.19,0.29,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6490000,0.71,0.0014,-0.014,0.71,0.0022,0.0056,-0.052,0.0031,0.00072,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-8.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00041,0.00034,0.00034,0.00037,0.24,0.24,1.5,0.23,0.23,0.26,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6590000,0.71,0.0014,-0.014,0.71,0.0017,0.0057,-0.099,0.0033,0.0013,-3.7e+02,-0.0015,-0.0057,4.4e-05,0,0,9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00033,0.00034,0.00034,0.00029,0.25,0.25,1.1,0.28,0.28,0.23,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6690000,0.7,0.0014,-0.014,0.71,0.0021,0.0068,-0.076,0.0035,0.0019,-3.7e+02,-0.0015,-0.0057,4.2e-05,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.00028,0.00035,0.00035,0.00024,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6790000,0.71,0.0014,-0.014,0.71,0.00076,0.0067,-0.11,0.0036,0.0026,-3.7e+02,-0.0015,-0.0057,4.3e-05,0,0,8.1e-06,0.37,0.0037,0.025,0,0,0,0,0,0.00025,0.00035,0.00035,0.00021,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6890000,0.71,0.0014,-0.014,0.71,-0.0013,0.0073,-0.12,0.0036,0.0033,-3.7e+02,-0.0015,-0.0057,4.3e-05,0,0,-4.3e-05,0.37,0.0037,0.025,0,0,0,0,0,0.00022,0.00036,0.00036,0.00018,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -6990000,0.7,0.0015,-0.014,0.71,-0.0013,0.0082,-0.12,0.0034,0.0041,-3.7e+02,-0.0015,-0.0057,3.8e-05,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00036,0.00036,0.00016,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7090000,0.7,0.0015,-0.014,0.71,-0.0019,0.0078,-0.13,0.0033,0.0048,-3.7e+02,-0.0015,-0.0057,3.3e-05,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00037,0.00037,0.00015,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7190000,0.7,0.0015,-0.014,0.71,-0.0036,0.008,-0.15,0.003,0.0056,-3.7e+02,-0.0015,-0.0057,3.1e-05,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00038,0.00038,0.00013,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7290000,0.7,0.0015,-0.014,0.71,-0.0051,0.0082,-0.15,0.0026,0.0064,-3.7e+02,-0.0015,-0.0057,3e-05,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00039,0.00039,0.00012,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 -7390000,0.7,0.0016,-0.014,0.71,-0.0052,0.0097,-0.16,0.002,0.0073,-3.7e+02,-0.0015,-0.0057,3.1e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.00015,0.00039,0.00039,0.00011,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7490000,0.7,0.0016,-0.014,0.71,-0.0068,0.01,-0.16,0.0014,0.0082,-3.7e+02,-0.0015,-0.0057,3e-05,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.00014,0.0004,0.0004,0.00011,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7590000,0.7,0.0016,-0.014,0.71,-0.0087,0.011,-0.17,0.00064,0.0092,-3.7e+02,-0.0015,-0.0057,3.3e-05,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00041,0.00041,9.8e-05,0.52,0.52,0.14,1.1,1.1,0.12,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7690000,0.7,0.0017,-0.014,0.71,-0.011,0.012,-0.16,-0.00036,0.01,-3.7e+02,-0.0015,-0.0057,3.2e-05,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.00013,0.00042,0.00042,9.3e-05,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7790000,0.7,0.0017,-0.014,0.71,-0.012,0.013,-0.16,-0.0015,0.011,-3.7e+02,-0.0015,-0.0057,2.4e-05,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00043,0.00043,8.7e-05,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 -7890000,0.7,0.0017,-0.014,0.71,-0.015,0.015,-0.16,-0.0028,0.013,-3.7e+02,-0.0015,-0.0057,2.6e-05,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00045,0.00045,8.2e-05,0.66,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,1.1e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -7990000,0.7,0.0018,-0.014,0.71,-0.017,0.016,-0.16,-0.0044,0.014,-3.7e+02,-0.0015,-0.0057,2.9e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00046,0.00046,7.8e-05,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,1.1e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0 -8090000,0.7,0.0018,-0.014,0.71,-0.018,0.018,-0.17,-0.0061,0.016,-3.7e+02,-0.0015,-0.0057,3.4e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.00011,0.00047,0.00047,7.5e-05,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,1e-05,0.04,0.04,0.037,0,0,0,0,0,0,0,0 -8190000,0.7,0.0018,-0.014,0.71,-0.021,0.019,-0.18,-0.0081,0.017,-3.7e+02,-0.0015,-0.0057,2.7e-05,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,0.0001,0.00049,0.00049,7.1e-05,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,1e-05,0.04,0.04,0.037,0,0,0,0,0,0,0,0 -8290000,0.7,0.0018,-0.014,0.71,-0.022,0.02,-0.17,-0.01,0.019,-3.7e+02,-0.0015,-0.0057,2.2e-05,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,0.0001,0.0005,0.0005,6.8e-05,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,1e-05,0.04,0.04,0.036,0,0,0,0,0,0,0,0 -8390000,0.7,0.0019,-0.014,0.71,-0.025,0.021,-0.17,-0.013,0.021,-3.7e+02,-0.0015,-0.0057,2.8e-05,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,9.8e-05,0.00051,0.00051,6.5e-05,0.95,0.95,0.097,2.5,2.5,0.091,0.00014,0.00014,1e-05,0.04,0.04,0.035,0,0,0,0,0,0,0,0 -8490000,0.7,0.0019,-0.014,0.71,-0.027,0.022,-0.17,-0.015,0.022,-3.7e+02,-0.0015,-0.0056,2.4e-05,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,9.5e-05,0.00052,0.00052,6.3e-05,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,1e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0 -8590000,0.7,0.0019,-0.014,0.71,-0.029,0.025,-0.17,-0.018,0.024,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,9.3e-05,0.00054,0.00054,6e-05,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,1e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0 -8690000,0.7,0.0019,-0.014,0.71,-0.032,0.025,-0.16,-0.021,0.025,-3.7e+02,-0.0015,-0.0056,2.5e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,9.1e-05,0.00055,0.00055,5.9e-05,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,1e-05,0.04,0.04,0.033,0,0,0,0,0,0,0,0 -8790000,0.7,0.0019,-0.014,0.71,-0.034,0.027,-0.15,-0.024,0.028,-3.7e+02,-0.0015,-0.0056,1.9e-05,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,8.9e-05,0.00056,0.00056,5.7e-05,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,1e-05,0.04,0.04,0.032,0,0,0,0,0,0,0,0 -8890000,0.7,0.0019,-0.014,0.71,-0.036,0.027,-0.15,-0.027,0.029,-3.7e+02,-0.0015,-0.0056,1.5e-05,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,8.7e-05,0.00057,0.00057,5.5e-05,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,1e-05,0.04,0.04,0.03,0,0,0,0,0,0,0,0 -8990000,0.7,0.002,-0.014,0.71,-0.038,0.028,-0.14,-0.031,0.032,-3.7e+02,-0.0015,-0.0056,7e-06,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,8.6e-05,0.00059,0.00059,5.3e-05,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,1e-05,0.04,0.04,0.029,0,0,0,0,0,0,0,0 -9090000,0.7,0.002,-0.014,0.71,-0.04,0.029,-0.14,-0.034,0.033,-3.7e+02,-0.0015,-0.0056,7.8e-07,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,8.4e-05,0.0006,0.0006,5.2e-05,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,1e-05,0.04,0.04,0.028,0,0,0,0,0,0,0,0 -9190000,0.7,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.038,0.035,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,8.3e-05,0.00062,0.00062,5e-05,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.027,0,0,0,0,0,0,0,0 -9290000,0.7,0.002,-0.014,0.71,-0.043,0.03,-0.14,-0.041,0.036,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,8.2e-05,0.00062,0.00062,4.9e-05,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.025,0,0,0,0,0,0,0,0 -9390000,0.7,0.002,-0.014,0.71,-0.044,0.032,-0.14,-0.046,0.039,-3.7e+02,-0.0015,-0.0056,1.6e-05,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,8e-05,0.00064,0.00064,4.8e-05,1.7,1.7,0.093,5.9,5.9,0.086,0.00013,0.00013,1e-05,0.04,0.04,0.024,0,0,0,0,0,0,0,0 -9490000,0.7,0.002,-0.014,0.71,-0.045,0.032,-0.13,-0.048,0.04,-3.7e+02,-0.0015,-0.0056,2.9e-05,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,7.9e-05,0.00064,0.00064,4.7e-05,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.023,0,0,0,0,0,0,0,0 -9590000,0.7,0.002,-0.014,0.71,-0.048,0.034,-0.13,-0.053,0.043,-3.7e+02,-0.0015,-0.0056,3.2e-05,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,7.8e-05,0.00066,0.00066,4.6e-05,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,1e-05,0.04,0.04,0.021,0,0,0,0,0,0,0,0 -9690000,0.7,0.0021,-0.014,0.71,-0.048,0.035,-0.12,-0.054,0.043,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,0.00065,0.00065,4.5e-05,1.9,1.9,0.089,6.8,6.8,0.086,0.00012,0.00012,1e-05,0.04,0.04,0.02,0,0,0,0,0,0,0,0 -9790000,0.7,0.0021,-0.014,0.71,-0.049,0.037,-0.11,-0.059,0.046,-3.7e+02,-0.0015,-0.0056,2.5e-05,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,7.7e-05,0.00067,0.00067,4.4e-05,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.019,0,0,0,0,0,0,0,0 -9890000,0.7,0.002,-0.014,0.71,-0.049,0.037,-0.11,-0.06,0.046,-3.7e+02,-0.0015,-0.0056,2.2e-05,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,7.6e-05,0.00067,0.00067,4.3e-05,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.018,0,0,0,0,0,0,0,0 -9990000,0.7,0.0021,-0.014,0.71,-0.051,0.038,-0.1,-0.065,0.049,-3.7e+02,-0.0015,-0.0056,1.5e-05,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,7.5e-05,0.00069,0.00069,4.2e-05,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,1e-05,0.04,0.04,0.017,0,0,0,0,0,0,0,0 -10090000,0.7,0.0021,-0.014,0.71,-0.049,0.037,-0.096,-0.065,0.049,-3.7e+02,-0.0015,-0.0056,1.7e-05,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,7.4e-05,0.00068,0.00068,4.2e-05,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.016,0,0,0,0,0,0,0,0 -10190000,0.7,0.0021,-0.014,0.71,-0.051,0.04,-0.096,-0.07,0.052,-3.7e+02,-0.0015,-0.0056,-5.2e-06,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,7.4e-05,0.0007,0.0007,4.1e-05,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,1e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0 -10290000,0.7,0.0021,-0.014,0.71,-0.052,0.04,-0.084,-0.075,0.056,-3.7e+02,-0.0015,-0.0056,-1.9e-05,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,0.00072,0.00072,4e-05,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,1e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0 -10390000,0.7,0.0021,-0.014,0.71,0.0095,-0.019,0.0096,0.00087,-0.0017,-3.7e+02,-0.0015,-0.0056,-2e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7.3e-05,0.00075,0.00075,4e-05,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,1e-05,0.04,0.04,0.013,0,0,0,0,0,0,0,0 -10490000,0.7,0.0021,-0.014,0.71,0.0082,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-0.0015,-0.0056,-3.5e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,7.2e-05,0.00077,0.00077,3.9e-05,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,9.9e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0 -10590000,0.7,0.0022,-0.014,0.71,0.0078,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-0.0015,-0.0056,-3.6e-05,-0.00027,3.1e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.00078,0.00078,3.9e-05,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,9.9e-06,0.04,0.04,0.012,0,0,0,0,0,0,0,0 -10690000,0.7,0.0023,-0.014,0.71,0.0057,-0.0058,0.03,0.0025,-0.0014,-3.7e+02,-0.0015,-0.0056,-4.3e-05,-0.00027,3.2e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.0008,0.0008,3.8e-05,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,9.9e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10790000,0.7,0.0023,-0.014,0.71,0.0052,-0.0031,0.024,0.0027,-0.00072,-3.7e+02,-0.0014,-0.0056,-4.3e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7.1e-05,0.00077,0.00077,3.8e-05,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,9.8e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10890000,0.7,0.0022,-0.014,0.71,0.004,-0.0017,0.02,0.0031,-0.00093,-3.7e+02,-0.0014,-0.0056,-4.6e-05,-0.00042,0.00016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.0008,0.0008,3.8e-05,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,9.8e-06,0.04,0.04,0.011,0,0,0,0,0,0,0,0 -10990000,0.7,0.0022,-0.014,0.71,0.0068,0.0033,0.014,0.0047,-0.0022,-3.7e+02,-0.0014,-0.0055,-3.6e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.00073,0.00073,3.7e-05,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,9.7e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0 -11090000,0.7,0.0022,-0.014,0.71,0.0056,0.0058,0.019,0.0053,-0.0018,-3.7e+02,-0.0014,-0.0055,-2.4e-05,-0.00082,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,7e-05,0.00075,0.00075,3.7e-05,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,9.7e-06,0.039,0.039,0.011,0,0,0,0,0,0,0,0 -11190000,0.7,0.0021,-0.014,0.71,0.01,0.0083,0.0077,0.0067,-0.0028,-3.7e+02,-0.0013,-0.0055,-3.9e-05,-0.00092,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.00065,0.00065,3.7e-05,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,9.6e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11290000,0.7,0.0022,-0.014,0.71,0.01,0.011,0.0074,0.0078,-0.0018,-3.7e+02,-0.0013,-0.0055,-6e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.00067,0.00067,3.6e-05,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,9.6e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11390000,0.7,0.0022,-0.014,0.71,0.0054,0.0091,0.0017,0.0055,-0.0019,-3.7e+02,-0.0013,-0.0056,-7.6e-05,-0.0005,0.00088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.9e-05,0.00055,0.00055,3.6e-05,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,9.5e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11490000,0.7,0.0022,-0.014,0.71,0.0029,0.012,0.0025,0.006,-0.00089,-3.7e+02,-0.0013,-0.0056,-0.00011,-0.00051,0.00088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00057,0.00057,3.6e-05,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,9.5e-06,0.038,0.038,0.01,0,0,0,0,0,0,0,0 -11590000,0.7,0.0021,-0.014,0.71,-0.0015,0.01,-0.0034,0.0045,-0.0014,-3.7e+02,-0.0014,-0.0056,-0.00012,-8.9e-05,0.00075,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00047,0.00047,3.6e-05,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,9.4e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11690000,0.7,0.0021,-0.014,0.71,-0.0043,0.013,-0.0079,0.0042,-0.00027,-3.7e+02,-0.0014,-0.0056,-0.00013,-7.9e-05,0.00074,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00048,0.00048,3.5e-05,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,9.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11790000,0.7,0.0021,-0.014,0.71,-0.01,0.013,-0.0098,0.0018,0.00056,-3.7e+02,-0.0014,-0.0056,-0.00013,2.7e-05,0.00054,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.0004,0.0004,3.5e-05,0.097,0.097,0.039,0.053,0.053,0.063,6.3e-05,6.4e-05,9.3e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11890000,0.7,0.0021,-0.014,0.71,-0.012,0.014,-0.011,0.00078,0.0019,-3.7e+02,-0.0014,-0.0056,-0.00015,2.1e-05,0.00054,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00041,0.00041,3.5e-05,0.12,0.12,0.037,0.061,0.061,0.063,6.3e-05,6.4e-05,9.2e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -11990000,0.7,0.0021,-0.014,0.71,-0.013,0.014,-0.016,-0.00029,0.0023,-3.7e+02,-0.0014,-0.0057,-0.00015,0.00016,0.00056,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.8e-05,0.00034,0.00034,3.5e-05,0.091,0.091,0.033,0.051,0.051,0.061,5.7e-05,5.7e-05,9.2e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12090000,0.7,0.0022,-0.014,0.71,-0.014,0.016,-0.022,-0.0017,0.0038,-3.7e+02,-0.0014,-0.0057,-0.00013,0.00018,0.00055,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00035,0.00035,3.5e-05,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,9.1e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12190000,0.7,0.0018,-0.014,0.71,-0.008,0.013,-0.017,0.0015,0.0019,-3.7e+02,-0.0013,-0.0057,-0.00013,0.00043,0.001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.0003,0.0003,3.5e-05,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12290000,0.7,0.0017,-0.014,0.71,-0.011,0.015,-0.016,0.00056,0.0033,-3.7e+02,-0.0013,-0.0057,-0.00013,0.0004,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00031,0.00031,3.4e-05,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12390000,0.7,0.0014,-0.014,0.71,-0.0051,0.011,-0.015,0.003,0.0016,-3.7e+02,-0.0012,-0.0058,-0.00014,0.00056,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00027,0.00027,3.4e-05,0.079,0.079,0.026,0.05,0.05,0.057,4.8e-05,4.8e-05,8.9e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12490000,0.7,0.0014,-0.014,0.71,-0.0062,0.013,-0.018,0.0025,0.0029,-3.7e+02,-0.0012,-0.0058,-0.00016,0.00056,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00028,0.00028,3.4e-05,0.093,0.093,0.026,0.059,0.059,0.057,4.8e-05,4.8e-05,8.8e-06,0.037,0.037,0.01,0,0,0,0,0,0,0,0 -12590000,0.7,0.0015,-0.014,0.71,-0.014,0.011,-0.023,-0.0028,0.0014,-3.7e+02,-0.0013,-0.0058,-0.00016,0.00069,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00025,0.00025,3.4e-05,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,8.8e-06,0.037,0.037,0.0099,0,0,0,0,0,0,0,0 -12690000,0.7,0.0015,-0.014,0.71,-0.014,0.012,-0.027,-0.0042,0.0026,-3.7e+02,-0.0013,-0.0058,-0.00017,0.00072,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00026,0.00026,3.4e-05,0.085,0.085,0.025,0.058,0.058,0.055,4.5e-05,4.5e-05,8.7e-06,0.037,0.037,0.0098,0,0,0,0,0,0,0,0 -12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0091,-0.03,-0.0076,0.0013,-3.7e+02,-0.0014,-0.0058,-0.00016,0.00076,0.001,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00023,0.00023,3.4e-05,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,8.6e-06,0.037,0.037,0.0097,0,0,0,0,0,0,0,0 -12890000,0.7,0.0015,-0.014,0.71,-0.021,0.0091,-0.029,-0.0096,0.0022,-3.7e+02,-0.0014,-0.0058,-0.00016,0.00069,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00024,0.00024,3.4e-05,0.079,0.079,0.025,0.058,0.058,0.054,4.2e-05,4.2e-05,8.6e-06,0.037,0.037,0.0096,0,0,0,0,0,0,0,0 -12990000,0.7,0.0012,-0.014,0.71,-0.0083,0.0065,-0.03,-0.001,0.0012,-3.7e+02,-0.0012,-0.0059,-0.00014,0.00067,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00022,0.00022,3.4e-05,0.064,0.064,0.025,0.049,0.049,0.052,4e-05,4e-05,8.5e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 -13090000,0.7,0.0012,-0.014,0.71,-0.009,0.0067,-0.03,-0.0019,0.0018,-3.7e+02,-0.0013,-0.0059,-0.00016,0.00064,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00023,0.00023,3.4e-05,0.073,0.073,0.025,0.058,0.058,0.052,4e-05,4e-05,8.4e-06,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 -13190000,0.7,0.00095,-0.014,0.71,5.6e-05,0.0061,-0.027,0.0044,0.0011,-3.7e+02,-0.0012,-0.0059,-0.00017,0.00049,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,8.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 -13290000,0.7,0.00096,-0.014,0.71,-0.0002,0.0069,-0.024,0.0044,0.0018,-3.7e+02,-0.0012,-0.0059,-0.00015,0.00036,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00022,0.00022,3.4e-05,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,8.3e-06,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 -13390000,0.7,0.00081,-0.014,0.71,0.00062,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-0.0012,-0.0059,-0.00013,0.0002,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,8.2e-06,0.037,0.037,0.0088,0,0,0,0,0,0,0,0 -13490000,0.7,0.00084,-0.014,0.71,0.00012,0.0058,-0.019,0.0034,0.0016,-3.7e+02,-0.0012,-0.0059,-0.00011,0.00011,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,8.1e-06,0.037,0.037,0.0087,0,0,0,0,0,0,0,0 -13590000,0.7,0.00078,-0.014,0.71,0.00037,0.006,-0.021,0.0024,0.001,-3.7e+02,-0.0012,-0.0059,-0.00013,8.4e-05,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,8.1e-06,0.036,0.036,0.0084,0,0,0,0,0,0,0,0 -13690000,0.7,0.00076,-0.014,0.71,0.0011,0.0078,-0.025,0.0025,0.0017,-3.7e+02,-0.0012,-0.0059,-0.0001,0.00012,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,8e-06,0.036,0.036,0.0083,0,0,0,0,0,0,0,0 -13790000,0.7,0.00064,-0.014,0.71,0.0016,0.0036,-0.027,0.0035,-0.00064,-3.7e+02,-0.0011,-0.006,-0.0001,-0.0001,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,7.9e-06,0.036,0.036,0.0079,0,0,0,0,0,0,0,0 -13890000,0.7,0.00061,-0.014,0.71,0.0021,0.0035,-0.031,0.0037,-0.0003,-3.7e+02,-0.0011,-0.006,-8.7e-05,-7e-05,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00021,0.00021,3.4e-05,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,7.8e-06,0.036,0.036,0.0078,0,0,0,0,0,0,0,0 -13990000,0.7,0.00054,-0.014,0.71,0.0024,0.001,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,-8.3e-05,-0.00034,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,7.8e-06,0.036,0.036,0.0074,0,0,0,0,0,0,0,0 -14090000,0.7,0.00052,-0.014,0.71,0.0024,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,-5.6e-05,-0.00032,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,7.7e-06,0.036,0.036,0.0073,0,0,0,0,0,0,0,0 -14190000,0.7,0.00042,-0.014,0.71,0.0058,0.00063,-0.033,0.0068,-0.0016,-3.7e+02,-0.0011,-0.006,-4.1e-05,-0.0003,0.00089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,7.6e-06,0.036,0.036,0.0069,0,0,0,0,0,0,0,0 -14290000,0.7,0.00043,-0.014,0.71,0.0066,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-0.0011,-0.006,-2.9e-05,-0.00037,0.00096,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,7.5e-06,0.036,0.036,0.0067,0,0,0,0,0,0,0,0 -14390000,0.7,0.00035,-0.014,0.71,0.0084,0.0023,-0.034,0.0087,-0.0013,-3.7e+02,-0.0011,-0.006,-1.2e-07,-0.00037,0.00071,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,7.4e-06,0.036,0.036,0.0063,0,0,0,0,0,0,0,0 -14490000,0.7,0.00033,-0.013,0.71,0.0084,0.0035,-0.037,0.0096,-0.001,-3.7e+02,-0.0011,-0.006,9.8e-06,-0.00032,0.00067,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,7.4e-06,0.036,0.036,0.0062,0,0,0,0,0,0,0,0 -14590000,0.7,0.00032,-0.013,0.71,0.0049,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-0.0011,-0.0061,1.3e-05,-0.00069,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,7.3e-06,0.036,0.036,0.0058,0,0,0,0,0,0,0,0 -14690000,0.7,0.00028,-0.013,0.71,0.0062,-0.001,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.00079,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.0002,3.4e-05,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,7.2e-06,0.036,0.036,0.0056,0,0,0,0,0,0,0,0 -14790000,0.7,0.0003,-0.013,0.71,0.003,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-0.0012,-0.0061,4.3e-05,-0.0012,0.0017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,7.1e-06,0.036,0.036,0.0053,0,0,0,0,0,0,0,0 -14890000,0.7,0.0003,-0.013,0.71,0.0046,-0.0016,-0.033,0.0041,-0.0036,-3.7e+02,-0.0012,-0.0061,5.9e-05,-0.0012,0.0017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.0002,0.00019,3.4e-05,0.048,0.047,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,7.1e-06,0.036,0.036,0.0051,0,0,0,0,0,0,0,0 -14990000,0.7,0.00029,-0.013,0.71,0.0034,-0.0018,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,5.7e-05,-0.0012,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,7e-06,0.036,0.036,0.0048,0,0,0,0,0,0,0,0 -15090000,0.7,0.00022,-0.013,0.71,0.0038,-0.002,-0.032,0.0035,-0.0031,-3.7e+02,-0.0012,-0.0061,5.9e-05,-0.0012,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,6.9e-06,0.036,0.036,0.0046,0,0,0,0,0,0,0,0 -15190000,0.7,0.00023,-0.013,0.71,0.0032,-0.00077,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,5.8e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,6.8e-06,0.035,0.035,0.0043,0,0,0,0,0,0,0,0 -15290000,0.7,0.0002,-0.013,0.71,0.0037,-0.00061,-0.027,0.0031,-0.0025,-3.7e+02,-0.0012,-0.0061,7.4e-05,-0.0013,0.0021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,6.7e-06,0.035,0.035,0.0042,0,0,0,0,0,0,0,0 -15390000,0.7,0.0002,-0.013,0.71,0.003,-0.00026,-0.024,0.00055,-0.002,-3.7e+02,-0.0012,-0.0061,0.00011,-0.0013,0.0024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,6.7e-06,0.035,0.035,0.0039,0,0,0,0,0,0,0,0 -15490000,0.7,0.00022,-0.013,0.71,0.0042,-0.00065,-0.024,0.00092,-0.0021,-3.7e+02,-0.0012,-0.0061,9.3e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.7e-05,0.00019,0.00019,3.4e-05,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,6.6e-06,0.035,0.035,0.0037,0,0,0,0,0,0,0,0 -15590000,0.7,0.00024,-0.013,0.71,0.0023,-0.00064,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,8.4e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,6.5e-06,0.035,0.035,0.0035,0,0,0,0,0,0,0,0 -15690000,0.7,0.00024,-0.013,0.71,0.0026,-0.00081,-0.023,-0.0011,-0.0018,-3.7e+02,-0.0012,-0.0061,8.6e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,6.4e-06,0.035,0.035,0.0033,0,0,0,0,0,0,0,0 -15790000,0.7,0.0002,-0.013,0.71,0.0031,-0.0025,-0.026,-0.00097,-0.0028,-3.7e+02,-0.0012,-0.0061,8.9e-05,-0.0015,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.0031,0,0,0,0,0,0,0,0 -15890000,0.7,0.00015,-0.013,0.71,0.004,-0.003,-0.024,-0.00058,-0.0031,-3.7e+02,-0.0012,-0.0061,9.5e-05,-0.0016,0.0026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,6.3e-06,0.035,0.035,0.003,0,0,0,0,0,0,0,0 -15990000,0.7,9.4e-05,-0.013,0.71,0.0039,-0.0039,-0.019,-0.00065,-0.0039,-3.7e+02,-0.0012,-0.0061,0.00012,-0.0018,0.0028,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,6.2e-06,0.034,0.034,0.0028,0,0,0,0,0,0,0,0 -16090000,0.7,9.5e-05,-0.013,0.71,0.0056,-0.0041,-0.016,-0.0002,-0.0043,-3.7e+02,-0.0012,-0.0061,0.00015,-0.0019,0.0029,-0.12,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00018,0.00018,3.4e-05,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,6.1e-06,0.034,0.034,0.0027,0,0,0,0,0,0,0,0 -16190000,0.7,0.00012,-0.013,0.71,0.0056,-0.0033,-0.014,-0.0004,-0.0035,-3.7e+02,-0.0012,-0.0061,0.00016,-0.0018,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,6e-06,0.034,0.034,0.0025,0,0,0,0,0,0,0,0 -16290000,0.7,0.00014,-0.013,0.71,0.0072,-0.0041,-0.016,0.00025,-0.0038,-3.7e+02,-0.0012,-0.0061,0.00019,-0.0018,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,6e-06,0.034,0.034,0.0024,0,0,0,0,0,0,0,0 -16390000,0.7,0.00013,-0.013,0.71,0.0061,-0.0043,-0.015,-7.1e-05,-0.0031,-3.7e+02,-0.0012,-0.0061,0.00019,-0.0017,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,5.9e-06,0.034,0.034,0.0022,0,0,0,0,0,0,0,0 -16490000,0.7,0.00015,-0.013,0.71,0.0053,-0.0039,-0.018,0.00048,-0.0035,-3.7e+02,-0.0012,-0.0061,0.0002,-0.0016,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00017,3.4e-05,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,5.8e-06,0.034,0.034,0.0021,0,0,0,0,0,0,0,0 -16590000,0.71,0.0004,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0025,-7.5e-05,-3.7e+02,-0.0013,-0.006,0.0002,-0.00094,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.4e-05,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,5.7e-06,0.033,0.033,0.002,0,0,0,0,0,0,0,0 -16690000,0.7,0.00039,-0.013,0.71,0.002,-0.0007,-0.015,-0.0023,-0.00017,-3.7e+02,-0.0013,-0.006,0.00019,-0.001,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00017,0.00016,3.4e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,5.7e-06,0.033,0.033,0.0019,0,0,0,0,0,0,0,0 -16790000,0.71,0.00054,-0.013,0.71,-0.0014,0.0015,-0.014,-0.0046,0.0025,-3.7e+02,-0.0013,-0.006,0.0002,-0.00043,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.4e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,5.6e-06,0.033,0.033,0.0018,0,0,0,0,0,0,0,0 -16890000,0.7,0.00055,-0.013,0.71,-0.0017,0.0023,-0.011,-0.0048,0.0027,-3.7e+02,-0.0013,-0.006,0.00019,-0.00047,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.4e-05,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,5.5e-06,0.033,0.033,0.0017,0,0,0,0,0,0,0,0 -16990000,0.7,0.00049,-0.013,0.71,-0.0016,0.00035,-0.01,-0.0052,0.00086,-3.7e+02,-0.0013,-0.006,0.00018,-0.00088,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,5.5e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 -17090000,0.7,0.00046,-0.013,0.71,-0.00086,0.0013,-0.01,-0.0053,0.00091,-3.7e+02,-0.0013,-0.006,0.00018,-0.00087,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00016,0.00016,3.3e-05,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,5.4e-06,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 -17190000,0.71,0.00045,-0.013,0.71,-0.0004,0.0013,-0.011,-0.0056,-0.00053,-3.7e+02,-0.0014,-0.006,0.0002,-0.0012,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,5.3e-06,0.032,0.032,0.0015,0,0,0,0,0,0,0,0 -17290000,0.7,0.00042,-0.013,0.71,0.0017,0.0023,-0.0066,-0.0056,-0.00036,-3.7e+02,-0.0014,-0.006,0.00019,-0.0013,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,5.2e-06,0.032,0.032,0.0014,0,0,0,0,0,0,0,0 -17390000,0.71,0.00039,-0.013,0.71,0.0023,0.0015,-0.0047,-0.0047,-0.0016,-3.7e+02,-0.0014,-0.006,0.00021,-0.0016,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,5.2e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 -17490000,0.71,0.00038,-0.013,0.71,0.0029,0.0011,-0.003,-0.0044,-0.0015,-3.7e+02,-0.0014,-0.006,0.00021,-0.0016,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00015,0.00015,3.3e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,5.1e-06,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 -17590000,0.71,0.00029,-0.013,0.71,0.0041,-8.3e-05,0.0025,-0.0037,-0.0026,-3.7e+02,-0.0014,-0.0061,0.00022,-0.002,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,5e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 -17690000,0.71,0.00026,-0.013,0.71,0.005,0.00063,0.0019,-0.0033,-0.0026,-3.7e+02,-0.0014,-0.0061,0.00023,-0.002,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,5e-06,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 -17790000,0.71,0.00017,-0.013,0.71,0.0076,0.00035,0.00059,-0.0021,-0.0022,-3.7e+02,-0.0013,-0.0061,0.00027,-0.0019,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,4.9e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 -17890000,0.71,0.00018,-0.013,0.71,0.0091,-0.00041,0.00069,-0.0013,-0.0022,-3.7e+02,-0.0013,-0.0061,0.00028,-0.0019,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,4.8e-06,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 -17990000,0.71,0.00013,-0.013,0.71,0.011,-0.0021,0.0019,-0.00055,-0.0019,-3.7e+02,-0.0013,-0.0061,0.00028,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,4.8e-06,0.031,0.031,0.001,0,0,0,0,0,0,0,0 -18090000,0.71,0.00013,-0.013,0.71,0.011,-0.0023,0.0043,0.00057,-0.0021,-3.7e+02,-0.0013,-0.0061,0.00026,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00014,0.00014,3.3e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,4.7e-06,0.031,0.031,0.00097,0,0,0,0,0,0,0,0 -18190000,0.71,9.9e-05,-0.013,0.71,0.012,-0.0012,0.0056,0.0014,-0.0017,-3.7e+02,-0.0013,-0.0061,0.00028,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,4.7e-06,0.031,0.031,0.00092,0,0,0,0,0,0,0,0 -18290000,0.71,4e-05,-0.012,0.71,0.012,-0.0018,0.0068,0.0026,-0.0018,-3.7e+02,-0.0013,-0.0061,0.00027,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,4.6e-06,0.031,0.031,0.00089,0,0,0,0,0,0,0,0 -18390000,0.71,5.6e-05,-0.013,0.71,0.013,-0.00016,0.008,0.0032,-0.0014,-3.7e+02,-0.0013,-0.0061,0.00029,-0.0017,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,4.5e-06,0.031,0.031,0.00084,0,0,0,0,0,0,0,0 -18490000,0.71,7.1e-05,-0.012,0.71,0.014,0.00025,0.0076,0.0046,-0.0014,-3.7e+02,-0.0013,-0.0061,0.0003,-0.0018,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,4.5e-06,0.031,0.031,0.00082,0,0,0,0,0,0,0,0 -18590000,0.71,7.6e-05,-0.012,0.71,0.013,0.00049,0.0058,0.0035,-0.0012,-3.7e+02,-0.0014,-0.0061,0.00033,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00012,0.00012,3.3e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,4.4e-06,0.031,0.031,0.00078,0,0,0,0,0,0,0,0 -18690000,0.71,4.5e-05,-0.012,0.71,0.014,-0.0002,0.0039,0.0049,-0.0011,-3.7e+02,-0.0014,-0.0061,0.00032,-0.0017,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00013,0.00013,3.3e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,4.3e-06,0.031,0.031,0.00075,0,0,0,0,0,0,0,0 -18790000,0.71,7.4e-05,-0.012,0.71,0.012,0.0001,0.0035,0.0037,-0.0009,-3.7e+02,-0.0014,-0.0061,0.00032,-0.0017,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.6e-05,0.00012,0.00012,3.3e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,4.3e-06,0.031,0.031,0.00072,0,0,0,0,0,0,0,0 -18890000,0.71,9.8e-05,-0.012,0.71,0.013,0.0006,0.0042,0.005,-0.00083,-3.7e+02,-0.0014,-0.0061,0.00035,-0.0017,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,4.2e-06,0.031,0.031,0.0007,0,0,0,0,0,0,0,0 -18990000,0.71,8.5e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.00069,-3.7e+02,-0.0014,-0.0061,0.00036,-0.0017,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,4.2e-06,0.031,0.031,0.00066,0,0,0,0,0,0,0,0 -19090000,0.71,7e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0077,-0.00048,-3.7e+02,-0.0014,-0.0061,0.00036,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,4.1e-06,0.031,0.031,0.00065,0,0,0,0,0,0,0,0 -19190000,0.71,7.2e-05,-0.012,0.71,0.015,0.0021,0.0059,0.0085,-0.00044,-3.7e+02,-0.0014,-0.0061,0.00037,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.3e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,4.1e-06,0.03,0.03,0.00062,0,0,0,0,0,0,0,0 -19290000,0.71,9.4e-05,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00025,-3.7e+02,-0.0014,-0.0061,0.00036,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00012,0.00012,3.2e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,4e-06,0.03,0.03,0.0006,0,0,0,0,0,0,0,0 -19390000,0.71,0.00011,-0.012,0.71,0.012,0.00042,0.012,0.008,-0.00026,-3.7e+02,-0.0014,-0.0061,0.00038,-0.0018,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,4e-06,0.03,0.03,0.00058,0,0,0,0,0,0,0,0 -19490000,0.71,0.00013,-0.012,0.71,0.012,-0.00029,0.0088,0.0092,-0.00026,-3.7e+02,-0.0014,-0.0061,0.0004,-0.0018,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,3.9e-06,0.03,0.03,0.00056,0,0,0,0,0,0,0,0 -19590000,0.71,0.00018,-0.012,0.71,0.0096,-0.0013,0.0081,0.0074,-0.00028,-3.7e+02,-0.0014,-0.0061,0.00043,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,3.9e-06,0.03,0.03,0.00054,0,0,0,0,0,0,0,0 -19690000,0.71,0.00018,-0.012,0.71,0.01,-0.0035,0.0096,0.0084,-0.00053,-3.7e+02,-0.0014,-0.0061,0.00041,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,3.8e-06,0.03,0.03,0.00052,0,0,0,0,0,0,0,0 -19790000,0.71,0.00025,-0.012,0.71,0.0077,-0.0043,0.01,0.0068,-0.00043,-3.7e+02,-0.0014,-0.0061,0.00042,-0.0018,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,3.7e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19890000,0.71,0.00019,-0.012,0.71,0.0064,-0.0046,0.011,0.0075,-0.00089,-3.7e+02,-0.0014,-0.0061,0.00045,-0.0018,0.0066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,3.7e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19990000,0.71,0.00018,-0.012,0.71,0.004,-0.0053,0.014,0.0061,-0.00074,-3.7e+02,-0.0014,-0.006,0.00049,-0.0017,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,3.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20090000,0.71,0.00017,-0.012,0.71,0.0037,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-0.0014,-0.006,0.00052,-0.0017,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.00011,0.00011,3.2e-05,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,3.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20190000,0.71,0.00028,-0.012,0.71,0.0014,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-0.0014,-0.006,0.00054,-0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-05,0.0001,0.0001,3.2e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,3.6e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20290000,0.71,0.00024,-0.012,0.71,0.00027,-0.0095,0.015,0.0043,-0.0019,-3.7e+02,-0.0014,-0.006,0.00055,-0.0016,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.00011,0.00011,3.2e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,3.5e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20390000,0.71,0.00026,-0.012,0.71,-0.0022,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-0.0014,-0.006,0.00055,-0.0015,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,3.5e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20490000,0.71,0.00031,-0.012,0.71,-0.0026,-0.011,0.016,0.0021,-0.0026,-3.7e+02,-0.0014,-0.006,0.00054,-0.0015,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,3.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20590000,0.71,0.00034,-0.012,0.71,-0.0023,-0.011,0.013,0.0018,-0.0021,-3.7e+02,-0.0014,-0.006,0.00054,-0.0013,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,1.9e-06,3.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20690000,0.71,0.00036,-0.012,0.71,-0.0023,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-0.0014,-0.006,0.00055,-0.0013,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.2e-05,0.026,0.026,0.0093,0.049,0.049,0.04,1.9e-06,1.9e-06,3.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20790000,0.71,0.00039,-0.012,0.71,-0.0034,-0.011,0.015,0.0013,-0.0025,-3.7e+02,-0.0014,-0.006,0.00055,-0.0011,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.1e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,3.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20890000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.014,0.00098,-0.0038,-3.7e+02,-0.0014,-0.006,0.00057,-0.0011,0.0073,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,0.0001,0.0001,3.1e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,3.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -20990000,0.71,0.00038,-0.012,0.71,-0.0041,-0.014,0.015,0.0026,-0.0031,-3.7e+02,-0.0014,-0.006,0.00058,-0.0009,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.9e-05,9.8e-05,3.1e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,3.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -21090000,0.71,0.00038,-0.012,0.71,-0.0042,-0.017,0.015,0.0022,-0.0047,-3.7e+02,-0.0014,-0.006,0.00059,-0.0009,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.9e-05,9.9e-05,3.1e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,3.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -21190000,0.71,0.00042,-0.012,0.71,-0.0034,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-0.0014,-0.006,0.00058,-0.00066,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.7e-05,9.7e-05,3.1e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21290000,0.71,0.00046,-0.012,0.71,-0.004,-0.018,0.016,0.0033,-0.0054,-3.7e+02,-0.0014,-0.006,0.00061,-0.00066,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.8e-05,9.8e-05,3.1e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21390000,0.71,0.0005,-0.012,0.71,-0.0048,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-0.0014,-0.006,0.0006,-0.00028,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.6e-05,9.6e-05,3.1e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21490000,0.71,0.00051,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-0.0014,-0.006,0.00061,-0.00028,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.4e-05,9.7e-05,9.7e-05,3.1e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21590000,0.71,0.00053,-0.012,0.71,-0.0059,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-0.0014,-0.006,0.0006,6.7e-05,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.5e-05,9.5e-05,3.1e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21690000,0.71,0.00054,-0.012,0.71,-0.0058,-0.016,0.017,0.0013,-0.0048,-3.7e+02,-0.0014,-0.006,0.00061,6.4e-05,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.6e-05,9.5e-05,3.1e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21790000,0.71,0.00056,-0.012,0.71,-0.0064,-0.011,0.015,4.8e-05,-0.00076,-3.7e+02,-0.0014,-0.0059,0.0006,0.00059,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.4e-05,9.4e-05,3.1e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.2e-06,1.2e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21890000,0.71,0.00056,-0.012,0.71,-0.0063,-0.012,0.016,-0.00059,-0.0019,-3.7e+02,-0.0014,-0.0059,0.0006,0.00059,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.5e-05,9.4e-05,3.1e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21990000,0.71,0.00062,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-0.0014,-0.0059,0.0006,0.001,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.3e-05,9.3e-05,3.1e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22090000,0.71,0.00063,-0.012,0.71,-0.0072,-0.0082,0.015,-0.0022,0.00062,-3.7e+02,-0.0014,-0.0059,0.00059,0.001,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.4e-05,9.3e-05,3e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,2.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22190000,0.71,0.0006,-0.012,0.71,-0.007,-0.0073,0.015,-0.0018,0.00058,-3.7e+02,-0.0014,-0.0059,0.0006,0.0011,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.2e-05,9.2e-05,3e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22290000,0.71,0.00064,-0.012,0.71,-0.0083,-0.0081,0.015,-0.0026,-0.0002,-3.7e+02,-0.0014,-0.0059,0.00059,0.0011,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.3e-05,9.3e-05,3e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22390000,0.71,0.00061,-0.012,0.71,-0.0089,-0.0076,0.017,-0.0022,-0.00019,-3.7e+02,-0.0014,-0.0059,0.00059,0.0012,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.1e-05,9.1e-05,3e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,2.7e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22490000,0.71,0.00062,-0.012,0.71,-0.0096,-0.0075,0.018,-0.0031,-0.00096,-3.7e+02,-0.0014,-0.0059,0.00059,0.0012,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.2e-05,9.2e-05,3e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22590000,0.71,0.0006,-0.012,0.71,-0.0093,-0.007,0.017,-0.0034,0.00012,-3.7e+02,-0.0014,-0.0059,0.00059,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,9.1e-05,9.1e-05,3e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22690000,0.71,0.00063,-0.012,0.71,-0.011,-0.0067,0.018,-0.0044,-0.00056,-3.7e+02,-0.0014,-0.0059,0.0006,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9.1e-05,9.1e-05,3e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,2.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22790000,0.71,0.00062,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00045,-3.7e+02,-0.0014,-0.0059,0.00057,0.0014,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22890000,0.71,0.00063,-0.012,0.71,-0.012,-0.0052,0.021,-0.0067,-0.00099,-3.7e+02,-0.0014,-0.0059,0.00057,0.0014,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -22990000,0.71,0.00061,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00087,-3.7e+02,-0.0014,-0.0059,0.00057,0.0015,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,3e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,2.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23090000,0.71,0.00058,-0.012,0.71,-0.013,-0.0056,0.022,-0.0087,-0.0014,-3.7e+02,-0.0014,-0.0059,0.00055,0.0015,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,9e-05,9e-05,3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23190000,0.71,0.00064,-0.012,0.71,-0.015,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,0.00055,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,2.9e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23290000,0.71,0.00058,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-0.0014,-0.0059,0.00055,0.0015,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.9e-05,2.9e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,2.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23390000,0.71,0.00067,-0.012,0.71,-0.016,-0.0081,0.022,-0.016,-0.0018,-3.7e+02,-0.0014,-0.0059,0.00055,0.0016,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.8e-05,8.8e-05,2.9e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,2.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-0.0014,-0.0059,0.00056,0.0016,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.9e-05,8.8e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,2.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0076,-0.044,-0.017,-0.0013,-3.7e+02,-0.0014,-0.0059,0.00055,0.0018,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.8e-05,8.8e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,2.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-0.0014,-0.0059,0.00055,0.0018,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.8e-05,8.8e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-07,7.4e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23790000,0.71,0.005,0.00065,0.71,-0.089,-0.027,-0.15,-0.021,-0.0018,-3.7e+02,-0.0014,-0.0059,0.00055,0.002,0.0062,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.2e-05,8.7e-05,8.7e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.005,-3.7e+02,-0.0014,-0.0059,0.00054,0.002,0.0062,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.7e-05,2.9e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -23990000,0.71,0.00096,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-0.0014,-0.0059,0.00055,0.0022,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.6e-05,2.9e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-07,6.7e-07,2.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24090000,0.71,0.0022,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-0.0014,-0.0059,0.00056,0.0022,0.0058,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.7e-05,8.7e-05,2.9e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.7e-07,6.7e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,0.00056,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.6e-05,2.8e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-07,6.4e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-0.0014,-0.0059,0.00055,0.0024,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.6e-05,2.8e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.4e-07,6.4e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24390000,0.71,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-0.0013,-0.0059,0.00054,0.0021,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,2.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24490000,0.71,0.0047,-0.0018,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-0.0013,-0.0059,0.00054,0.0021,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.6e-05,8.5e-05,2.8e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.069,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,0.00055,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-0.0013,-0.0059,0.00056,0.002,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.5e-05,8.5e-05,2.8e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-07,5.9e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,0.00054,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.4e-05,8.4e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-0.0013,-0.0059,0.00053,0.0024,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.4e-05,8.4e-05,2.8e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,0.00052,0.0033,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.1e-05,8.3e-05,8.3e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.4e-07,5.4e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-0.0013,-0.0059,0.00051,0.0034,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.4e-05,8.3e-05,2.8e-05,0.018,0.017,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,0.00051,0.003,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.3e-05,8.2e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-07,5.2e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,0.00051,0.003,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.3e-05,8.3e-05,2.8e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,1.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,0.00051,0.0032,-0.00027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.2e-05,8.2e-05,2.8e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,0.00052,0.0032,-0.00026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.2e-05,8.2e-05,2.7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,0.00052,0.0029,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8.1e-05,2.7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-07,4.9e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,0.00052,0.0029,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8.1e-05,2.7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-07,4.9e-07,1.8e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,0.00053,0.0037,-0.0038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-07,4.7e-07,1.7e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,0.00054,0.0036,-0.0038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8.1e-05,8e-05,2.7e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-07,4.7e-07,1.7e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,0.00054,0.0032,-0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-07,4.6e-07,1.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,0.00052,0.0033,-0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,8e-05,8e-05,2.7e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-07,4.6e-07,1.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -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,0.00052,0.0044,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.9e-05,7.9e-05,2.7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-07,4.4e-07,1.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -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,0.00052,0.0044,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.9e-05,7.9e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-07,4.5e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,0.00052,0.0031,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.8e-05,7.8e-05,2.7e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-07,4.3e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,0.00052,0.0031,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.8e-05,7.8e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-07,4.3e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-0.00095,-0.0059,0.00049,0.0041,-0.014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.8e-05,7.7e-05,2.7e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-07,4.2e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-0.00095,-0.0059,0.00049,0.0041,-0.014,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.8e-05,7.7e-05,2.7e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-07,4.2e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-0.0009,-0.006,0.00048,0.0018,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.7e-05,2.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.1e-07,4.1e-07,1.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-0.0009,-0.006,0.00049,0.0018,-0.016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.7e-05,2.7e-05,0.015,0.015,0.0081,0.043,0.043,0.035,4.1e-07,4.1e-07,1.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-0.00079,-0.006,0.00048,0.0026,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.6e-05,7.6e-05,2.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0 -27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-0.00079,-0.006,0.00048,0.0026,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.7e-05,7.6e-05,2.7e-05,0.015,0.015,0.0081,0.043,0.043,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0015,0.0025,0.0025,0.0025,0.0025,0,0 -27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00078,-0.0059,0.00048,0.0037,-0.021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-05,7.6e-05,7.6e-05,2.7e-05,0.015,0.015,0.0081,0.045,0.045,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,0,0 -27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00078,-0.0059,0.00049,0.0036,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.7e-05,0.017,0.017,0.0081,0.049,0.049,0.035,4e-07,4e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0 -27390000,0.71,0.036,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.00072,-0.0059,0.0005,0.0057,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.7e-05,0.017,0.017,0.0081,0.052,0.052,0.035,3.9e-07,3.9e-07,1.5e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0 -27490000,0.71,0.031,0.062,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-0.00072,-0.0059,0.00049,0.0056,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.8e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0 -27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-0.00075,-0.0059,0.0005,0.0055,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.059,0.059,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00056,0.0025,0.0025,0.0025,0.0025,0,0 -27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-0.00075,-0.0059,0.00049,0.0055,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.7e-05,2.6e-05,0.019,0.019,0.0082,0.065,0.065,0.035,3.9e-07,3.9e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0 -27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-0.00075,-0.0058,0.00048,0.0057,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.018,0.018,0.0082,0.067,0.067,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0 -27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-0.00075,-0.0058,0.00048,0.0055,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0083,0.074,0.073,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0 -27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-0.00079,-0.0058,0.00048,0.0051,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.019,0.019,0.0083,0.076,0.076,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0 -28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-0.00079,-0.0058,0.00046,0.005,-0.017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0084,0.083,0.082,0.035,3.8e-07,3.8e-07,1.4e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0 -28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-0.00082,-0.0058,0.00047,0.0047,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.7e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0 -28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.089,-4.4,-2.4,-3.7e+02,-0.00082,-0.0058,0.00045,0.0045,-0.016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.6e-05,2.6e-05,0.02,0.02,0.0086,0.092,0.092,0.036,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0 -28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-0.00082,-0.0058,0.00044,0.0043,-0.015,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.7e-05,7.7e-05,2.5e-05,0.021,0.021,0.0087,0.099,0.099,0.036,3.7e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0 -28490000,0.71,0.0026,0.0044,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-0.00082,-0.0058,0.00043,0.004,-0.014,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.022,0.022,0.0088,0.11,0.11,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0 -28590000,0.71,0.00081,0.00092,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-0.00082,-0.0058,0.00043,0.0036,-0.013,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.023,0.024,0.0089,0.12,0.12,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0 -28690000,0.71,0.0001,5.7e-06,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-0.00082,-0.0058,0.00042,0.0032,-0.012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.025,0.025,0.009,0.12,0.12,0.036,3.8e-07,3.8e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0 -28790000,0.71,-0.00019,-0.00023,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-0.00089,-0.0058,0.00042,0.00016,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.5e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-07,3.7e-07,1.3e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0 -28890000,0.71,-0.0002,-1.4e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-0.00089,-0.0058,0.00042,-0.00027,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,7.8e-05,7.7e-05,2.4e-05,0.025,0.025,0.009,0.14,0.14,0.036,3.7e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0 -28990000,0.71,-1e-05,0.00044,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-0.00098,-0.0058,0.00041,-0.0023,-0.026,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.8e-05,7.7e-05,2.4e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.6e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0 -29090000,0.71,0.00014,0.00085,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-0.00098,-0.0058,0.0004,-0.0028,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-07,3.7e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0 -29190000,0.71,0.00036,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-0.001,-0.0058,0.0004,-0.0047,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-07,3.6e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 -29290000,0.71,0.00072,0.0021,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-0.001,-0.0058,0.00039,-0.0053,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.025,0.026,0.0091,0.16,0.16,0.036,3.6e-07,3.6e-07,1.2e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 -29390000,0.71,0.0013,0.0036,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-0.0011,-0.0058,0.00037,-0.0068,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.024,0.009,0.16,0.16,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0 -29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-0.0011,-0.0058,0.00037,-0.0073,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 -29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-0.0011,-0.0057,0.00036,-0.0096,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.024,0.025,0.009,0.17,0.17,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 -29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-0.0011,-0.0057,0.00035,-0.01,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,7.9e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-07,3.5e-07,1.2e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 -29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.94,-8.5,-4.1,-3.7e+02,-0.0012,-0.0057,0.00035,-0.012,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.0091,0.18,0.17,0.037,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 -29890000,0.71,0.0029,0.0073,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-0.0012,-0.0057,0.00034,-0.013,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 -29990000,0.71,0.003,0.0075,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-0.0012,-0.0057,0.00032,-0.015,-0.027,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.18,0.18,0.036,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 -30090000,0.71,0.003,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-0.0012,-0.0057,0.00031,-0.015,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.2,0.2,0.036,3.4e-07,3.4e-07,1.1e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 -30190000,0.71,0.0031,0.0074,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-0.0013,-0.0057,0.00031,-0.016,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.025,0.025,0.009,0.19,0.19,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 -30290000,0.71,0.003,0.0072,0.71,-2,-1,0.86,-9.6,-4.6,-3.7e+02,-0.0013,-0.0057,0.0003,-0.017,-0.025,-0.11,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.8e-05,2.4e-05,0.026,0.026,0.0091,0.21,0.21,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 -30390000,0.71,0.003,0.007,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-0.0013,-0.0057,0.0003,-0.018,-0.024,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.2,0.2,0.036,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 -30490000,0.71,0.0029,0.0068,0.71,-2,-1,0.83,-10,-4.8,-3.7e+02,-0.0013,-0.0057,0.0003,-0.018,-0.024,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.026,0.026,0.0091,0.22,0.22,0.037,3.3e-07,3.3e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 -30590000,0.71,0.0028,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-0.0013,-0.0057,0.0003,-0.019,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 -30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-0.0013,-0.0057,0.0003,-0.02,-0.022,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.026,0.026,0.009,0.23,0.23,0.037,3.2e-07,3.2e-07,1.1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 -30790000,0.71,0.0026,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-0.0013,-0.0057,0.00028,-0.02,-0.021,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8e-05,7.7e-05,2.3e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 -30890000,0.71,0.0025,0.0054,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0057,0.00028,-0.021,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.009,0.24,0.24,0.037,3.2e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 -30990000,0.71,0.0024,0.005,0.71,-1.9,-0.96,0.76,-11,-5.3,-3.7e+02,-0.0013,-0.0057,0.00027,-0.022,-0.02,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.1e-07,3.1e-07,1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 -31090000,0.71,0.0022,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-0.0013,-0.0057,0.00027,-0.022,-0.018,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.009,0.25,0.25,0.037,3.1e-07,3.2e-07,1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 -31190000,0.71,0.0022,0.0042,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-0.0014,-0.0057,0.00026,-0.023,-0.016,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-07,3.1e-07,1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 -31290000,0.71,0.0019,0.0037,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-0.0014,-0.0057,0.00026,-0.024,-0.014,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.7e-05,2.3e-05,0.026,0.026,0.0089,0.25,0.25,0.037,3.1e-07,3.1e-07,9.9e-07,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -31390000,0.71,0.0018,0.0032,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-0.0014,-0.0057,0.00025,-0.025,-0.012,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-07,3.1e-07,9.9e-07,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -31490000,0.71,0.0016,0.0026,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-0.0014,-0.0057,0.00024,-0.025,-0.011,-0.1,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.026,0.026,0.0088,0.26,0.26,0.037,3.1e-07,3.1e-07,9.8e-07,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -31590000,0.71,0.0016,0.0023,0.71,-1.7,-0.91,0.72,-12,-5.8,-3.7e+02,-0.0014,-0.0057,0.00024,-0.026,-0.0095,-0.099,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3e-07,3e-07,9.7e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31690000,0.71,0.0013,0.0016,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-0.0014,-0.0057,0.00024,-0.027,-0.0083,-0.099,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,8.1e-05,7.6e-05,2.3e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3e-07,3e-07,9.6e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31790000,0.71,0.0011,0.001,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-0.0014,-0.0057,0.00024,-0.028,-0.0064,-0.098,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.3e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-07,3e-07,9.5e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31890000,0.71,0.00087,0.00033,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-0.0014,-0.0057,0.00024,-0.028,-0.0051,-0.097,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.6e-05,2.2e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-07,3e-07,9.4e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -31990000,0.71,0.00074,-0.00013,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-0.0014,-0.0057,0.00023,-0.029,-0.0032,-0.097,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-07,3e-07,9.3e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -32090000,0.71,0.00045,-0.00085,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-0.0014,-0.0057,0.00023,-0.03,-0.0017,-0.096,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-07,3e-07,9.3e-07,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 -32190000,0.71,0.00024,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-0.0014,-0.0057,0.00021,-0.031,0.00037,-0.096,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-07,2.9e-07,9.2e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32290000,0.71,9.8e-06,-0.0024,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-0.0014,-0.0057,0.00021,-0.031,0.002,-0.095,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0086,0.3,0.3,0.037,2.9e-07,2.9e-07,9.1e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32390000,0.71,-0.00017,-0.003,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-0.0014,-0.0057,0.00021,-0.032,0.0029,-0.095,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-07,2.9e-07,9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32490000,0.71,-0.00029,-0.0032,0.71,-1.4,-0.81,0.72,-14,-6.6,-3.7e+02,-0.0014,-0.0057,0.00021,-0.032,0.004,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-07,2.9e-07,9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32590000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-0.0015,-0.0057,0.0002,-0.033,0.0048,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.024,0.025,0.0084,0.31,0.31,0.036,2.9e-07,2.9e-07,8.9e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32690000,0.71,-0.00033,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-0.0015,-0.0057,0.0002,-0.033,0.0053,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.5e-05,2.2e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-07,2.9e-07,8.8e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32790000,0.71,-0.0003,-0.0035,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-0.0015,-0.0057,0.0002,-0.033,0.0063,-0.094,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.024,0.025,0.0084,0.31,0.31,0.036,2.8e-07,2.8e-07,8.7e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32890000,0.71,-0.0002,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-0.0015,-0.0057,0.00018,-0.034,0.0074,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.8e-07,2.9e-07,8.7e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -32990000,0.71,-7.4e-05,-0.0034,0.71,-1.3,-0.76,0.7,-15,-7,-3.7e+02,-0.0015,-0.0057,0.00019,-0.034,0.0087,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.024,0.024,0.0083,0.32,0.32,0.036,2.8e-07,2.8e-07,8.6e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -33090000,0.71,-0.00011,-0.0034,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-0.0015,-0.0057,0.0002,-0.035,0.0092,-0.093,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.2e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-07,2.8e-07,8.5e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-0.0015,-0.0057,0.0002,-0.035,0.0099,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.3e-05,8.1e-05,7.4e-05,2.1e-05,0.024,0.024,0.0083,0.33,0.33,0.036,2.8e-07,2.8e-07,8.5e-07,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 -33290000,0.65,0.015,-0.0015,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-0.0015,-0.0057,0.00021,-0.035,0.01,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.5e-05,8e-05,7.4e-05,1.8e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-07,2.8e-07,8.4e-07,0.027,0.025,0.0005,0.0025,9.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33390000,0.55,0.013,-0.0018,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.9e-05,7.5e-05,1.4e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-07,2.8e-07,8.3e-07,0.027,0.025,0.0005,0.0025,9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33490000,0.41,0.0068,0.00068,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,7.8e-05,7.7e-05,1.1e-05,0.026,0.026,0.0081,0.35,0.35,0.036,2.8e-07,2.8e-07,8.3e-07,0.027,0.025,0.0005,0.0025,8.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33590000,0.25,0.00096,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-0.0015,-0.0057,0.00021,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6.3e-05,7.6e-05,7.8e-05,1.1e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.7e-07,2.8e-07,8.2e-07,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33690000,0.087,-0.0023,-0.0049,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-0.0015,-0.0057,0.00022,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,6e-05,7.5e-05,8e-05,1.3e-05,0.028,0.028,0.0076,0.36,0.36,0.036,2.7e-07,2.8e-07,8.1e-07,0.027,0.025,0.0005,0.0025,8.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33790000,-0.082,-0.0038,-0.0067,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-0.0015,-0.0057,0.00022,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,5.4e-05,7.2e-05,8e-05,1.8e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-07,2.7e-07,8.1e-07,0.027,0.025,0.0005,0.0025,8.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33890000,-0.25,-0.005,-0.0075,0.97,-1,-0.66,0.77,-16,-7.6,-3.7e+02,-0.0015,-0.0057,0.00022,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,4.7e-05,7.2e-05,8.1e-05,2.5e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-07,2.7e-07,8e-07,0.027,0.025,0.0005,0.0025,8.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -33990000,-0.39,-0.0032,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0056,0.00022,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.9e-05,6.9e-05,7.8e-05,3.2e-05,0.031,0.032,0.007,0.37,0.37,0.035,2.7e-07,2.7e-07,8e-07,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34090000,-0.5,-0.0021,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0056,0.00023,-0.036,0.011,-0.092,0.37,0.0037,0.025,0,0,0,0,0,3.3e-05,6.9e-05,7.8e-05,3.7e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-07,2.7e-07,7.9e-07,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34190000,-0.57,-0.0014,-0.011,0.82,-0.91,-0.54,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,0.00023,-0.038,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,6.5e-05,7.3e-05,4e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-07,2.7e-07,7.9e-07,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34290000,-0.61,-0.0024,-0.0085,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-0.0015,-0.0057,0.00023,-0.038,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,6.5e-05,7.3e-05,4.1e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-07,2.7e-07,7.8e-07,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34390000,-0.64,-0.0025,-0.006,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-0.0016,-0.0057,0.00023,-0.043,0.018,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,6e-05,6.7e-05,4.1e-05,0.041,0.043,0.0065,0.39,0.39,0.035,2.6e-07,2.7e-07,7.8e-07,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34490000,-0.65,-0.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-0.0016,-0.0057,0.00023,-0.043,0.018,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,6.1e-05,6.7e-05,4.1e-05,0.048,0.05,0.0064,0.4,0.4,0.035,2.7e-07,2.7e-07,7.7e-07,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00024,-0.053,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,5.5e-05,6.1e-05,4e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-07,2.6e-07,7.7e-07,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.36,0.73,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00024,-0.053,0.026,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.5e-05,6.1e-05,4e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.6e-07,2.7e-07,7.7e-07,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34790000,-0.67,-0.0021,-0.0017,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00024,-0.064,0.037,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.1e-05,5.5e-05,3.9e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-07,2.6e-07,7.6e-07,0.026,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34890000,-0.68,-0.0021,-0.0016,0.74,-0.7,-0.32,0.72,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00025,-0.064,0.037,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,5.1e-05,5.5e-05,3.8e-05,0.058,0.061,0.0062,0.42,0.42,0.034,2.6e-07,2.7e-07,7.6e-07,0.026,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -34990000,-0.68,-0.0085,-0.0044,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00024,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.8e-05,0.056,0.058,0.0068,0.42,0.42,0.034,2.6e-07,2.6e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35090000,-0.68,-0.0085,-0.0045,0.73,0.43,0.31,-0.19,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00025,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.7e-05,0.061,0.063,0.0068,0.43,0.43,0.034,2.6e-07,2.7e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35190000,-0.68,-0.0085,-0.0045,0.73,0.46,0.34,-0.18,-17,-8.2,-3.7e+02,-0.0016,-0.0057,0.00025,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.6e-05,0.066,0.068,0.0067,0.44,0.44,0.034,2.7e-07,2.7e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35290000,-0.68,-0.0086,-0.0046,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00025,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.5e-05,0.071,0.074,0.0066,0.45,0.45,0.033,2.7e-07,2.7e-07,7.5e-07,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35390000,-0.68,-0.0086,-0.0045,0.73,0.5,0.41,-0.18,-17,-8.1,-3.7e+02,-0.0016,-0.0057,0.00024,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.5e-05,0.077,0.08,0.0066,0.47,0.47,0.034,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35490000,-0.68,-0.0087,-0.0045,0.73,0.52,0.44,-0.18,-17,-8,-3.7e+02,-0.0016,-0.0057,0.00024,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,4.6e-05,5e-05,3.4e-05,0.083,0.087,0.0065,0.49,0.49,0.034,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35590000,-0.68,-0.0056,-0.0045,0.73,0.42,0.36,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00026,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.9e-05,4.2e-05,3.3e-05,0.067,0.069,0.0062,0.48,0.48,0.033,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35690000,-0.68,-0.0056,-0.0045,0.73,0.44,0.38,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00026,-0.077,0.051,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.9e-05,4.2e-05,3.3e-05,0.072,0.075,0.0061,0.49,0.49,0.033,2.7e-07,2.7e-07,7.4e-07,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35790000,-0.68,-0.0034,-0.0044,0.73,0.36,0.32,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00028,-0.079,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,3.3e-05,3.6e-05,3.2e-05,0.06,0.062,0.0059,0.48,0.48,0.033,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35890000,-0.68,-0.0034,-0.0045,0.73,0.38,0.35,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,0.00029,-0.079,0.052,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,3.3e-05,3.6e-05,3.1e-05,0.066,0.068,0.0058,0.5,0.5,0.033,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -35990000,-0.68,-0.0015,-0.0044,0.73,0.31,0.29,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0003,-0.087,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.9e-05,3.1e-05,3.1e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36090000,-0.68,-0.0016,-0.0044,0.73,0.32,0.31,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00031,-0.087,0.059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.9e-05,3.1e-05,3e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-07,2.7e-07,7.3e-07,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36190000,-0.68,-0.00018,-0.0043,0.73,0.27,0.27,-0.19,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00032,-0.098,0.068,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.6e-05,2.8e-05,3e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-07,2.7e-07,7.2e-07,0.024,0.022,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36290000,-0.68,-0.0003,-0.0042,0.73,0.28,0.29,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00033,-0.098,0.068,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.6e-05,2.8e-05,2.9e-05,0.06,0.062,0.0056,0.51,0.51,0.032,2.7e-07,2.8e-07,7.2e-07,0.024,0.022,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36390000,-0.68,0.00075,-0.0041,0.73,0.23,0.24,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00035,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.4e-05,2.5e-05,2.9e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-07,2.8e-07,7.2e-07,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36490000,-0.68,0.00066,-0.0042,0.73,0.24,0.26,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00037,-0.11,0.078,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.4e-05,2.5e-05,2.9e-05,0.059,0.061,0.0055,0.52,0.52,0.032,2.8e-07,2.8e-07,7.2e-07,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36590000,-0.68,0.0014,-0.004,0.73,0.2,0.22,-0.18,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00038,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.2e-05,2.3e-05,2.8e-05,0.053,0.054,0.0055,0.52,0.52,0.031,2.8e-07,2.8e-07,7.2e-07,0.023,0.021,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36690000,-0.68,0.0014,-0.004,0.73,0.2,0.24,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00039,-0.12,0.088,-0.092,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2.2e-05,2.3e-05,2.8e-05,0.058,0.06,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,7.1e-07,0.023,0.021,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36790000,-0.68,0.002,-0.0039,0.74,0.17,0.21,-0.17,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00039,-0.14,0.097,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2e-05,2.1e-05,2.7e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-07,2.8e-07,7.1e-07,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36890000,-0.68,0.0019,-0.0039,0.74,0.17,0.22,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0004,-0.14,0.097,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.4e-05,2e-05,2.1e-05,2.7e-05,0.057,0.059,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,7.1e-07,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -36990000,-0.68,0.0024,-0.0037,0.74,0.14,0.19,-0.16,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00041,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.9e-05,2e-05,2.7e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-07,2.8e-07,7.1e-07,0.021,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37090000,-0.68,0.0023,-0.0037,0.74,0.14,0.19,-0.15,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00043,-0.15,0.11,-0.093,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.9e-05,2e-05,2.6e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-07,2.8e-07,7.1e-07,0.021,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37190000,-0.68,0.0026,-0.0036,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00044,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.6e-05,0.05,0.051,0.0057,0.55,0.55,0.031,2.8e-07,2.8e-07,7e-07,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37290000,-0.68,0.0026,-0.0036,0.74,0.12,0.17,-0.14,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00046,-0.16,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.6e-05,0.055,0.057,0.0058,0.56,0.56,0.031,2.8e-07,2.9e-07,7e-07,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37390000,-0.68,0.0028,-0.0035,0.74,0.097,0.15,-0.13,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00047,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.5e-05,0.05,0.051,0.0059,0.56,0.56,0.031,2.8e-07,2.9e-07,7e-07,0.02,0.018,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37490000,-0.68,0.0028,-0.0034,0.74,0.096,0.15,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00047,-0.17,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.9e-05,2.5e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-07,2.9e-07,7e-07,0.02,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37590000,-0.68,0.0029,-0.0033,0.74,0.077,0.13,-0.12,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00048,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.8e-05,2.5e-05,0.049,0.049,0.0061,0.57,0.57,0.031,2.9e-07,2.9e-07,7e-07,0.019,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37690000,-0.68,0.0029,-0.0034,0.74,0.075,0.14,-0.11,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0005,-0.18,0.13,-0.095,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.8e-05,1.8e-05,2.4e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-07,2.9e-07,7e-07,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37790000,-0.68,0.003,-0.0033,0.74,0.059,0.12,-0.1,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00051,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,2.5e-05,1.7e-05,1.8e-05,2.4e-05,0.048,0.048,0.0063,0.58,0.58,0.03,2.9e-07,2.9e-07,7e-07,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37890000,-0.68,0.003,-0.0033,0.74,0.056,0.12,-0.093,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00052,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.4e-05,0.052,0.053,0.0064,0.59,0.59,0.03,2.9e-07,2.9e-07,6.9e-07,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -37990000,-0.68,0.003,-0.0033,0.74,0.042,0.1,-0.084,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00053,-0.2,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.4e-05,0.046,0.047,0.0065,0.59,0.59,0.031,2.9e-07,2.9e-07,6.9e-07,0.017,0.016,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38090000,-0.68,0.003,-0.0033,0.74,0.038,0.11,-0.074,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00054,-0.2,0.13,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-07,2.9e-07,6.9e-07,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38190000,-0.68,0.003,-0.0032,0.74,0.025,0.089,-0.066,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00055,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-07,2.9e-07,6.9e-07,0.016,0.015,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38290000,-0.68,0.003,-0.0032,0.74,0.022,0.09,-0.059,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00056,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.049,0.05,0.0068,0.61,0.61,0.031,2.9e-07,2.9e-07,6.9e-07,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38390000,-0.68,0.003,-0.0032,0.74,0.013,0.078,-0.051,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00058,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.3e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-07,3e-07,6.9e-07,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38490000,-0.68,0.003,-0.0032,0.74,0.01,0.079,-0.044,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00059,-0.21,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.2e-05,0.048,0.048,0.007,0.62,0.62,0.031,3e-07,3e-07,6.8e-07,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38590000,-0.68,0.003,-0.0031,0.74,0.0054,0.068,-0.037,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.0006,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.6e-05,1.7e-05,1.8e-05,2.2e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-07,3e-07,6.8e-07,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38690000,-0.68,0.0029,-0.0031,0.74,0.001,0.068,-0.03,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00061,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,1.7e-05,1.8e-05,2.2e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-07,3e-07,6.8e-07,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38790000,-0.68,0.0029,-0.003,0.74,-0.0041,0.056,-0.022,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00062,-0.22,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,1.7e-05,1.8e-05,2.2e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-07,3e-07,6.8e-07,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 -38890000,-0.68,0.0027,-0.0031,0.74,-0.014,0.045,0.48,-17,-8.2,-3.7e+02,-0.0017,-0.0057,0.00063,-0.22,0.14,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-05,1.8e-05,1.8e-05,2.2e-05,0.045,0.045,0.0075,0.64,0.64,0.032,3e-07,3e-07,6.8e-07,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +6190000,0.71,0.0013,-0.015,0.71,0.0035,0.0029,-0.005,0.0023,-0.00066,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-8.8e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.00034,0.00034,0.0028,0.22,0.22,4.9,0.13,0.13,0.32,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6290000,0.71,0.0013,-0.015,0.71,0.0034,0.0043,-0.012,0.0026,-0.00028,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-9.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.00034,0.00034,0.0028,0.22,0.22,3.2,0.16,0.16,0.3,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6390000,0.71,0.0013,-0.014,0.71,0.0024,0.0048,-0.05,0.0029,0.00018,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-3.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0029,0.00034,0.00034,0.0028,0.23,0.23,2.3,0.19,0.19,0.29,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6490000,0.71,0.0013,-0.014,0.71,0.0022,0.0056,-0.052,0.0031,0.00072,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-8.6e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00034,0.00034,0.0022,0.24,0.24,1.5,0.23,0.23,0.26,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6590000,0.71,0.0013,-0.014,0.71,0.0017,0.0057,-0.099,0.0033,0.0013,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,9.5e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00035,0.00034,0.0022,0.25,0.25,1.1,0.28,0.28,0.23,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6690000,0.71,0.0014,-0.014,0.71,0.0021,0.0068,-0.076,0.0035,0.0019,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.00022,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00035,0.00035,0.0022,0.26,0.26,0.78,0.33,0.33,0.21,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6790000,0.71,0.0014,-0.014,0.71,0.00077,0.0068,-0.11,0.0037,0.0026,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,8.1e-06,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00035,0.00035,0.0022,0.28,0.28,0.6,0.38,0.38,0.2,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6890000,0.71,0.0014,-0.014,0.71,-0.0013,0.0073,-0.12,0.0036,0.0033,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-4.3e-05,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00036,0.00036,0.0022,0.3,0.3,0.46,0.44,0.44,0.18,0.00015,0.00015,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +6990000,0.71,0.0014,-0.014,0.71,-0.0013,0.0082,-0.12,0.0035,0.0041,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.00034,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00037,0.00036,0.0022,0.32,0.32,0.36,0.51,0.51,0.16,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7090000,0.71,0.0014,-0.014,0.71,-0.0019,0.0079,-0.13,0.0033,0.0049,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.0007,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00037,0.00037,0.0022,0.35,0.35,0.29,0.58,0.58,0.16,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7190000,0.71,0.0014,-0.014,0.71,-0.0036,0.0081,-0.15,0.003,0.0057,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.00049,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00038,0.00038,0.0022,0.37,0.37,0.24,0.66,0.66,0.15,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7290000,0.71,0.0015,-0.014,0.71,-0.0051,0.0083,-0.15,0.0026,0.0065,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.0012,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00039,0.00039,0.0022,0.41,0.41,0.2,0.76,0.76,0.14,0.00014,0.00014,1.1e-05,0.04,0.04,0.04,0,0,0,0,0,0,0,0 +7390000,0.71,0.0015,-0.014,0.71,-0.0052,0.0098,-0.16,0.002,0.0073,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.0013,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0004,0.00039,0.0022,0.44,0.44,0.18,0.85,0.85,0.13,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7490000,0.71,0.0016,-0.014,0.71,-0.0068,0.01,-0.16,0.0014,0.0083,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.0021,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00041,0.0004,0.0022,0.48,0.48,0.15,0.96,0.96,0.12,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7590000,0.71,0.0016,-0.014,0.71,-0.0086,0.012,-0.17,0.00067,0.0093,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.003,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00041,0.00041,0.0022,0.52,0.52,0.14,1.1,1.1,0.12,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7690000,0.71,0.0016,-0.014,0.71,-0.01,0.012,-0.16,-0.00032,0.01,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.005,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00043,0.00042,0.0022,0.56,0.56,0.13,1.2,1.2,0.11,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7790000,0.71,0.0017,-0.014,0.71,-0.012,0.013,-0.16,-0.0014,0.011,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.007,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00044,0.00043,0.0022,0.6,0.6,0.12,1.3,1.3,0.11,0.00014,0.00014,1.1e-05,0.04,0.04,0.039,0,0,0,0,0,0,0,0 +7890000,0.71,0.0017,-0.014,0.71,-0.015,0.015,-0.16,-0.0028,0.013,-3.7e+02,-0.0015,-0.0057,4.6e-05,0,0,-0.0096,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00045,0.00045,0.0022,0.66,0.66,0.11,1.5,1.5,0.1,0.00014,0.00014,1.1e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +7990000,0.71,0.0017,-0.014,0.71,-0.016,0.016,-0.16,-0.0043,0.014,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00046,0.00046,0.0022,0.7,0.7,0.1,1.7,1.7,0.099,0.00014,0.00014,1.1e-05,0.04,0.04,0.038,0,0,0,0,0,0,0,0 +8090000,0.71,0.0017,-0.014,0.71,-0.018,0.018,-0.17,-0.0061,0.016,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-0.011,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00047,0.00047,0.0022,0.76,0.76,0.1,1.9,1.9,0.097,0.00014,0.00014,1.1e-05,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +8190000,0.71,0.0017,-0.014,0.71,-0.021,0.019,-0.18,-0.0081,0.018,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-0.013,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00049,0.00048,0.0022,0.83,0.83,0.099,2.1,2.1,0.094,0.00014,0.00014,1.1e-05,0.04,0.04,0.037,0,0,0,0,0,0,0,0 +8290000,0.71,0.0017,-0.014,0.71,-0.022,0.02,-0.17,-0.01,0.019,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-0.017,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0005,0.0005,0.0022,0.88,0.88,0.097,2.3,2.3,0.091,0.00014,0.00014,1.1e-05,0.04,0.04,0.036,0,0,0,0,0,0,0,0 +8390000,0.71,0.0018,-0.014,0.71,-0.024,0.021,-0.17,-0.013,0.021,-3.7e+02,-0.0015,-0.0057,4.5e-05,0,0,-0.021,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00051,0.00051,0.0023,0.96,0.96,0.097,2.5,2.5,0.091,0.00014,0.00014,1.1e-05,0.04,0.04,0.035,0,0,0,0,0,0,0,0 +8490000,0.71,0.0018,-0.014,0.71,-0.026,0.023,-0.17,-0.015,0.022,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.025,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00052,0.00052,0.0023,1,1,0.096,2.8,2.8,0.089,0.00014,0.00014,1.1e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +8590000,0.71,0.0018,-0.014,0.71,-0.029,0.025,-0.17,-0.018,0.024,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.029,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00054,0.00054,0.0023,1.1,1.1,0.095,3.1,3.1,0.088,0.00014,0.00014,1.1e-05,0.04,0.04,0.034,0,0,0,0,0,0,0,0 +8690000,0.71,0.0019,-0.014,0.71,-0.032,0.026,-0.16,-0.021,0.026,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.035,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00055,0.00055,0.0023,1.1,1.1,0.096,3.3,3.3,0.088,0.00014,0.00014,1.1e-05,0.04,0.04,0.033,0,0,0,0,0,0,0,0 +8790000,0.71,0.0018,-0.014,0.71,-0.034,0.027,-0.15,-0.024,0.028,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.041,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00057,0.00056,0.0023,1.2,1.2,0.095,3.7,3.7,0.087,0.00014,0.00014,1.1e-05,0.04,0.04,0.032,0,0,0,0,0,0,0,0 +8890000,0.71,0.0018,-0.014,0.71,-0.036,0.028,-0.15,-0.027,0.03,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.045,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00057,0.00057,0.0023,1.3,1.3,0.095,3.9,3.9,0.086,0.00013,0.00013,1.1e-05,0.04,0.04,0.03,0,0,0,0,0,0,0,0 +8990000,0.71,0.0019,-0.014,0.71,-0.038,0.029,-0.14,-0.031,0.032,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.051,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00059,0.00059,0.0023,1.4,1.4,0.096,4.3,4.3,0.087,0.00013,0.00013,1.1e-05,0.04,0.04,0.029,0,0,0,0,0,0,0,0 +9090000,0.71,0.0019,-0.014,0.71,-0.04,0.029,-0.14,-0.034,0.033,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.053,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0006,0.0006,0.0023,1.4,1.4,0.095,4.6,4.6,0.086,0.00013,0.00013,1.1e-05,0.04,0.04,0.028,0,0,0,0,0,0,0,0 +9190000,0.71,0.002,-0.014,0.71,-0.042,0.03,-0.14,-0.038,0.036,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.057,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00062,0.00061,0.0023,1.5,1.5,0.094,5.1,5.1,0.085,0.00013,0.00013,1.1e-05,0.04,0.04,0.027,0,0,0,0,0,0,0,0 +9290000,0.71,0.0019,-0.014,0.71,-0.042,0.031,-0.14,-0.041,0.037,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.061,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00062,0.00062,0.0023,1.6,1.6,0.093,5.3,5.3,0.085,0.00013,0.00013,1.1e-05,0.04,0.04,0.025,0,0,0,0,0,0,0,0 +9390000,0.71,0.0019,-0.014,0.71,-0.044,0.033,-0.14,-0.045,0.04,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.065,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00064,0.00064,0.0023,1.7,1.7,0.093,5.9,5.9,0.086,0.00013,0.00013,1.1e-05,0.04,0.04,0.024,0,0,0,0,0,0,0,0 +9490000,0.71,0.0019,-0.014,0.71,-0.045,0.033,-0.13,-0.047,0.04,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.068,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00064,0.00064,0.0023,1.7,1.7,0.091,6.1,6.1,0.085,0.00013,0.00013,1.1e-05,0.04,0.04,0.023,0,0,0,0,0,0,0,0 +9590000,0.71,0.0019,-0.014,0.71,-0.047,0.034,-0.13,-0.052,0.043,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.072,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00066,0.00066,0.0023,1.8,1.8,0.09,6.7,6.7,0.085,0.00013,0.00013,1.1e-05,0.04,0.04,0.021,0,0,0,0,0,0,0,0 +9690000,0.71,0.002,-0.014,0.71,-0.048,0.035,-0.12,-0.054,0.043,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.077,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00065,0.00065,0.0023,1.9,1.9,0.089,6.9,6.9,0.086,0.00012,0.00012,1.1e-05,0.04,0.04,0.02,0,0,0,0,0,0,0,0 +9790000,0.71,0.002,-0.014,0.71,-0.048,0.037,-0.11,-0.059,0.047,-3.7e+02,-0.0015,-0.0056,4.5e-05,0,0,-0.082,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00067,0.00067,0.0023,2,2,0.087,7.5,7.5,0.085,0.00012,0.00012,1.1e-05,0.04,0.04,0.019,0,0,0,0,0,0,0,0 +9890000,0.71,0.002,-0.014,0.71,-0.048,0.038,-0.11,-0.059,0.047,-3.7e+02,-0.0015,-0.0056,4.4e-05,0,0,-0.085,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00067,0.00067,0.0023,2,2,0.084,7.6,7.6,0.085,0.00012,0.00012,1.1e-05,0.04,0.04,0.018,0,0,0,0,0,0,0,0 +9990000,0.71,0.002,-0.014,0.71,-0.05,0.038,-0.1,-0.065,0.05,-3.7e+02,-0.0015,-0.0056,4.4e-05,0,0,-0.089,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00069,0.00069,0.0023,2.1,2.1,0.083,8.4,8.4,0.086,0.00012,0.00012,1.1e-05,0.04,0.04,0.017,0,0,0,0,0,0,0,0 +10090000,0.71,0.002,-0.014,0.71,-0.049,0.037,-0.096,-0.064,0.049,-3.7e+02,-0.0015,-0.0056,4.4e-05,0,0,-0.091,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00068,0.00068,0.0023,2.1,2.1,0.08,8.4,8.4,0.085,0.00012,0.00012,1.1e-05,0.04,0.04,0.016,0,0,0,0,0,0,0,0 +10190000,0.71,0.002,-0.014,0.71,-0.051,0.04,-0.096,-0.069,0.053,-3.7e+02,-0.0015,-0.0056,4.4e-05,0,0,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0007,0.0007,0.0023,2.2,2.2,0.078,9.2,9.2,0.084,0.00012,0.00012,1.1e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +10290000,0.71,0.002,-0.014,0.71,-0.052,0.041,-0.084,-0.075,0.057,-3.7e+02,-0.0015,-0.0056,4.4e-05,0,0,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00072,0.00072,0.0023,2.4,2.4,0.076,10,10,0.085,0.00012,0.00012,1.1e-05,0.04,0.04,0.014,0,0,0,0,0,0,0,0 +10390000,0.71,0.002,-0.014,0.71,0.0095,-0.019,0.0096,0.00087,-0.0017,-3.7e+02,-0.0015,-0.0056,4.4e-05,-6.6e-08,4.9e-08,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00075,0.00074,0.0023,0.25,0.25,0.56,0.25,0.25,0.078,0.00012,0.00012,1.1e-05,0.04,0.04,0.013,0,0,0,0,0,0,0,0 +10490000,0.71,0.0021,-0.014,0.71,0.0083,-0.017,0.023,0.0017,-0.0035,-3.7e+02,-0.0015,-0.0056,4.4e-05,-1.7e-06,1.3e-06,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00077,0.00077,0.0023,0.26,0.26,0.55,0.26,0.26,0.08,0.00012,0.00012,1.1e-05,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +10590000,0.71,0.0022,-0.014,0.71,0.0078,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-0.0015,-0.0056,4.4e-05,-0.00027,2.8e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00078,0.00078,0.0023,0.14,0.14,0.27,0.13,0.13,0.073,0.00012,0.00012,1.1e-05,0.04,0.04,0.012,0,0,0,0,0,0,0,0 +10690000,0.71,0.0022,-0.014,0.71,0.0057,-0.0058,0.03,0.0025,-0.0014,-3.7e+02,-0.0015,-0.0056,4.4e-05,-0.00027,2.9e-05,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0008,0.0008,0.0023,0.15,0.15,0.26,0.14,0.14,0.078,0.00012,0.00012,1.1e-05,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10790000,0.71,0.0022,-0.014,0.71,0.0052,-0.003,0.024,0.0027,-0.00072,-3.7e+02,-0.0014,-0.0056,4.3e-05,-0.00042,0.00015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00077,0.00077,0.0023,0.11,0.11,0.17,0.091,0.091,0.072,0.00011,0.00011,1.1e-05,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10890000,0.71,0.0022,-0.014,0.71,0.004,-0.0017,0.02,0.0031,-0.00092,-3.7e+02,-0.0014,-0.0056,4.3e-05,-0.00042,0.00015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0008,0.0008,0.0023,0.13,0.13,0.16,0.098,0.098,0.075,0.00011,0.00011,1.1e-05,0.04,0.04,0.011,0,0,0,0,0,0,0,0 +10990000,0.71,0.0021,-0.014,0.71,0.0067,0.0034,0.014,0.0047,-0.0022,-3.7e+02,-0.0014,-0.0055,4.1e-05,-0.00082,0.00075,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00073,0.00073,0.0023,0.1,0.1,0.12,0.073,0.073,0.071,0.0001,0.0001,1.1e-05,0.039,0.039,0.011,0,0,0,0,0,0,0,0 +11090000,0.71,0.0021,-0.014,0.71,0.0056,0.0059,0.019,0.0053,-0.0018,-3.7e+02,-0.0014,-0.0055,4.1e-05,-0.00083,0.00075,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00075,0.00075,0.0023,0.13,0.13,0.11,0.08,0.08,0.074,0.0001,0.0001,1.1e-05,0.039,0.039,0.011,0,0,0,0,0,0,0,0 +11190000,0.71,0.002,-0.014,0.71,0.01,0.0083,0.0077,0.0067,-0.0028,-3.7e+02,-0.0013,-0.0055,3.9e-05,-0.00093,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00065,0.00065,0.0023,0.1,0.1,0.084,0.063,0.063,0.069,9.3e-05,9.3e-05,1.1e-05,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11290000,0.71,0.0021,-0.014,0.71,0.01,0.011,0.0074,0.0078,-0.0018,-3.7e+02,-0.0013,-0.0055,3.9e-05,-0.00094,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00067,0.00067,0.0023,0.13,0.13,0.078,0.071,0.071,0.072,9.3e-05,9.3e-05,1.1e-05,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11390000,0.71,0.0021,-0.014,0.71,0.0053,0.0092,0.0017,0.0055,-0.0019,-3.7e+02,-0.0013,-0.0056,4.1e-05,-0.00051,0.00088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00055,0.00055,0.0023,0.1,0.1,0.063,0.058,0.058,0.068,8.2e-05,8.2e-05,1.1e-05,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11490000,0.71,0.0021,-0.014,0.71,0.0028,0.012,0.0025,0.0059,-0.00089,-3.7e+02,-0.0013,-0.0056,4.1e-05,-0.00051,0.00088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00057,0.00057,0.0023,0.13,0.13,0.058,0.066,0.066,0.069,8.2e-05,8.2e-05,1.1e-05,0.038,0.038,0.01,0,0,0,0,0,0,0,0 +11590000,0.71,0.002,-0.014,0.71,-0.0015,0.01,-0.0034,0.0045,-0.0014,-3.7e+02,-0.0014,-0.0056,4.2e-05,-8.9e-05,0.00076,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00047,0.00047,0.0023,0.1,0.1,0.049,0.054,0.054,0.066,7.2e-05,7.2e-05,1.1e-05,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11690000,0.71,0.002,-0.014,0.71,-0.0043,0.013,-0.0079,0.0042,-0.00026,-3.7e+02,-0.0014,-0.0056,4.2e-05,-8e-05,0.00075,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00048,0.00048,0.0023,0.12,0.12,0.046,0.063,0.063,0.066,7.2e-05,7.2e-05,1.1e-05,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11790000,0.71,0.002,-0.014,0.71,-0.01,0.013,-0.0098,0.0018,0.00056,-3.7e+02,-0.0014,-0.0056,4.2e-05,3.1e-05,0.00056,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0004,0.0004,0.0023,0.097,0.097,0.039,0.053,0.053,0.063,6.4e-05,6.4e-05,1.1e-05,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11890000,0.71,0.0021,-0.014,0.71,-0.012,0.014,-0.011,0.00076,0.0019,-3.7e+02,-0.0014,-0.0056,4.2e-05,2.5e-05,0.00056,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00041,0.00041,0.0023,0.12,0.12,0.037,0.061,0.061,0.063,6.4e-05,6.4e-05,1.1e-05,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +11990000,0.71,0.0021,-0.014,0.71,-0.013,0.014,-0.016,-0.0003,0.0023,-3.7e+02,-0.0014,-0.0057,4.2e-05,0.00017,0.00058,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00034,0.00034,0.0023,0.091,0.091,0.033,0.051,0.051,0.061,5.7e-05,5.7e-05,1.1e-05,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12090000,0.71,0.0021,-0.014,0.71,-0.015,0.016,-0.022,-0.0017,0.0038,-3.7e+02,-0.0014,-0.0057,4.2e-05,0.00018,0.00056,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00035,0.00035,0.0023,0.11,0.11,0.031,0.06,0.06,0.061,5.7e-05,5.7e-05,1.1e-05,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12190000,0.71,0.0017,-0.014,0.71,-0.008,0.013,-0.017,0.0015,0.0019,-3.7e+02,-0.0013,-0.0057,4e-05,0.00043,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.0003,0.0003,0.0023,0.085,0.085,0.028,0.051,0.051,0.059,5.2e-05,5.2e-05,1.1e-05,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12290000,0.71,0.0017,-0.014,0.71,-0.011,0.015,-0.016,0.00055,0.0033,-3.7e+02,-0.0013,-0.0057,4e-05,0.0004,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00031,0.00031,0.0023,0.1,0.1,0.028,0.06,0.06,0.059,5.2e-05,5.2e-05,1.1e-05,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12390000,0.71,0.0014,-0.014,0.71,-0.0051,0.011,-0.015,0.003,0.0016,-3.7e+02,-0.0012,-0.0058,3.8e-05,0.00057,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00027,0.00027,0.0023,0.079,0.079,0.026,0.05,0.05,0.057,4.8e-05,4.8e-05,1.1e-05,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12490000,0.71,0.0013,-0.014,0.71,-0.0062,0.013,-0.018,0.0025,0.0029,-3.7e+02,-0.0012,-0.0058,3.8e-05,0.00056,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00028,0.00028,0.0023,0.093,0.093,0.026,0.059,0.059,0.057,4.8e-05,4.8e-05,1.1e-05,0.037,0.037,0.01,0,0,0,0,0,0,0,0 +12590000,0.71,0.0014,-0.014,0.71,-0.014,0.011,-0.023,-0.0028,0.0014,-3.7e+02,-0.0013,-0.0058,4e-05,0.0007,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00025,0.00025,0.0023,0.074,0.074,0.025,0.05,0.05,0.055,4.5e-05,4.5e-05,1.1e-05,0.037,0.037,0.0099,0,0,0,0,0,0,0,0 +12690000,0.71,0.0015,-0.014,0.71,-0.014,0.012,-0.027,-0.0042,0.0026,-3.7e+02,-0.0013,-0.0058,4e-05,0.00073,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00026,0.00026,0.0023,0.085,0.085,0.025,0.058,0.058,0.055,4.5e-05,4.5e-05,1.1e-05,0.037,0.037,0.0098,0,0,0,0,0,0,0,0 +12790000,0.71,0.0015,-0.013,0.71,-0.02,0.0092,-0.03,-0.0076,0.0013,-3.7e+02,-0.0014,-0.0059,4.1e-05,0.00077,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00023,0.00023,0.0023,0.068,0.068,0.024,0.049,0.049,0.053,4.2e-05,4.2e-05,1.1e-05,0.037,0.037,0.0097,0,0,0,0,0,0,0,0 +12890000,0.71,0.0015,-0.013,0.71,-0.021,0.0091,-0.029,-0.0096,0.0022,-3.7e+02,-0.0014,-0.0059,4.1e-05,0.0007,0.0011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00024,0.00024,0.0023,0.079,0.079,0.025,0.058,0.058,0.054,4.2e-05,4.2e-05,1.1e-05,0.037,0.037,0.0096,0,0,0,0,0,0,0,0 +12990000,0.71,0.0011,-0.014,0.71,-0.0083,0.0065,-0.03,-0.001,0.0012,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00068,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00022,0.00022,0.0023,0.064,0.064,0.025,0.049,0.049,0.052,4e-05,4e-05,1.1e-05,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 +13090000,0.71,0.0011,-0.014,0.71,-0.009,0.0067,-0.03,-0.0019,0.0018,-3.7e+02,-0.0012,-0.0059,3.8e-05,0.00065,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00023,0.00023,0.0023,0.073,0.073,0.025,0.058,0.058,0.052,4e-05,4e-05,1.1e-05,0.037,0.037,0.0094,0,0,0,0,0,0,0,0 +13190000,0.71,0.00087,-0.014,0.71,4.2e-05,0.0061,-0.027,0.0044,0.0012,-3.7e+02,-0.0012,-0.0059,3.6e-05,0.0005,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00021,0.00021,0.0023,0.06,0.06,0.025,0.049,0.049,0.051,3.8e-05,3.8e-05,1.1e-05,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 +13290000,0.71,0.00088,-0.014,0.71,-0.0002,0.0069,-0.024,0.0044,0.0018,-3.7e+02,-0.0012,-0.0059,3.6e-05,0.00037,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0023,0.00022,0.00022,0.0023,0.068,0.068,0.027,0.057,0.057,0.051,3.8e-05,3.8e-05,1.1e-05,0.037,0.037,0.0091,0,0,0,0,0,0,0,0 +13390000,0.71,0.00073,-0.014,0.71,0.00063,0.0059,-0.02,0.0033,0.0011,-3.7e+02,-0.0012,-0.0059,3.6e-05,0.0002,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00021,0.00021,0.0023,0.056,0.056,0.026,0.049,0.049,0.05,3.6e-05,3.6e-05,1.1e-05,0.037,0.037,0.0088,0,0,0,0,0,0,0,0 +13490000,0.71,0.00076,-0.014,0.71,0.00013,0.0058,-0.019,0.0034,0.0016,-3.7e+02,-0.0012,-0.0059,3.6e-05,0.00011,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00021,0.00021,0.0023,0.064,0.064,0.028,0.057,0.057,0.05,3.6e-05,3.6e-05,1.1e-05,0.037,0.037,0.0087,0,0,0,0,0,0,0,0 +13590000,0.71,0.0007,-0.014,0.71,0.00039,0.006,-0.021,0.0024,0.001,-3.7e+02,-0.0012,-0.006,3.6e-05,8.8e-05,0.0015,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0002,0.0002,0.0023,0.053,0.053,0.028,0.049,0.049,0.05,3.4e-05,3.4e-05,1.1e-05,0.036,0.036,0.0084,0,0,0,0,0,0,0,0 +13690000,0.71,0.00068,-0.014,0.71,0.0011,0.0078,-0.025,0.0025,0.0017,-3.7e+02,-0.0012,-0.006,3.6e-05,0.00011,0.0014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00021,0.00021,0.0023,0.06,0.06,0.029,0.056,0.056,0.05,3.4e-05,3.4e-05,1.1e-05,0.036,0.036,0.0083,0,0,0,0,0,0,0,0 +13790000,0.71,0.00056,-0.014,0.71,0.0017,0.0036,-0.027,0.0035,-0.00064,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.0001,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0002,0.0002,0.0023,0.051,0.051,0.029,0.048,0.048,0.049,3.3e-05,3.3e-05,1.1e-05,0.036,0.036,0.0079,0,0,0,0,0,0,0,0 +13890000,0.71,0.00053,-0.014,0.71,0.0022,0.0035,-0.031,0.0037,-0.0003,-3.7e+02,-0.0011,-0.006,3.5e-05,-7.2e-05,0.0013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00021,0.00021,0.0023,0.057,0.057,0.03,0.056,0.056,0.05,3.3e-05,3.3e-05,1.1e-05,0.036,0.036,0.0078,0,0,0,0,0,0,0,0 +13990000,0.71,0.00046,-0.014,0.71,0.0024,0.001,-0.03,0.0045,-0.002,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00034,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0002,0.0002,0.0023,0.048,0.048,0.03,0.048,0.048,0.05,3.1e-05,3.1e-05,1.1e-05,0.036,0.036,0.0074,0,0,0,0,0,0,0,0 +14090000,0.71,0.00044,-0.014,0.71,0.0025,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-0.0011,-0.006,3.5e-05,-0.00033,0.0012,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0002,0.0002,0.0023,0.055,0.055,0.031,0.055,0.055,0.05,3.1e-05,3.1e-05,1.1e-05,0.036,0.036,0.0073,0,0,0,0,0,0,0,0 +14190000,0.71,0.00034,-0.014,0.71,0.0059,0.00061,-0.033,0.0068,-0.0017,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00031,0.00088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0002,0.0002,0.0023,0.046,0.046,0.031,0.048,0.048,0.05,2.9e-05,2.9e-05,1.1e-05,0.036,0.036,0.0069,0,0,0,0,0,0,0,0 +14290000,0.71,0.00035,-0.014,0.71,0.0066,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-0.0011,-0.006,3.4e-05,-0.00038,0.00094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0002,0.0002,0.0023,0.052,0.052,0.032,0.055,0.055,0.051,2.9e-05,2.9e-05,1.1e-05,0.036,0.036,0.0067,0,0,0,0,0,0,0,0 +14390000,0.71,0.00027,-0.014,0.71,0.0084,0.0023,-0.034,0.0088,-0.0013,-3.7e+02,-0.0011,-0.006,3.3e-05,-0.00039,0.00068,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00019,0.00019,0.0023,0.045,0.045,0.031,0.048,0.048,0.05,2.8e-05,2.8e-05,1.1e-05,0.036,0.036,0.0063,0,0,0,0,0,0,0,0 +14490000,0.71,0.00025,-0.014,0.71,0.0085,0.0035,-0.037,0.0096,-0.0011,-3.7e+02,-0.0011,-0.006,3.3e-05,-0.00033,0.00064,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0002,0.0002,0.0023,0.05,0.05,0.032,0.055,0.055,0.051,2.8e-05,2.8e-05,1.1e-05,0.036,0.036,0.0062,0,0,0,0,0,0,0,0 +14590000,0.71,0.00024,-0.013,0.71,0.005,0.0019,-0.037,0.006,-0.0025,-3.7e+02,-0.0011,-0.0061,3.4e-05,-0.00071,0.001,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00019,0.00019,0.0023,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-05,2.6e-05,1.1e-05,0.036,0.036,0.0058,0,0,0,0,0,0,0,0 +14690000,0.71,0.0002,-0.013,0.71,0.0063,-0.0011,-0.034,0.0066,-0.0024,-3.7e+02,-0.0011,-0.0061,3.4e-05,-0.00082,0.0011,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0002,0.0002,0.0023,0.049,0.049,0.032,0.054,0.054,0.051,2.6e-05,2.6e-05,1.1e-05,0.036,0.036,0.0056,0,0,0,0,0,0,0,0 +14790000,0.71,0.00023,-0.013,0.71,0.0031,-0.0026,-0.03,0.0038,-0.0034,-3.7e+02,-0.0011,-0.0061,3.6e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00019,0.00019,0.0023,0.042,0.042,0.031,0.047,0.047,0.051,2.5e-05,2.5e-05,1.1e-05,0.036,0.036,0.0053,0,0,0,0,0,0,0,0 +14890000,0.71,0.00022,-0.013,0.71,0.0046,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-0.0011,-0.0061,3.5e-05,-0.0012,0.0016,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.0002,0.00019,0.0023,0.048,0.048,0.031,0.054,0.054,0.052,2.5e-05,2.5e-05,1.1e-05,0.036,0.036,0.0051,0,0,0,0,0,0,0,0 +14990000,0.71,0.00022,-0.013,0.71,0.0034,-0.0019,-0.029,0.0032,-0.0029,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00019,0.00019,0.0024,0.041,0.041,0.03,0.047,0.047,0.051,2.3e-05,2.3e-05,1.1e-05,0.036,0.036,0.0048,0,0,0,0,0,0,0,0 +15090000,0.71,0.00014,-0.013,0.71,0.0038,-0.0021,-0.032,0.0035,-0.0031,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.0018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00019,0.00019,0.0024,0.046,0.046,0.031,0.054,0.054,0.052,2.3e-05,2.3e-05,1.1e-05,0.036,0.036,0.0046,0,0,0,0,0,0,0,0 +15190000,0.71,0.00016,-0.013,0.71,0.0032,-0.00082,-0.029,0.0028,-0.0024,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0012,0.002,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00019,0.00019,0.0024,0.04,0.04,0.03,0.047,0.047,0.052,2.2e-05,2.2e-05,1.1e-05,0.035,0.035,0.0043,0,0,0,0,0,0,0,0 +15290000,0.71,0.00012,-0.013,0.71,0.0038,-0.00067,-0.027,0.0032,-0.0025,-3.7e+02,-0.0012,-0.0061,3.6e-05,-0.0013,0.0021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00019,0.00019,0.0024,0.045,0.045,0.03,0.054,0.054,0.052,2.2e-05,2.2e-05,1.1e-05,0.035,0.035,0.0042,0,0,0,0,0,0,0,0 +15390000,0.71,0.00013,-0.013,0.71,0.003,-0.00033,-0.024,0.00058,-0.002,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00018,0.00018,0.0024,0.04,0.04,0.029,0.047,0.047,0.051,2e-05,2e-05,1.1e-05,0.035,0.035,0.0039,0,0,0,0,0,0,0,0 +15490000,0.71,0.00015,-0.013,0.71,0.0043,-0.00072,-0.024,0.00096,-0.0021,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00019,0.00019,0.0024,0.045,0.045,0.029,0.053,0.053,0.053,2e-05,2e-05,1.1e-05,0.035,0.035,0.0037,0,0,0,0,0,0,0,0 +15590000,0.71,0.00016,-0.013,0.71,0.0024,-0.0007,-0.023,-0.0013,-0.0017,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00018,0.00018,0.0024,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-05,1.9e-05,1.1e-05,0.035,0.035,0.0035,0,0,0,0,0,0,0,0 +15690000,0.71,0.00016,-0.013,0.71,0.0027,-0.00088,-0.023,-0.001,-0.0018,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0013,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00019,0.00018,0.0024,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-05,1.9e-05,1.1e-05,0.035,0.035,0.0033,0,0,0,0,0,0,0,0 +15790000,0.71,0.00013,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00095,-0.0028,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00018,0.00018,0.0024,0.038,0.038,0.027,0.046,0.046,0.051,1.7e-05,1.7e-05,1.1e-05,0.035,0.035,0.0031,0,0,0,0,0,0,0,0 +15890000,0.71,7.8e-05,-0.013,0.71,0.0041,-0.003,-0.024,-0.00055,-0.0031,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0016,0.0025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00018,0.00018,0.0024,0.043,0.043,0.027,0.053,0.053,0.052,1.7e-05,1.7e-05,1.1e-05,0.035,0.035,0.003,0,0,0,0,0,0,0,0 +15990000,0.71,2.2e-05,-0.013,0.71,0.004,-0.0039,-0.019,-0.00063,-0.0039,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.0019,0.0027,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00017,0.00017,0.0024,0.038,0.038,0.026,0.046,0.046,0.051,1.6e-05,1.6e-05,1.1e-05,0.034,0.034,0.0028,0,0,0,0,0,0,0,0 +16090000,0.71,2.5e-05,-0.013,0.71,0.0057,-0.0042,-0.016,-0.00016,-0.0043,-3.7e+02,-0.0012,-0.0061,3.7e-05,-0.002,0.0028,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00018,0.00018,0.0024,0.043,0.043,0.025,0.053,0.053,0.052,1.6e-05,1.6e-05,1.1e-05,0.034,0.034,0.0027,0,0,0,0,0,0,0,0 +16190000,0.71,5.1e-05,-0.013,0.71,0.0057,-0.0034,-0.014,-0.00037,-0.0035,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0019,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00017,0.00017,0.0024,0.037,0.037,0.025,0.046,0.046,0.051,1.5e-05,1.5e-05,1.1e-05,0.034,0.034,0.0025,0,0,0,0,0,0,0,0 +16290000,0.71,7.2e-05,-0.013,0.71,0.0073,-0.0042,-0.016,0.00029,-0.0039,-3.7e+02,-0.0012,-0.0061,3.8e-05,-0.0018,0.003,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00017,0.00017,0.0024,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-05,1.5e-05,1.1e-05,0.034,0.034,0.0024,0,0,0,0,0,0,0,0 +16390000,0.71,6e-05,-0.013,0.71,0.0062,-0.0044,-0.015,-4e-05,-0.0031,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00017,0.00017,0.0024,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-05,1.4e-05,1.1e-05,0.034,0.034,0.0022,0,0,0,0,0,0,0,0 +16490000,0.71,7.8e-05,-0.013,0.71,0.0054,-0.004,-0.018,0.00052,-0.0035,-3.7e+02,-0.0013,-0.0061,3.8e-05,-0.0017,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00017,0.00017,0.0024,0.041,0.041,0.023,0.052,0.052,0.052,1.4e-05,1.4e-05,1.1e-05,0.034,0.034,0.0021,0,0,0,0,0,0,0,0 +16590000,0.71,0.00034,-0.013,0.71,0.0018,-0.0012,-0.018,-0.0024,-9.4e-05,-3.7e+02,-0.0013,-0.006,3.9e-05,-0.001,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00016,0.00016,0.0024,0.036,0.036,0.022,0.046,0.046,0.051,1.2e-05,1.2e-05,1.1e-05,0.033,0.033,0.002,0,0,0,0,0,0,0,0 +16690000,0.71,0.00032,-0.013,0.71,0.002,-0.00078,-0.015,-0.0022,-0.0002,-3.7e+02,-0.0013,-0.006,3.9e-05,-0.0011,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00017,0.00016,0.0024,0.041,0.041,0.022,0.052,0.052,0.051,1.2e-05,1.2e-05,1.1e-05,0.033,0.033,0.0019,0,0,0,0,0,0,0,0 +16790000,0.71,0.00047,-0.013,0.71,-0.0014,0.0014,-0.014,-0.0046,0.0025,-3.7e+02,-0.0013,-0.006,4e-05,-0.00051,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00016,0.00016,0.0024,0.036,0.036,0.021,0.046,0.046,0.05,1.1e-05,1.1e-05,1.1e-05,0.033,0.033,0.0018,0,0,0,0,0,0,0,0 +16890000,0.71,0.00049,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0047,0.0027,-3.7e+02,-0.0013,-0.006,4e-05,-0.00055,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00016,0.00016,0.0024,0.04,0.04,0.021,0.052,0.052,0.051,1.1e-05,1.1e-05,1.1e-05,0.033,0.033,0.0017,0,0,0,0,0,0,0,0 +16990000,0.71,0.00043,-0.013,0.71,-0.0016,0.00029,-0.01,-0.0052,0.00084,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00096,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00015,0.00015,0.0024,0.035,0.035,0.02,0.046,0.046,0.05,1e-05,1e-05,1.1e-05,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 +17090000,0.71,0.00039,-0.013,0.71,-0.0008,0.0012,-0.01,-0.0053,0.00089,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.00095,0.0051,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00016,0.00016,0.0024,0.039,0.039,0.02,0.052,0.052,0.05,1e-05,1e-05,1.1e-05,0.033,0.033,0.0016,0,0,0,0,0,0,0,0 +17190000,0.71,0.00038,-0.013,0.71,-0.00033,0.0012,-0.011,-0.0056,-0.00055,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00015,0.00015,0.0024,0.035,0.035,0.019,0.046,0.046,0.049,9.4e-06,9.4e-06,1.1e-05,0.032,0.032,0.0015,0,0,0,0,0,0,0,0 +17290000,0.71,0.00036,-0.013,0.71,0.0018,0.0022,-0.0066,-0.0056,-0.00039,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0013,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00015,0.00015,0.0024,0.039,0.039,0.019,0.052,0.052,0.049,9.4e-06,9.4e-06,1.1e-05,0.032,0.032,0.0014,0,0,0,0,0,0,0,0 +17390000,0.71,0.00032,-0.013,0.71,0.0024,0.0014,-0.0047,-0.0046,-0.0017,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0024,0.00015,0.00015,0.0024,0.034,0.034,0.018,0.046,0.046,0.048,8.5e-06,8.5e-06,1.1e-05,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 +17490000,0.71,0.00032,-0.013,0.71,0.003,0.00099,-0.003,-0.0044,-0.0015,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0017,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00015,0.00015,0.0024,0.038,0.038,0.018,0.052,0.052,0.049,8.5e-06,8.5e-06,1.1e-05,0.032,0.032,0.0013,0,0,0,0,0,0,0,0 +17590000,0.71,0.00023,-0.013,0.71,0.0042,-0.00018,0.0025,-0.0037,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00014,0.00014,0.0024,0.034,0.034,0.017,0.045,0.045,0.048,7.7e-06,7.7e-06,1.1e-05,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 +17690000,0.71,0.0002,-0.013,0.71,0.0051,0.00052,0.0019,-0.0032,-0.0026,-3.7e+02,-0.0014,-0.0061,4.1e-05,-0.002,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00014,0.00014,0.0024,0.037,0.037,0.017,0.052,0.052,0.048,7.7e-06,7.7e-06,1.1e-05,0.032,0.032,0.0012,0,0,0,0,0,0,0,0 +17790000,0.71,0.00012,-0.013,0.71,0.0077,0.00025,0.00059,-0.0021,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00014,0.00014,0.0024,0.033,0.033,0.016,0.045,0.045,0.048,7e-06,7e-06,1.1e-05,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 +17890000,0.71,0.00013,-0.013,0.71,0.0092,-0.00053,0.00069,-0.0012,-0.0022,-3.7e+02,-0.0013,-0.0061,4.1e-05,-0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00014,0.00014,0.0024,0.037,0.037,0.016,0.052,0.052,0.048,7e-06,7e-06,1.1e-05,0.032,0.032,0.0011,0,0,0,0,0,0,0,0 +17990000,0.71,7e-05,-0.013,0.71,0.011,-0.0022,0.0019,-0.00052,-0.0019,-3.7e+02,-0.0013,-0.0061,4e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00013,0.00013,0.0024,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-06,6.4e-06,1.1e-05,0.031,0.031,0.001,0,0,0,0,0,0,0,0 +18090000,0.71,7.3e-05,-0.013,0.71,0.012,-0.0024,0.0043,0.0006,-0.0022,-3.7e+02,-0.0013,-0.0061,4e-05,-0.0019,0.0048,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00014,0.00014,0.0024,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-06,6.4e-06,1.1e-05,0.031,0.031,0.00097,0,0,0,0,0,0,0,0 +18190000,0.71,4.3e-05,-0.013,0.71,0.012,-0.0014,0.0056,0.0015,-0.0017,-3.7e+02,-0.0013,-0.0061,4e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00013,0.00013,0.0024,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-06,5.8e-06,1.1e-05,0.031,0.031,0.00092,0,0,0,0,0,0,0,0 +18290000,0.71,-1.6e-05,-0.012,0.71,0.012,-0.0019,0.0068,0.0027,-0.0019,-3.7e+02,-0.0013,-0.0061,4e-05,-0.0019,0.0049,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00013,0.00013,0.0024,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-06,5.8e-06,1.1e-05,0.031,0.031,0.00089,0,0,0,0,0,0,0,0 +18390000,0.71,1.2e-06,-0.013,0.71,0.013,-0.00026,0.008,0.0032,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00013,0.00013,0.0024,0.031,0.031,0.014,0.045,0.045,0.046,5.2e-06,5.2e-06,1.1e-05,0.031,0.031,0.00084,0,0,0,0,0,0,0,0 +18490000,0.71,1.7e-05,-0.012,0.71,0.014,0.00015,0.0076,0.0047,-0.0014,-3.7e+02,-0.0013,-0.006,4.1e-05,-0.0018,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00013,0.00013,0.0025,0.034,0.034,0.014,0.051,0.051,0.046,5.2e-06,5.2e-06,1.1e-05,0.031,0.031,0.00082,0,0,0,0,0,0,0,0 +18590000,0.71,2.4e-05,-0.012,0.71,0.013,0.0004,0.0058,0.0035,-0.0012,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00012,0.00012,0.0025,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-06,4.8e-06,1.1e-05,0.031,0.031,0.00078,0,0,0,0,0,0,0,0 +18690000,0.71,-7.3e-06,-0.012,0.71,0.014,-0.0003,0.0039,0.0049,-0.0012,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0054,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00013,0.00013,0.0025,0.033,0.033,0.013,0.051,0.051,0.045,4.8e-06,4.8e-06,1.1e-05,0.031,0.031,0.00075,0,0,0,0,0,0,0,0 +18790000,0.71,2.3e-05,-0.012,0.71,0.012,1.6e-05,0.0035,0.0038,-0.00093,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00012,0.00012,0.0025,0.03,0.03,0.013,0.045,0.045,0.045,4.3e-06,4.3e-06,1.1e-05,0.031,0.031,0.00072,0,0,0,0,0,0,0,0 +18890000,0.71,4.8e-05,-0.012,0.71,0.013,0.00051,0.0042,0.005,-0.00087,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0057,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00012,0.00012,0.0025,0.033,0.033,0.013,0.051,0.051,0.045,4.3e-06,4.3e-06,1.1e-05,0.031,0.031,0.0007,0,0,0,0,0,0,0,0 +18990000,0.71,3.7e-05,-0.012,0.71,0.014,0.0014,0.0028,0.0063,-0.00072,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00012,0.00012,0.0025,0.029,0.029,0.012,0.045,0.045,0.044,3.9e-06,3.9e-06,1.1e-05,0.031,0.031,0.00066,0,0,0,0,0,0,0,0 +19090000,0.71,2.2e-05,-0.012,0.71,0.015,0.002,0.0058,0.0078,-0.00052,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0018,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00012,0.00012,0.0025,0.032,0.032,0.012,0.051,0.051,0.044,3.9e-06,3.9e-06,1.1e-05,0.031,0.031,0.00065,0,0,0,0,0,0,0,0 +19190000,0.71,2.6e-05,-0.012,0.71,0.015,0.002,0.0059,0.0086,-0.00047,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00012,0.00012,0.0025,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-06,3.6e-06,1.1e-05,0.03,0.03,0.00062,0,0,0,0,0,0,0,0 +19290000,0.71,4.8e-05,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00028,-3.7e+02,-0.0014,-0.006,4.1e-05,-0.0019,0.0056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00012,0.00012,0.0025,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-06,3.6e-06,1.1e-05,0.03,0.03,0.0006,0,0,0,0,0,0,0,0 +19390000,0.71,6.1e-05,-0.012,0.71,0.013,0.00036,0.012,0.008,-0.00029,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00011,0.00011,0.0025,0.027,0.027,0.012,0.044,0.044,0.043,3.3e-06,3.3e-06,1.1e-05,0.03,0.03,0.00058,0,0,0,0,0,0,0,0 +19490000,0.71,8.5e-05,-0.012,0.71,0.012,-0.00034,0.0088,0.0092,-0.00029,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00011,0.00011,0.0025,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-06,3.3e-06,1.1e-05,0.03,0.03,0.00056,0,0,0,0,0,0,0,0 +19590000,0.71,0.00014,-0.012,0.71,0.0096,-0.0014,0.0081,0.0075,-0.00031,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00011,0.00011,0.0025,0.027,0.027,0.011,0.044,0.044,0.042,3e-06,3e-06,1.1e-05,0.03,0.03,0.00054,0,0,0,0,0,0,0,0 +19690000,0.71,0.00014,-0.012,0.71,0.01,-0.0036,0.0096,0.0084,-0.00056,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00011,0.00011,0.0025,0.029,0.029,0.011,0.05,0.05,0.042,3e-06,3e-06,1.1e-05,0.03,0.03,0.00052,0,0,0,0,0,0,0,0 +19790000,0.71,0.0002,-0.012,0.71,0.0077,-0.0044,0.01,0.0068,-0.00045,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00011,0.00011,0.0025,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-06,2.7e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19890000,0.71,0.00015,-0.012,0.71,0.0064,-0.0047,0.011,0.0075,-0.00092,-3.7e+02,-0.0014,-0.006,4.2e-05,-0.0019,0.0065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00011,0.00011,0.0025,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-06,2.7e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19990000,0.71,0.00014,-0.012,0.71,0.004,-0.0053,0.014,0.0061,-0.00077,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00011,0.00011,0.0025,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-06,2.5e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20090000,0.71,0.00014,-0.012,0.71,0.0037,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0018,0.0067,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00011,0.00011,0.0025,0.028,0.028,0.01,0.049,0.049,0.042,2.5e-06,2.5e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20190000,0.71,0.00025,-0.012,0.71,0.0014,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00011,0.0001,0.0025,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-06,2.3e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20290000,0.71,0.00021,-0.012,0.71,0.00026,-0.0096,0.015,0.0043,-0.002,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0017,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.00011,0.00011,0.0025,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-06,2.3e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20390000,0.71,0.00023,-0.012,0.71,-0.0022,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-0.0015,-0.006,4.3e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,0.0001,0.0001,0.0025,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-06,2.1e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20490000,0.71,0.00028,-0.012,0.71,-0.0027,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-0.0015,-0.006,4.3e-05,-0.0016,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0001,0.0001,0.0025,0.026,0.026,0.0096,0.049,0.049,0.041,2.1e-06,2.1e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20590000,0.71,0.0003,-0.012,0.71,-0.0023,-0.011,0.013,0.0018,-0.0021,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0001,0.0001,0.0025,0.024,0.024,0.0094,0.044,0.044,0.04,1.9e-06,2e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20690000,0.71,0.00033,-0.012,0.71,-0.0023,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0014,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0001,0.0001,0.0025,0.026,0.026,0.0093,0.049,0.049,0.04,2e-06,2e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20790000,0.71,0.00036,-0.012,0.71,-0.0034,-0.011,0.015,0.0013,-0.0025,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0001,0.0001,0.0025,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-06,1.8e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20890000,0.71,0.00035,-0.012,0.71,-0.0039,-0.014,0.014,0.00098,-0.0038,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.0012,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0001,0.0001,0.0025,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-06,1.8e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +20990000,0.71,0.00035,-0.012,0.71,-0.0041,-0.014,0.015,0.0026,-0.0031,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.9e-05,9.8e-05,0.0025,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-06,1.7e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +21090000,0.71,0.00035,-0.012,0.71,-0.0043,-0.017,0.015,0.0022,-0.0047,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.00098,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,0.0001,9.9e-05,0.0025,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-06,1.7e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +21190000,0.71,0.00039,-0.012,0.71,-0.0035,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.00074,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.8e-05,9.7e-05,0.0025,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-06,1.5e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21290000,0.71,0.00043,-0.012,0.71,-0.0041,-0.018,0.016,0.0033,-0.0055,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.00073,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.9e-05,9.8e-05,0.0026,0.024,0.024,0.0086,0.048,0.048,0.039,1.5e-06,1.5e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21390000,0.71,0.00048,-0.012,0.71,-0.0049,-0.017,0.016,0.0028,-0.0034,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.00036,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.7e-05,9.6e-05,0.0026,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-06,1.4e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21490000,0.71,0.00049,-0.012,0.71,-0.0054,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-0.0014,-0.006,4.3e-05,-0.00036,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.7e-05,9.7e-05,0.0026,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-06,1.4e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21590000,0.71,0.00051,-0.012,0.71,-0.0059,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-0.0014,-0.006,4.4e-05,-9e-06,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.6e-05,9.5e-05,0.0026,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-06,1.3e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21690000,0.71,0.00052,-0.012,0.71,-0.0058,-0.016,0.017,0.0013,-0.0048,-3.7e+02,-0.0014,-0.006,4.4e-05,-1e-05,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.6e-05,9.5e-05,0.0026,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-06,1.3e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21790000,0.71,0.00054,-0.012,0.71,-0.0064,-0.011,0.015,3.7e-05,-0.00076,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.00051,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.5e-05,9.4e-05,0.0026,0.021,0.021,0.0082,0.042,0.042,0.038,1.3e-06,1.3e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21890000,0.71,0.00054,-0.012,0.71,-0.0064,-0.012,0.016,-0.00061,-0.0019,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.00051,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.5e-05,9.4e-05,0.0026,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-06,1.3e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21990000,0.71,0.00059,-0.012,0.71,-0.0069,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.00095,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.4e-05,9.3e-05,0.0026,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-06,1.2e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22090000,0.71,0.0006,-0.012,0.71,-0.0073,-0.0082,0.015,-0.0022,0.00062,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.00094,0.0072,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.4e-05,9.3e-05,0.0026,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-06,1.2e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22190000,0.71,0.00058,-0.012,0.71,-0.0071,-0.0073,0.015,-0.0018,0.00058,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.001,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.3e-05,9.2e-05,0.0026,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-06,1.1e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22290000,0.71,0.00062,-0.012,0.71,-0.0084,-0.008,0.015,-0.0026,-0.0002,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.001,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.3e-05,9.3e-05,0.0026,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-06,1.1e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22390000,0.71,0.00059,-0.012,0.71,-0.009,-0.0075,0.017,-0.0022,-0.00018,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0011,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.2e-05,9.1e-05,0.0026,0.019,0.019,0.0079,0.042,0.042,0.037,1e-06,1e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22490000,0.71,0.0006,-0.012,0.71,-0.0096,-0.0074,0.018,-0.0032,-0.00095,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0011,0.007,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.3e-05,9.2e-05,0.0026,0.021,0.021,0.0079,0.047,0.047,0.037,1e-06,1e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22590000,0.71,0.00058,-0.012,0.71,-0.0093,-0.007,0.017,-0.0034,0.00013,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.1e-05,9.1e-05,0.0026,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-07,9.7e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22690000,0.71,0.00062,-0.012,0.71,-0.011,-0.0067,0.018,-0.0044,-0.00055,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.2e-05,9.1e-05,0.0026,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-07,9.7e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22790000,0.71,0.0006,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00044,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.1e-05,9e-05,0.0026,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-07,9.2e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22890000,0.71,0.00061,-0.012,0.71,-0.013,-0.0051,0.021,-0.0067,-0.00097,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0013,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,9.1e-05,9e-05,0.0026,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-07,9.2e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +22990000,0.71,0.00059,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00086,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,9e-05,8.9e-05,0.0026,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-07,8.7e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23090000,0.71,0.00056,-0.012,0.71,-0.013,-0.0056,0.022,-0.0087,-0.0014,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0014,0.0068,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,9.1e-05,9e-05,0.0026,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-07,8.7e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23190000,0.71,0.00062,-0.012,0.71,-0.015,-0.0065,0.024,-0.012,-0.0013,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0014,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,9e-05,8.9e-05,0.0026,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-07,8.2e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23290000,0.71,0.00056,-0.012,0.71,-0.015,-0.0078,0.024,-0.014,-0.002,-3.7e+02,-0.0014,-0.0059,4.4e-05,0.0014,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,9e-05,8.9e-05,0.0026,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-07,8.2e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23390000,0.71,0.00065,-0.012,0.71,-0.016,-0.008,0.022,-0.016,-0.0018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.9e-05,8.8e-05,0.0026,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-07,7.8e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23490000,0.71,0.003,-0.0096,0.71,-0.023,-0.0088,-0.012,-0.018,-0.0026,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0015,0.0071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.9e-05,8.9e-05,0.0026,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-07,7.8e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0075,-0.044,-0.017,-0.0013,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.8e-05,8.8e-05,0.0026,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-07,7.4e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0017,0.0069,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.8e-05,8.8e-05,0.0026,0.019,0.019,0.0078,0.045,0.045,0.036,7.5e-07,7.4e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23790000,0.71,0.005,0.00064,0.71,-0.089,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.7e-05,8.7e-05,0.0027,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-07,7.1e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.031,-0.0049,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0019,0.0063,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.8e-05,8.7e-05,0.0027,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-07,7.1e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +23990000,0.71,0.00094,-0.01,0.71,-0.11,-0.039,-0.25,-0.034,-0.0081,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.7e-05,8.6e-05,0.0027,0.017,0.017,0.0077,0.041,0.041,0.035,6.8e-07,6.8e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24090000,0.71,0.0022,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0021,0.0059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.7e-05,8.7e-05,0.0027,0.018,0.019,0.0078,0.045,0.045,0.035,6.8e-07,6.8e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0023,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.6e-05,8.6e-05,0.0027,0.017,0.017,0.0077,0.04,0.04,0.035,6.5e-07,6.5e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-0.0014,-0.0059,4.5e-05,0.0023,0.0053,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.6e-05,8.6e-05,0.0027,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-07,6.5e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24390000,0.71,0.0038,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.6e-05,8.5e-05,0.0027,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-07,6.2e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24490000,0.71,0.0047,-0.0018,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-0.0014,-0.0059,4.3e-05,0.002,0.005,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.6e-05,8.6e-05,0.0027,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-07,6.2e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.068,-0.56,-0.081,-0.045,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0019,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.5e-05,8.5e-05,0.0027,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-07,5.9e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-0.0013,-0.0059,4.1e-05,0.0019,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.5e-05,8.5e-05,0.0027,0.018,0.018,0.0078,0.044,0.044,0.035,6e-07,5.9e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24790000,0.71,0.0049,0.0014,0.71,-0.2,-0.094,-0.72,-0.1,-0.063,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0023,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.4e-05,8.4e-05,0.0027,0.017,0.017,0.0078,0.04,0.04,0.035,5.7e-07,5.7e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0023,0.0034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.4e-05,8.4e-05,0.0027,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-07,5.7e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-0.0013,-0.0059,4.5e-05,0.0032,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.3e-05,8.4e-05,0.0027,0.016,0.017,0.0078,0.04,0.04,0.035,5.5e-07,5.5e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-0.0013,-0.0059,4.5e-05,0.0032,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.4e-05,8.4e-05,0.0027,0.018,0.019,0.0079,0.044,0.044,0.035,5.5e-07,5.5e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0029,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.3e-05,8.3e-05,0.0027,0.016,0.017,0.0078,0.04,0.04,0.035,5.3e-07,5.3e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-0.0013,-0.0059,4.2e-05,0.0029,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.3e-05,8.3e-05,0.0027,0.017,0.019,0.0079,0.044,0.044,0.035,5.3e-07,5.3e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0031,-0.00025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.2e-05,8.2e-05,0.0027,0.016,0.017,0.0078,0.04,0.04,0.035,5.1e-07,5.1e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-0.0012,-0.0059,3.9e-05,0.0031,-0.00023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.3e-05,8.3e-05,0.0027,0.017,0.019,0.0079,0.044,0.044,0.035,5.1e-07,5.1e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0028,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.2e-05,8.2e-05,0.0026,0.016,0.018,0.0079,0.04,0.04,0.035,4.9e-07,5e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-0.0012,-0.0059,3.7e-05,0.0028,-0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.3e-05,8.2e-05,0.0027,0.017,0.02,0.0079,0.044,0.044,0.035,5e-07,5e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-0.0012,-0.0059,4e-05,0.0036,-0.0038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.2e-05,8.1e-05,0.0026,0.016,0.019,0.0079,0.04,0.04,0.035,4.8e-07,4.8e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25890000,0.71,0.017,0.028,0.71,-0.6,-0.29,-1.3,-0.4,-0.29,-3.7e+02,-0.0012,-0.0059,4e-05,0.0036,-0.0038,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.3e-05,8.2e-05,0.0026,0.017,0.021,0.008,0.044,0.044,0.035,4.8e-07,4.8e-07,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0032,-0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,8.1e-05,8.1e-05,0.0026,0.016,0.02,0.0079,0.04,0.04,0.035,4.6e-07,4.7e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-0.0011,-0.0059,3.7e-05,0.0032,-0.0055,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0027,8.3e-05,8.1e-05,0.0026,0.017,0.023,0.008,0.044,0.044,0.035,4.7e-07,4.7e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26190000,0.7,0.023,0.044,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-0.0011,-0.0059,4.2e-05,0.0043,-0.0094,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,8.4e-05,8.1e-05,0.0025,0.016,0.022,0.0079,0.039,0.04,0.035,4.5e-07,4.6e-07,1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26290000,0.7,0.024,0.047,0.71,-0.87,-0.43,-1.3,-0.62,-0.46,-3.7e+02,-0.0011,-0.0059,4.2e-05,0.0043,-0.0093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0026,8.5e-05,8.1e-05,0.0025,0.017,0.025,0.008,0.044,0.045,0.035,4.5e-07,4.6e-07,1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-0.001,-0.0059,3.9e-05,0.003,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.2e-05,8e-05,0.0024,0.016,0.024,0.0079,0.039,0.04,0.035,4.4e-07,4.5e-07,1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-0.001,-0.0059,3.9e-05,0.003,-0.011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0025,8.8e-05,8.2e-05,0.0024,0.018,0.027,0.008,0.043,0.045,0.035,4.4e-07,4.5e-07,1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26590000,0.7,0.037,0.075,0.71,-1.1,-0.58,-1.3,-0.82,-0.66,-3.7e+02,-0.00096,-0.0059,5.3e-05,0.0038,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,9.3e-05,8.2e-05,0.0023,0.017,0.027,0.008,0.039,0.041,0.035,4.3e-07,4.5e-07,1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26690000,0.7,0.038,0.078,0.7,-1.3,-0.64,-1.3,-0.94,-0.73,-3.7e+02,-0.00096,-0.0059,5.3e-05,0.0038,-0.015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0023,9.4e-05,8.3e-05,0.0023,0.018,0.032,0.008,0.043,0.046,0.035,4.3e-07,4.5e-07,1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-0.00091,-0.006,2e-05,0.0017,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0022,8.8e-05,8.1e-05,0.0021,0.017,0.031,0.008,0.039,0.041,0.035,4.2e-07,4.4e-07,1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-0.00091,-0.006,2e-05,0.0017,-0.017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0022,0.0001,8.3e-05,0.0021,0.019,0.037,0.0081,0.043,0.046,0.035,4.2e-07,4.5e-07,1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-0.00079,-0.006,1.8e-05,0.0025,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.00011,8.3e-05,0.0019,0.018,0.037,0.008,0.039,0.042,0.035,4.1e-07,4.4e-07,1e-05,0.028,0.028,0.0005,0.0025,0.0023,0.0025,0.0025,0.0025,0.0025,0,0 +27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-0.00079,-0.006,1.8e-05,0.0025,-0.022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0019,0.00011,8.4e-05,0.0019,0.02,0.045,0.0081,0.043,0.047,0.035,4.1e-07,4.4e-07,1e-05,0.028,0.028,0.0005,0.0025,0.0015,0.0025,0.0025,0.0025,0.0025,0,0 +27190000,0.71,0.049,0.11,0.69,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-0.00078,-0.006,0.00017,0.0023,-0.023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0017,9.8e-05,8.1e-05,0.0017,0.02,0.046,0.0081,0.046,0.05,0.035,4.1e-07,4.4e-07,1e-05,0.028,0.028,0.0005,0.0025,0.0011,0.0025,0.0025,0.0025,0.0025,0,0 +27290000,0.71,0.043,0.094,0.69,-2.3,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-0.00077,-0.006,0.00017,0.0023,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0017,9.1e-05,8e-05,0.0017,0.023,0.053,0.0081,0.051,0.057,0.035,4.1e-07,4.4e-07,1e-05,0.028,0.028,0.0005,0.0025,0.0009,0.0025,0.0025,0.0025,0.0025,0,0 +27390000,0.72,0.037,0.077,0.69,-2.4,-1.1,-1.2,-2,-1.4,-3.7e+02,-0.0007,-0.0059,0.00027,0.0031,-0.025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0015,8.3e-05,7.8e-05,0.0015,0.022,0.048,0.0081,0.053,0.059,0.035,4.1e-07,4.4e-07,9.8e-06,0.028,0.028,0.0005,0.0025,0.00074,0.0025,0.0025,0.0025,0.0025,0,0 +27490000,0.72,0.031,0.062,0.69,-2.4,-1.1,-1.2,-2.3,-1.5,-3.7e+02,-0.0007,-0.0059,0.00027,0.003,-0.025,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0015,8e-05,7.8e-05,0.0015,0.023,0.052,0.0082,0.059,0.067,0.035,4.1e-07,4.4e-07,9.8e-06,0.028,0.028,0.0005,0.0025,0.00063,0.0025,0.0025,0.0025,0.0025,0,0 +27590000,0.72,0.026,0.05,0.69,-2.5,-1.1,-1.2,-2.5,-1.6,-3.7e+02,-0.00071,-0.0059,0.00038,0.0019,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.7e-05,7.7e-05,0.0013,0.022,0.045,0.0082,0.061,0.068,0.035,4e-07,4.4e-07,9.7e-06,0.028,0.028,0.0005,0.0025,0.00056,0.0025,0.0025,0.0025,0.0025,0,0 +27690000,0.72,0.026,0.048,0.69,-2.6,-1.1,-1.2,-2.8,-1.7,-3.7e+02,-0.00071,-0.0059,0.00038,0.0018,-0.024,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.7e-05,7.7e-05,0.0013,0.023,0.046,0.0082,0.067,0.077,0.035,4e-07,4.5e-07,9.7e-06,0.028,0.028,0.0005,0.0025,0.00049,0.0025,0.0025,0.0025,0.0025,0,0 +27790000,0.72,0.026,0.05,0.69,-2.6,-1.1,-1.2,-3.1,-1.8,-3.7e+02,-0.00071,-0.0059,0.00044,0.0012,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.7e-05,7.7e-05,0.0012,0.022,0.04,0.0082,0.069,0.078,0.035,4e-07,4.5e-07,9.6e-06,0.028,0.028,0.0005,0.0025,0.00044,0.0025,0.0025,0.0025,0.0025,0,0 +27890000,0.72,0.025,0.048,0.69,-2.6,-1.2,-1.2,-3.3,-1.9,-3.7e+02,-0.0007,-0.0059,0.00044,0.001,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.7e-05,7.7e-05,0.0012,0.023,0.042,0.0083,0.076,0.087,0.035,4e-07,4.5e-07,9.6e-06,0.028,0.028,0.0005,0.0025,0.0004,0.0025,0.0025,0.0025,0.0025,0,0 +27990000,0.73,0.024,0.044,0.69,-2.7,-1.2,-1.2,-3.6,-2,-3.7e+02,-0.00073,-0.006,0.00049,0.00022,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.7e-05,7.6e-05,0.0011,0.022,0.037,0.0083,0.078,0.088,0.035,3.9e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00037,0.0025,0.0025,0.0025,0.0025,0,0 +28090000,0.73,0.03,0.057,0.69,-2.7,-1.2,-1.2,-3.9,-2.1,-3.7e+02,-0.00073,-0.006,0.00049,8e-05,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.7e-05,7.7e-05,0.0011,0.023,0.038,0.0084,0.085,0.097,0.035,4e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00034,0.0025,0.0025,0.0025,0.0025,0,0 +28190000,0.73,0.036,0.071,0.68,-2.8,-1.2,-0.95,-4.2,-2.2,-3.7e+02,-0.00075,-0.006,0.00052,-0.0005,-0.021,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00099,7.8e-05,7.6e-05,0.001,0.022,0.034,0.0084,0.087,0.097,0.035,3.9e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00032,0.0025,0.0025,0.0025,0.0025,0,0 +28290000,0.73,0.028,0.054,0.68,-2.8,-1.2,-0.089,-4.5,-2.4,-3.7e+02,-0.00075,-0.006,0.00052,-0.00068,-0.02,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00099,7.7e-05,7.6e-05,0.001,0.023,0.035,0.0086,0.094,0.11,0.036,3.9e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.0003,0.0025,0.0025,0.0025,0.0025,0,0 +28390000,0.73,0.011,0.023,0.68,-2.8,-1.2,0.77,-4.8,-2.5,-3.7e+02,-0.00075,-0.006,0.00052,-0.00099,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00099,7.9e-05,7.7e-05,0.001,0.023,0.036,0.0087,0.1,0.12,0.036,3.9e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00028,0.0025,0.0025,0.0025,0.0025,0,0 +28490000,0.73,0.0013,0.0048,0.68,-2.7,-1.2,1.1,-5,-2.6,-3.7e+02,-0.00075,-0.006,0.00052,-0.0013,-0.019,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00099,8.2e-05,7.7e-05,0.001,0.025,0.036,0.0088,0.11,0.13,0.036,3.9e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00026,0.0025,0.0025,0.0025,0.0025,0,0 +28590000,0.73,-0.00054,0.0013,0.68,-2.7,-1.2,0.96,-5.3,-2.7,-3.7e+02,-0.00075,-0.006,0.00052,-0.0017,-0.018,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00099,8.3e-05,7.8e-05,0.001,0.025,0.035,0.0089,0.12,0.14,0.036,3.9e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00025,0.0025,0.0025,0.0025,0.0025,0,0 +28690000,0.73,-0.0013,0.00041,0.68,-2.6,-1.2,0.96,-5.6,-2.8,-3.7e+02,-0.00075,-0.006,0.00052,-0.0021,-0.017,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.001,8.3e-05,7.8e-05,0.001,0.027,0.034,0.009,0.13,0.15,0.036,3.9e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00023,0.0025,0.0025,0.0025,0.0025,0,0 +28790000,0.73,-0.0017,0.0002,0.68,-2.6,-1.2,0.97,-5.9,-2.9,-3.7e+02,-0.0008,-0.006,0.00056,-0.0029,-0.023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.3e-05,7.8e-05,0.00097,0.025,0.03,0.0089,0.13,0.15,0.036,3.9e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00022,0.0025,0.0025,0.0025,0.0025,0,0 +28890000,0.73,-0.0017,0.00043,0.68,-2.5,-1.2,0.96,-6.1,-3,-3.7e+02,-0.0008,-0.006,0.00056,-0.0034,-0.022,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00097,8.4e-05,7.8e-05,0.00097,0.026,0.03,0.009,0.14,0.16,0.036,3.9e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00021,0.0025,0.0025,0.0025,0.0025,0,0 +28990000,0.73,-0.0016,0.00088,0.68,-2.5,-1.1,0.95,-6.5,-3.1,-3.7e+02,-0.00088,-0.006,0.00059,-0.0029,-0.03,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8.4e-05,7.8e-05,0.00096,0.025,0.027,0.009,0.14,0.16,0.036,3.8e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.0002,0.0025,0.0025,0.0025,0.0025,0,0 +29090000,0.73,-0.0014,0.0013,0.68,-2.4,-1.1,0.94,-6.7,-3.3,-3.7e+02,-0.00088,-0.006,0.00059,-0.0034,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8.4e-05,7.8e-05,0.00096,0.026,0.027,0.009,0.15,0.17,0.036,3.9e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00019,0.0025,0.0025,0.0025,0.0025,0,0 +29190000,0.73,-0.0012,0.0017,0.68,-2.4,-1.1,0.94,-7,-3.4,-3.7e+02,-0.00092,-0.006,0.0006,-0.0035,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8.4e-05,7.8e-05,0.00096,0.025,0.025,0.009,0.15,0.17,0.036,3.8e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 +29290000,0.73,-0.00088,0.0025,0.68,-2.3,-1.1,0.96,-7.3,-3.5,-3.7e+02,-0.00092,-0.006,0.0006,-0.0041,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8.4e-05,7.8e-05,0.00096,0.026,0.026,0.0091,0.16,0.18,0.036,3.8e-07,4.5e-07,9.5e-06,0.028,0.028,0.0005,0.0025,0.00018,0.0025,0.0025,0.0025,0.0025,0,0 +29390000,0.73,-0.00029,0.004,0.68,-2.3,-1.1,0.97,-7.6,-3.6,-3.7e+02,-0.00098,-0.006,0.0006,-0.0037,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8.4e-05,7.8e-05,0.00096,0.024,0.025,0.009,0.16,0.18,0.036,3.7e-07,4.4e-07,9.5e-06,0.028,0.027,0.0005,0.0025,0.00017,0.0025,0.0025,0.0025,0.0025,0,0 +29490000,0.73,0.00024,0.0051,0.68,-2.2,-1.1,0.97,-7.8,-3.7,-3.7e+02,-0.00098,-0.006,0.0006,-0.0042,-0.032,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8.4e-05,7.8e-05,0.00096,0.026,0.026,0.0091,0.17,0.19,0.037,3.8e-07,4.4e-07,9.5e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 +29590000,0.73,0.00067,0.0062,0.68,-2.2,-1.1,0.96,-8.1,-3.8,-3.7e+02,-0.001,-0.006,0.00057,-0.0054,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.4e-05,7.8e-05,0.00097,0.025,0.025,0.009,0.17,0.19,0.036,3.7e-07,4.4e-07,9.5e-06,0.028,0.027,0.0005,0.0025,0.00016,0.0025,0.0025,0.0025,0.0025,0,0 +29690000,0.73,0.00097,0.0069,0.68,-2.2,-1.1,0.95,-8.3,-3.9,-3.7e+02,-0.001,-0.006,0.00057,-0.0059,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.4e-05,7.8e-05,0.00097,0.026,0.027,0.0091,0.18,0.2,0.036,3.7e-07,4.4e-07,9.5e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 +29790000,0.73,0.0013,0.0073,0.68,-2.2,-1.1,0.94,-8.6,-4,-3.7e+02,-0.0011,-0.006,0.00054,-0.0062,-0.033,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.4e-05,7.8e-05,0.00097,0.025,0.026,0.0091,0.18,0.2,0.037,3.6e-07,4.3e-07,9.4e-06,0.028,0.027,0.0005,0.0025,0.00015,0.0025,0.0025,0.0025,0.0025,0,0 +29890000,0.73,0.0014,0.0076,0.68,-2.1,-1.1,0.92,-8.8,-4.1,-3.7e+02,-0.0011,-0.006,0.00054,-0.007,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.4e-05,7.8e-05,0.00098,0.026,0.027,0.0091,0.19,0.21,0.037,3.6e-07,4.3e-07,9.4e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 +29990000,0.73,0.0016,0.0077,0.68,-2.1,-1.1,0.91,-9,-4.2,-3.7e+02,-0.0011,-0.006,0.0005,-0.0083,-0.031,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.4e-05,7.8e-05,0.00098,0.025,0.026,0.009,0.19,0.21,0.036,3.6e-07,4.2e-07,9.4e-06,0.028,0.027,0.0005,0.0025,0.00014,0.0025,0.0025,0.0025,0.0025,0,0 +30090000,0.73,0.0016,0.0077,0.68,-2.1,-1.1,0.89,-9.2,-4.3,-3.7e+02,-0.0011,-0.006,0.0005,-0.0089,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.5e-05,7.8e-05,0.00098,0.026,0.028,0.0091,0.2,0.22,0.036,3.6e-07,4.2e-07,9.4e-06,0.028,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30190000,0.73,0.0017,0.0075,0.68,-2,-1.1,0.88,-9.5,-4.4,-3.7e+02,-0.0011,-0.0059,0.00044,-0.0092,-0.03,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.5e-05,7.8e-05,0.00098,0.025,0.027,0.009,0.2,0.22,0.037,3.5e-07,4.1e-07,9.4e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30290000,0.73,0.0016,0.0073,0.68,-2,-1.1,0.87,-9.7,-4.5,-3.7e+02,-0.0011,-0.0059,0.00044,-0.0095,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.5e-05,7.8e-05,0.00098,0.026,0.029,0.0091,0.21,0.23,0.037,3.5e-07,4.1e-07,9.4e-06,0.027,0.027,0.0005,0.0025,0.00013,0.0025,0.0025,0.0025,0.0025,0,0 +30390000,0.73,0.0017,0.0071,0.68,-2,-1.1,0.85,-9.9,-4.6,-3.7e+02,-0.0012,-0.0059,0.0004,-0.01,-0.029,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.5e-05,7.8e-05,0.00097,0.025,0.028,0.009,0.21,0.23,0.036,3.5e-07,4e-07,9.3e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 +30490000,0.73,0.0015,0.0069,0.68,-2,-1.1,0.84,-10,-4.7,-3.7e+02,-0.0012,-0.0059,0.0004,-0.011,-0.028,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00096,8.5e-05,7.8e-05,0.00097,0.026,0.03,0.0091,0.22,0.24,0.037,3.5e-07,4e-07,9.3e-06,0.027,0.027,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 +30590000,0.73,0.0015,0.0065,0.68,-1.9,-1,0.8,-10,-4.8,-3.7e+02,-0.0012,-0.0059,0.00034,-0.011,-0.028,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8.5e-05,7.8e-05,0.00096,0.025,0.029,0.009,0.22,0.24,0.037,3.4e-07,3.9e-07,9.3e-06,0.027,0.026,0.0005,0.0025,0.00012,0.0025,0.0025,0.0025,0.0025,0,0 +30690000,0.73,0.0014,0.0062,0.68,-1.9,-1,0.79,-11,-4.9,-3.7e+02,-0.0012,-0.0059,0.00034,-0.011,-0.026,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8.5e-05,7.8e-05,0.00097,0.026,0.031,0.009,0.23,0.25,0.037,3.4e-07,3.9e-07,9.3e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30790000,0.73,0.0014,0.0058,0.68,-1.9,-1,0.78,-11,-5,-3.7e+02,-0.0012,-0.0059,0.00028,-0.011,-0.026,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00093,8.5e-05,7.8e-05,0.00095,0.025,0.03,0.0089,0.23,0.25,0.037,3.4e-07,3.8e-07,9.2e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30890000,0.73,0.0012,0.0054,0.68,-1.9,-1,0.77,-11,-5.1,-3.7e+02,-0.0012,-0.0059,0.00028,-0.012,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00094,8.6e-05,7.8e-05,0.00095,0.026,0.032,0.009,0.24,0.26,0.037,3.4e-07,3.8e-07,9.2e-06,0.027,0.026,0.0005,0.0025,0.00011,0.0025,0.0025,0.0025,0.0025,0,0 +30990000,0.73,0.0013,0.0048,0.68,-1.8,-1,0.76,-11,-5.2,-3.7e+02,-0.0013,-0.0059,0.00021,-0.011,-0.025,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00092,8.5e-05,7.7e-05,0.00094,0.025,0.031,0.0089,0.24,0.26,0.036,3.3e-07,3.7e-07,9.1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31090000,0.73,0.0011,0.0044,0.68,-1.8,-1,0.75,-11,-5.3,-3.7e+02,-0.0013,-0.0059,0.00021,-0.012,-0.023,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00092,8.6e-05,7.7e-05,0.00094,0.027,0.033,0.0089,0.25,0.27,0.037,3.3e-07,3.7e-07,9.1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31190000,0.73,0.0011,0.0041,0.68,-1.8,-1,0.74,-12,-5.4,-3.7e+02,-0.0013,-0.0059,0.00016,-0.013,-0.021,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.0009,8.5e-05,7.7e-05,0.00092,0.025,0.031,0.0088,0.25,0.27,0.037,3.3e-07,3.6e-07,9.1e-06,0.027,0.026,0.0005,0.0025,0.0001,0.0025,0.0025,0.0025,0.0025,0,0 +31290000,0.73,0.00085,0.0036,0.68,-1.8,-1,0.74,-12,-5.5,-3.7e+02,-0.0013,-0.0059,0.00016,-0.013,-0.019,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00091,8.6e-05,7.7e-05,0.00092,0.027,0.033,0.0089,0.26,0.28,0.037,3.3e-07,3.6e-07,9.1e-06,0.027,0.026,0.0005,0.0025,9.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31390000,0.73,0.00083,0.003,0.68,-1.7,-0.99,0.73,-12,-5.5,-3.7e+02,-0.0013,-0.0058,0.00011,-0.013,-0.018,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00088,8.5e-05,7.7e-05,0.0009,0.025,0.032,0.0088,0.25,0.28,0.036,3.2e-07,3.5e-07,9e-06,0.027,0.026,0.0005,0.0025,9.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31490000,0.73,0.0006,0.0024,0.68,-1.7,-0.98,0.73,-12,-5.6,-3.7e+02,-0.0013,-0.0058,0.00011,-0.014,-0.017,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00089,8.6e-05,7.7e-05,0.0009,0.027,0.034,0.0088,0.27,0.29,0.037,3.2e-07,3.5e-07,9e-06,0.027,0.026,0.0005,0.0025,9.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +31590000,0.73,0.00067,0.002,0.69,-1.7,-0.96,0.72,-12,-5.7,-3.7e+02,-0.0013,-0.0058,4.4e-05,-0.014,-0.015,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00086,8.5e-05,7.6e-05,0.00088,0.025,0.032,0.0087,0.26,0.29,0.037,3.2e-07,3.4e-07,8.9e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31690000,0.73,0.0004,0.0014,0.69,-1.7,-0.96,0.73,-13,-5.8,-3.7e+02,-0.0013,-0.0058,4.3e-05,-0.015,-0.014,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00087,8.5e-05,7.6e-05,0.00088,0.027,0.034,0.0087,0.28,0.3,0.037,3.2e-07,3.4e-07,8.9e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31790000,0.73,0.00033,0.00067,0.69,-1.6,-0.94,0.73,-13,-5.9,-3.7e+02,-0.0014,-0.0058,-1.8e-05,-0.014,-0.012,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00084,8.5e-05,7.6e-05,0.00086,0.025,0.032,0.0087,0.27,0.3,0.037,3.1e-07,3.3e-07,8.9e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31890000,0.73,6.3e-05,-1.5e-05,0.69,-1.6,-0.94,0.72,-13,-6,-3.7e+02,-0.0014,-0.0058,-1.9e-05,-0.015,-0.011,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00084,8.5e-05,7.6e-05,0.00086,0.027,0.034,0.0087,0.29,0.31,0.037,3.1e-07,3.3e-07,8.9e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +31990000,0.73,4.6e-05,-0.00053,0.69,-1.6,-0.92,0.71,-13,-6.1,-3.7e+02,-0.0014,-0.0058,-7.5e-05,-0.015,-0.0091,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00082,8.5e-05,7.6e-05,0.00083,0.025,0.032,0.0086,0.28,0.31,0.036,3.1e-07,3.2e-07,8.8e-06,0.027,0.026,0.0005,0,0,0,0,0,0,0,0 +32090000,0.73,-0.00026,-0.0012,0.69,-1.5,-0.91,0.72,-13,-6.2,-3.7e+02,-0.0014,-0.0058,-7.5e-05,-0.016,-0.0076,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00082,8.5e-05,7.6e-05,0.00084,0.027,0.035,0.0087,0.3,0.32,0.037,3.1e-07,3.3e-07,8.8e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32190000,0.72,-0.00036,-0.0021,0.69,-1.5,-0.9,0.72,-13,-6.2,-3.7e+02,-0.0014,-0.0058,-0.00013,-0.016,-0.0055,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.0008,8.5e-05,7.5e-05,0.00081,0.025,0.032,0.0086,0.29,0.32,0.036,3e-07,3.2e-07,8.8e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32290000,0.72,-0.00061,-0.0028,0.69,-1.5,-0.89,0.71,-14,-6.3,-3.7e+02,-0.0014,-0.0058,-0.00013,-0.017,-0.0039,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.0008,8.5e-05,7.5e-05,0.00081,0.027,0.035,0.0086,0.3,0.33,0.037,3e-07,3.2e-07,8.8e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32390000,0.72,-0.00071,-0.0035,0.69,-1.5,-0.87,0.71,-14,-6.4,-3.7e+02,-0.0014,-0.0058,-0.00017,-0.017,-0.0031,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00077,8.4e-05,7.5e-05,0.00079,0.025,0.032,0.0085,0.3,0.33,0.037,3e-07,3.1e-07,8.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32490000,0.72,-0.00084,-0.0037,0.69,-1.4,-0.87,0.72,-14,-6.5,-3.7e+02,-0.0014,-0.0058,-0.00017,-0.017,-0.0019,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00078,8.5e-05,7.5e-05,0.00079,0.027,0.034,0.0085,0.31,0.34,0.037,3e-07,3.1e-07,8.7e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32590000,0.72,-0.00073,-0.004,0.69,-1.4,-0.85,0.72,-14,-6.6,-3.7e+02,-0.0014,-0.0057,-0.0002,-0.017,-0.001,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00075,8.4e-05,7.5e-05,0.00076,0.025,0.032,0.0084,0.31,0.34,0.036,2.9e-07,3e-07,8.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32690000,0.72,-0.00078,-0.0041,0.69,-1.4,-0.84,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-0.0002,-0.017,-0.00046,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00075,8.4e-05,7.5e-05,0.00077,0.027,0.034,0.0085,0.32,0.35,0.036,3e-07,3.1e-07,8.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32790000,0.72,-0.00064,-0.004,0.69,-1.3,-0.83,0.71,-14,-6.7,-3.7e+02,-0.0014,-0.0057,-0.00024,-0.017,0.0005,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00073,8.4e-05,7.4e-05,0.00074,0.025,0.032,0.0084,0.32,0.35,0.036,2.9e-07,3e-07,8.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32890000,0.72,-0.00056,-0.004,0.69,-1.3,-0.82,0.71,-14,-6.8,-3.7e+02,-0.0014,-0.0057,-0.00024,-0.018,0.0016,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00073,8.4e-05,7.4e-05,0.00075,0.027,0.034,0.0084,0.33,0.36,0.036,2.9e-07,3e-07,8.6e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +32990000,0.72,-0.00033,-0.004,0.69,-1.3,-0.81,0.7,-15,-6.9,-3.7e+02,-0.0014,-0.0057,-0.00027,-0.018,0.003,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00071,8.3e-05,7.4e-05,0.00072,0.025,0.032,0.0083,0.33,0.36,0.036,2.9e-07,2.9e-07,8.5e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33090000,0.72,-0.00036,-0.004,0.69,-1.3,-0.8,0.7,-15,-7,-3.7e+02,-0.0014,-0.0057,-0.00027,-0.018,0.0036,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00071,8.3e-05,7.4e-05,0.00072,0.027,0.034,0.0084,0.34,0.37,0.036,2.9e-07,2.9e-07,8.5e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33190000,0.72,0.0031,-0.0031,0.7,-1.2,-0.78,0.64,-15,-7,-3.7e+02,-0.0015,-0.0057,-0.0003,-0.018,0.0044,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0007,8.3e-05,7.4e-05,0.0007,0.025,0.032,0.0083,0.34,0.37,0.036,2.8e-07,2.9e-07,8.5e-06,0.027,0.025,0.0005,0,0,0,0,0,0,0,0 +33290000,0.67,0.015,-0.0024,0.75,-1.2,-0.77,0.62,-15,-7.1,-3.7e+02,-0.0015,-0.0057,-0.0003,-0.018,0.0048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0008,8.2e-05,7.5e-05,0.0006,0.027,0.033,0.0083,0.35,0.38,0.036,2.9e-07,2.9e-07,8.5e-06,0.027,0.025,0.0005,0.0025,9.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33390000,0.56,0.013,-0.0027,0.83,-1.2,-0.75,0.81,-15,-7.2,-3.7e+02,-0.0015,-0.0057,-0.00031,-0.018,0.0058,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00095,8.1e-05,7.5e-05,0.00042,0.025,0.03,0.0083,0.35,0.38,0.036,2.8e-07,2.9e-07,8.5e-06,0.027,0.025,0.0005,0.0025,9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33490000,0.43,0.0066,-6.1e-05,0.9,-1.2,-0.75,0.83,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00031,-0.019,0.0059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0011,7.9e-05,7.7e-05,0.00025,0.027,0.032,0.0081,0.36,0.39,0.036,2.8e-07,2.9e-07,8.5e-06,0.027,0.025,0.0005,0.0025,8.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33590000,0.27,0.00061,-0.0025,0.96,-1.2,-0.74,0.79,-15,-7.3,-3.7e+02,-0.0015,-0.0057,-0.00034,-0.019,0.0059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.7e-05,7.9e-05,0.0001,0.026,0.031,0.0078,0.36,0.39,0.036,2.8e-07,2.8e-07,8.4e-06,0.027,0.025,0.0005,0.0025,8.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33690000,0.1,-0.0028,-0.0055,0.99,-1.1,-0.74,0.8,-15,-7.4,-3.7e+02,-0.0015,-0.0057,-0.00034,-0.019,0.0059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.6e-05,8.1e-05,2.7e-05,0.028,0.035,0.0076,0.37,0.4,0.036,2.8e-07,2.8e-07,8.4e-06,0.027,0.025,0.0005,0.0025,8.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33790000,-0.068,-0.0044,-0.0073,1,-1.1,-0.72,0.78,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00037,-0.019,0.0059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0013,7.3e-05,8e-05,2.5e-05,0.028,0.034,0.0074,0.36,0.4,0.036,2.7e-07,2.8e-07,8.4e-06,0.027,0.025,0.0005,0.0025,8.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33890000,-0.24,-0.0056,-0.0079,0.97,-1,-0.7,0.77,-16,-7.5,-3.7e+02,-0.0015,-0.0057,-0.00037,-0.019,0.0059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0012,7.2e-05,8.2e-05,9.5e-05,0.032,0.039,0.0072,0.38,0.41,0.036,2.8e-07,2.8e-07,8.4e-06,0.027,0.025,0.0005,0.0025,8.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +33990000,-0.38,-0.0039,-0.012,0.92,-0.96,-0.65,0.74,-16,-7.6,-3.7e+02,-0.0015,-0.0057,-0.00041,-0.019,0.0059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.0011,6.9e-05,7.8e-05,0.00021,0.032,0.039,0.007,0.37,0.41,0.035,2.7e-07,2.7e-07,8.4e-06,0.027,0.025,0.0005,0.0025,8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34090000,-0.49,-0.0029,-0.013,0.87,-0.91,-0.61,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00041,-0.019,0.0059,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00097,6.9e-05,7.8e-05,0.00033,0.037,0.044,0.0069,0.39,0.42,0.036,2.7e-07,2.8e-07,8.4e-06,0.027,0.025,0.0005,0.0025,7.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34190000,-0.56,-0.0022,-0.012,0.83,-0.89,-0.56,0.74,-16,-7.7,-3.7e+02,-0.0015,-0.0057,-0.00044,-0.021,0.0081,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00085,6.5e-05,7.3e-05,0.00041,0.037,0.043,0.0067,0.38,0.42,0.035,2.7e-07,2.7e-07,8.3e-06,0.027,0.025,0.0005,0.0025,7.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34290000,-0.6,-0.0032,-0.0091,0.8,-0.84,-0.51,0.74,-16,-7.8,-3.7e+02,-0.0015,-0.0057,-0.00044,-0.021,0.0081,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00079,6.6e-05,7.2e-05,0.00048,0.043,0.05,0.0066,0.4,0.43,0.035,2.7e-07,2.7e-07,8.3e-06,0.027,0.025,0.0005,0.0025,7.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34390000,-0.63,-0.0032,-0.0067,0.78,-0.83,-0.47,0.74,-16,-7.8,-3.7e+02,-0.0016,-0.0057,-0.00046,-0.026,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00073,6.1e-05,6.7e-05,0.00051,0.043,0.048,0.0065,0.39,0.43,0.035,2.7e-07,2.7e-07,8.3e-06,0.027,0.025,0.0005,0.0025,7.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34490000,-0.65,-0.0042,-0.0045,0.76,-0.78,-0.42,0.74,-16,-7.9,-3.7e+02,-0.0016,-0.0057,-0.00046,-0.026,0.013,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00071,6.1e-05,6.6e-05,0.00053,0.05,0.056,0.0064,0.4,0.44,0.035,2.7e-07,2.7e-07,8.3e-06,0.027,0.025,0.0005,0.0025,7.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34590000,-0.66,-0.0035,-0.0035,0.75,-0.78,-0.4,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00047,-0.036,0.023,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00068,5.6e-05,6e-05,0.00054,0.048,0.052,0.0063,0.4,0.44,0.034,2.7e-07,2.7e-07,8.3e-06,0.026,0.024,0.0005,0.0025,7.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34690000,-0.66,-0.0039,-0.0027,0.75,-0.72,-0.36,0.73,-17,-8,-3.7e+02,-0.0016,-0.0057,-0.00047,-0.036,0.023,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00068,5.6e-05,6e-05,0.00055,0.055,0.06,0.0063,0.41,0.45,0.034,2.7e-07,2.7e-07,8.3e-06,0.026,0.024,0.0005,0.0025,7.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34790000,-0.67,-0.0027,-0.0025,0.75,-0.73,-0.35,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00048,-0.048,0.034,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00066,5.1e-05,5.5e-05,0.00055,0.052,0.056,0.0062,0.41,0.45,0.034,2.6e-07,2.7e-07,8.3e-06,0.026,0.024,0.0005,0.0025,7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34890000,-0.67,-0.0027,-0.0024,0.74,-0.68,-0.32,0.72,-17,-8.1,-3.7e+02,-0.0016,-0.0057,-0.00048,-0.048,0.034,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00066,5.1e-05,5.5e-05,0.00055,0.059,0.064,0.0062,0.42,0.46,0.034,2.7e-07,2.7e-07,8.3e-06,0.026,0.024,0.0005,0.0025,6.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +34990000,-0.67,-0.009,-0.0051,0.74,0.34,0.28,-0.13,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00049,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00065,4.7e-05,5e-05,0.00055,0.06,0.071,0.0068,0.42,0.46,0.034,2.7e-07,2.7e-07,8.2e-06,0.025,0.023,0.0005,0.0025,6.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35090000,-0.67,-0.009,-0.0051,0.74,0.46,0.3,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00048,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00065,4.7e-05,5e-05,0.00055,0.066,0.077,0.0068,0.43,0.46,0.034,2.7e-07,2.7e-07,8.2e-06,0.025,0.023,0.0005,0.0025,6.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35190000,-0.67,-0.009,-0.0052,0.74,0.49,0.33,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00048,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00065,4.7e-05,5e-05,0.00056,0.071,0.083,0.0067,0.44,0.47,0.034,2.7e-07,2.7e-07,8.2e-06,0.025,0.023,0.0005,0.0025,6.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35290000,-0.67,-0.0091,-0.0052,0.74,0.51,0.37,-0.18,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00048,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00066,4.7e-05,5e-05,0.00056,0.077,0.088,0.0066,0.46,0.48,0.033,2.7e-07,2.7e-07,8.2e-06,0.025,0.023,0.0005,0.0025,6.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35390000,-0.67,-0.0092,-0.0052,0.74,0.53,0.4,-0.18,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00048,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00066,4.7e-05,5e-05,0.00056,0.083,0.094,0.0066,0.47,0.49,0.034,2.7e-07,2.7e-07,8.2e-06,0.025,0.023,0.0005,0.0025,6.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35490000,-0.67,-0.0092,-0.0052,0.74,0.56,0.44,-0.18,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00048,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00066,4.6e-05,5e-05,0.00056,0.089,0.1,0.0065,0.49,0.51,0.034,2.7e-07,2.7e-07,8.2e-06,0.025,0.023,0.0005,0.0025,6.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35590000,-0.67,-0.0061,-0.0053,0.74,0.44,0.36,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00045,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00063,3.9e-05,4.3e-05,0.00053,0.07,0.076,0.0062,0.48,0.5,0.033,2.7e-07,2.7e-07,8.2e-06,0.025,0.023,0.0005,0.0025,6.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35690000,-0.67,-0.0061,-0.0053,0.74,0.46,0.39,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00045,-0.062,0.048,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00063,3.9e-05,4.3e-05,0.00053,0.075,0.082,0.0062,0.5,0.52,0.033,2.7e-07,2.7e-07,8.2e-06,0.025,0.023,0.0005,0.0025,6.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35790000,-0.67,-0.0038,-0.0053,0.74,0.38,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00043,-0.064,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00061,3.4e-05,3.8e-05,0.00052,0.062,0.066,0.0059,0.49,0.51,0.033,2.7e-07,2.8e-07,8.1e-06,0.025,0.023,0.0005,0.0025,6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35890000,-0.67,-0.0038,-0.0053,0.74,0.4,0.36,-0.19,-17,-8,-3.7e+02,-0.0017,-0.0057,-0.00042,-0.064,0.05,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00062,3.4e-05,3.8e-05,0.00052,0.068,0.071,0.0059,0.5,0.53,0.033,2.7e-07,2.8e-07,8.1e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +35990000,-0.67,-0.0019,-0.0052,0.74,0.33,0.31,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00041,-0.072,0.057,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00061,3e-05,3.5e-05,0.00051,0.058,0.06,0.0057,0.5,0.52,0.033,2.7e-07,2.8e-07,8.1e-06,0.025,0.023,0.0005,0.0025,5.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36090000,-0.67,-0.002,-0.0052,0.74,0.34,0.33,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.00041,-0.072,0.057,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00061,3e-05,3.5e-05,0.00051,0.063,0.066,0.0057,0.51,0.53,0.032,2.7e-07,2.8e-07,8.1e-06,0.025,0.023,0.0005,0.0025,5.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36190000,-0.67,-0.00046,-0.0051,0.74,0.28,0.28,-0.19,-17,-8.1,-3.7e+02,-0.0017,-0.0057,-0.0004,-0.083,0.066,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00061,2.7e-05,3.2e-05,0.00051,0.055,0.057,0.0056,0.51,0.53,0.032,2.7e-07,2.8e-07,8.1e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36290000,-0.67,-0.00058,-0.005,0.74,0.29,0.31,-0.18,-17,-8.1,-3.7e+02,-0.0017,-0.0058,-0.0004,-0.083,0.066,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00061,2.7e-05,3.2e-05,0.00051,0.061,0.063,0.0056,0.52,0.54,0.032,2.8e-07,2.8e-07,8.1e-06,0.024,0.023,0.0005,0.0025,5.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36390000,-0.67,0.00053,-0.0049,0.74,0.24,0.26,-0.18,-17,-8.1,-3.7e+02,-0.0018,-0.0058,-0.00039,-0.097,0.076,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00061,2.4e-05,2.9e-05,0.00051,0.054,0.055,0.0055,0.51,0.54,0.032,2.8e-07,2.8e-07,8.1e-06,0.024,0.022,0.0005,0.0025,5.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36490000,-0.67,0.00043,-0.0049,0.74,0.25,0.28,-0.18,-17,-8.1,-3.7e+02,-0.0018,-0.0058,-0.00039,-0.097,0.076,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00061,2.4e-05,3e-05,0.00052,0.059,0.061,0.0055,0.53,0.55,0.032,2.8e-07,2.8e-07,8.1e-06,0.024,0.022,0.0005,0.0025,5.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36590000,-0.67,0.0013,-0.0047,0.74,0.21,0.24,-0.18,-17,-8.1,-3.7e+02,-0.0018,-0.0058,-0.0004,-0.11,0.086,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00061,2.2e-05,2.8e-05,0.00052,0.053,0.054,0.0055,0.52,0.55,0.031,2.8e-07,2.8e-07,8.1e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36690000,-0.67,0.0012,-0.0046,0.74,0.21,0.26,-0.17,-17,-8.1,-3.7e+02,-0.0018,-0.0058,-0.00039,-0.11,0.086,-0.092,0.37,0.0037,0.025,0,0,0,0,0,0.00062,2.2e-05,2.8e-05,0.00052,0.058,0.06,0.0055,0.54,0.56,0.031,2.8e-07,2.8e-07,8.1e-06,0.023,0.022,0.0005,0.0025,5.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36790000,-0.67,0.0019,-0.0045,0.74,0.18,0.22,-0.17,-17,-8.1,-3.7e+02,-0.0018,-0.0058,-0.0004,-0.12,0.096,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00062,2.1e-05,2.6e-05,0.00052,0.052,0.053,0.0055,0.53,0.56,0.031,2.8e-07,2.8e-07,8.1e-06,0.022,0.021,0.0005,0.0025,5.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36890000,-0.67,0.0018,-0.0045,0.74,0.18,0.24,-0.16,-17,-8.1,-3.7e+02,-0.0018,-0.0058,-0.0004,-0.13,0.096,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00062,2.1e-05,2.6e-05,0.00052,0.057,0.059,0.0056,0.55,0.57,0.031,2.8e-07,2.9e-07,8.1e-06,0.022,0.021,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +36990000,-0.67,0.0023,-0.0042,0.74,0.15,0.2,-0.16,-17,-8.1,-3.7e+02,-0.0018,-0.0058,-0.00041,-0.14,0.1,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00062,2e-05,2.5e-05,0.00053,0.051,0.052,0.0056,0.54,0.57,0.031,2.8e-07,2.9e-07,8.1e-06,0.022,0.02,0.0005,0.0025,5.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37090000,-0.67,0.0022,-0.0042,0.74,0.15,0.21,-0.15,-17,-8.1,-3.7e+02,-0.0018,-0.0058,-0.0004,-0.14,0.1,-0.093,0.37,0.0037,0.025,0,0,0,0,0,0.00063,2e-05,2.5e-05,0.00053,0.056,0.058,0.0057,0.56,0.58,0.031,2.8e-07,2.9e-07,8.1e-06,0.022,0.02,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37190000,-0.67,0.0026,-0.004,0.74,0.12,0.18,-0.14,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00041,-0.15,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00063,1.9e-05,2.4e-05,0.00053,0.05,0.052,0.0057,0.55,0.58,0.031,2.8e-07,2.9e-07,8.1e-06,0.021,0.019,0.0005,0.0025,5.1e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37290000,-0.67,0.0025,-0.004,0.74,0.12,0.19,-0.14,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00041,-0.15,0.11,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00063,1.9e-05,2.4e-05,0.00053,0.055,0.057,0.0059,0.57,0.59,0.031,2.8e-07,2.9e-07,8.1e-06,0.021,0.019,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37390000,-0.67,0.0028,-0.0038,0.74,0.1,0.16,-0.13,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00042,-0.16,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00063,1.8e-05,2.3e-05,0.00053,0.05,0.051,0.0059,0.56,0.59,0.031,2.9e-07,2.9e-07,8.1e-06,0.02,0.018,0.0005,0.0025,5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37490000,-0.67,0.0027,-0.0038,0.74,0.099,0.17,-0.13,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00042,-0.16,0.12,-0.094,0.37,0.0037,0.025,0,0,0,0,0,0.00064,1.8e-05,2.3e-05,0.00054,0.054,0.056,0.006,0.57,0.6,0.031,2.9e-07,2.9e-07,8.1e-06,0.02,0.018,0.0005,0.0025,4.9e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37590000,-0.67,0.0029,-0.0036,0.74,0.08,0.14,-0.12,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00043,-0.17,0.12,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00064,1.8e-05,2.3e-05,0.00054,0.049,0.05,0.0061,0.57,0.6,0.031,2.9e-07,2.9e-07,8.1e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37690000,-0.67,0.0028,-0.0037,0.74,0.078,0.15,-0.11,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00043,-0.17,0.12,-0.095,0.37,0.0037,0.025,0,0,0,0,0,0.00064,1.8e-05,2.3e-05,0.00054,0.053,0.055,0.0062,0.58,0.61,0.031,2.9e-07,2.9e-07,8.1e-06,0.019,0.018,0.0005,0.0025,4.8e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37790000,-0.67,0.003,-0.0036,0.74,0.062,0.13,-0.1,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00044,-0.18,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00064,1.8e-05,2.3e-05,0.00054,0.048,0.049,0.0063,0.58,0.61,0.03,2.9e-07,2.9e-07,8.1e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37890000,-0.67,0.003,-0.0036,0.74,0.059,0.13,-0.094,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00044,-0.18,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00064,1.8e-05,2.3e-05,0.00054,0.052,0.053,0.0064,0.59,0.62,0.03,2.9e-07,3e-07,8.1e-06,0.018,0.017,0.0005,0.0025,4.7e-05,0.0025,0.0025,0.0025,0.0025,0,0 +37990000,-0.67,0.003,-0.0035,0.74,0.044,0.11,-0.085,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00045,-0.19,0.13,-0.096,0.37,0.0037,0.025,0,0,0,0,0,0.00065,1.8e-05,2.2e-05,0.00054,0.047,0.048,0.0065,0.59,0.62,0.031,2.9e-07,3e-07,8.1e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38090000,-0.67,0.003,-0.0035,0.74,0.041,0.12,-0.075,-17,-8.1,-3.7e+02,-0.0018,-0.0057,-0.00045,-0.19,0.13,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00065,1.8e-05,2.2e-05,0.00054,0.051,0.052,0.0066,0.6,0.63,0.031,2.9e-07,3e-07,8.1e-06,0.017,0.016,0.0005,0.0025,4.6e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38190000,-0.67,0.003,-0.0034,0.74,0.027,0.1,-0.067,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00046,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00065,1.7e-05,2.2e-05,0.00054,0.046,0.047,0.0067,0.6,0.63,0.031,2.9e-07,3e-07,8.1e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38290000,-0.67,0.003,-0.0034,0.74,0.024,0.1,-0.06,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00046,-0.2,0.14,-0.097,0.37,0.0037,0.025,0,0,0,0,0,0.00065,1.8e-05,2.2e-05,0.00055,0.049,0.051,0.0068,0.61,0.64,0.031,2.9e-07,3e-07,8.1e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38390000,-0.67,0.003,-0.0032,0.74,0.016,0.087,-0.052,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00046,-0.2,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00065,1.8e-05,2.2e-05,0.00055,0.044,0.046,0.0069,0.61,0.64,0.031,2.9e-07,3e-07,8.1e-06,0.016,0.015,0.0005,0.0025,4.5e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38490000,-0.67,0.003,-0.0032,0.74,0.013,0.089,-0.045,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00046,-0.2,0.14,-0.098,0.37,0.0037,0.025,0,0,0,0,0,0.00065,1.8e-05,2.2e-05,0.00055,0.048,0.049,0.007,0.62,0.65,0.031,3e-07,3e-07,8.1e-06,0.016,0.015,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38590000,-0.67,0.003,-0.0031,0.74,0.008,0.076,-0.038,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00047,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00065,1.8e-05,2.2e-05,0.00055,0.043,0.044,0.0071,0.62,0.65,0.031,3e-07,3e-07,8.1e-06,0.015,0.014,0.0005,0.0025,4.4e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38690000,-0.67,0.0029,-0.0031,0.74,0.0038,0.076,-0.031,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00047,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00066,1.8e-05,2.2e-05,0.00055,0.047,0.048,0.0072,0.63,0.66,0.031,3e-07,3e-07,8.1e-06,0.015,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38790000,-0.67,0.0029,-0.003,0.74,-0.0014,0.063,-0.023,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00048,-0.21,0.14,-0.099,0.37,0.0037,0.025,0,0,0,0,0,0.00066,1.8e-05,2.2e-05,0.00055,0.042,0.043,0.0073,0.63,0.66,0.031,3e-07,3e-07,8.1e-06,0.014,0.014,0.0005,0.0025,4.3e-05,0.0025,0.0025,0.0025,0.0025,0,0 +38890000,-0.67,0.0027,-0.0031,0.74,-0.011,0.052,0.48,-17,-8.2,-3.7e+02,-0.0018,-0.0057,-0.00048,-0.21,0.14,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00066,1.8e-05,2.2e-05,0.00055,0.045,0.046,0.0075,0.64,0.67,0.032,3e-07,3e-07,8.1e-06,0.014,0.014,0.0005,0.0025,4.2e-05,0.0025,0.0025,0.0025,0.0025,0,0 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv index cd77461d7384..f12c1acdb6b9 100644 --- a/src/modules/ekf2/test/change_indication/iris_gps.csv +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -61,291 +61,291 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7 5890000,1,-0.0088,-0.011,0.00048,0.011,0.015,-0.048,0.0033,0.0035,-0.056,-0.002,-0.0055,9.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,7.7e-08,0.00039,0.00039,3.3e-05,0.23,0.23,0.048,0.1,0.1,0.075,0.00018,0.00018,1.2e-05,0.04,0.04,0.0054,0,0,0,0,0,0,0,0 5990000,1,-0.0088,-0.012,0.00045,0.013,0.016,-0.041,0.0046,0.005,-0.05,-0.002,-0.0055,9.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,8.3e-08,0.00041,0.00041,3.5e-05,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,1.2e-05,0.04,0.04,0.005,0,0,0,0,0,0,0,0 6090000,1,-0.0088,-0.012,0.00025,0.013,0.017,-0.039,0.0059,0.0066,-0.047,-0.002,-0.0055,9.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,8.8e-08,0.00044,0.00044,3.7e-05,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,1.2e-05,0.04,0.04,0.0047,0,0,0,0,0,0,0,0 -6190000,0.98,-0.0066,-0.013,0.19,0.0098,0.016,-0.037,0.0045,0.0054,-0.047,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00012,0.00034,0.00034,0.0031,0.22,0.22,0.042,0.13,0.13,0.073,0.00015,0.00015,1.1e-05,0.04,0.04,0.0044,0,0,0,0,0,0,0,0 -6290000,0.98,-0.0066,-0.013,0.19,0.0083,0.018,-0.041,0.0054,0.0071,-0.053,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,5.6e-05,0.00034,0.00034,0.0014,0.22,0.22,0.04,0.16,0.16,0.072,0.00015,0.00015,1.1e-05,0.04,0.04,0.0041,0,0,0,0,0,0,0,0 -6390000,0.98,-0.0065,-0.013,0.19,0.011,0.02,-0.042,0.0064,0.009,-0.056,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.8e-05,0.00034,0.00034,0.00099,0.23,0.23,0.039,0.19,0.19,0.072,0.00015,0.00015,1.1e-05,0.04,0.04,0.0038,0,0,0,0,0,0,0,0 -6490000,0.98,-0.0064,-0.013,0.19,0.0084,0.019,-0.039,0.0073,0.011,-0.053,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,2.9e-05,0.00034,0.00034,0.00072,0.24,0.24,0.038,0.23,0.23,0.07,0.00015,0.00015,1.1e-05,0.04,0.04,0.0036,0,0,0,0,0,0,0,0 -6590000,0.98,-0.0064,-0.013,0.19,0.0077,0.022,-0.042,0.0082,0.013,-0.056,-0.0019,-0.0056,9.3e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,2.3e-05,0.00035,0.00035,0.00057,0.26,0.26,0.036,0.28,0.28,0.069,0.00015,0.00015,1.1e-05,0.04,0.04,0.0033,0,0,0,0,0,0,0,0 -6690000,0.98,-0.0063,-0.013,0.19,0.0052,0.025,-0.044,0.0088,0.015,-0.057,-0.0019,-0.0056,9.1e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.9e-05,0.00035,0.00035,0.00047,0.28,0.28,0.035,0.33,0.33,0.068,0.00015,0.00015,1.1e-05,0.04,0.04,0.0031,0,0,0,0,0,0,0,0 -6790000,0.98,-0.0063,-0.013,0.19,0.007,0.027,-0.042,0.0093,0.018,-0.058,-0.0019,-0.0056,9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.7e-05,0.00036,0.00036,0.00041,0.3,0.3,0.034,0.38,0.38,0.068,0.00015,0.00015,1.1e-05,0.04,0.04,0.0029,0,0,0,0,0,0,0,0 -6890000,0.98,-0.0061,-0.013,0.19,0.0066,0.028,-0.038,0.01,0.02,-0.055,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.5e-05,0.00036,0.00036,0.00036,0.32,0.32,0.032,0.45,0.45,0.067,0.00015,0.00015,1.1e-05,0.04,0.04,0.0027,0,0,0,0,0,0,0,0 -6990000,0.98,-0.006,-0.013,0.19,0.0066,0.029,-0.037,0.011,0.023,-0.055,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.3e-05,0.00037,0.00037,0.00032,0.35,0.35,0.031,0.52,0.52,0.066,0.00015,0.00015,1.1e-05,0.04,0.04,0.0026,0,0,0,0,0,0,0,0 -7090000,0.98,-0.0059,-0.013,0.19,0.0057,0.035,-0.037,0.011,0.026,-0.056,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.2e-05,0.00037,0.00037,0.00029,0.39,0.39,0.03,0.6,0.6,0.066,0.00015,0.00015,1.1e-05,0.04,0.04,0.0024,0,0,0,0,0,0,0,0 -7190000,0.98,-0.0058,-0.013,0.19,0.0053,0.038,-0.036,0.012,0.03,-0.058,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1.1e-05,0.00038,0.00038,0.00026,0.42,0.42,0.029,0.69,0.69,0.065,0.00015,0.00015,1.1e-05,0.04,0.04,0.0023,0,0,0,0,0,0,0,0 -7290000,0.98,-0.0058,-0.013,0.19,0.0061,0.042,-0.034,0.012,0.034,-0.054,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,1e-05,0.00039,0.00039,0.00024,0.46,0.46,0.028,0.79,0.79,0.064,0.00015,0.00015,1.1e-05,0.04,0.04,0.0021,0,0,0,0,0,0,0,0 -7390000,0.98,-0.0057,-0.013,0.19,0.0044,0.046,-0.032,0.013,0.038,-0.052,-0.0019,-0.0056,8.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,9.6e-06,0.0004,0.0004,0.00022,0.51,0.51,0.027,0.9,0.9,0.064,0.00014,0.00014,1.1e-05,0.04,0.04,0.002,0,0,0,0,0,0,0,0 -7490000,0.98,-0.0057,-0.013,0.19,0.0068,0.05,-0.026,0.013,0.043,-0.046,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,9e-06,0.00041,0.00041,0.0002,0.56,0.56,0.026,1,1,0.063,0.00014,0.00014,1e-05,0.04,0.04,0.0019,0,0,0,0,0,0,0,0 -7590000,0.98,-0.0057,-0.013,0.19,0.0077,0.053,-0.023,0.014,0.048,-0.041,-0.0019,-0.0056,8.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,8.5e-06,0.00042,0.00042,0.00019,0.6,0.61,0.025,1.2,1.2,0.062,0.00014,0.00014,1e-05,0.04,0.04,0.0018,0,0,0,0,0,0,0,0 -7690000,0.98,-0.0057,-0.013,0.19,0.0074,0.057,-0.022,0.015,0.053,-0.036,-0.0019,-0.0056,8.8e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,8.1e-06,0.00043,0.00043,0.00018,0.66,0.66,0.025,1.3,1.3,0.062,0.00014,0.00014,1e-05,0.04,0.04,0.0017,0,0,0,0,0,0,0,0 -7790000,0.98,-0.0056,-0.013,0.19,0.009,0.06,-0.024,0.015,0.058,-0.041,-0.0019,-0.0056,8.6e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7.7e-06,0.00043,0.00043,0.00017,0.72,0.72,0.024,1.5,1.5,0.061,0.00014,0.00014,1e-05,0.04,0.04,0.0016,0,0,0,0,0,0,0,0 -7890000,0.98,-0.0056,-0.013,0.19,0.0077,0.065,-0.025,0.016,0.064,-0.045,-0.0019,-0.0056,8.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7.3e-06,0.00045,0.00045,0.00016,0.78,0.78,0.023,1.7,1.7,0.06,0.00014,0.00014,1e-05,0.04,0.04,0.0015,0,0,0,0,0,0,0,0 -7990000,0.98,-0.0056,-0.013,0.19,0.0078,0.068,-0.021,0.016,0.07,-0.041,-0.0019,-0.0056,8.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,7e-06,0.00045,0.00045,0.00015,0.84,0.84,0.022,1.9,1.9,0.059,0.00014,0.00014,1e-05,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 -8090000,0.98,-0.0054,-0.013,0.19,0.0093,0.073,-0.022,0.017,0.077,-0.044,-0.0019,-0.0056,7.7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.8e-06,0.00047,0.00047,0.00014,0.92,0.92,0.022,2.1,2.1,0.059,0.00014,0.00014,1e-05,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 -8190000,0.98,-0.0055,-0.013,0.19,0.01,0.08,-0.018,0.018,0.085,-0.038,-0.0019,-0.0056,7.2e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.5e-06,0.00048,0.00048,0.00014,1,1,0.021,2.4,2.4,0.058,0.00014,0.00014,1e-05,0.04,0.04,0.0013,0,0,0,0,0,0,0,0 -8290000,0.98,-0.0055,-0.013,0.19,0.012,0.084,-0.016,0.019,0.091,-0.038,-0.0019,-0.0056,6.9e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,6.3e-06,0.00049,0.00049,0.00013,1.1,1.1,0.02,2.6,2.6,0.057,0.00014,0.00014,1e-05,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 -8390000,0.98,-0.0054,-0.013,0.19,0.0099,0.087,-0.015,0.02,0.1,-0.036,-0.0019,-0.0056,6.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,6.1e-06,0.0005,0.0005,0.00013,1.1,1.1,0.02,2.9,2.9,0.057,0.00014,0.00014,1e-05,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 -8490000,0.98,-0.0053,-0.013,0.19,0.0095,0.091,-0.017,0.02,0.11,-0.041,-0.0018,-0.0056,7e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,5.9e-06,0.00051,0.00051,0.00012,1.2,1.2,0.019,3.2,3.2,0.056,0.00014,0.00014,1e-05,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 -8590000,0.98,-0.0052,-0.013,0.19,0.011,0.095,-0.012,0.021,0.11,-0.036,-0.0018,-0.0056,6.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.8e-06,0.00052,0.00052,0.00012,1.3,1.3,0.018,3.6,3.6,0.055,0.00014,0.00014,1e-05,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 -8690000,0.98,-0.0053,-0.013,0.19,0.01,0.096,-0.014,0.021,0.12,-0.037,-0.0018,-0.0056,6.6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.6e-06,0.00053,0.00053,0.00011,1.4,1.4,0.018,3.9,3.9,0.055,0.00013,0.00013,1e-05,0.04,0.04,0.001,0,0,0,0,0,0,0,0 -8790000,0.98,-0.0053,-0.013,0.19,0.012,0.1,-0.013,0.022,0.13,-0.035,-0.0018,-0.0056,6e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.5e-06,0.00054,0.00054,0.00011,1.5,1.5,0.018,4.3,4.3,0.055,0.00013,0.00013,1e-05,0.04,0.04,0.00096,0,0,0,0,0,0,0,0 -8890000,0.98,-0.0053,-0.013,0.19,0.011,0.1,-0.0091,0.023,0.13,-0.029,-0.0018,-0.0056,6.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.3e-06,0.00054,0.00054,0.00011,1.5,1.5,0.017,4.6,4.6,0.054,0.00013,0.00013,1e-05,0.04,0.04,0.00091,0,0,0,0,0,0,0,0 -8990000,0.98,-0.0053,-0.013,0.19,0.011,0.11,-0.0083,0.024,0.15,-0.032,-0.0018,-0.0056,7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.2e-06,0.00056,0.00056,0.0001,1.6,1.6,0.017,5.2,5.2,0.054,0.00013,0.00013,1e-05,0.04,0.04,0.00088,0,0,0,0,0,0,0,0 -9090000,0.98,-0.0053,-0.013,0.19,0.011,0.11,-0.0093,0.024,0.15,-0.032,-0.0018,-0.0056,7.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5.1e-06,0.00055,0.00055,0.0001,1.7,1.7,0.016,5.4,5.5,0.053,0.00013,0.00013,1e-05,0.04,0.04,0.00084,0,0,0,0,0,0,0,0 -9190000,0.98,-0.0053,-0.013,0.19,0.014,0.11,-0.0088,0.025,0.16,-0.032,-0.0018,-0.0056,8.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,5e-06,0.00057,0.00057,9.8e-05,1.8,1.8,0.016,6.1,6.1,0.052,0.00013,0.00013,1e-05,0.04,0.04,0.0008,0,0,0,0,0,0,0,0 -9290000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0072,0.025,0.16,-0.03,-0.0017,-0.0056,8.5e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.9e-06,0.00056,0.00055,9.5e-05,1.8,1.8,0.015,6.3,6.3,0.052,0.00012,0.00012,1e-05,0.04,0.04,0.00076,0,0,0,0,0,0,0,0 -9390000,0.98,-0.0051,-0.013,0.19,0.016,0.12,-0.006,0.027,0.17,-0.03,-0.0017,-0.0056,7.7e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.9e-06,0.00057,0.00057,9.3e-05,1.9,1.9,0.015,7,7,0.052,0.00012,0.00012,1e-05,0.04,0.04,0.00073,0,0,0,0,0,0,0,0 -9490000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0044,0.026,0.17,-0.027,-0.0017,-0.0056,7.9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.8e-06,0.00056,0.00056,9.1e-05,1.9,1.9,0.015,7.2,7.2,0.051,0.00012,0.00012,1e-05,0.04,0.04,0.0007,0,0,0,0,0,0,0,0 -9590000,0.98,-0.0052,-0.013,0.19,0.015,0.12,-0.0043,0.028,0.18,-0.028,-0.0017,-0.0056,6.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.7e-06,0.00057,0.00057,8.9e-05,2,2,0.014,7.9,7.9,0.05,0.00012,0.00012,1e-05,0.04,0.04,0.00067,0,0,0,0,0,0,0,0 -9690000,0.98,-0.0053,-0.013,0.19,0.015,0.11,-0.0014,0.027,0.18,-0.027,-0.0017,-0.0056,5.8e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.6e-06,0.00055,0.00055,8.7e-05,2,2,0.014,8.1,8.1,0.05,0.00012,0.00012,1e-05,0.04,0.04,0.00065,0,0,0,0,0,0,0,0 -9790000,0.98,-0.0053,-0.013,0.19,0.016,0.12,-0.0027,0.028,0.19,-0.028,-0.0017,-0.0056,4.1e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.6e-06,0.00057,0.00057,8.5e-05,2.1,2.2,0.014,8.9,8.9,0.05,0.00012,0.00012,1e-05,0.04,0.04,0.00062,0,0,0,0,0,0,0,0 -9890000,0.98,-0.0054,-0.013,0.19,0.018,0.11,-0.0014,0.027,0.19,-0.029,-0.0016,-0.0056,4.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.5e-06,0.00054,0.00054,8.4e-05,2.1,2.1,0.013,8.9,8.9,0.049,0.00011,0.00011,1e-05,0.04,0.04,0.0006,0,0,0,0,0,0,0,0 -9990000,0.98,-0.0054,-0.013,0.19,0.019,0.12,-0.00072,0.029,0.2,-0.031,-0.0016,-0.0056,3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.5e-06,0.00056,0.00056,8.2e-05,2.2,2.2,0.013,9.8,9.8,0.049,0.00011,0.00011,1e-05,0.04,0.04,0.00058,0,0,0,0,0,0,0,0 -10090000,0.98,-0.0055,-0.013,0.19,0.017,0.11,0.00048,0.028,0.19,-0.029,-0.0016,-0.0057,1.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.4e-06,0.00053,0.00053,8.1e-05,2.1,2.1,0.013,9.7,9.7,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.00056,0,0,0,0,0,0,0,0 -10190000,0.98,-0.0054,-0.013,0.19,0.015,0.11,0.0014,0.029,0.2,-0.03,-0.0016,-0.0057,-5.6e-06,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00055,0.00055,8e-05,2.3,2.3,0.012,11,11,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.00054,0,0,0,0,0,0,0,0 -10290000,0.98,-0.0054,-0.013,0.19,0.016,0.11,0.0003,0.031,0.21,-0.029,-0.0016,-0.0057,1.4e-06,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00057,0.00057,7.9e-05,2.4,2.4,0.012,12,12,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.00052,0,0,0,0,0,0,0,0 -10390000,0.98,-0.0054,-0.013,0.19,0.007,0.0052,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0057,6e-06,-3.6e-08,2.5e-08,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.3e-06,0.00059,0.00058,7.8e-05,0.25,0.25,0.56,0.25,0.25,0.048,0.00011,0.00011,1e-05,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10490000,0.98,-0.0053,-0.012,0.19,0.0084,0.0077,0.007,0.0015,0.00075,-0.023,-0.0016,-0.0057,-9.5e-06,-1.2e-06,8.3e-07,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.0006,0.0006,7.6e-05,0.26,0.26,0.55,0.26,0.26,0.057,0.00011,0.00011,9.9e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10590000,0.98,-0.0053,-0.012,0.19,-0.0013,0.0055,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,-5.9e-07,0.00032,8.8e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.00061,0.00061,7.5e-05,0.13,0.13,0.27,0.13,0.13,0.055,0.00011,0.00011,9.9e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10690000,0.98,-0.0052,-0.012,0.19,-0.00013,0.0067,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,-6.1e-06,0.00032,9.5e-06,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.2e-06,0.00063,0.00063,7.5e-05,0.15,0.15,0.26,0.14,0.14,0.065,0.00011,0.00011,9.8e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10790000,0.98,-0.0054,-0.013,0.19,0.0017,0.0031,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,-8.7e-06,0.00052,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00062,0.00062,7.4e-05,0.1,0.1,0.17,0.091,0.091,0.062,0.00011,0.00011,9.8e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10890000,0.98,-0.0053,-0.013,0.19,0.0018,0.0066,0.01,-0.0006,-0.0042,-0.018,-0.0016,-0.0057,9.2e-06,0.00052,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00064,0.00064,7.3e-05,0.12,0.12,0.16,0.098,0.098,0.068,0.00011,0.00011,9.7e-06,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 -10990000,0.98,-0.0054,-0.013,0.19,0.0013,0.012,0.016,-0.00045,-0.003,-0.011,-0.0015,-0.0057,2.8e-06,0.00067,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.0006,0.0006,7.2e-05,0.096,0.096,0.12,0.073,0.073,0.065,9.9e-05,9.9e-05,9.7e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 -11090000,0.98,-0.0055,-0.013,0.19,0.0022,0.017,0.02,-0.00032,-0.0016,-0.0074,-0.0015,-0.0057,-1.7e-05,0.00067,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4.1e-06,0.00062,0.00062,7.2e-05,0.12,0.12,0.11,0.08,0.08,0.069,9.9e-05,9.9e-05,9.7e-06,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 -11190000,0.98,-0.0058,-0.013,0.19,0.0039,0.017,0.026,0.0011,-0.0018,-0.00035,-0.0015,-0.0057,-2.9e-05,0.00065,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00055,0.00055,7.1e-05,0.096,0.096,0.083,0.063,0.063,0.066,9.1e-05,9.1e-05,9.6e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11290000,0.98,-0.0058,-0.013,0.19,0.0041,0.018,0.026,0.0014,-2.5e-05,-0.00012,-0.0015,-0.0057,-3.5e-05,0.00065,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00057,0.00057,7.1e-05,0.12,0.12,0.077,0.07,0.07,0.069,9.1e-05,9.1e-05,9.6e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11390000,0.98,-0.006,-0.013,0.19,0.0025,0.015,0.016,0.00088,-0.00088,-0.0086,-0.0014,-0.0058,-3.4e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.00049,0.00049,7e-05,0.097,0.097,0.062,0.057,0.057,0.066,8.3e-05,8.3e-05,9.5e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11490000,0.98,-0.0059,-0.013,0.19,0.0015,0.016,0.02,0.001,0.00072,-0.0025,-0.0014,-0.0058,-3.1e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,4e-06,0.0005,0.0005,7e-05,0.12,0.12,0.057,0.065,0.065,0.067,8.3e-05,8.3e-05,9.4e-06,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 -11590000,0.98,-0.0062,-0.012,0.19,0.0033,0.013,0.018,0.00083,-0.00036,-0.0036,-0.0013,-0.0058,-3.1e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00042,0.00042,6.9e-05,0.096,0.096,0.048,0.054,0.054,0.065,7.5e-05,7.5e-05,9.4e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 -11690000,0.98,-0.0062,-0.012,0.19,0.0038,0.017,0.018,0.0012,0.0011,-0.0049,-0.0013,-0.0058,-2.4e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00044,0.00044,6.9e-05,0.12,0.12,0.044,0.062,0.062,0.066,7.5e-05,7.5e-05,9.3e-06,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 -11790000,0.98,-0.0066,-0.012,0.19,0.0024,0.011,0.019,0.0007,-0.0018,-0.002,-0.0012,-0.0059,-3.6e-06,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00037,0.00037,6.8e-05,0.092,0.092,0.037,0.052,0.052,0.063,6.8e-05,6.8e-05,9.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -11890000,0.98,-0.0067,-0.012,0.19,0.0051,0.012,0.017,0.001,-0.0007,-0.0013,-0.0012,-0.0059,-5.8e-06,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00038,0.00038,6.8e-05,0.11,0.11,0.034,0.061,0.061,0.063,6.8e-05,6.8e-05,9.2e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -11990000,0.98,-0.0069,-0.012,0.19,0.0081,0.012,0.015,0.0021,-0.0018,-0.0049,-0.0012,-0.0059,2.5e-06,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.9e-06,0.00032,0.00032,6.8e-05,0.088,0.088,0.03,0.051,0.051,0.061,6.2e-05,6.2e-05,9.2e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12090000,0.98,-0.0068,-0.012,0.19,0.0097,0.012,0.018,0.003,-0.00063,0.0011,-0.0012,-0.0059,4e-06,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00033,0.00033,6.7e-05,0.11,0.11,0.027,0.06,0.06,0.06,6.2e-05,6.2e-05,9.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12190000,0.98,-0.0067,-0.012,0.19,0.0077,0.011,0.017,0.0018,0.00039,0.0029,-0.0012,-0.0059,-2.4e-06,0.0022,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00029,0.00029,6.7e-05,0.083,0.083,0.024,0.05,0.05,0.058,5.7e-05,5.7e-05,9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12290000,0.98,-0.0068,-0.012,0.19,0.0054,0.011,0.016,0.0025,0.0015,0.0039,-0.0012,-0.0059,-7.7e-06,0.0022,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.0003,0.0003,6.7e-05,0.098,0.098,0.022,0.059,0.059,0.058,5.7e-05,5.7e-05,9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12390000,0.98,-0.0069,-0.012,0.19,0.004,0.0072,0.014,0.0017,0.00049,-0.0021,-0.0012,-0.006,-7.3e-06,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00026,0.00026,6.7e-05,0.078,0.078,0.02,0.05,0.05,0.056,5.3e-05,5.3e-05,8.9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12490000,0.98,-0.0069,-0.012,0.19,0.004,0.0082,0.018,0.0021,0.0013,-6.6e-05,-0.0012,-0.006,-7.2e-06,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00027,0.00027,6.7e-05,0.091,0.091,0.018,0.059,0.059,0.055,5.3e-05,5.3e-05,8.8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12590000,0.98,-0.0071,-0.012,0.19,0.0078,0.0015,0.02,0.0033,-0.0014,0.0017,-0.0011,-0.006,-7.6e-06,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00024,0.00024,6.7e-05,0.072,0.072,0.017,0.049,0.049,0.054,5e-05,5e-05,8.8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12690000,0.98,-0.007,-0.012,0.19,0.0083,-0.00065,0.019,0.004,-0.0013,0.0033,-0.0011,-0.006,-4.2e-06,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00025,0.00025,6.6e-05,0.084,0.084,0.016,0.058,0.058,0.053,5e-05,5e-05,8.7e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12790000,0.98,-0.0073,-0.012,0.19,0.0099,-0.004,0.021,0.0041,-0.0044,0.0054,-0.0011,-0.006,2.7e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00023,0.00023,6.6e-05,0.068,0.068,0.014,0.049,0.049,0.052,4.7e-05,4.7e-05,8.6e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12890000,0.98,-0.0073,-0.012,0.19,0.01,-0.005,0.022,0.0052,-0.0049,0.0085,-0.0011,-0.006,4.9e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.8e-06,0.00024,0.00024,6.6e-05,0.078,0.078,0.013,0.058,0.058,0.051,4.7e-05,4.7e-05,8.6e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -12990000,0.98,-0.0072,-0.012,0.19,0.0079,-0.0029,0.022,0.0036,-0.0036,0.0096,-0.0011,-0.006,7e-05,0.0026,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00022,0.00022,6.6e-05,0.064,0.064,0.012,0.049,0.049,0.05,4.5e-05,4.5e-05,8.5e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13090000,0.98,-0.0073,-0.012,0.19,0.0089,-0.0028,0.02,0.0044,-0.0038,0.0085,-0.0011,-0.006,9.8e-05,0.0027,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00023,0.00023,6.6e-05,0.073,0.073,0.012,0.057,0.057,0.049,4.5e-05,4.5e-05,8.4e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13190000,0.98,-0.0073,-0.012,0.19,0.0038,-0.0045,0.019,0.00096,-0.0046,0.0091,-0.0011,-0.006,0.00012,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.06,0.06,0.011,0.049,0.049,0.047,4.3e-05,4.3e-05,8.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13290000,0.98,-0.0073,-0.012,0.19,0.0035,-0.0054,0.016,0.0013,-0.005,0.0085,-0.0011,-0.006,0.00012,0.0028,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00022,0.00022,6.6e-05,0.068,0.068,0.01,0.057,0.057,0.047,4.3e-05,4.3e-05,8.3e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13390000,0.98,-0.0072,-0.012,0.19,0.0026,-0.0035,0.016,0.00085,-0.0037,0.0091,-0.0011,-0.006,0.00012,0.0029,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.056,0.056,0.0097,0.049,0.049,0.046,4e-05,4.1e-05,8.2e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13490000,0.98,-0.0072,-0.012,0.19,0.003,-0.0018,0.015,0.0011,-0.0039,0.0053,-0.0011,-0.006,0.00013,0.003,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.064,0.064,0.0093,0.057,0.057,0.045,4e-05,4.1e-05,8.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13590000,0.98,-0.0072,-0.012,0.19,0.0076,-0.002,0.017,0.004,-0.0032,0.0038,-0.0011,-0.006,0.00012,0.0032,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.053,0.053,0.0088,0.048,0.048,0.044,3.9e-05,3.9e-05,8.1e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13690000,0.98,-0.0072,-0.012,0.19,0.0076,-0.0035,0.017,0.0048,-0.0034,0.0064,-0.0011,-0.006,0.00014,0.0032,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.061,0.061,0.0085,0.056,0.056,0.044,3.9e-05,3.9e-05,8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13790000,0.98,-0.0071,-0.012,0.19,0.015,0.00072,0.017,0.0083,-0.00093,0.0059,-0.0011,-0.0059,0.00014,0.0035,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.051,0.051,0.0082,0.048,0.048,0.043,3.7e-05,3.7e-05,7.9e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13890000,0.98,-0.007,-0.012,0.19,0.016,0.0014,0.018,0.0098,-0.00082,0.0081,-0.0011,-0.0059,0.00016,0.0035,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.6e-05,0.058,0.058,0.008,0.056,0.056,0.042,3.7e-05,3.7e-05,7.8e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0015,0.017,0.0074,-0.0023,0.007,-0.0011,-0.006,0.00018,0.0034,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.049,0.049,0.0077,0.048,0.048,0.041,3.5e-05,3.5e-05,7.7e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.0029,0.018,0.0088,-0.0024,0.0034,-0.0011,-0.006,0.00014,0.0035,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00021,0.00021,6.5e-05,0.055,0.055,0.0076,0.055,0.055,0.041,3.5e-05,3.5e-05,7.7e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -14190000,0.98,-0.0071,-0.011,0.19,0.01,-0.0016,0.018,0.008,-0.0018,0.0036,-0.0011,-0.006,0.00013,0.0036,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-05,3.3e-05,7.6e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0017,0.016,0.009,-0.002,0.0079,-0.0011,-0.006,0.00013,0.0035,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.053,0.053,0.0073,0.055,0.055,0.04,3.3e-05,3.3e-05,7.5e-06,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 -14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0047,0.017,0.0084,-0.0031,0.012,-0.0011,-0.006,0.00015,0.0034,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-05,3.1e-05,7.4e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0045,0.021,0.0095,-0.0036,0.015,-0.0011,-0.006,0.00013,0.0034,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-05,3.1e-05,7.4e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14590000,0.98,-0.0073,-0.011,0.19,0.0079,-0.0046,0.019,0.0059,-0.0042,0.011,-0.0011,-0.006,0.00013,0.0031,0.0033,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.6e-05,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-05,2.9e-05,7.3e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14690000,0.98,-0.0073,-0.011,0.19,0.0071,-0.0046,0.019,0.0066,-0.0046,0.011,-0.0011,-0.006,0.00014,0.0032,0.0032,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.5e-05,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-05,2.9e-05,7.2e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14790000,0.98,-0.0072,-0.011,0.19,0.0088,0.0025,0.019,0.0053,0.00078,0.014,-0.0012,-0.006,0.00017,0.0032,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-05,2.8e-05,7.1e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14890000,0.98,-0.0071,-0.011,0.19,0.0074,5e-05,0.023,0.006,0.00092,0.014,-0.0012,-0.006,0.00019,0.0033,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.0002,6.6e-05,0.049,0.049,0.007,0.054,0.054,0.037,2.7e-05,2.8e-05,7e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -14990000,0.98,-0.0073,-0.011,0.19,0.0062,-0.0016,0.026,0.0047,-0.00069,0.017,-0.0012,-0.0061,0.0002,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-05,2.6e-05,7e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15090000,0.98,-0.0072,-0.011,0.19,0.0062,-0.00052,0.03,0.0054,-0.00084,0.019,-0.0012,-0.0061,0.00021,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.0002,0.00019,6.5e-05,0.048,0.048,0.007,0.054,0.054,0.036,2.6e-05,2.6e-05,6.9e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15190000,0.98,-0.0073,-0.011,0.19,0.0044,-0.0016,0.03,0.0042,-0.00076,0.021,-0.0012,-0.0061,0.0002,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.6e-05,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-05,2.4e-05,6.8e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15290000,0.98,-0.0074,-0.011,0.19,0.005,-0.0027,0.03,0.0047,-0.00095,0.018,-0.0012,-0.0061,0.00022,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.047,0.047,0.0071,0.054,0.054,0.035,2.4e-05,2.4e-05,6.7e-06,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 -15390000,0.98,-0.0075,-0.011,0.19,0.0052,-0.00028,0.029,0.0038,-0.00065,0.018,-0.0012,-0.0061,0.00022,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-05,2.2e-05,6.7e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15490000,0.98,-0.0076,-0.011,0.19,0.0046,-0.0028,0.029,0.0042,-0.00078,0.019,-0.0012,-0.0061,0.00022,0.0035,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.6e-05,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-05,2.2e-05,6.6e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15590000,0.98,-0.0078,-0.011,0.19,0.0081,-0.0067,0.029,0.0063,-0.0047,0.018,-0.0011,-0.0061,0.00024,0.0039,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-05,2.1e-05,6.5e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15690000,0.98,-0.0077,-0.011,0.19,0.0099,-0.0098,0.029,0.0072,-0.0055,0.019,-0.0011,-0.0061,0.00026,0.0039,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00019,0.00019,6.5e-05,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-05,2.1e-05,6.4e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15790000,0.98,-0.0077,-0.011,0.19,0.0064,-0.0091,0.029,0.0055,-0.0043,0.02,-0.0011,-0.0061,0.00029,0.0038,0.0027,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.04,0.04,0.0073,0.046,0.046,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15890000,0.98,-0.0078,-0.011,0.19,0.0053,-0.0075,0.03,0.0061,-0.0051,0.02,-0.0011,-0.0061,0.00027,0.004,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.045,0.045,0.0074,0.053,0.053,0.034,1.9e-05,1.9e-05,6.3e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -15990000,0.98,-0.0076,-0.011,0.19,0.0033,-0.006,0.027,0.0048,-0.0039,0.019,-0.0012,-0.0061,0.00028,0.0042,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-05,1.7e-05,6.2e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -16090000,0.98,-0.0076,-0.011,0.19,0.0026,-0.0073,0.024,0.005,-0.0046,0.019,-0.0012,-0.0061,0.00027,0.0044,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00018,0.00018,6.5e-05,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,6.1e-06,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 -16190000,0.98,-0.0075,-0.011,0.19,-0.0013,-0.0049,0.023,0.0027,-0.0034,0.016,-0.0012,-0.0061,0.00025,0.0045,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-05,1.6e-05,6e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16290000,0.98,-0.0075,-0.011,0.19,-0.001,-0.0065,0.023,0.0025,-0.004,0.017,-0.0012,-0.0061,0.00026,0.0045,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-05,1.6e-05,6e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16390000,0.98,-0.0074,-0.011,0.19,0.0015,-0.0057,0.023,0.0036,-0.003,0.017,-0.0012,-0.0061,0.00028,0.0051,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00016,6.5e-05,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-05,1.5e-05,5.9e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16490000,0.98,-0.0076,-0.011,0.19,0.0034,-0.0074,0.026,0.0038,-0.0037,0.021,-0.0012,-0.0061,0.00028,0.005,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00017,0.00017,6.5e-05,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-05,1.5e-05,5.8e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16590000,0.98,-0.0075,-0.011,0.19,0.0075,-0.0074,0.029,0.0034,-0.0029,0.021,-0.0012,-0.0061,0.00028,0.0051,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-05,1.3e-05,5.7e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16690000,0.98,-0.0076,-0.011,0.19,0.009,-0.012,0.029,0.0042,-0.0038,0.022,-0.0012,-0.0061,0.00029,0.0053,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.042,0.042,0.008,0.053,0.053,0.034,1.3e-05,1.3e-05,5.7e-06,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 -16790000,0.98,-0.0074,-0.011,0.19,0.0098,-0.011,0.028,0.0033,-0.0027,0.022,-0.0012,-0.0061,0.0003,0.0053,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,5.6e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -16890000,0.98,-0.0074,-0.011,0.19,0.0088,-0.011,0.029,0.0042,-0.0038,0.02,-0.0012,-0.0061,0.00033,0.0056,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00016,6.5e-05,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,5.5e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -16990000,0.98,-0.0074,-0.011,0.19,0.0085,-0.011,0.029,0.004,-0.0028,0.019,-0.0013,-0.0061,0.00033,0.0062,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-05,1.1e-05,5.5e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.005,-0.0041,0.018,-0.0013,-0.0061,0.00033,0.0064,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00016,0.00015,6.5e-05,0.04,0.041,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,5.4e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17190000,0.98,-0.0076,-0.011,0.19,0.0089,-0.018,0.03,0.0033,-0.0075,0.021,-0.0012,-0.0061,0.00031,0.0063,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-06,9.9e-06,5.3e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17290000,0.98,-0.0076,-0.011,0.19,0.0099,-0.019,0.03,0.0043,-0.0094,0.021,-0.0012,-0.0061,0.00029,0.0065,0.002,-0.14,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-06,9.9e-06,5.2e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17390000,0.98,-0.0074,-0.011,0.19,0.0066,-0.018,0.029,0.0057,-0.0059,0.021,-0.0013,-0.006,0.00031,0.0073,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00014,0.00014,6.5e-05,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-06,8.9e-06,5.2e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17490000,0.98,-0.0075,-0.011,0.19,0.0047,-0.019,0.029,0.0062,-0.0078,0.023,-0.0013,-0.006,0.0003,0.0074,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.7e-06,0.00015,0.00015,6.5e-05,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-06,8.9e-06,5.1e-06,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 -17590000,0.98,-0.0074,-0.011,0.19,0.00086,-0.015,0.028,0.0024,-0.0058,0.02,-0.0013,-0.0061,0.0003,0.0073,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-06,8.1e-06,5e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17690000,0.98,-0.0075,-0.011,0.19,-9.1e-05,-0.016,0.029,0.0025,-0.0074,0.023,-0.0013,-0.0061,0.00031,0.0073,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-06,8.1e-06,5e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17790000,0.98,-0.0074,-0.011,0.19,0.0026,-0.014,0.029,0.0035,-0.0062,0.028,-0.0014,-0.006,0.00031,0.0076,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00013,6.5e-05,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-06,7.3e-06,4.9e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17890000,0.98,-0.0073,-0.011,0.19,0.0047,-0.016,0.029,0.0039,-0.0077,0.032,-0.0014,-0.006,0.00032,0.0075,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00014,0.00014,6.5e-05,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-06,7.3e-06,4.8e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -17990000,0.98,-0.0071,-0.011,0.19,0.0041,-0.0093,0.029,0.0031,-0.002,0.033,-0.0014,-0.006,0.00032,0.0079,0.0047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-06,6.6e-06,4.8e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -18090000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0098,0.028,0.0035,-0.003,0.031,-0.0014,-0.006,0.00032,0.0082,0.0045,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-06,6.6e-06,4.7e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -18190000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0088,0.028,0.0041,-0.0022,0.029,-0.0014,-0.006,0.00034,0.0088,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.032,0.032,0.0086,0.045,0.045,0.035,6e-06,6e-06,4.7e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -18290000,0.98,-0.0072,-0.011,0.19,0.0045,-0.0093,0.027,0.0045,-0.0031,0.027,-0.0014,-0.006,0.00034,0.009,0.0042,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.036,0.036,0.0087,0.051,0.051,0.035,6e-06,6e-06,4.6e-06,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 -18390000,0.98,-0.0072,-0.011,0.19,0.0054,-0.008,0.027,0.0061,-0.0023,0.026,-0.0014,-0.006,0.00034,0.0096,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00012,6.4e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-06,5.4e-06,4.5e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 -18490000,0.98,-0.0072,-0.011,0.19,0.0082,-0.008,0.026,0.0069,-0.0031,0.028,-0.0014,-0.006,0.00035,0.0097,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00013,0.00013,6.4e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-06,5.4e-06,4.5e-06,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 -18590000,0.98,-0.007,-0.011,0.19,0.0066,-0.0074,0.026,0.0055,-0.0024,0.031,-0.0015,-0.006,0.00033,0.0095,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-06,4.9e-06,4.4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18690000,0.98,-0.007,-0.011,0.19,0.0066,-0.0063,0.024,0.0062,-0.0031,0.029,-0.0015,-0.006,0.00034,0.0097,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-06,4.9e-06,4.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18790000,0.98,-0.007,-0.011,0.19,0.0056,-0.006,0.024,0.0062,-0.0025,0.027,-0.0015,-0.006,0.00034,0.01,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,4.3e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18890000,0.98,-0.0069,-0.011,0.19,0.0043,-0.0056,0.021,0.0067,-0.0032,0.023,-0.0015,-0.006,0.00033,0.01,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.4e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-06,4.4e-06,4.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -18990000,0.98,-0.0069,-0.011,0.19,0.0027,-0.0057,0.022,0.0055,-0.0025,0.026,-0.0015,-0.006,0.00033,0.01,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.3e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-06,4e-06,4.2e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19090000,0.98,-0.007,-0.011,0.19,0.00066,-0.0062,0.023,0.0058,-0.0031,0.022,-0.0015,-0.006,0.00034,0.011,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00012,0.00012,6.3e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,4.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19190000,0.98,-0.0069,-0.011,0.19,-0.00084,-0.0059,0.022,0.0048,-0.0025,0.022,-0.0015,-0.006,0.00031,0.011,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-06,3.7e-06,4.1e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19290000,0.98,-0.0069,-0.011,0.19,-0.0017,-0.0057,0.023,0.0047,-0.0031,0.021,-0.0015,-0.006,0.00031,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.031,0.031,0.0087,0.05,0.051,0.036,3.7e-06,3.7e-06,4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19390000,0.98,-0.0069,-0.011,0.19,-0.0021,-0.0022,0.024,0.004,-0.0012,0.02,-0.0015,-0.006,0.0003,0.011,0.0037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-06,3.3e-06,4e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19490000,0.98,-0.007,-0.011,0.19,-0.003,-0.0022,0.023,0.0038,-0.0014,0.019,-0.0015,-0.006,0.00028,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,3.9e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19590000,0.98,-0.0069,-0.011,0.19,-0.0041,-0.0051,0.025,0.0044,-0.0024,0.019,-0.0015,-0.006,0.00028,0.012,0.0033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.6e-06,0.00011,0.00011,6.3e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-06,3e-06,3.8e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19690000,0.98,-0.0069,-0.011,0.19,-0.0057,-0.0037,0.023,0.0039,-0.0028,0.019,-0.0015,-0.006,0.00028,0.012,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,3.8e-06,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 -19790000,0.98,-0.007,-0.011,0.19,-0.0058,-0.0022,0.022,0.0063,-0.0023,0.014,-0.0015,-0.006,0.00027,0.012,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-06,2.8e-06,3.7e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 -19890000,0.98,-0.0071,-0.011,0.19,-0.0058,-0.002,0.022,0.0057,-0.0025,0.013,-0.0015,-0.006,0.00026,0.013,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.00011,6.2e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,3.7e-06,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 -19990000,0.98,-0.0071,-0.011,0.19,-0.0055,-0.0019,0.019,0.0061,-0.00091,0.0097,-0.0015,-0.0059,0.00026,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,3.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20090000,0.98,-0.0071,-0.011,0.19,-0.005,-0.0041,0.019,0.0055,-0.0012,0.013,-0.0015,-0.0059,0.00026,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.00011,0.0001,6.2e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-06,2.5e-06,3.6e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20190000,0.98,-0.0071,-0.011,0.19,-0.0039,-0.0016,0.02,0.0065,-0.0009,0.013,-0.0015,-0.0059,0.00025,0.013,0.0027,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-06,2.3e-06,3.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20290000,0.98,-0.0071,-0.011,0.19,-0.0071,-0.0026,0.02,0.006,-0.0011,0.013,-0.0015,-0.0059,0.00024,0.013,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,3.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20390000,0.98,-0.007,-0.011,0.19,-0.0078,-0.0015,0.021,0.0069,-0.00077,0.014,-0.0015,-0.0059,0.00025,0.014,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.2e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,3.5e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0024,0.02,0.0059,-0.00094,0.012,-0.0015,-0.0059,0.00025,0.014,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,0.0001,6.1e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,3.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20590000,0.98,-0.007,-0.011,0.19,-0.011,-0.0034,0.02,0.0069,-0.00079,0.011,-0.0015,-0.0059,0.00026,0.014,0.0022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,9.9e-05,6.1e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,3.4e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0021,0.021,0.0057,-0.001,0.011,-0.0015,-0.0059,0.00025,0.014,0.0022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,0.0001,9.9e-05,6.1e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-06,2e-06,3.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20790000,0.98,-0.0063,-0.011,0.19,-0.016,0.00042,0.0055,0.0048,-0.0008,0.0097,-0.0015,-0.0059,0.00025,0.014,0.0021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.8e-05,9.7e-05,6.1e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,3.3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20890000,0.98,0.0028,-0.0073,0.19,-0.022,0.012,-0.11,0.0029,-0.00012,0.0034,-0.0015,-0.0059,0.00025,0.015,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.9e-05,9.8e-05,6.1e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,3.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -20990000,0.98,0.0061,-0.0038,0.19,-0.032,0.03,-0.25,0.0022,0.00052,-0.011,-0.0015,-0.0059,0.00025,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.7e-05,9.6e-05,6.1e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,3.2e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21090000,0.98,0.0045,-0.0042,0.19,-0.046,0.046,-0.37,-0.0017,0.0044,-0.042,-0.0015,-0.0059,0.00025,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.8e-05,9.6e-05,6.1e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-06,1.7e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21190000,0.98,0.0017,-0.0059,0.19,-0.049,0.05,-0.5,-0.0013,0.0035,-0.078,-0.0014,-0.0059,0.00025,0.015,0.0013,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.5e-05,9.4e-05,6e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-06,1.6e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21290000,0.98,-0.00051,-0.0072,0.19,-0.049,0.054,-0.63,-0.0062,0.0087,-0.14,-0.0014,-0.0059,0.00023,0.015,0.0012,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.6e-05,9.5e-05,6e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-06,1.6e-06,3.1e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.2,-0.0014,-0.0059,0.00023,0.015,0.00089,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.5e-06,9.4e-05,9.2e-05,6e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0093,0.016,-0.29,-0.0014,-0.0059,0.00024,0.015,0.00079,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.4e-05,9.3e-05,6e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,3e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.008,0.016,-0.38,-0.0014,-0.0059,0.00024,0.015,0.00074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.2e-05,9e-05,6e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.49,-0.0014,-0.0059,0.00025,0.015,0.00056,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9.2e-05,9.1e-05,6e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,2.9e-06,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 -21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0038,0.018,-0.61,-0.0014,-0.0058,0.00027,0.016,0.00036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9e-05,8.9e-05,5.9e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,2.9e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0057,0.021,-0.75,-0.0014,-0.0058,0.00026,0.016,0.00024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,9e-05,8.9e-05,5.9e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,2.8e-06,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 -21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00036,0.017,-0.89,-0.0014,-0.0058,0.00027,0.015,0.00047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.8e-05,8.7e-05,5.9e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-06,1.1e-06,2.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0017,0.019,-1,-0.0014,-0.0058,0.00028,0.016,0.00034,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.8e-05,8.7e-05,5.9e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-06,1.1e-06,2.8e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.006,0.013,-1.2,-0.0014,-0.0058,0.00029,0.016,0.00037,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.6e-05,8.5e-05,5.9e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,2.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22290000,0.98,-0.0069,-0.01,0.19,0.0016,0.0078,-1.4,0.0059,0.014,-1.3,-0.0014,-0.0058,0.00028,0.016,0.00028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.7e-05,8.5e-05,5.8e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-06,1.1e-06,2.7e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22390000,0.98,-0.0073,-0.01,0.19,0.0066,-0.0018,-1.4,0.013,0.0041,-1.5,-0.0014,-0.0058,0.00027,0.016,-0.0001,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.5e-05,8.3e-05,5.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1e-06,1e-06,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22490000,0.98,-0.0074,-0.011,0.19,0.01,-0.0078,-1.4,0.014,0.0036,-1.6,-0.0014,-0.0058,0.00026,0.016,-0.00017,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.5e-05,8.4e-05,5.8e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-06,1e-06,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-0.0014,-0.0058,0.00027,0.016,-0.00033,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.3e-05,8.2e-05,5.8e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-07,9.4e-07,2.6e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22690000,0.98,-0.0072,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0073,-1.9,-0.0014,-0.0058,0.00026,0.016,-0.00041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.4e-05,8.2e-05,5.8e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-07,9.4e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22790000,0.98,-0.0072,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-0.0014,-0.0058,0.00025,0.016,-0.00052,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.2e-05,8.1e-05,5.8e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-07,8.9e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.035,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,0.00026,0.016,-0.0006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.4e-06,8.2e-05,8.1e-05,5.7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-0.0014,-0.0058,0.00028,0.017,-0.00074,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8.1e-05,8e-05,5.7e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,2.5e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-0.0014,-0.0058,0.00028,0.017,-0.00077,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8.1e-05,8e-05,5.7e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-07,8.4e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23190000,0.98,-0.0074,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-0.0014,-0.0058,0.00027,0.017,-0.00092,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.9e-05,5.7e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-07,7.9e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23290000,0.98,-0.0079,-0.013,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-0.0014,-0.0058,0.00027,0.017,-0.00098,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.9e-05,5.7e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8e-07,8e-07,2.4e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23390000,0.98,-0.0078,-0.014,0.19,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-0.0014,-0.0058,0.00026,0.017,-0.00071,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.8e-05,5.7e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-07,7.5e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23490000,0.98,-0.0079,-0.014,0.19,0.061,-0.055,-1.4,0.088,-0.061,-3,-0.0014,-0.0058,0.00027,0.017,-0.00076,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,8e-05,7.8e-05,5.6e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-07,7.6e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23590000,0.98,-0.0082,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-0.0014,-0.0058,0.00027,0.017,-0.00088,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.7e-05,5.6e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-07,7.2e-07,2.3e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23690000,0.98,-0.0088,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0059,0.00028,0.017,-0.00091,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.9e-05,7.8e-05,5.6e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-0.0014,-0.0058,0.00029,0.017,-0.00092,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-07,6.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23890000,0.98,-0.014,-0.021,0.18,0.052,-0.059,-0.52,0.12,-0.087,-3.5,-0.0014,-0.0058,0.00029,0.017,-0.00093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-07,6.9e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -23990000,0.98,-0.016,-0.024,0.18,0.054,-0.058,-0.14,0.12,-0.089,-3.6,-0.0014,-0.0058,0.00029,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.6e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-07,6.6e-07,2.2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24090000,0.98,-0.016,-0.023,0.18,0.06,-0.066,0.09,0.13,-0.095,-3.6,-0.0014,-0.0058,0.00028,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-07,6.6e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24190000,0.98,-0.013,-0.019,0.18,0.071,-0.071,0.077,0.14,-0.1,-3.6,-0.0014,-0.0058,0.00029,0.019,-0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.3e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-07,6.3e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00029,0.019,-0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-07,6.3e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,0.00031,0.019,-0.0031,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,2.1e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24490000,0.98,-0.0098,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0031,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24590000,0.98,-0.01,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0038,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.5e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-07,5.9e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24690000,0.98,-0.011,-0.015,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.6,-0.0014,-0.0058,0.00032,0.019,-0.0038,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-07,5.9e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.6,-0.0015,-0.0058,0.00032,0.019,-0.0044,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-07,5.7e-07,2e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0044,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-07,5.7e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0051,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.4e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.6,-0.0015,-0.0058,0.00033,0.019,-0.0051,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.4e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-07,5.5e-07,1.9e-06,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 -25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.6,-0.0015,-0.0058,0.00032,0.019,-0.0056,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.8e-05,7.7e-05,5.3e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-07,5.3e-07,1.9e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25290000,0.98,-0.011,-0.012,0.18,0.032,-0.052,0.029,0.18,-0.11,-3.6,-0.0015,-0.0058,0.0003,0.019,-0.0056,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.3e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-07,5.3e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.028,0.18,-0.1,-3.6,-0.0015,-0.0058,0.0003,0.019,-0.0064,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.7e-05,5.3e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-07,5.1e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25490000,0.98,-0.011,-0.012,0.18,0.019,-0.044,0.027,0.18,-0.11,-3.6,-0.0015,-0.0058,0.0003,0.019,-0.0064,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.1e-07,5.1e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25590000,0.98,-0.012,-0.012,0.18,0.014,-0.04,0.028,0.18,-0.098,-3.6,-0.0015,-0.0058,0.00029,0.018,-0.0067,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-07,5e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25690000,0.98,-0.011,-0.011,0.18,0.013,-0.039,0.017,0.18,-0.1,-3.6,-0.0015,-0.0058,0.00029,0.019,-0.0067,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.2e-06,7.9e-05,7.8e-05,5.3e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-07,5e-07,1.8e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25790000,0.98,-0.011,-0.011,0.18,0.0021,-0.031,0.017,0.17,-0.093,-3.6,-0.0016,-0.0058,0.00028,0.019,-0.0072,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.3e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-07,4.8e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25890000,0.98,-0.011,-0.011,0.19,-0.0037,-0.028,0.019,0.17,-0.096,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0072,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-07,4.8e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -25990000,0.98,-0.011,-0.011,0.19,-0.013,-0.022,0.013,0.16,-0.086,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-07,4.7e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26090000,0.98,-0.01,-0.011,0.18,-0.018,-0.021,0.011,0.16,-0.088,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-07,4.7e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26190000,0.98,-0.01,-0.011,0.18,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-0.0016,-0.0058,0.00027,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,7.9e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-07,4.6e-07,1.7e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26290000,0.98,-0.01,-0.012,0.18,-0.026,-0.014,0.00051,0.15,-0.083,-3.6,-0.0016,-0.0058,0.00026,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-07,4.6e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26390000,0.98,-0.0098,-0.012,0.18,-0.032,-0.0064,0.0045,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00025,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.8e-05,5.2e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.4e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0033,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,0.00024,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26590000,0.98,-0.009,-0.012,0.18,-0.036,0.0047,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,0.00023,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.3e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0098,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,0.00021,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-07,4.3e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26790000,0.98,-0.0087,-0.011,0.18,-0.045,0.013,0.012,0.11,-0.062,-3.6,-0.0016,-0.0058,0.0002,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-07,4.2e-07,1.6e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26890000,0.98,-0.008,-0.011,0.18,-0.051,0.017,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,0.0002,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-07,4.2e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -26990000,0.98,-0.0075,-0.011,0.18,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-0.0016,-0.0058,0.0002,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5.1e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4.1e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27090000,0.98,-0.0073,-0.012,0.18,-0.06,0.03,0.0089,0.082,-0.052,-3.6,-0.0016,-0.0058,0.00019,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-07,4.1e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27190000,0.98,-0.0074,-0.012,0.18,-0.066,0.036,0.011,0.071,-0.046,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3.1e-06,8e-05,7.9e-05,5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-07,4e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27290000,0.98,-0.0076,-0.013,0.18,-0.073,0.042,0.12,0.064,-0.042,-3.6,-0.0016,-0.0058,0.00018,0.02,-0.0092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8e-05,7.9e-05,5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-07,4e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27390000,0.98,-0.009,-0.015,0.18,-0.078,0.047,0.45,0.055,-0.035,-3.5,-0.0016,-0.0058,0.00018,0.02,-0.0094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8e-05,7.9e-05,5e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.5e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27490000,0.98,-0.01,-0.017,0.18,-0.081,0.053,0.76,0.047,-0.029,-3.5,-0.0016,-0.0058,0.00016,0.02,-0.0095,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.014,0.014,0.008,0.042,0.042,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27590000,0.98,-0.01,-0.016,0.18,-0.075,0.055,0.85,0.038,-0.025,-3.4,-0.0016,-0.0058,0.00016,0.02,-0.0096,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27690000,0.98,-0.009,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-0.0016,-0.0058,0.00015,0.02,-0.0097,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,7.9e-05,5e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,1.4e-06,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 -27790000,0.98,-0.0076,-0.011,0.18,-0.071,0.05,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,0.00015,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27890000,0.98,-0.0073,-0.012,0.18,-0.078,0.057,0.79,0.017,-0.012,-3.2,-0.0016,-0.0058,0.00015,0.02,-0.0091,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -27990000,0.98,-0.0077,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.011,-3.1,-0.0016,-0.0058,0.00015,0.02,-0.0088,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0043,-0.0047,-3,-0.0016,-0.0058,0.00015,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.7e-07,3.7e-07,1.4e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28190000,0.98,-0.0074,-0.012,0.18,-0.082,0.055,0.79,-0.0023,-0.0043,-3,-0.0016,-0.0058,0.00015,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28290000,0.98,-0.0069,-0.012,0.18,-0.087,0.059,0.79,-0.011,0.0015,-2.9,-0.0016,-0.0058,0.00015,0.02,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28390000,0.98,-0.0069,-0.013,0.18,-0.088,0.061,0.79,-0.015,0.0044,-2.8,-0.0015,-0.0058,0.00016,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28490000,0.98,-0.0072,-0.014,0.18,-0.089,0.066,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,0.00015,0.02,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28590000,0.98,-0.0073,-0.014,0.18,-0.083,0.061,0.79,-0.027,0.0084,-2.7,-0.0015,-0.0058,0.00015,0.02,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28690000,0.98,-0.007,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.6,-0.0015,-0.0058,0.00015,0.02,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,0.00015,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28890000,0.98,-0.0062,-0.012,0.18,-0.084,0.064,0.78,-0.046,0.023,-2.5,-0.0015,-0.0058,0.00016,0.02,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,1.3e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.4,-0.0015,-0.0058,0.00016,0.02,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,3e-06,8.2e-05,8.1e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,0.00015,0.02,-0.0087,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,0.00016,0.02,-0.0089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29290000,0.98,-0.0061,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.034,-2.2,-0.0015,-0.0058,0.00016,0.02,-0.009,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.065,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,0.00016,0.02,-0.0091,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,0.00017,0.02,-0.0092,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,0.00018,0.02,-0.0094,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29690000,0.98,-0.0065,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.9,-0.0015,-0.0058,0.00019,0.02,-0.0095,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.7e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,1.2e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29790000,0.98,-0.0063,-0.013,0.18,-0.074,0.056,0.78,-0.065,0.044,-1.8,-0.0014,-0.0058,0.00019,0.02,-0.0097,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29890000,0.98,-0.0058,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-0.0014,-0.0058,0.0002,0.02,-0.0099,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -29990000,0.98,-0.0059,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,0.0002,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30090000,0.98,-0.0061,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.6,-0.0014,-0.0058,0.00019,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30190000,0.98,-0.006,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,0.00018,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30290000,0.98,-0.0061,-0.013,0.19,-0.062,0.05,0.77,-0.074,0.053,-1.4,-0.0014,-0.0057,0.00018,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.6e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30390000,0.98,-0.0061,-0.013,0.19,-0.055,0.044,0.76,-0.066,0.049,-1.4,-0.0014,-0.0057,0.00019,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.6e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30490000,0.98,-0.0061,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.3,-0.0014,-0.0057,0.0002,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.3e-05,8.1e-05,4.5e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30590000,0.98,-0.0064,-0.014,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-0.0014,-0.0057,0.00021,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30690000,0.98,-0.0068,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-0.0014,-0.0057,0.00021,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-07,3e-07,1.1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30790000,0.98,-0.0065,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1.1,-0.0014,-0.0057,0.00021,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30890000,0.98,-0.0058,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-0.0014,-0.0057,0.0002,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -30990000,0.98,-0.006,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.94,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31090000,0.98,-0.0062,-0.013,0.19,-0.035,0.025,0.76,-0.061,0.051,-0.86,-0.0014,-0.0057,0.00019,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-07,3e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31190000,0.98,-0.0064,-0.013,0.18,-0.031,0.021,0.76,-0.052,0.046,-0.79,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.5e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-07,2.9e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.72,-0.0014,-0.0057,0.00021,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.9e-06,8.2e-05,8.1e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1e-06,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31390000,0.98,-0.0064,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.65,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,9.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31490000,0.98,-0.0061,-0.014,0.19,-0.022,0.009,0.76,-0.049,0.043,-0.58,-0.0014,-0.0057,0.0002,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8.1e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,9.8e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31590000,0.98,-0.006,-0.014,0.18,-0.018,0.0067,0.76,-0.038,0.039,-0.51,-0.0014,-0.0057,0.00021,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,9.7e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31690000,0.98,-0.006,-0.015,0.18,-0.02,0.0057,0.76,-0.04,0.039,-0.44,-0.0014,-0.0057,0.00022,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,9.6e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31790000,0.98,-0.0062,-0.015,0.18,-0.011,0.0031,0.76,-0.028,0.037,-0.36,-0.0014,-0.0057,0.00022,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.4e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-07,2.8e-07,9.6e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31890000,0.98,-0.0059,-0.015,0.18,-0.008,0.00081,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,0.00023,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.2e-05,8e-05,4.4e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -31990000,0.98,-0.0062,-0.015,0.18,-0.0001,0.00015,0.75,-0.017,0.034,-0.23,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.4e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,9.4e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32090000,0.98,-0.0065,-0.014,0.18,-0.00064,-0.0033,0.76,-0.017,0.034,-0.16,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32190000,0.98,-0.0067,-0.015,0.18,0.0047,-0.0065,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,9.2e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32290000,0.98,-0.0066,-0.015,0.18,0.0063,-0.0092,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,0.00022,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,9.2e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32390000,0.98,-0.0067,-0.015,0.18,0.013,-0.01,0.75,0.0057,0.03,0.051,-0.0013,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,7.9e-05,4.3e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-07,2.7e-07,9.1e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.073,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8.1e-05,8e-05,4.3e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32590000,0.98,-0.0095,-0.013,0.18,0.039,-0.075,-0.12,0.021,0.02,0.035,-0.0014,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8e-05,7.8e-05,4.3e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-07,2.7e-07,8.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32690000,0.98,-0.0095,-0.013,0.18,0.035,-0.08,-0.12,0.025,0.012,0.02,-0.0014,-0.0057,0.00022,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,8e-05,7.9e-05,4.3e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-07,2.7e-07,8.9e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32790000,0.98,-0.0092,-0.013,0.18,0.034,-0.078,-0.12,0.034,0.01,0.0044,-0.0014,-0.0057,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.7e-05,7.6e-05,4.3e-05,0.019,0.02,0.0071,0.037,0.037,0.035,2.7e-07,2.7e-07,8.8e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32890000,0.98,-0.0092,-0.013,0.18,0.033,-0.084,-0.13,0.038,0.0021,-0.011,-0.0014,-0.0057,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.7e-05,7.6e-05,4.2e-05,0.023,0.023,0.007,0.041,0.041,0.035,2.7e-07,2.7e-07,8.7e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.0011,-0.024,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.3e-05,7.2e-05,4.2e-05,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-07,2.7e-07,8.7e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33090000,0.98,-0.0088,-0.013,0.18,0.026,-0.083,-0.12,0.048,-0.0092,-0.031,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,7.3e-05,7.2e-05,4.2e-05,0.028,0.029,0.0066,0.042,0.042,0.035,2.7e-07,2.7e-07,8.6e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33190000,0.98,-0.0085,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-0.0014,-0.0056,0.00023,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.7e-05,6.6e-05,4.2e-05,0.029,0.029,0.0064,0.038,0.038,0.035,2.6e-07,2.6e-07,8.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33290000,0.98,-0.0086,-0.013,0.18,0.019,-0.08,-0.12,0.056,-0.019,-0.045,-0.0014,-0.0056,0.00024,0.026,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.7e-05,6.6e-05,4.2e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-07,2.6e-07,8.5e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,0.00024,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.1e-05,6e-05,4.2e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-07,2.6e-07,8.4e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33490000,0.98,-0.0081,-0.013,0.18,0.0094,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,0.00024,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.8e-06,6.1e-05,6e-05,4.2e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-07,2.6e-07,8.3e-07,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 -33590000,0.98,-0.0077,-0.013,0.18,0.0055,-0.058,-0.11,0.063,-0.017,-0.069,-0.0014,-0.0056,0.00025,0.025,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,5.3e-05,5.3e-05,4.2e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-07,2.6e-07,8.3e-07,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 -33690000,0.98,-0.0077,-0.013,0.18,0.00078,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,0.00025,0.025,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,5.4e-05,5.3e-05,4.2e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-07,2.6e-07,8.2e-07,0.026,0.027,0.0005,0,0,0,0,0,0,0,0 -33790000,0.98,-0.0075,-0.013,0.18,-0.0024,-0.047,-0.11,0.067,-0.018,-0.083,-0.0014,-0.0056,0.00024,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.7e-05,4.6e-05,4.1e-05,0.045,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,8.1e-07,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 -33890000,0.98,-0.0075,-0.013,0.18,-0.0066,-0.045,-0.11,0.066,-0.023,-0.089,-0.0014,-0.0056,0.00025,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.7e-05,4.6e-05,4.1e-05,0.052,0.053,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,8.1e-07,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 -33990000,0.98,-0.0072,-0.013,0.18,-0.0062,-0.031,-0.1,0.069,-0.015,-0.092,-0.0014,-0.0056,0.00024,0.021,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.1e-05,4.1e-05,4.1e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,8e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 -34090000,0.98,-0.0072,-0.013,0.18,-0.011,-0.031,-0.1,0.069,-0.018,-0.096,-0.0014,-0.0056,0.00024,0.021,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,4.1e-05,4.1e-05,4.1e-05,0.054,0.055,0.0058,0.049,0.049,0.033,2.6e-07,2.6e-07,8e-07,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 -34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.02,-0.098,0.072,-0.013,-0.099,-0.0014,-0.0056,0.00024,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.7e-05,3.6e-05,4.1e-05,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-07,2.6e-07,7.9e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 -34290000,0.98,-0.0069,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-0.0014,-0.0056,0.00024,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.7e-05,3.7e-05,4.1e-05,0.055,0.055,0.0058,0.05,0.05,0.033,2.6e-07,2.6e-07,7.8e-07,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 -34390000,0.98,-0.0068,-0.013,0.18,-0.013,-0.01,-0.092,0.073,-0.01,-0.11,-0.0014,-0.0056,0.00024,0.018,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.3e-05,3.3e-05,4.1e-05,0.047,0.047,0.0058,0.044,0.044,0.033,2.6e-07,2.6e-07,7.8e-07,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 -34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0091,-0.089,0.071,-0.011,-0.11,-0.0014,-0.0056,0.00024,0.017,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.4e-05,3.3e-05,4.1e-05,0.053,0.054,0.0059,0.051,0.051,0.032,2.6e-07,2.6e-07,7.7e-07,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 -34590000,0.98,-0.0069,-0.013,0.18,-0.014,-0.0049,0.71,0.073,-0.0087,-0.081,-0.0014,-0.0056,0.00024,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.1e-05,3.1e-05,4.1e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-07,2.6e-07,7.7e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 -34690000,0.98,-0.0068,-0.012,0.18,-0.017,-0.0027,1.7,0.071,-0.0091,0.038,-0.0014,-0.0056,0.00023,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3.1e-05,3.1e-05,4.1e-05,0.047,0.048,0.006,0.052,0.052,0.032,2.6e-07,2.6e-07,7.6e-07,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 -34790000,0.98,-0.0068,-0.012,0.18,-0.019,0.0019,2.7,0.072,-0.0068,0.21,-0.0014,-0.0056,0.00023,0.018,-0.029,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3e-05,2.9e-05,4e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-07,2.6e-07,7.6e-07,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 -34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0043,3.6,0.07,-0.0063,0.5,-0.0014,-0.0056,0.00023,0.018,-0.03,-0.1,0.37,0.0037,0.025,0,0,0,0,0,2.7e-06,3e-05,3e-05,4e-05,0.044,0.044,0.0061,0.052,0.052,0.032,2.6e-07,2.6e-07,7.5e-07,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 +6190000,0.98,-0.0066,-0.013,0.19,0.0098,0.016,-0.037,0.0045,0.0054,-0.047,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.0054,0.22,0.22,0.042,0.13,0.13,0.073,0.00015,0.00015,1.1e-05,0.04,0.04,0.0044,0,0,0,0,0,0,0,0 +6290000,0.98,-0.0065,-0.013,0.19,0.0083,0.018,-0.041,0.0054,0.0071,-0.053,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.0054,0.22,0.22,0.04,0.16,0.16,0.072,0.00015,0.00015,1.1e-05,0.04,0.04,0.0041,0,0,0,0,0,0,0,0 +6390000,0.98,-0.0065,-0.013,0.19,0.01,0.02,-0.042,0.0064,0.009,-0.056,-0.0019,-0.0056,9.4e-05,0,0,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00034,0.00034,0.0054,0.23,0.23,0.039,0.19,0.19,0.072,0.00015,0.00015,1.1e-05,0.04,0.04,0.0038,0,0,0,0,0,0,0,0 +6490000,0.98,-0.0064,-0.013,0.19,0.0084,0.019,-0.039,0.0073,0.011,-0.053,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00035,0.00034,0.0054,0.24,0.24,0.038,0.23,0.23,0.07,0.00015,0.00015,1.1e-05,0.04,0.04,0.0036,0,0,0,0,0,0,0,0 +6590000,0.98,-0.0064,-0.013,0.19,0.0077,0.022,-0.042,0.0081,0.013,-0.056,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00035,0.00035,0.0054,0.26,0.26,0.036,0.28,0.28,0.069,0.00015,0.00015,1.1e-05,0.04,0.04,0.0033,0,0,0,0,0,0,0,0 +6690000,0.98,-0.0063,-0.013,0.19,0.0052,0.025,-0.044,0.0088,0.015,-0.057,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00035,0.00035,0.0054,0.28,0.28,0.035,0.33,0.33,0.068,0.00015,0.00015,1.1e-05,0.04,0.04,0.0031,0,0,0,0,0,0,0,0 +6790000,0.98,-0.0063,-0.013,0.19,0.007,0.027,-0.042,0.0093,0.018,-0.058,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00036,0.00036,0.0054,0.3,0.3,0.034,0.38,0.38,0.068,0.00015,0.00015,1.1e-05,0.04,0.04,0.0029,0,0,0,0,0,0,0,0 +6890000,0.98,-0.0061,-0.013,0.19,0.0066,0.028,-0.038,0.01,0.02,-0.055,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00036,0.00036,0.0054,0.32,0.32,0.032,0.45,0.45,0.067,0.00015,0.00015,1.1e-05,0.04,0.04,0.0027,0,0,0,0,0,0,0,0 +6990000,0.98,-0.006,-0.013,0.19,0.0066,0.029,-0.037,0.011,0.023,-0.055,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00037,0.00037,0.0054,0.35,0.35,0.031,0.52,0.52,0.066,0.00015,0.00015,1.1e-05,0.04,0.04,0.0026,0,0,0,0,0,0,0,0 +7090000,0.98,-0.0059,-0.013,0.19,0.0057,0.035,-0.037,0.011,0.026,-0.056,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00038,0.00037,0.0054,0.39,0.39,0.03,0.6,0.6,0.066,0.00015,0.00015,1.1e-05,0.04,0.04,0.0024,0,0,0,0,0,0,0,0 +7190000,0.98,-0.0058,-0.013,0.19,0.0053,0.038,-0.036,0.012,0.03,-0.058,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00038,0.00038,0.0054,0.42,0.42,0.029,0.69,0.69,0.065,0.00015,0.00015,1.1e-05,0.04,0.04,0.0023,0,0,0,0,0,0,0,0 +7290000,0.98,-0.0058,-0.013,0.19,0.0061,0.042,-0.034,0.012,0.034,-0.054,-0.0019,-0.0056,9.4e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.0002,0.00039,0.00039,0.0054,0.46,0.46,0.028,0.79,0.79,0.064,0.00015,0.00015,1.1e-05,0.04,0.04,0.0021,0,0,0,0,0,0,0,0 +7390000,0.98,-0.0057,-0.013,0.19,0.0045,0.046,-0.032,0.013,0.038,-0.052,-0.0019,-0.0056,9.6e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0004,0.0004,0.0043,0.51,0.51,0.027,0.9,0.9,0.064,0.00014,0.00014,1.1e-05,0.04,0.04,0.002,0,0,0,0,0,0,0,0 +7490000,0.98,-0.0057,-0.013,0.19,0.0069,0.05,-0.026,0.013,0.043,-0.046,-0.0019,-0.0056,9.6e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00041,0.00041,0.0043,0.56,0.56,0.026,1,1,0.063,0.00014,0.00014,1.1e-05,0.04,0.04,0.0019,0,0,0,0,0,0,0,0 +7590000,0.98,-0.0058,-0.013,0.19,0.0078,0.053,-0.023,0.014,0.048,-0.041,-0.0019,-0.0056,9.6e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00042,0.00042,0.0043,0.6,0.61,0.025,1.2,1.2,0.062,0.00014,0.00014,1.1e-05,0.04,0.04,0.0018,0,0,0,0,0,0,0,0 +7690000,0.98,-0.0058,-0.013,0.19,0.0076,0.057,-0.022,0.015,0.053,-0.036,-0.0019,-0.0056,9.6e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00043,0.00043,0.0043,0.66,0.66,0.025,1.3,1.3,0.062,0.00014,0.00014,1.1e-05,0.04,0.04,0.0017,0,0,0,0,0,0,0,0 +7790000,0.98,-0.0056,-0.013,0.19,0.0091,0.06,-0.024,0.015,0.058,-0.041,-0.0019,-0.0056,9.5e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00044,0.00043,0.0043,0.72,0.72,0.024,1.5,1.5,0.061,0.00014,0.00014,1.1e-05,0.04,0.04,0.0016,0,0,0,0,0,0,0,0 +7890000,0.98,-0.0056,-0.013,0.19,0.0078,0.065,-0.025,0.016,0.064,-0.045,-0.0019,-0.0056,9.5e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00045,0.00045,0.0043,0.78,0.78,0.023,1.7,1.7,0.06,0.00014,0.00014,1.1e-05,0.04,0.04,0.0015,0,0,0,0,0,0,0,0 +7990000,0.98,-0.0056,-0.013,0.19,0.008,0.068,-0.021,0.017,0.07,-0.041,-0.0019,-0.0056,9.5e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00046,0.00045,0.0043,0.84,0.84,0.022,1.9,1.9,0.059,0.00014,0.00014,1.1e-05,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 +8090000,0.98,-0.0054,-0.013,0.19,0.0096,0.073,-0.022,0.017,0.077,-0.044,-0.0019,-0.0056,9.5e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00047,0.00047,0.0043,0.92,0.92,0.022,2.1,2.1,0.059,0.00014,0.00014,1.1e-05,0.04,0.04,0.0014,0,0,0,0,0,0,0,0 +8190000,0.98,-0.0055,-0.013,0.19,0.01,0.08,-0.018,0.018,0.085,-0.038,-0.0019,-0.0056,9.5e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00048,0.00048,0.0043,1,1,0.021,2.4,2.4,0.058,0.00014,0.00014,1.1e-05,0.04,0.04,0.0013,0,0,0,0,0,0,0,0 +8290000,0.98,-0.0055,-0.013,0.19,0.012,0.084,-0.016,0.019,0.091,-0.038,-0.0019,-0.0056,9.5e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00049,0.00049,0.0043,1.1,1.1,0.02,2.6,2.6,0.057,0.00014,0.00014,1.1e-05,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 +8390000,0.98,-0.0054,-0.013,0.19,0.01,0.087,-0.015,0.02,0.099,-0.036,-0.0019,-0.0056,9.5e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0005,0.0005,0.0043,1.1,1.1,0.02,2.9,2.9,0.057,0.00014,0.00014,1.1e-05,0.04,0.04,0.0012,0,0,0,0,0,0,0,0 +8490000,0.98,-0.0053,-0.013,0.19,0.0098,0.091,-0.017,0.021,0.11,-0.041,-0.0018,-0.0056,9.5e-05,0,0,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00051,0.00051,0.0044,1.2,1.2,0.019,3.2,3.2,0.056,0.00014,0.00014,1.1e-05,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 +8590000,0.98,-0.0053,-0.013,0.19,0.011,0.095,-0.012,0.022,0.11,-0.036,-0.0018,-0.0056,9.5e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00052,0.00052,0.0044,1.3,1.3,0.018,3.6,3.6,0.055,0.00014,0.00014,1.1e-05,0.04,0.04,0.0011,0,0,0,0,0,0,0,0 +8690000,0.98,-0.0053,-0.013,0.19,0.011,0.096,-0.014,0.022,0.12,-0.037,-0.0018,-0.0056,9.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00053,0.00053,0.0044,1.4,1.4,0.018,3.9,3.9,0.055,0.00013,0.00013,1.1e-05,0.04,0.04,0.001,0,0,0,0,0,0,0,0 +8790000,0.98,-0.0053,-0.013,0.19,0.012,0.1,-0.013,0.023,0.13,-0.035,-0.0018,-0.0056,9.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00054,0.00054,0.0044,1.5,1.5,0.018,4.3,4.3,0.055,0.00013,0.00013,1.1e-05,0.04,0.04,0.00096,0,0,0,0,0,0,0,0 +8890000,0.98,-0.0054,-0.013,0.19,0.012,0.1,-0.0091,0.023,0.13,-0.029,-0.0018,-0.0056,9.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00054,0.00054,0.0044,1.5,1.5,0.017,4.6,4.6,0.054,0.00013,0.00013,1.1e-05,0.04,0.04,0.00091,0,0,0,0,0,0,0,0 +8990000,0.98,-0.0053,-0.013,0.19,0.011,0.11,-0.0083,0.024,0.14,-0.032,-0.0018,-0.0056,9.4e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00056,0.00056,0.0044,1.6,1.6,0.017,5.2,5.2,0.054,0.00013,0.00013,1.1e-05,0.04,0.04,0.00088,0,0,0,0,0,0,0,0 +9090000,0.98,-0.0053,-0.013,0.19,0.011,0.11,-0.0093,0.024,0.15,-0.032,-0.0018,-0.0056,9.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00055,0.00055,0.0044,1.7,1.7,0.016,5.4,5.5,0.053,0.00013,0.00013,1.1e-05,0.04,0.04,0.00084,0,0,0,0,0,0,0,0 +9190000,0.98,-0.0053,-0.013,0.19,0.015,0.11,-0.0088,0.025,0.16,-0.032,-0.0018,-0.0056,9.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,1.8,1.8,0.016,6.1,6.1,0.052,0.00013,0.00013,1.1e-05,0.04,0.04,0.0008,0,0,0,0,0,0,0,0 +9290000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0072,0.026,0.16,-0.03,-0.0017,-0.0056,9.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00056,0.00056,0.0044,1.8,1.8,0.015,6.3,6.3,0.052,0.00012,0.00012,1.1e-05,0.04,0.04,0.00076,0,0,0,0,0,0,0,0 +9390000,0.98,-0.0051,-0.013,0.19,0.017,0.12,-0.006,0.027,0.17,-0.03,-0.0017,-0.0056,9.3e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,1.9,1.9,0.015,7,7,0.052,0.00012,0.00012,1.1e-05,0.04,0.04,0.00073,0,0,0,0,0,0,0,0 +9490000,0.98,-0.0052,-0.013,0.19,0.016,0.11,-0.0044,0.027,0.17,-0.027,-0.0017,-0.0056,9.2e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00056,0.00056,0.0044,1.9,1.9,0.015,7.2,7.2,0.051,0.00012,0.00012,1.1e-05,0.04,0.04,0.0007,0,0,0,0,0,0,0,0 +9590000,0.98,-0.0053,-0.013,0.19,0.016,0.12,-0.0043,0.028,0.18,-0.028,-0.0017,-0.0056,9.2e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,2,2,0.014,7.9,7.9,0.05,0.00012,0.00012,1.1e-05,0.04,0.04,0.00067,0,0,0,0,0,0,0,0 +9690000,0.98,-0.0054,-0.013,0.19,0.015,0.11,-0.0014,0.028,0.18,-0.027,-0.0017,-0.0056,9.1e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00055,0.00055,0.0044,2,2,0.014,8.1,8.1,0.05,0.00012,0.00012,1.1e-05,0.04,0.04,0.00065,0,0,0,0,0,0,0,0 +9790000,0.98,-0.0053,-0.013,0.19,0.017,0.12,-0.0027,0.029,0.19,-0.028,-0.0017,-0.0056,9.1e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,2.1,2.2,0.014,8.9,8.9,0.05,0.00012,0.00012,1.1e-05,0.04,0.04,0.00062,0,0,0,0,0,0,0,0 +9890000,0.98,-0.0054,-0.013,0.19,0.018,0.11,-0.0014,0.028,0.19,-0.029,-0.0016,-0.0056,9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00054,0.00054,0.0044,2.1,2.1,0.013,8.9,8.9,0.049,0.00011,0.00011,1.1e-05,0.04,0.04,0.0006,0,0,0,0,0,0,0,0 +9990000,0.98,-0.0054,-0.013,0.19,0.02,0.11,-0.00072,0.03,0.2,-0.031,-0.0016,-0.0056,9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00056,0.00056,0.0044,2.2,2.2,0.013,9.8,9.8,0.049,0.00011,0.00011,1.1e-05,0.04,0.04,0.00058,0,0,0,0,0,0,0,0 +10090000,0.98,-0.0055,-0.013,0.19,0.017,0.11,0.00048,0.029,0.19,-0.029,-0.0016,-0.0057,9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00053,0.00053,0.0044,2.1,2.1,0.013,9.7,9.7,0.048,0.00011,0.00011,1.1e-05,0.04,0.04,0.00056,0,0,0,0,0,0,0,0 +10190000,0.98,-0.0055,-0.013,0.19,0.016,0.11,0.0014,0.031,0.2,-0.03,-0.0016,-0.0057,9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00055,0.00055,0.0044,2.3,2.3,0.012,11,11,0.048,0.00011,0.00011,1.1e-05,0.04,0.04,0.00054,0,0,0,0,0,0,0,0 +10290000,0.98,-0.0055,-0.013,0.19,0.017,0.11,0.0003,0.032,0.21,-0.029,-0.0016,-0.0057,9e-05,0,0,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,2.4,2.4,0.012,12,12,0.048,0.00011,0.00011,1.1e-05,0.04,0.04,0.00052,0,0,0,0,0,0,0,0 +10390000,0.98,-0.0055,-0.013,0.19,0.0071,0.0052,-0.0025,0.00076,0.00015,-0.028,-0.0016,-0.0057,9e-05,-3.6e-08,2.5e-08,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00059,0.00059,0.0044,0.25,0.25,0.56,0.25,0.25,0.048,0.00011,0.00011,1.1e-05,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10490000,0.98,-0.0054,-0.012,0.19,0.0085,0.0077,0.007,0.0015,0.00076,-0.023,-0.0016,-0.0057,9e-05,-1.2e-06,8.3e-07,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00061,0.0006,0.0044,0.26,0.26,0.55,0.26,0.26,0.057,0.00011,0.00011,1.1e-05,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10590000,0.98,-0.0053,-0.012,0.19,-0.0012,0.0055,0.013,-0.0012,-0.0054,-0.021,-0.0016,-0.0057,8.9e-05,0.00032,1e-05,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00061,0.00061,0.0044,0.13,0.13,0.27,0.13,0.13,0.055,0.00011,0.00011,1.1e-05,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10690000,0.98,-0.0053,-0.012,0.19,-4.6e-05,0.0067,0.016,-0.0012,-0.0048,-0.017,-0.0016,-0.0057,8.9e-05,0.00032,1.1e-05,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00063,0.00063,0.0044,0.15,0.15,0.26,0.14,0.14,0.065,0.00011,0.00011,1.1e-05,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10790000,0.98,-0.0054,-0.012,0.19,0.0018,0.0031,0.014,-0.00078,-0.0047,-0.015,-0.0016,-0.0057,8.8e-05,0.00052,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00062,0.00062,0.0044,0.1,0.1,0.17,0.091,0.091,0.062,0.00011,0.00011,1.1e-05,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10890000,0.98,-0.0054,-0.013,0.19,0.0019,0.0066,0.01,-0.00058,-0.0042,-0.018,-0.0016,-0.0057,8.8e-05,0.00052,0.00048,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00064,0.00064,0.0044,0.12,0.12,0.16,0.098,0.098,0.068,0.00011,0.00011,1.1e-05,0.04,0.04,0.0005,0,0,0,0,0,0,0,0 +10990000,0.98,-0.0054,-0.013,0.19,0.0014,0.012,0.016,-0.00045,-0.003,-0.011,-0.0015,-0.0057,8.8e-05,0.00067,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0006,0.0006,0.0044,0.096,0.096,0.12,0.073,0.073,0.065,9.9e-05,9.9e-05,1.1e-05,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 +11090000,0.98,-0.0056,-0.013,0.19,0.0024,0.017,0.02,-0.00029,-0.0016,-0.0074,-0.0015,-0.0057,8.8e-05,0.00067,0.00072,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00062,0.00062,0.0044,0.12,0.12,0.11,0.08,0.08,0.069,9.9e-05,9.9e-05,1.1e-05,0.039,0.039,0.0005,0,0,0,0,0,0,0,0 +11190000,0.98,-0.0059,-0.013,0.19,0.0041,0.017,0.026,0.0011,-0.0018,-0.00035,-0.0015,-0.0057,8.6e-05,0.00066,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00055,0.00055,0.0044,0.096,0.096,0.083,0.063,0.063,0.066,9.1e-05,9.2e-05,1.1e-05,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11290000,0.98,-0.0058,-0.013,0.19,0.0043,0.018,0.026,0.0015,-2.6e-05,-0.00012,-0.0015,-0.0057,8.6e-05,0.00067,0.0016,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00057,0.00057,0.0044,0.12,0.12,0.077,0.07,0.07,0.069,9.1e-05,9.2e-05,1.1e-05,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11390000,0.98,-0.006,-0.013,0.19,0.0026,0.015,0.016,0.0009,-0.00088,-0.0086,-0.0014,-0.0058,8.4e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00049,0.00049,0.0044,0.097,0.097,0.062,0.057,0.057,0.066,8.3e-05,8.3e-05,1.1e-05,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11490000,0.98,-0.0059,-0.013,0.19,0.0017,0.016,0.02,0.001,0.00072,-0.0025,-0.0014,-0.0058,8.4e-05,0.0012,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0005,0.0005,0.0044,0.12,0.12,0.057,0.065,0.065,0.067,8.3e-05,8.3e-05,1.1e-05,0.038,0.038,0.0005,0,0,0,0,0,0,0,0 +11590000,0.98,-0.0063,-0.012,0.19,0.0035,0.013,0.018,0.00085,-0.00036,-0.0036,-0.0013,-0.0058,8.3e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00042,0.00042,0.0044,0.096,0.096,0.048,0.054,0.054,0.065,7.5e-05,7.5e-05,1.1e-05,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 +11690000,0.98,-0.0062,-0.012,0.19,0.0039,0.017,0.018,0.0012,0.0011,-0.0049,-0.0013,-0.0058,8.3e-05,0.0015,0.0028,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00044,0.00044,0.0044,0.12,0.12,0.044,0.062,0.062,0.066,7.5e-05,7.5e-05,1.1e-05,0.037,0.037,0.0005,0,0,0,0,0,0,0,0 +11790000,0.98,-0.0066,-0.012,0.19,0.0026,0.011,0.019,0.0007,-0.0018,-0.002,-0.0012,-0.0059,8e-05,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00037,0.00037,0.0044,0.092,0.092,0.037,0.052,0.052,0.063,6.8e-05,6.8e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +11890000,0.98,-0.0067,-0.012,0.19,0.0052,0.012,0.017,0.001,-0.0007,-0.0013,-0.0012,-0.0059,8e-05,0.002,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00038,0.00038,0.0044,0.11,0.11,0.034,0.061,0.061,0.063,6.8e-05,6.8e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +11990000,0.98,-0.0069,-0.012,0.19,0.0082,0.012,0.015,0.0021,-0.0018,-0.0049,-0.0012,-0.0059,8e-05,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00032,0.00032,0.0044,0.088,0.088,0.03,0.051,0.051,0.061,6.2e-05,6.2e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12090000,0.98,-0.0068,-0.012,0.19,0.0098,0.012,0.018,0.003,-0.00064,0.0011,-0.0012,-0.0059,8e-05,0.002,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00033,0.00033,0.0044,0.11,0.11,0.027,0.06,0.06,0.06,6.2e-05,6.2e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12190000,0.98,-0.0067,-0.012,0.19,0.0078,0.011,0.017,0.0018,0.00039,0.0029,-0.0012,-0.0059,8e-05,0.0022,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00029,0.00029,0.0044,0.083,0.083,0.024,0.05,0.05,0.058,5.7e-05,5.7e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12290000,0.98,-0.0068,-0.012,0.19,0.0055,0.01,0.016,0.0025,0.0015,0.0039,-0.0012,-0.0059,8e-05,0.0023,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.0003,0.0003,0.0044,0.098,0.098,0.022,0.059,0.059,0.058,5.7e-05,5.7e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12390000,0.98,-0.0069,-0.012,0.19,0.0041,0.0072,0.014,0.0017,0.00048,-0.0021,-0.0012,-0.006,7.9e-05,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00026,0.00026,0.0044,0.078,0.078,0.02,0.05,0.05,0.056,5.3e-05,5.3e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12490000,0.98,-0.0069,-0.012,0.19,0.0041,0.0082,0.018,0.0021,0.0013,-6.6e-05,-0.0012,-0.006,7.9e-05,0.0025,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00027,0.00027,0.0044,0.091,0.091,0.018,0.059,0.059,0.055,5.3e-05,5.3e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12590000,0.98,-0.0071,-0.012,0.19,0.0078,0.0015,0.02,0.0033,-0.0014,0.0017,-0.0011,-0.006,7.8e-05,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00024,0.00024,0.0044,0.072,0.072,0.017,0.049,0.049,0.054,5e-05,5e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12690000,0.98,-0.0071,-0.012,0.19,0.0083,-0.00068,0.019,0.0041,-0.0013,0.0033,-0.0011,-0.006,7.8e-05,0.0025,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00025,0.00025,0.0044,0.084,0.084,0.016,0.058,0.058,0.053,5e-05,5e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12790000,0.98,-0.0073,-0.012,0.19,0.0099,-0.0041,0.021,0.0041,-0.0044,0.0054,-0.0011,-0.006,7.7e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00023,0.00023,0.0044,0.068,0.068,0.014,0.049,0.049,0.052,4.7e-05,4.7e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12890000,0.98,-0.0073,-0.012,0.19,0.01,-0.005,0.022,0.0052,-0.0049,0.0085,-0.0011,-0.006,7.7e-05,0.0026,0.0042,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00024,0.00024,0.0045,0.078,0.078,0.013,0.058,0.058,0.051,4.7e-05,4.7e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +12990000,0.98,-0.0073,-0.012,0.19,0.0079,-0.003,0.022,0.0036,-0.0036,0.0096,-0.0011,-0.006,7.7e-05,0.0026,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00016,0.00022,0.00022,0.0045,0.064,0.064,0.012,0.049,0.049,0.05,4.5e-05,4.5e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13090000,0.98,-0.0073,-0.012,0.19,0.0088,-0.0029,0.02,0.0044,-0.0038,0.0085,-0.0011,-0.006,7.7e-05,0.0027,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00023,0.00023,0.0045,0.073,0.073,0.012,0.057,0.057,0.049,4.5e-05,4.5e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13190000,0.98,-0.0073,-0.012,0.19,0.0038,-0.0045,0.019,0.00095,-0.0046,0.0091,-0.0011,-0.006,7.7e-05,0.0027,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00021,0.00021,0.0045,0.06,0.06,0.011,0.049,0.049,0.047,4.3e-05,4.3e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13290000,0.98,-0.0073,-0.012,0.19,0.0034,-0.0055,0.016,0.0013,-0.005,0.0085,-0.0011,-0.006,7.7e-05,0.0028,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00022,0.00022,0.0045,0.068,0.068,0.01,0.057,0.057,0.047,4.3e-05,4.3e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13390000,0.98,-0.0073,-0.012,0.19,0.0026,-0.0035,0.016,0.00083,-0.0037,0.0091,-0.0011,-0.006,7.7e-05,0.0028,0.0039,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00021,0.00021,0.0045,0.056,0.056,0.0097,0.049,0.049,0.046,4.1e-05,4.1e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13490000,0.98,-0.0072,-0.012,0.19,0.003,-0.0018,0.015,0.0011,-0.0039,0.0053,-0.0011,-0.006,7.7e-05,0.0029,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00022,0.00021,0.0045,0.064,0.064,0.0093,0.057,0.057,0.045,4.1e-05,4.1e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13590000,0.98,-0.0072,-0.012,0.19,0.0075,-0.002,0.017,0.004,-0.0032,0.0038,-0.0011,-0.006,7.7e-05,0.0031,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0002,0.0002,0.0045,0.053,0.053,0.0088,0.048,0.048,0.044,3.9e-05,3.9e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13690000,0.98,-0.0072,-0.012,0.19,0.0075,-0.0035,0.017,0.0047,-0.0035,0.0064,-0.0011,-0.006,7.7e-05,0.0031,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00021,0.00021,0.0045,0.061,0.061,0.0085,0.056,0.056,0.044,3.9e-05,3.9e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13790000,0.98,-0.0071,-0.012,0.19,0.014,0.00068,0.017,0.0083,-0.00094,0.0059,-0.0011,-0.0059,7.8e-05,0.0035,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0002,0.0002,0.0045,0.051,0.051,0.0082,0.048,0.048,0.043,3.7e-05,3.7e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13890000,0.98,-0.0071,-0.012,0.19,0.016,0.0014,0.018,0.0098,-0.00083,0.0081,-0.0011,-0.0059,7.8e-05,0.0035,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00021,0.00021,0.0045,0.058,0.058,0.008,0.056,0.056,0.042,3.7e-05,3.7e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0015,0.017,0.0074,-0.0023,0.007,-0.0011,-0.006,7.7e-05,0.0033,0.0036,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0002,0.0002,0.0045,0.049,0.049,0.0077,0.048,0.048,0.041,3.5e-05,3.5e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +14090000,0.98,-0.0071,-0.012,0.19,0.013,-0.003,0.018,0.0088,-0.0024,0.0034,-0.0011,-0.006,7.7e-05,0.0034,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00021,0.00021,0.0045,0.055,0.055,0.0076,0.055,0.055,0.041,3.5e-05,3.5e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +14190000,0.98,-0.0071,-0.011,0.19,0.0099,-0.0016,0.018,0.008,-0.0018,0.0036,-0.0011,-0.006,7.8e-05,0.0035,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0002,0.0002,0.0045,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-05,3.3e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +14290000,0.98,-0.007,-0.011,0.19,0.012,-0.0017,0.016,0.009,-0.002,0.0079,-0.0011,-0.006,7.8e-05,0.0035,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0002,0.0002,0.0045,0.053,0.053,0.0073,0.055,0.055,0.04,3.3e-05,3.3e-05,1.1e-05,0.036,0.036,0.0005,0,0,0,0,0,0,0,0 +14390000,0.98,-0.0071,-0.011,0.19,0.012,-0.0047,0.017,0.0084,-0.0031,0.012,-0.0011,-0.006,7.7e-05,0.0033,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0002,0.0002,0.0045,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-05,3.1e-05,1.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14490000,0.98,-0.0072,-0.011,0.19,0.01,-0.0045,0.021,0.0094,-0.0036,0.015,-0.0011,-0.006,7.7e-05,0.0033,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0002,0.0002,0.0045,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-05,3.1e-05,1.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14590000,0.98,-0.0073,-0.011,0.19,0.0078,-0.0046,0.019,0.0059,-0.0042,0.011,-0.0011,-0.006,7.7e-05,0.0031,0.0032,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00019,0.00019,0.0045,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-05,2.9e-05,1.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14690000,0.98,-0.0073,-0.011,0.19,0.007,-0.0046,0.019,0.0066,-0.0047,0.011,-0.0011,-0.006,7.7e-05,0.0031,0.0032,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0002,0.0002,0.0045,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-05,2.9e-05,1.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14790000,0.98,-0.0072,-0.011,0.19,0.0087,0.0024,0.019,0.0053,0.00078,0.014,-0.0012,-0.006,7.9e-05,0.0032,0.0041,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00019,0.00019,0.0045,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-05,2.8e-05,1.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14890000,0.98,-0.0071,-0.011,0.19,0.0074,1.6e-05,0.023,0.006,0.00091,0.014,-0.0012,-0.006,7.9e-05,0.0032,0.004,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0002,0.0002,0.0045,0.049,0.049,0.007,0.054,0.054,0.037,2.7e-05,2.8e-05,1.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +14990000,0.98,-0.0073,-0.011,0.19,0.0061,-0.0016,0.026,0.0047,-0.0007,0.017,-0.0012,-0.0061,7.8e-05,0.003,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00019,0.00019,0.0045,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-05,2.6e-05,1.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +15090000,0.98,-0.0072,-0.011,0.19,0.0062,-0.00056,0.03,0.0053,-0.00085,0.019,-0.0012,-0.0061,7.8e-05,0.0031,0.0038,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.0002,0.0002,0.0045,0.048,0.048,0.007,0.054,0.054,0.036,2.6e-05,2.6e-05,1.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +15190000,0.98,-0.0074,-0.011,0.19,0.0043,-0.0016,0.03,0.0042,-0.00077,0.021,-0.0012,-0.0061,7.8e-05,0.003,0.0037,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00019,0.00019,0.0045,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-05,2.4e-05,1.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +15290000,0.98,-0.0075,-0.011,0.19,0.0049,-0.0027,0.03,0.0047,-0.00097,0.018,-0.0012,-0.0061,7.8e-05,0.0033,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00019,0.00019,0.0045,0.047,0.047,0.0071,0.054,0.054,0.035,2.4e-05,2.4e-05,1.1e-05,0.035,0.035,0.0005,0,0,0,0,0,0,0,0 +15390000,0.98,-0.0075,-0.011,0.19,0.0051,-0.00031,0.029,0.0037,-0.00066,0.018,-0.0012,-0.0061,7.8e-05,0.0033,0.0035,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00019,0.00018,0.0046,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-05,2.2e-05,1.1e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15490000,0.98,-0.0076,-0.011,0.19,0.0045,-0.0029,0.029,0.0042,-0.00079,0.019,-0.0012,-0.0061,7.8e-05,0.0034,0.0034,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00019,0.00019,0.0046,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-05,2.2e-05,1.1e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15590000,0.98,-0.0078,-0.011,0.19,0.0081,-0.0067,0.029,0.0062,-0.0047,0.018,-0.0011,-0.0061,7.7e-05,0.0038,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00018,0.00018,0.0046,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-05,2.1e-05,1.1e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15690000,0.98,-0.0077,-0.011,0.19,0.0099,-0.0099,0.029,0.0072,-0.0056,0.019,-0.0011,-0.0061,7.7e-05,0.0039,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00019,0.00019,0.0046,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-05,2.1e-05,1.1e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15790000,0.98,-0.0077,-0.011,0.19,0.0064,-0.0092,0.029,0.0055,-0.0043,0.02,-0.0011,-0.0061,7.8e-05,0.0039,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00018,0.00018,0.0046,0.04,0.04,0.0073,0.046,0.046,0.034,1.9e-05,1.9e-05,1.1e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15890000,0.98,-0.0078,-0.011,0.19,0.0053,-0.0076,0.03,0.0061,-0.0052,0.02,-0.0011,-0.0061,7.8e-05,0.0041,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00018,0.00018,0.0046,0.045,0.045,0.0074,0.053,0.053,0.034,1.9e-05,1.9e-05,1.1e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +15990000,0.98,-0.0076,-0.011,0.19,0.0033,-0.0061,0.027,0.0048,-0.004,0.019,-0.0012,-0.0061,7.8e-05,0.0043,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00017,0.0046,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-05,1.7e-05,1.1e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +16090000,0.98,-0.0076,-0.011,0.19,0.0026,-0.0074,0.024,0.0051,-0.0046,0.019,-0.0012,-0.0061,7.8e-05,0.0044,0.0022,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00018,0.00018,0.0046,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-05,1.7e-05,1.1e-05,0.034,0.034,0.0005,0,0,0,0,0,0,0,0 +16190000,0.98,-0.0075,-0.011,0.19,-0.0013,-0.005,0.023,0.0027,-0.0034,0.016,-0.0012,-0.0061,7.8e-05,0.0045,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00017,0.0046,0.039,0.039,0.0076,0.046,0.046,0.034,1.6e-05,1.6e-05,1.1e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16290000,0.98,-0.0075,-0.011,0.19,-0.001,-0.0065,0.023,0.0026,-0.004,0.017,-0.0012,-0.0061,7.8e-05,0.0046,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00017,0.0046,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-05,1.6e-05,1.1e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16390000,0.98,-0.0075,-0.011,0.19,0.0015,-0.0058,0.023,0.0036,-0.0031,0.017,-0.0012,-0.0061,7.9e-05,0.0051,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00017,0.0046,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-05,1.5e-05,1.1e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16490000,0.98,-0.0076,-0.011,0.19,0.0034,-0.0074,0.026,0.0039,-0.0038,0.021,-0.0012,-0.0061,7.9e-05,0.005,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00017,0.0046,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-05,1.5e-05,1.1e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16590000,0.98,-0.0075,-0.011,0.19,0.0075,-0.0075,0.029,0.0034,-0.0029,0.021,-0.0012,-0.0061,7.9e-05,0.0052,0.0025,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00016,0.00016,0.0046,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-05,1.3e-05,1.1e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16690000,0.98,-0.0076,-0.011,0.19,0.0089,-0.012,0.029,0.0042,-0.0039,0.022,-0.0012,-0.0061,7.9e-05,0.0053,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00017,0.00016,0.0046,0.042,0.042,0.008,0.053,0.053,0.034,1.3e-05,1.3e-05,1.1e-05,0.033,0.033,0.0005,0,0,0,0,0,0,0,0 +16790000,0.98,-0.0074,-0.011,0.19,0.0098,-0.011,0.028,0.0033,-0.0028,0.022,-0.0012,-0.0061,7.9e-05,0.0054,0.0026,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00016,0.00016,0.0046,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-05,1.2e-05,1.1e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16890000,0.98,-0.0074,-0.011,0.19,0.0088,-0.011,0.029,0.0042,-0.0039,0.02,-0.0012,-0.0061,7.9e-05,0.0057,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00016,0.00016,0.0046,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-05,1.2e-05,1.1e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +16990000,0.98,-0.0074,-0.011,0.19,0.0085,-0.011,0.029,0.004,-0.0029,0.019,-0.0013,-0.0061,8e-05,0.0063,0.0024,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00015,0.00015,0.0046,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-05,1.1e-05,1.1e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17090000,0.98,-0.0075,-0.011,0.19,0.01,-0.013,0.028,0.005,-0.0041,0.018,-0.0013,-0.0061,8e-05,0.0065,0.0023,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00016,0.00015,0.0046,0.041,0.041,0.0083,0.052,0.052,0.034,1.1e-05,1.1e-05,1.1e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17190000,0.98,-0.0076,-0.011,0.19,0.0089,-0.018,0.03,0.0033,-0.0076,0.021,-0.0012,-0.0061,8e-05,0.0063,0.0021,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00015,0.00015,0.0046,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-06,9.9e-06,1.1e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17290000,0.98,-0.0076,-0.011,0.19,0.0098,-0.019,0.03,0.0043,-0.0094,0.021,-0.0012,-0.0061,8e-05,0.0065,0.0019,-0.14,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00015,0.00015,0.0046,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-06,9.9e-06,1.1e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17390000,0.98,-0.0075,-0.011,0.19,0.0065,-0.018,0.029,0.0057,-0.0059,0.021,-0.0013,-0.006,8.1e-05,0.0073,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00014,0.00014,0.0047,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-06,8.9e-06,1.1e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17490000,0.98,-0.0075,-0.011,0.19,0.0046,-0.019,0.029,0.0062,-0.0078,0.023,-0.0013,-0.006,8.1e-05,0.0073,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00015,0.00015,0.0047,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-06,8.9e-06,1.1e-05,0.032,0.032,0.0005,0,0,0,0,0,0,0,0 +17590000,0.98,-0.0074,-0.011,0.19,0.00076,-0.015,0.028,0.0024,-0.0058,0.02,-0.0013,-0.0061,8.1e-05,0.0072,0.0029,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00014,0.00014,0.0047,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-06,8.1e-06,1.1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17690000,0.98,-0.0075,-0.011,0.19,-0.00018,-0.016,0.029,0.0025,-0.0074,0.023,-0.0013,-0.0061,8.1e-05,0.0073,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00014,0.00014,0.0047,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-06,8.1e-06,1.1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17790000,0.98,-0.0074,-0.011,0.19,0.0025,-0.014,0.029,0.0034,-0.0062,0.028,-0.0014,-0.006,8.2e-05,0.0076,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00014,0.00014,0.0047,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-06,7.3e-06,1.1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17890000,0.98,-0.0073,-0.011,0.19,0.0046,-0.016,0.029,0.0038,-0.0077,0.032,-0.0014,-0.006,8.2e-05,0.0075,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00014,0.00014,0.0047,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-06,7.3e-06,1.1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +17990000,0.98,-0.0071,-0.011,0.19,0.004,-0.0093,0.029,0.003,-0.002,0.033,-0.0014,-0.006,8.4e-05,0.0079,0.0046,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00013,0.0047,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-06,6.6e-06,1.1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +18090000,0.98,-0.0072,-0.011,0.19,0.0035,-0.0099,0.028,0.0035,-0.003,0.031,-0.0014,-0.006,8.4e-05,0.0082,0.0044,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00013,0.0047,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-06,6.6e-06,1.1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +18190000,0.98,-0.0072,-0.011,0.19,0.0036,-0.0088,0.028,0.0041,-0.0022,0.029,-0.0014,-0.006,8.4e-05,0.0087,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00013,0.0047,0.032,0.032,0.0086,0.045,0.045,0.035,6e-06,6e-06,1.1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +18290000,0.98,-0.0073,-0.011,0.19,0.0045,-0.0093,0.027,0.0045,-0.0031,0.027,-0.0014,-0.006,8.4e-05,0.009,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00013,0.0047,0.036,0.036,0.0087,0.051,0.051,0.035,6e-06,6e-06,1.1e-05,0.031,0.031,0.0005,0,0,0,0,0,0,0,0 +18390000,0.98,-0.0072,-0.011,0.19,0.0054,-0.008,0.027,0.0061,-0.0023,0.026,-0.0014,-0.006,8.4e-05,0.0096,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00012,0.0047,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-06,5.4e-06,1.1e-05,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 +18490000,0.98,-0.0072,-0.011,0.19,0.0081,-0.0081,0.026,0.0069,-0.0032,0.028,-0.0014,-0.006,8.4e-05,0.0096,0.004,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00013,0.00013,0.0047,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-06,5.4e-06,1.1e-05,0.03,0.031,0.0005,0,0,0,0,0,0,0,0 +18590000,0.98,-0.007,-0.011,0.19,0.0065,-0.0074,0.026,0.0055,-0.0024,0.031,-0.0015,-0.006,8.4e-05,0.0095,0.0043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0047,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-06,4.9e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18690000,0.98,-0.007,-0.011,0.19,0.0066,-0.0064,0.024,0.0062,-0.0031,0.029,-0.0015,-0.006,8.4e-05,0.0097,0.0041,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0047,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-06,4.9e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18790000,0.98,-0.007,-0.011,0.19,0.0056,-0.006,0.024,0.0062,-0.0025,0.027,-0.0015,-0.006,8.5e-05,0.01,0.0039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0047,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-06,4.4e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18890000,0.98,-0.007,-0.011,0.19,0.0043,-0.0057,0.021,0.0067,-0.0032,0.023,-0.0015,-0.006,8.5e-05,0.01,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0047,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-06,4.4e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +18990000,0.98,-0.0069,-0.011,0.19,0.0026,-0.0057,0.022,0.0055,-0.0025,0.026,-0.0015,-0.006,8.5e-05,0.01,0.0039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00017,0.00012,0.00012,0.0047,0.029,0.029,0.0086,0.045,0.045,0.035,4e-06,4e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19090000,0.98,-0.007,-0.011,0.19,0.00058,-0.0063,0.023,0.0057,-0.0031,0.022,-0.0015,-0.006,8.5e-05,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00012,0.0048,0.032,0.032,0.0087,0.051,0.051,0.036,4e-06,4e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19190000,0.98,-0.0069,-0.011,0.19,-0.00089,-0.0059,0.022,0.0048,-0.0025,0.022,-0.0015,-0.006,8.5e-05,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,0.0048,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-06,3.7e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19290000,0.98,-0.0069,-0.011,0.19,-0.0018,-0.0057,0.023,0.0047,-0.0031,0.021,-0.0015,-0.006,8.5e-05,0.011,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00012,0.00011,0.0048,0.031,0.031,0.0087,0.05,0.051,0.036,3.7e-06,3.7e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19390000,0.98,-0.0069,-0.011,0.19,-0.0022,-0.0022,0.024,0.004,-0.0012,0.019,-0.0015,-0.006,8.5e-05,0.011,0.0036,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,0.0048,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-06,3.3e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19490000,0.98,-0.007,-0.011,0.19,-0.003,-0.0022,0.023,0.0038,-0.0014,0.019,-0.0015,-0.006,8.5e-05,0.011,0.0035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,0.0048,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-06,3.3e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19590000,0.98,-0.0069,-0.011,0.19,-0.0041,-0.0051,0.025,0.0043,-0.0024,0.019,-0.0015,-0.006,8.5e-05,0.012,0.0032,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,0.0048,0.027,0.027,0.0086,0.044,0.044,0.036,3e-06,3e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19690000,0.98,-0.007,-0.011,0.19,-0.0058,-0.0037,0.023,0.0039,-0.0028,0.019,-0.0015,-0.006,8.5e-05,0.012,0.0031,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,0.0048,0.03,0.03,0.0086,0.05,0.05,0.036,3e-06,3e-06,1.1e-05,0.03,0.03,0.0005,0,0,0,0,0,0,0,0 +19790000,0.98,-0.0071,-0.011,0.19,-0.0058,-0.0022,0.022,0.0063,-0.0023,0.014,-0.0015,-0.006,8.5e-05,0.012,0.0028,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,0.0048,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-06,2.8e-06,1.1e-05,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 +19890000,0.98,-0.0071,-0.011,0.19,-0.0058,-0.002,0.022,0.0057,-0.0025,0.013,-0.0015,-0.006,8.5e-05,0.013,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.00011,0.0048,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-06,2.8e-06,1.1e-05,0.029,0.03,0.0005,0,0,0,0,0,0,0,0 +19990000,0.98,-0.0071,-0.011,0.19,-0.0055,-0.0019,0.019,0.0061,-0.00092,0.0097,-0.0015,-0.0059,8.6e-05,0.013,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.0001,0.0048,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-06,2.5e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20090000,0.98,-0.0071,-0.011,0.19,-0.005,-0.0041,0.019,0.0055,-0.0012,0.013,-0.0015,-0.0059,8.6e-05,0.013,0.0026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.00011,0.0001,0.0048,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-06,2.5e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20190000,0.98,-0.0071,-0.011,0.19,-0.004,-0.0016,0.02,0.0065,-0.00091,0.013,-0.0015,-0.0059,8.6e-05,0.013,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,0.0048,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-06,2.3e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20290000,0.98,-0.0071,-0.011,0.19,-0.0072,-0.0026,0.02,0.006,-0.0011,0.013,-0.0015,-0.0059,8.6e-05,0.013,0.0025,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,0.0048,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-06,2.3e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20390000,0.98,-0.007,-0.011,0.19,-0.0078,-0.0014,0.021,0.0069,-0.00077,0.014,-0.0015,-0.0059,8.6e-05,0.014,0.0024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,0.0048,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-06,2.1e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20490000,0.98,-0.007,-0.011,0.19,-0.012,-0.0024,0.02,0.0059,-0.00095,0.012,-0.0015,-0.0059,8.6e-05,0.014,0.0023,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,0.0001,0.0049,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-06,2.1e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20590000,0.98,-0.007,-0.011,0.19,-0.012,-0.0033,0.02,0.0069,-0.00079,0.011,-0.0015,-0.0059,8.6e-05,0.014,0.0021,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,9.9e-05,0.0049,0.024,0.024,0.0084,0.044,0.044,0.036,2e-06,2e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20690000,0.98,-0.0069,-0.011,0.19,-0.013,-0.0021,0.021,0.0057,-0.001,0.011,-0.0015,-0.0059,8.6e-05,0.014,0.002,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,0.0001,9.9e-05,0.0049,0.026,0.026,0.0084,0.049,0.049,0.036,2e-06,2e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20790000,0.98,-0.0064,-0.011,0.18,-0.016,0.00046,0.0055,0.0048,-0.0008,0.0097,-0.0015,-0.0059,8.6e-05,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.9e-05,9.7e-05,0.0049,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-06,1.8e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20890000,0.98,0.0028,-0.0073,0.18,-0.022,0.012,-0.11,0.0029,-0.00012,0.0034,-0.0015,-0.0059,8.6e-05,0.015,0.0019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.9e-05,9.8e-05,0.0049,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-06,1.8e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +20990000,0.98,0.0061,-0.0038,0.18,-0.032,0.03,-0.25,0.0022,0.00053,-0.011,-0.0015,-0.0059,8.6e-05,0.015,0.0018,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.7e-05,9.6e-05,0.0049,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-06,1.7e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21090000,0.98,0.0045,-0.0042,0.19,-0.046,0.047,-0.37,-0.0017,0.0044,-0.042,-0.0015,-0.0059,8.6e-05,0.015,0.0018,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.8e-05,9.7e-05,0.0049,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-06,1.7e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21190000,0.98,0.0016,-0.0059,0.19,-0.049,0.051,-0.5,-0.0013,0.0035,-0.078,-0.0014,-0.0059,8.6e-05,0.015,0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.6e-05,9.4e-05,0.0049,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-06,1.6e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21290000,0.98,-0.00053,-0.0072,0.19,-0.049,0.054,-0.63,-0.0062,0.0088,-0.14,-0.0014,-0.0059,8.6e-05,0.015,0.0011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.6e-05,9.5e-05,0.0049,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-06,1.6e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21390000,0.98,-0.002,-0.0079,0.19,-0.044,0.05,-0.75,-0.005,0.011,-0.2,-0.0014,-0.0059,8.6e-05,0.015,0.00075,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.4e-05,9.2e-05,0.0049,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-06,1.4e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21490000,0.98,-0.0028,-0.0083,0.19,-0.04,0.047,-0.89,-0.0093,0.016,-0.29,-0.0014,-0.0059,8.6e-05,0.015,0.00065,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.5e-05,9.3e-05,0.0049,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-06,1.4e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21590000,0.98,-0.0033,-0.0083,0.19,-0.031,0.043,-1,-0.008,0.017,-0.38,-0.0014,-0.0059,8.6e-05,0.015,0.0006,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.2e-05,9.1e-05,0.0049,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-06,1.3e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21690000,0.98,-0.0036,-0.0082,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.49,-0.0014,-0.0059,8.6e-05,0.015,0.00043,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.3e-05,9.1e-05,0.0049,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-06,1.3e-06,1.1e-05,0.029,0.029,0.0005,0,0,0,0,0,0,0,0 +21790000,0.98,-0.004,-0.0084,0.19,-0.021,0.033,-1.3,-0.0038,0.018,-0.61,-0.0014,-0.0058,8.7e-05,0.016,0.00024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9e-05,8.9e-05,0.0049,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,1.1e-05,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +21890000,0.98,-0.0043,-0.0085,0.19,-0.018,0.028,-1.4,-0.0057,0.021,-0.75,-0.0014,-0.0058,8.7e-05,0.016,0.00011,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,9.1e-05,8.9e-05,0.0049,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,1.1e-05,0.028,0.029,0.0005,0,0,0,0,0,0,0,0 +21990000,0.98,-0.005,-0.0088,0.19,-0.014,0.023,-1.4,-0.00035,0.017,-0.89,-0.0014,-0.0058,8.6e-05,0.015,0.00035,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.8e-05,8.7e-05,0.005,0.022,0.022,0.0082,0.043,0.043,0.036,1.2e-06,1.2e-06,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22090000,0.98,-0.0057,-0.0096,0.19,-0.012,0.019,-1.4,-0.0017,0.019,-1,-0.0014,-0.0058,8.6e-05,0.016,0.00022,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.9e-05,8.7e-05,0.005,0.024,0.024,0.0082,0.048,0.048,0.036,1.2e-06,1.2e-06,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22190000,0.98,-0.0062,-0.0099,0.19,-0.0035,0.013,-1.4,0.006,0.013,-1.2,-0.0014,-0.0058,8.6e-05,0.016,0.00026,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.7e-05,8.5e-05,0.005,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-06,1.1e-06,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22290000,0.98,-0.0069,-0.01,0.19,0.0016,0.0078,-1.4,0.0059,0.014,-1.3,-0.0014,-0.0058,8.6e-05,0.016,0.00016,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.7e-05,8.6e-05,0.005,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-06,1.1e-06,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22390000,0.98,-0.0073,-0.01,0.19,0.0066,-0.0017,-1.4,0.013,0.0042,-1.5,-0.0014,-0.0058,8.6e-05,0.016,-0.00019,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.5e-05,8.4e-05,0.005,0.021,0.021,0.0081,0.043,0.043,0.036,1e-06,1e-06,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22490000,0.98,-0.0074,-0.011,0.19,0.01,-0.0077,-1.4,0.014,0.0037,-1.6,-0.0014,-0.0058,8.6e-05,0.016,-0.00024,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.6e-05,8.4e-05,0.005,0.022,0.022,0.0081,0.047,0.047,0.036,1e-06,1e-06,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22590000,0.98,-0.0073,-0.011,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-0.0014,-0.0058,8.6e-05,0.016,-0.00039,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.4e-05,8.2e-05,0.005,0.02,0.02,0.0081,0.042,0.042,0.036,9.5e-07,9.4e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22690000,0.98,-0.0073,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.9,-0.0014,-0.0058,8.6e-05,0.016,-0.00047,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.5e-05,8.3e-05,0.005,0.021,0.021,0.0081,0.047,0.047,0.036,9.5e-07,9.5e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22790000,0.98,-0.0073,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-0.0014,-0.0058,8.6e-05,0.016,-0.00059,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.005,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-07,8.9e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22890000,0.98,-0.0074,-0.012,0.19,0.031,-0.035,-1.4,0.041,-0.02,-2.2,-0.0014,-0.0058,8.6e-05,0.016,-0.00066,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.3e-05,8.1e-05,0.005,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-07,8.9e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +22990000,0.98,-0.0074,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-0.0014,-0.0058,8.7e-05,0.016,-0.0008,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.2e-05,8e-05,0.005,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-07,8.4e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23090000,0.98,-0.0074,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.5,-0.0014,-0.0058,8.7e-05,0.017,-0.00083,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.2e-05,8e-05,0.005,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-07,8.4e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23190000,0.98,-0.0074,-0.013,0.18,0.047,-0.046,-1.4,0.066,-0.045,-2.6,-0.0014,-0.0058,8.7e-05,0.017,-0.00098,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.1e-05,7.9e-05,0.0051,0.018,0.018,0.008,0.042,0.042,0.035,8e-07,8e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23290000,0.98,-0.0079,-0.013,0.18,0.052,-0.051,-1.4,0.071,-0.05,-2.8,-0.0014,-0.0058,8.7e-05,0.017,-0.001,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8.2e-05,7.9e-05,0.0051,0.02,0.02,0.0081,0.046,0.046,0.036,8e-07,8e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23390000,0.98,-0.0078,-0.014,0.18,0.057,-0.053,-1.4,0.082,-0.055,-2.9,-0.0014,-0.0058,8.7e-05,0.017,-0.00077,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00018,8e-05,7.8e-05,0.0051,0.018,0.018,0.008,0.041,0.041,0.036,7.6e-07,7.6e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23490000,0.98,-0.0079,-0.014,0.18,0.061,-0.055,-1.4,0.088,-0.061,-3,-0.0014,-0.0058,8.7e-05,0.017,-0.00081,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.9e-05,0.0051,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-07,7.6e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23590000,0.98,-0.0082,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.2,-0.0014,-0.0058,8.8e-05,0.017,-0.00093,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.8e-05,0.0051,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-07,7.2e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23690000,0.98,-0.0088,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-0.0014,-0.0058,8.8e-05,0.017,-0.00095,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.8e-05,0.0051,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-07,7.2e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.96,0.11,-0.081,-3.4,-0.0014,-0.0058,8.7e-05,0.017,-0.00095,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.7e-05,0.0051,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-07,6.9e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23890000,0.98,-0.014,-0.021,0.18,0.052,-0.059,-0.52,0.12,-0.087,-3.5,-0.0014,-0.0058,8.7e-05,0.017,-0.00097,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.8e-05,0.0051,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-07,6.9e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +23990000,0.98,-0.016,-0.024,0.18,0.054,-0.058,-0.14,0.12,-0.089,-3.6,-0.0014,-0.0058,8.7e-05,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.8e-05,0.0051,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-07,6.6e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24090000,0.98,-0.016,-0.023,0.18,0.06,-0.066,0.09,0.13,-0.095,-3.6,-0.0014,-0.0058,8.7e-05,0.018,-0.0015,-0.13,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.8e-05,0.0051,0.017,0.017,0.0081,0.045,0.045,0.036,6.6e-07,6.6e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24190000,0.98,-0.013,-0.019,0.18,0.071,-0.071,0.077,0.14,-0.1,-3.6,-0.0014,-0.0058,8.7e-05,0.019,-0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.7e-05,0.0051,0.015,0.015,0.008,0.04,0.04,0.035,6.4e-07,6.3e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24290000,0.98,-0.01,-0.016,0.18,0.075,-0.075,0.055,0.15,-0.11,-3.6,-0.0014,-0.0058,8.7e-05,0.019,-0.0023,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.9e-05,7.7e-05,0.0051,0.016,0.016,0.0081,0.044,0.044,0.036,6.4e-07,6.4e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24390000,0.98,-0.0096,-0.015,0.18,0.069,-0.069,0.071,0.15,-0.11,-3.6,-0.0014,-0.0058,8.5e-05,0.019,-0.003,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.9e-05,7.7e-05,0.0052,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-07,6.1e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24490000,0.98,-0.0098,-0.015,0.18,0.064,-0.066,0.069,0.16,-0.11,-3.6,-0.0014,-0.0058,8.5e-05,0.019,-0.003,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.9e-05,7.7e-05,0.0052,0.016,0.016,0.008,0.044,0.044,0.035,6.1e-07,6.1e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24590000,0.98,-0.01,-0.015,0.18,0.061,-0.062,0.065,0.16,-0.11,-3.6,-0.0014,-0.0058,8.4e-05,0.019,-0.0037,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.9e-05,7.7e-05,0.0052,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-07,5.9e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24690000,0.98,-0.011,-0.014,0.18,0.059,-0.061,0.064,0.17,-0.12,-3.6,-0.0014,-0.0058,8.4e-05,0.019,-0.0037,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.9e-05,7.8e-05,0.0052,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-07,5.9e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24790000,0.98,-0.011,-0.014,0.18,0.056,-0.059,0.056,0.17,-0.11,-3.6,-0.0015,-0.0058,8.3e-05,0.019,-0.0043,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.9e-05,7.7e-05,0.0052,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-07,5.7e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24890000,0.98,-0.011,-0.013,0.18,0.054,-0.062,0.045,0.18,-0.12,-3.6,-0.0015,-0.0058,8.3e-05,0.019,-0.0043,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.9e-05,7.8e-05,0.0052,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-07,5.7e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +24990000,0.98,-0.011,-0.013,0.18,0.045,-0.058,0.038,0.18,-0.11,-3.6,-0.0015,-0.0058,8.3e-05,0.019,-0.005,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.9e-05,7.8e-05,0.0052,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-07,5.5e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +25090000,0.98,-0.011,-0.013,0.18,0.042,-0.057,0.035,0.18,-0.12,-3.6,-0.0015,-0.0058,8.3e-05,0.019,-0.0051,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.8e-05,0.0052,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-07,5.5e-07,1.1e-05,0.028,0.028,0.0005,0,0,0,0,0,0,0,0 +25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.035,0.18,-0.11,-3.6,-0.0015,-0.0058,8.2e-05,0.018,-0.0055,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,7.9e-05,7.8e-05,0.0052,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-07,5.3e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25290000,0.98,-0.011,-0.012,0.19,0.032,-0.052,0.029,0.18,-0.11,-3.6,-0.0015,-0.0058,8.2e-05,0.018,-0.0055,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.8e-05,0.0052,0.016,0.016,0.0081,0.043,0.043,0.036,5.4e-07,5.3e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25390000,0.98,-0.011,-0.012,0.19,0.024,-0.044,0.028,0.18,-0.1,-3.6,-0.0015,-0.0058,8.3e-05,0.018,-0.0062,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.8e-05,0.0052,0.015,0.015,0.008,0.039,0.039,0.035,5.2e-07,5.2e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25490000,0.98,-0.011,-0.012,0.19,0.019,-0.044,0.027,0.18,-0.11,-3.6,-0.0015,-0.0058,8.3e-05,0.018,-0.0063,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.8e-05,0.0053,0.016,0.016,0.008,0.043,0.043,0.035,5.2e-07,5.2e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25590000,0.98,-0.011,-0.012,0.19,0.014,-0.04,0.028,0.18,-0.098,-3.6,-0.0015,-0.0058,8.3e-05,0.018,-0.0066,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.8e-05,0.0053,0.014,0.014,0.008,0.039,0.039,0.035,5e-07,5e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25690000,0.98,-0.011,-0.011,0.19,0.013,-0.039,0.017,0.18,-0.1,-3.6,-0.0015,-0.0058,8.3e-05,0.018,-0.0066,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.8e-05,0.0053,0.015,0.015,0.0081,0.043,0.043,0.035,5e-07,5e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25790000,0.98,-0.011,-0.011,0.19,0.002,-0.031,0.017,0.17,-0.093,-3.6,-0.0016,-0.0058,8.4e-05,0.018,-0.0071,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.8e-05,0.0053,0.014,0.014,0.008,0.039,0.039,0.035,4.9e-07,4.9e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25890000,0.98,-0.011,-0.011,0.19,-0.0038,-0.028,0.019,0.17,-0.095,-3.6,-0.0016,-0.0058,8.4e-05,0.018,-0.0071,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.9e-05,0.0053,0.015,0.015,0.0081,0.043,0.043,0.036,4.9e-07,4.9e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +25990000,0.98,-0.011,-0.011,0.19,-0.013,-0.022,0.013,0.16,-0.086,-3.6,-0.0016,-0.0058,8.5e-05,0.018,-0.0075,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.9e-05,0.0053,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-07,4.7e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26090000,0.98,-0.01,-0.011,0.18,-0.018,-0.021,0.011,0.16,-0.088,-3.6,-0.0016,-0.0058,8.5e-05,0.018,-0.0075,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.9e-05,0.0053,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-07,4.7e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26190000,0.98,-0.01,-0.011,0.19,-0.024,-0.015,0.0063,0.15,-0.081,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8e-05,7.9e-05,0.0053,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-07,4.6e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26290000,0.98,-0.01,-0.012,0.18,-0.026,-0.013,0.00052,0.15,-0.083,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0077,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.9e-05,0.0053,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-07,4.6e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26390000,0.98,-0.0098,-0.012,0.18,-0.032,-0.0064,0.0045,0.13,-0.074,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.008,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.9e-05,0.0053,0.014,0.014,0.008,0.038,0.038,0.035,4.5e-07,4.5e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26490000,0.98,-0.0096,-0.011,0.18,-0.035,-0.0032,0.014,0.13,-0.075,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0079,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.9e-05,0.0053,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-07,4.5e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26590000,0.98,-0.009,-0.012,0.18,-0.036,0.0047,0.014,0.12,-0.068,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.9e-05,0.0054,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-07,4.4e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26690000,0.98,-0.0089,-0.011,0.18,-0.038,0.0098,0.013,0.12,-0.067,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.9e-05,0.0054,0.015,0.015,0.0081,0.042,0.042,0.035,4.4e-07,4.4e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26790000,0.98,-0.0087,-0.011,0.18,-0.045,0.013,0.012,0.1,-0.062,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00019,8.1e-05,7.9e-05,0.0054,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-07,4.2e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26890000,0.98,-0.008,-0.011,0.18,-0.051,0.017,0.007,0.1,-0.06,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,8.1e-05,7.9e-05,0.0054,0.015,0.015,0.0081,0.042,0.042,0.036,4.3e-07,4.3e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +26990000,0.98,-0.0075,-0.011,0.18,-0.058,0.023,0.0061,0.088,-0.054,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0086,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,8.1e-05,7.9e-05,0.0054,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-07,4.1e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27090000,0.98,-0.0073,-0.012,0.18,-0.06,0.03,0.0089,0.082,-0.051,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,8.1e-05,7.9e-05,0.0054,0.015,0.015,0.0081,0.042,0.042,0.035,4.2e-07,4.2e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27190000,0.98,-0.0074,-0.012,0.18,-0.066,0.036,0.011,0.071,-0.045,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,8.1e-05,7.9e-05,0.0054,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-07,4e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27290000,0.98,-0.0076,-0.013,0.18,-0.073,0.042,0.12,0.064,-0.042,-3.6,-0.0016,-0.0058,8.5e-05,0.019,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,8.2e-05,7.9e-05,0.0054,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-07,4.1e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27390000,0.98,-0.009,-0.015,0.18,-0.078,0.048,0.45,0.055,-0.034,-3.5,-0.0016,-0.0058,8.8e-05,0.02,-0.0092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.0002,8.2e-05,7.9e-05,0.0054,0.013,0.013,0.008,0.038,0.038,0.035,4e-07,4e-07,1.1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27490000,0.98,-0.01,-0.017,0.19,-0.082,0.053,0.76,0.047,-0.029,-3.5,-0.0016,-0.0058,6.5e-05,0.02,-0.0092,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.2e-05,8e-05,0.0044,0.014,0.014,0.008,0.042,0.042,0.035,4e-07,4e-07,1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27590000,0.98,-0.01,-0.016,0.19,-0.076,0.055,0.85,0.038,-0.025,-3.4,-0.0016,-0.0058,6.6e-05,0.02,-0.0094,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.2e-05,8e-05,0.0044,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-07,3.9e-07,1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27690000,0.98,-0.0089,-0.013,0.19,-0.072,0.052,0.76,0.031,-0.02,-3.3,-0.0016,-0.0058,6.6e-05,0.02,-0.0095,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.2e-05,8e-05,0.0044,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-07,3.9e-07,1e-05,0.027,0.028,0.0005,0,0,0,0,0,0,0,0 +27790000,0.98,-0.0076,-0.011,0.19,-0.071,0.05,0.75,0.025,-0.018,-3.3,-0.0016,-0.0058,6.6e-05,0.02,-0.0089,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.2e-05,8e-05,0.0044,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.8e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27890000,0.98,-0.0072,-0.012,0.19,-0.078,0.057,0.79,0.017,-0.012,-3.2,-0.0016,-0.0058,6.6e-05,0.02,-0.009,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.2e-05,8e-05,0.0044,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-07,3.8e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +27990000,0.98,-0.0077,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.011,-3.1,-0.0016,-0.0058,6.7e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.2e-05,8e-05,0.0044,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-07,3.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28090000,0.98,-0.008,-0.012,0.18,-0.082,0.059,0.78,0.0042,-0.0047,-3,-0.0016,-0.0058,6.7e-05,0.019,-0.0087,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.2e-05,8e-05,0.0044,0.014,0.014,0.008,0.041,0.041,0.035,3.8e-07,3.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28190000,0.98,-0.0074,-0.012,0.18,-0.082,0.055,0.79,-0.0023,-0.0042,-3,-0.0016,-0.0058,6.7e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.2e-05,8e-05,0.0044,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-07,3.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28290000,0.98,-0.0069,-0.012,0.18,-0.088,0.059,0.79,-0.011,0.0015,-2.9,-0.0016,-0.0058,6.7e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.2e-05,8e-05,0.0044,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-07,3.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28390000,0.98,-0.0069,-0.013,0.18,-0.088,0.062,0.79,-0.015,0.0045,-2.8,-0.0015,-0.0058,7e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8e-05,0.0044,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.6e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28490000,0.98,-0.0072,-0.014,0.18,-0.09,0.066,0.79,-0.024,0.011,-2.8,-0.0015,-0.0058,7e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0044,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-07,3.6e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28590000,0.98,-0.0073,-0.014,0.18,-0.083,0.061,0.79,-0.027,0.0085,-2.7,-0.0015,-0.0058,7e-05,0.019,-0.0081,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0044,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-07,3.5e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28690000,0.98,-0.007,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.6,-0.0015,-0.0058,7e-05,0.019,-0.0082,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0044,0.014,0.014,0.008,0.041,0.041,0.035,3.6e-07,3.6e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28790000,0.98,-0.0064,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.016,-2.5,-0.0015,-0.0058,7.3e-05,0.019,-0.0083,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0044,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.5e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28890000,0.98,-0.0062,-0.012,0.18,-0.084,0.064,0.78,-0.046,0.023,-2.5,-0.0015,-0.0058,7.3e-05,0.019,-0.0084,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-07,3.5e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +28990000,0.98,-0.006,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.4,-0.0015,-0.0058,7.5e-05,0.02,-0.0085,-0.12,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-07,3.4e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29090000,0.98,-0.0058,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-0.0015,-0.0058,7.5e-05,0.02,-0.0086,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-07,3.4e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29190000,0.98,-0.0058,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-0.0015,-0.0058,7.9e-05,0.02,-0.0087,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.4e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29290000,0.98,-0.0061,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.034,-2.2,-0.0015,-0.0058,7.9e-05,0.02,-0.0088,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-07,3.4e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29390000,0.98,-0.0065,-0.012,0.18,-0.075,0.066,0.78,-0.057,0.034,-2.1,-0.0015,-0.0058,8.2e-05,0.02,-0.0089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-07,3.3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29490000,0.98,-0.0065,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-0.0015,-0.0058,8.2e-05,0.02,-0.0089,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.014,0.014,0.0081,0.041,0.041,0.036,3.4e-07,3.3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29590000,0.98,-0.0064,-0.012,0.18,-0.074,0.064,0.78,-0.062,0.04,-1.9,-0.0015,-0.0058,8.5e-05,0.02,-0.0091,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29690000,0.98,-0.0065,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.046,-1.9,-0.0015,-0.0058,8.5e-05,0.02,-0.0092,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29790000,0.98,-0.0063,-0.013,0.18,-0.073,0.056,0.78,-0.065,0.044,-1.8,-0.0014,-0.0058,8.7e-05,0.02,-0.0095,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-07,3.2e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29890000,0.98,-0.0058,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-0.0014,-0.0058,8.7e-05,0.02,-0.0096,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.4e-05,8.1e-05,0.0045,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-07,3.3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +29990000,0.98,-0.0059,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.044,-1.6,-0.0014,-0.0058,8.9e-05,0.02,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.3e-05,8.1e-05,0.0045,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30090000,0.98,-0.0061,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.6,-0.0014,-0.0058,8.9e-05,0.02,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00016,8.4e-05,8.1e-05,0.0046,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30190000,0.98,-0.0061,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.5,-0.0014,-0.0057,9.2e-05,0.021,-0.01,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0046,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-07,3.2e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30290000,0.98,-0.0061,-0.013,0.18,-0.062,0.05,0.77,-0.074,0.053,-1.4,-0.0014,-0.0057,9.2e-05,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.4e-05,8.1e-05,0.0046,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-07,3.2e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30390000,0.98,-0.0061,-0.013,0.18,-0.055,0.044,0.76,-0.066,0.05,-1.4,-0.0014,-0.0057,9.5e-05,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0046,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-07,3.1e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30490000,0.98,-0.0061,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.3,-0.0014,-0.0057,9.5e-05,0.021,-0.011,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.4e-05,8.1e-05,0.0046,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-07,3.1e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30590000,0.98,-0.0064,-0.013,0.18,-0.053,0.041,0.76,-0.065,0.05,-1.2,-0.0014,-0.0057,9.8e-05,0.021,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0046,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3.1e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30690000,0.98,-0.0068,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-0.0014,-0.0057,9.8e-05,0.021,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.4e-05,8.1e-05,0.0046,0.014,0.013,0.008,0.041,0.041,0.035,3.1e-07,3.1e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30790000,0.98,-0.0065,-0.013,0.18,-0.044,0.035,0.76,-0.063,0.052,-1.1,-0.0014,-0.0057,0.0001,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0046,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-07,3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30890000,0.98,-0.0058,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-1,-0.0014,-0.0057,0.0001,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0046,0.013,0.013,0.008,0.041,0.041,0.035,3.1e-07,3.1e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +30990000,0.98,-0.006,-0.013,0.18,-0.037,0.026,0.76,-0.057,0.049,-0.94,-0.0014,-0.0057,0.0001,0.022,-0.012,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0046,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31090000,0.98,-0.0062,-0.013,0.18,-0.035,0.025,0.76,-0.061,0.051,-0.86,-0.0014,-0.0057,0.0001,0.022,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0046,0.013,0.013,0.008,0.041,0.04,0.036,3e-07,3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31190000,0.98,-0.0064,-0.013,0.18,-0.031,0.021,0.76,-0.052,0.046,-0.79,-0.0014,-0.0057,0.0001,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0047,0.013,0.013,0.008,0.037,0.037,0.035,3e-07,3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31290000,0.98,-0.0066,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.72,-0.0014,-0.0057,0.0001,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0047,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31390000,0.98,-0.0064,-0.013,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.65,-0.0014,-0.0057,0.0001,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0047,0.013,0.013,0.0079,0.037,0.037,0.035,3e-07,2.9e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31490000,0.98,-0.0061,-0.014,0.18,-0.022,0.0089,0.76,-0.048,0.043,-0.58,-0.0014,-0.0057,0.0001,0.023,-0.013,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0047,0.013,0.013,0.008,0.04,0.04,0.035,3e-07,3e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31590000,0.98,-0.006,-0.014,0.18,-0.018,0.0067,0.76,-0.038,0.039,-0.51,-0.0014,-0.0057,0.00011,0.023,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0047,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31690000,0.98,-0.006,-0.015,0.18,-0.02,0.0056,0.76,-0.04,0.039,-0.44,-0.0014,-0.0057,0.00011,0.023,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8.1e-05,0.0047,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31790000,0.98,-0.0062,-0.015,0.18,-0.011,0.003,0.76,-0.028,0.037,-0.36,-0.0014,-0.0057,0.00011,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8e-05,0.0047,0.012,0.012,0.008,0.037,0.037,0.035,2.9e-07,2.9e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31890000,0.98,-0.0059,-0.015,0.18,-0.0081,0.00072,0.76,-0.029,0.038,-0.3,-0.0014,-0.0057,0.00011,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8e-05,0.0047,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +31990000,0.98,-0.0062,-0.015,0.18,-0.00022,4.8e-05,0.75,-0.017,0.035,-0.23,-0.0013,-0.0057,0.00011,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,0.0047,0.012,0.012,0.0079,0.037,0.037,0.035,2.9e-07,2.9e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32090000,0.98,-0.0066,-0.014,0.18,-0.00077,-0.0034,0.76,-0.017,0.034,-0.16,-0.0013,-0.0057,0.00011,0.024,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.3e-05,8e-05,0.0047,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-07,2.9e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32190000,0.98,-0.0067,-0.015,0.18,0.0045,-0.0066,0.76,-0.006,0.033,-0.092,-0.0013,-0.0057,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,0.0048,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-07,2.8e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32290000,0.98,-0.0066,-0.015,0.18,0.0061,-0.0093,0.75,-0.0055,0.032,-0.024,-0.0013,-0.0057,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,0.0048,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-07,2.8e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32390000,0.98,-0.0068,-0.015,0.18,0.012,-0.011,0.75,0.0057,0.03,0.051,-0.0013,-0.0057,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,0.0048,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-07,2.8e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32490000,0.98,-0.0096,-0.013,0.18,0.039,-0.074,-0.12,0.0089,0.023,0.054,-0.0013,-0.0057,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.2e-05,8e-05,0.0048,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-07,2.8e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32590000,0.98,-0.0096,-0.013,0.18,0.039,-0.075,-0.12,0.021,0.02,0.035,-0.0014,-0.0057,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,0.0048,0.016,0.016,0.0075,0.037,0.037,0.035,2.8e-07,2.8e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32690000,0.98,-0.0095,-0.013,0.18,0.035,-0.08,-0.12,0.025,0.012,0.02,-0.0014,-0.0057,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,8.1e-05,7.9e-05,0.0048,0.019,0.019,0.0074,0.041,0.041,0.035,2.8e-07,2.8e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32790000,0.98,-0.0092,-0.013,0.18,0.033,-0.078,-0.12,0.034,0.01,0.0044,-0.0014,-0.0056,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.8e-05,7.6e-05,0.0048,0.02,0.02,0.0071,0.037,0.037,0.035,2.7e-07,2.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32890000,0.98,-0.0092,-0.013,0.18,0.033,-0.084,-0.13,0.038,0.002,-0.011,-0.0014,-0.0056,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00017,7.8e-05,7.7e-05,0.0048,0.023,0.024,0.007,0.041,0.041,0.035,2.8e-07,2.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +32990000,0.98,-0.0089,-0.013,0.18,0.03,-0.08,-0.13,0.045,-0.0011,-0.024,-0.0014,-0.0056,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.4e-05,7.2e-05,0.0048,0.024,0.024,0.0067,0.038,0.038,0.035,2.7e-07,2.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33090000,0.98,-0.0089,-0.013,0.18,0.026,-0.084,-0.12,0.048,-0.0093,-0.031,-0.0014,-0.0056,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,7.4e-05,7.2e-05,0.0048,0.029,0.029,0.0066,0.042,0.042,0.035,2.7e-07,2.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33190000,0.98,-0.0086,-0.013,0.18,0.022,-0.079,-0.12,0.054,-0.011,-0.037,-0.0014,-0.0056,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,6.8e-05,6.7e-05,0.0049,0.029,0.029,0.0064,0.038,0.038,0.035,2.7e-07,2.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33290000,0.98,-0.0086,-0.013,0.18,0.019,-0.08,-0.12,0.056,-0.019,-0.045,-0.0014,-0.0056,0.00011,0.025,-0.014,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,6.8e-05,6.7e-05,0.0049,0.035,0.035,0.0063,0.043,0.043,0.034,2.7e-07,2.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33390000,0.98,-0.0081,-0.013,0.18,0.014,-0.066,-0.12,0.059,-0.014,-0.053,-0.0014,-0.0056,0.00011,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,6.1e-05,6e-05,0.0049,0.035,0.035,0.0062,0.039,0.039,0.034,2.7e-07,2.6e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33490000,0.98,-0.0081,-0.013,0.18,0.0092,-0.067,-0.12,0.06,-0.021,-0.063,-0.0014,-0.0056,0.00011,0.025,-0.016,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,6.1e-05,6e-05,0.0049,0.042,0.042,0.0061,0.044,0.044,0.034,2.7e-07,2.7e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33590000,0.98,-0.0077,-0.013,0.18,0.0054,-0.058,-0.11,0.063,-0.017,-0.069,-0.0014,-0.0056,0.00011,0.024,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,5.4e-05,5.3e-05,0.0049,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-07,2.6e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33690000,0.98,-0.0077,-0.013,0.18,0.00071,-0.058,-0.11,0.063,-0.023,-0.077,-0.0014,-0.0056,0.00011,0.024,-0.019,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,5.4e-05,5.3e-05,0.0049,0.048,0.048,0.0059,0.046,0.046,0.034,2.7e-07,2.6e-07,1e-05,0.027,0.027,0.0005,0,0,0,0,0,0,0,0 +33790000,0.98,-0.0075,-0.013,0.18,-0.0024,-0.047,-0.11,0.067,-0.018,-0.083,-0.0014,-0.0056,0.00011,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,4.8e-05,4.7e-05,0.0049,0.045,0.045,0.0059,0.041,0.041,0.034,2.6e-07,2.6e-07,1e-05,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 +33890000,0.98,-0.0075,-0.013,0.18,-0.0066,-0.045,-0.11,0.066,-0.023,-0.089,-0.0014,-0.0056,0.00011,0.023,-0.021,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,4.8e-05,4.7e-05,0.0049,0.052,0.053,0.0058,0.047,0.047,0.033,2.6e-07,2.6e-07,1e-05,0.026,0.026,0.0005,0,0,0,0,0,0,0,0 +33990000,0.98,-0.0072,-0.013,0.18,-0.0062,-0.031,-0.1,0.069,-0.015,-0.092,-0.0014,-0.0056,0.00011,0.02,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,4.2e-05,4.1e-05,0.0049,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-07,2.6e-07,1e-05,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 +34090000,0.98,-0.0072,-0.013,0.18,-0.01,-0.031,-0.1,0.069,-0.018,-0.096,-0.0014,-0.0056,0.00011,0.02,-0.024,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,4.2e-05,4.1e-05,0.0049,0.054,0.055,0.0058,0.049,0.049,0.033,2.6e-07,2.6e-07,1e-05,0.025,0.025,0.0005,0,0,0,0,0,0,0,0 +34190000,0.98,-0.0071,-0.013,0.18,-0.011,-0.02,-0.098,0.072,-0.013,-0.099,-0.0014,-0.0056,0.00011,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,3.8e-05,3.7e-05,0.005,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-07,2.6e-07,1e-05,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 +34290000,0.98,-0.007,-0.013,0.18,-0.012,-0.02,-0.097,0.071,-0.015,-0.1,-0.0014,-0.0056,0.00011,0.019,-0.026,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,3.8e-05,3.7e-05,0.005,0.055,0.055,0.0058,0.05,0.05,0.033,2.7e-07,2.6e-07,1e-05,0.024,0.024,0.0005,0,0,0,0,0,0,0,0 +34390000,0.98,-0.0069,-0.013,0.18,-0.013,-0.01,-0.092,0.072,-0.01,-0.11,-0.0014,-0.0056,0.00011,0.017,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,3.4e-05,3.3e-05,0.005,0.047,0.047,0.0058,0.044,0.044,0.033,2.7e-07,2.6e-07,1e-05,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 +34490000,0.98,-0.0069,-0.013,0.18,-0.016,-0.0091,-0.089,0.071,-0.011,-0.11,-0.0014,-0.0056,0.00011,0.017,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,3.4e-05,3.3e-05,0.005,0.053,0.054,0.0059,0.051,0.051,0.032,2.7e-07,2.6e-07,1e-05,0.023,0.023,0.0005,0,0,0,0,0,0,0,0 +34590000,0.98,-0.0069,-0.013,0.18,-0.014,-0.0048,0.71,0.073,-0.0088,-0.081,-0.0014,-0.0056,0.00011,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,3.2e-05,3.1e-05,0.005,0.044,0.044,0.0059,0.045,0.045,0.032,2.7e-07,2.7e-07,1e-05,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 +34690000,0.98,-0.0069,-0.012,0.18,-0.017,-0.0027,1.7,0.071,-0.0091,0.038,-0.0014,-0.0056,0.00011,0.016,-0.028,-0.11,0.37,0.0037,0.025,0,0,0,0,0,0.00018,3.2e-05,3.1e-05,0.005,0.047,0.048,0.006,0.052,0.052,0.032,2.7e-07,2.7e-07,1e-05,0.022,0.022,0.0005,0,0,0,0,0,0,0,0 +34790000,0.98,-0.0068,-0.012,0.18,-0.018,0.0019,2.7,0.072,-0.0068,0.21,-0.0014,-0.0056,0.00011,0.017,-0.029,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00018,3.1e-05,3e-05,0.005,0.04,0.04,0.0061,0.045,0.045,0.032,2.7e-07,2.7e-07,1e-05,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 +34890000,0.98,-0.0068,-0.012,0.18,-0.022,0.0044,3.6,0.07,-0.0063,0.5,-0.0014,-0.0056,0.00011,0.018,-0.03,-0.1,0.37,0.0037,0.025,0,0,0,0,0,0.00018,3.1e-05,3e-05,0.005,0.044,0.044,0.0061,0.052,0.052,0.032,2.7e-07,2.7e-07,1e-05,0.021,0.021,0.0005,0,0,0,0,0,0,0,0 diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp index 95ccb1e3cc8e..bba4df845995 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp @@ -205,6 +205,11 @@ bool EkfWrapper::isIntendingMag3DFusion() const return _ekf->control_status_flags().mag_3D; } +bool EkfWrapper::isMagHeadingConsistent() const +{ + return _ekf->control_status_flags().mag_heading_consistent; +} + void EkfWrapper::setMagFuseTypeNone() { _ekf_params->mag_fusion_type = MagFuseType::NONE; diff --git a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h index 9e5350539572..e1c3ce0d9c7a 100644 --- a/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h @@ -100,6 +100,7 @@ class EkfWrapper bool isIntendingMagHeadingFusion() const; bool isIntendingMag3DFusion() const; + bool isMagHeadingConsistent() const; void setMagFuseTypeNone(); void enableMagStrengthCheck(); void enableMagInclinationCheck(); diff --git a/src/modules/ekf2/test/test_EKF_externalVision.cpp b/src/modules/ekf2/test/test_EKF_externalVision.cpp index 3be67e2da70b..650c8aaf2791 100644 --- a/src/modules/ekf2/test/test_EKF_externalVision.cpp +++ b/src/modules/ekf2/test/test_EKF_externalVision.cpp @@ -61,9 +61,8 @@ class EkfExternalVisionTest : public ::testing::Test // 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) + // 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); } diff --git a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp index 6222c0502049..432183ac968c 100644 --- a/src/modules/ekf2/test/test_EKF_gps_yaw.cpp +++ b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp @@ -61,9 +61,8 @@ class EkfGpsHeadingTest : public ::testing::Test // 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) + // 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); @@ -304,9 +303,12 @@ TEST_F(EkfGpsHeadingTest, yawJumpInAir) _sensor_simulator.runSeconds(7.5); // THEN: after a few seconds, the fusion should stop and - // the estimator should fall back to mag fusion + // the estimator doesn't fall back to mag fusion because it has + // been declared inconsistent with the filter states EXPECT_FALSE(_ekf_wrapper.isIntendingGpsHeadingFusion()); - EXPECT_TRUE(_ekf_wrapper.isIntendingMagHeadingFusion()); + EXPECT_FALSE(_ekf_wrapper.isMagHeadingConsistent()); + //TODO: should we force a reset to mag if the GNSS yaw fusion was forced to stop? + EXPECT_FALSE(_ekf_wrapper.isIntendingMagHeadingFusion()); } TEST_F(EkfGpsHeadingTest, stopOnGround) diff --git a/src/modules/ekf2/test/test_EKF_gyroscope.cpp b/src/modules/ekf2/test/test_EKF_gyroscope.cpp index e19bd2586b0d..8d3daac16957 100644 --- a/src/modules/ekf2/test/test_EKF_gyroscope.cpp +++ b/src/modules/ekf2/test/test_EKF_gyroscope.cpp @@ -58,9 +58,8 @@ class EkfGyroscopeTest : public ::testing::Test // 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) + // 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); } @@ -70,22 +69,25 @@ class EkfGyroscopeTest : public ::testing::Test { } - void testBias(const Vector3f &bias, float duration, float tolerance); + void testBias(const Vector3f &bias, float duration, const Vector3f &tolerance); }; -void EkfGyroscopeTest::testBias(const Vector3f &bias, float duration, float tolerance) +void EkfGyroscopeTest::testBias(const Vector3f &bias, float duration, const Vector3f &tolerance) { _sensor_simulator._imu.setGyroData(bias); _sensor_simulator.runSeconds(duration); + EXPECT_TRUE(_ekf->control_status_flags().vehicle_at_rest); const Vector3f estimated_bias = _ekf->getGyroBias(); - EXPECT_TRUE(matrix::isEqual(estimated_bias, bias, - tolerance)) << estimated_bias - bias; + + for (int i = 0; i < 3; i++) { + EXPECT_NEAR(estimated_bias(i), bias(i), tolerance(i)) << "index " << i; + } } TEST_F(EkfGyroscopeTest, biasEstimateZero) { - testBias(Vector3f(), 10, 0.f); + testBias(Vector3f(), 10, Vector3f()); } TEST_F(EkfGyroscopeTest, biasEstimatePositive) @@ -96,7 +98,8 @@ TEST_F(EkfGyroscopeTest, biasEstimatePositive) for (int i = 0; i < 4; i ++) { bias.setAll(biases[i]); - testBias(bias, 30, 0.0008f); + // The Z gyro bias takes more time to converge as the Z rotation variance is higher + testBias(bias, 30, Vector3f(0.0008f, 0.0008f, 0.004f)); } } @@ -107,6 +110,6 @@ TEST_F(EkfGyroscopeTest, biasEstimateNegative) for (int i = 0; i < 4; i ++) { bias.setAll(biases[i]); - testBias(bias, 30, 0.0008f); + testBias(bias, 30, Vector3f(0.0008f, 0.0008f, 0.004f)); } } diff --git a/src/modules/ekf2/test/test_EKF_mag.cpp b/src/modules/ekf2/test/test_EKF_mag.cpp index b166aea45ff2..b38d5fb38709 100644 --- a/src/modules/ekf2/test/test_EKF_mag.cpp +++ b/src/modules/ekf2/test/test_EKF_mag.cpp @@ -57,9 +57,8 @@ class EkfMagTest : public ::testing::Test // 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) + // 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); } From 09a2dc633daef585ef2f364117c216a833068721 Mon Sep 17 00:00:00 2001 From: bresch <[brescianimathieu@gmail.com](mailto:brescianimathieu@gmail.com)> Date: Fri, 18 Aug 2023 13:32:43 +0200 Subject: [PATCH 10/11] fw-atune: limit max test signal Whe the P gain is high, the test signal is large too. However, it should not exceed what is allowed from the max rate parameter. --- .../fw_autotune_attitude_control.cpp | 8 +++++--- .../fw_autotune_attitude_control.hpp | 6 +++++- 2 files changed, 10 insertions(+), 4 deletions(-) diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp index ec274f28dac2..f5832ea2af05 100644 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp +++ b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp @@ -638,19 +638,21 @@ const Vector3f FwAutotuneAttitudeControl::getIdentificationSignal() if (_state == state::roll || _state == state::test) { // Scale the signal such that the attitude controller is // able to cancel it completely at an attitude error of pi/8 - signal_scaled = signal * M_PI_F / (8.f * _param_fw_r_tc.get()); + signal_scaled = math::min(signal * M_PI_F / (8.f * _param_fw_r_tc.get()), math::radians(_param_fw_r_rmax.get())); rate_sp(0) = signal_scaled - _signal_filter.getState(); } if (_state == state::pitch || _state == state::test) { - signal_scaled = signal * M_PI_F / (8.f * _param_fw_p_tc.get()); + const float pitch_rate_max_deg = math::min(_param_fw_p_rmax_pos.get(), _param_fw_p_rmax_neg.get()); + signal_scaled = math::min(signal * M_PI_F / (8.f * _param_fw_p_tc.get()), math::radians(pitch_rate_max_deg)); rate_sp(1) = signal_scaled - _signal_filter.getState(); } if (_state == state::yaw) { // Do not send a signal that produces more than a full deflection of the rudder - signal_scaled = math::min(signal, 1.f / (_param_fw_yr_ff.get() + _param_fw_yr_p.get())); + signal_scaled = math::min(signal, 1.f / (_param_fw_yr_ff.get() + _param_fw_yr_p.get()), + math::radians(_param_fw_y_rmax.get())); rate_sp(2) = signal_scaled - _signal_filter.getState(); } diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.hpp b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.hpp index 213518ef7206..9be5f5559664 100644 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.hpp +++ b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.hpp @@ -193,14 +193,18 @@ class FwAutotuneAttitudeControl : public ModuleBase, (ParamFloat) _param_fw_rr_p, (ParamFloat) _param_fw_rr_i, (ParamFloat) _param_fw_rr_ff, + (ParamFloat) _param_fw_r_rmax, (ParamFloat) _param_fw_r_tc, (ParamFloat) _param_fw_pr_p, (ParamFloat) _param_fw_pr_i, (ParamFloat) _param_fw_pr_ff, + (ParamFloat) _param_fw_p_rmax_pos, + (ParamFloat) _param_fw_p_rmax_neg, (ParamFloat) _param_fw_p_tc, (ParamFloat) _param_fw_yr_p, (ParamFloat) _param_fw_yr_i, - (ParamFloat) _param_fw_yr_ff + (ParamFloat) _param_fw_yr_ff, + (ParamFloat) _param_fw_y_rmax ) static constexpr float _publishing_dt_s = 100e-3f; From 3c4cca67379adbf965dc540e33612742ae8ca1ba Mon Sep 17 00:00:00 2001 From: bresch <[brescianimathieu@gmail.com](mailto:brescianimathieu@gmail.com)> Date: Fri, 18 Aug 2023 14:13:38 +0200 Subject: [PATCH 11/11] fw-atune: use same attitude P rule as for multirotors The current rule was producing too high gains. Also constrain the value using the prameter's limits. --- .../fw_autotune_attitude_control.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp index f5832ea2af05..eee05880fdd5 100644 --- a/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp +++ b/src/modules/fw_autotune_attitude_control/fw_autotune_attitude_control.cpp @@ -180,7 +180,11 @@ void FwAutotuneAttitudeControl::Run() Vector3f kid = pid_design::computePidGmvc(num_design, den, _sample_interval_avg, 0.2f, 0.f, 0.4f); _kiff(0) = kid(0); _kiff(1) = kid(1); - _attitude_p = 8.f / (M_PI_F * (_kiff(2) + _kiff(0))); // Maximum control power at an attitude error of pi/8 + + // To compute the attitude gain, use the following empirical rule: + // "An error of 60 degrees should produce the maximum control output" + // or K_att * (K_rate + K_ff) * rad(60) = 1 + _attitude_p = math::constrain(1.f / (math::radians(60.f) * (_kiff(0) + _kiff(2))), 1.f, 5.f); const Vector &coeff_var = _sys_id.getVariances(); const Vector3f rate_sp = _sys_id.areFiltersInitialized()