Compare commits

..

20 Commits

Author SHA1 Message Date
bresch bc9df1a2d4 slew_rate: pass vector by const ref 2024-03-13 10:35:40 +01:00
bresch d32680f87f AutoTrim: allow auto-trimming when no airspeed is available 2024-03-13 10:35:40 +01:00
bresch 8eadfa8bf6 HACK: temporarily deactivate modules for flash space 2024-03-13 10:35:40 +01:00
bresch badfbd7bac FwRateControl: remove redundant if
Same as outer if
2024-03-13 10:35:40 +01:00
bresch 8cc190e327 remove print 2024-03-13 10:35:40 +01:00
bresch bbfc772f1f AutoTrimStatus: add comments to message fields 2024-03-13 10:35:40 +01:00
bresch 8bf3c2960c FwTrim: print trim update 2024-03-13 10:35:40 +01:00
bresch 797bf6e775 correctly reset auto-trim after save 2024-03-13 10:35:40 +01:00
bresch a86b9fc6c9 FwAutoTrim: only use auto-trim values if enabled 2024-03-13 10:35:40 +01:00
bresch 6fc91f9a76 FwAutoTrim: save estimated trim back to params 2024-03-13 10:35:40 +01:00
bresch afc9d6dfab FwTrim class 2024-03-13 10:35:40 +01:00
bresch 5f992423c1 remove kconfig 2024-03-13 10:35:40 +01:00
bresch d526cb7d6c use auto_trim on top of current trim 2024-03-13 10:35:40 +01:00
bresch d6c141dd29 add slew-rate 2024-03-13 10:35:40 +01:00
bresch 215081b6e2 migrate fw_auto_trim module to fw_rate_control 2024-03-13 10:35:40 +01:00
bresch 96517c05a0 TEMP: verbose auto-trim logging 2024-03-13 10:35:40 +01:00
bresch c661a6dfa7 address review comments 2024-03-13 10:35:40 +01:00
bresch 42a8e1b1c0 add fw_auto_trim on v5 and v6 boards 2024-03-13 10:35:40 +01:00
bresch 6b42fb0ff7 Add new auto-trim module for fixed-wings
Estimates the torque trim values while flying
2024-03-13 10:35:40 +01:00
bresch f671e036e8 WelfordMeanVector: include matrix lib 2024-03-13 10:35:40 +01:00
118 changed files with 2190 additions and 3263 deletions

View File

@ -1,14 +0,0 @@
root = true
[*]
insert_final_newline = false
[{*.{c,cpp,cc,h,hpp},CMakeLists.txt,Kconfig}]
indent_style = tab
tab_width = 8
# Not in the official standard, but supported by many editors
max_line_length = 120
[*.yaml]
indent_style = space
indent_size = 2

2
.gitmodules vendored
View File

@ -81,5 +81,5 @@
url = https://github.com/PX4/PX4-gazebo-models.git
branch = main
[submodule "boards/modalai/voxl2/libfc-sensor-api"]
path = boards/modalai/voxl2/libfc-sensor-api
path = src/modules/muorb/apps/libfc-sensor-api
url = https://gitlab.com/voxl-public/voxl-sdk/core-libs/libfc-sensor-api.git

View File

@ -30,5 +30,5 @@ exec find boards msg src platforms test \
-path src/lib/cdrstream/cyclonedds -prune -o \
-path src/lib/cdrstream/rosidl -prune -o \
-path src/modules/zenoh/zenoh-pico -prune -o \
-path boards/modalai/voxl2/libfc-sensor-api -prune -o \
-path src/modules/muorb/apps/libfc-sensor-api -prune -o \
-type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) | grep $PATTERN

View File

@ -20,7 +20,6 @@ CONFIG_UAVCANNODE_RTK_DATA=y
CONFIG_UAVCANNODE_SAFETY_BUTTON=y
CONFIG_UAVCANNODE_STATIC_PRESSURE=y
CONFIG_UAVCANNODE_STATIC_TEMPERATURE=y
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_MAG_BIAS_ESTIMATOR=y
CONFIG_MODULES_SENSORS=y

View File

@ -11,5 +11,3 @@ param set-default SENS_IMU_CLPNOTI 0
safety_button start
tone_alarm start
ekf2 start

View File

@ -50,7 +50,6 @@ CONFIG_STACK_COLORATION=y
CONFIG_START_DAY=30
CONFIG_START_MONTH=11
CONFIG_STDIO_DISABLE_BUFFERING=y
CONFIG_STM32_FLASH_CONFIG_G=y
CONFIG_STM32_NOEXT_VECTORS=y
CONFIG_STM32_TIM8=y
CONFIG_TASK_NAME_SIZE=0

View File

@ -123,7 +123,6 @@ CONFIG_STM32_ADC1=y
CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
CONFIG_STM32_DMA1=y
CONFIG_STM32_DMA2=y
CONFIG_STM32_FLASH_CONFIG_G=y
CONFIG_STM32_FLASH_PREFETCH=y
CONFIG_STM32_FLOWCONTROL_BROKEN=y
CONFIG_STM32_I2C1=y

View File

@ -33,7 +33,7 @@
*
****************************************************************************/
/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and
/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
* 256Kb of SRAM. SRAM is split up into three blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000

View File

@ -33,7 +33,7 @@
*
****************************************************************************/
/* The STM32F412 has 1M of FLASH beginning at address 0x0800:0000 and
/* The STM32F412 has 512Kb of FLASH beginning at address 0x0800:0000 and
* 256Kb of SRAM. SRAM is split up into three blocks:
*
* 1) 112Kb of SRAM beginning at address 0x2000:0000

View File

@ -60,7 +60,7 @@ CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
# CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
CONFIG_MODULES_UXRCE_DDS_CLIENT=y
CONFIG_MODULES_VTOL_ATT_CONTROL=y

View File

@ -4,7 +4,6 @@ CONFIG_DRIVERS_ACTUATORS_VOXL_ESC=y
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP101XX=y
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L0X=y
CONFIG_DRIVERS_DISTANCE_SENSOR_VL53L1X=y
CONFIG_DRIVERS_GPS=y
CONFIG_DRIVERS_IMU_INVENSENSE_ICM42688P=y
CONFIG_DRIVERS_LIGHTS_RGBLED_NCP5623C=y
CONFIG_DRIVERS_MAGNETOMETER_ISENTEK_IST8308=y

View File

@ -1,7 +1,7 @@
# Link against the public stub version of the proprietary fc sensor library
target_link_libraries(px4 PRIVATE
${PX4_BOARD_DIR}/libfc-sensor-api/build/libfc_sensor.so
${PX4_SOURCE_DIR}/src//modules/muorb/apps/libfc-sensor-api/build/libfc_sensor.so
px4_layer
${module_libraries}
)

View File

@ -11,6 +11,7 @@ CONFIG_DRIVERS_VOXL2_IO=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_LOAD_MON=y
CONFIG_MODULES_LOGGER=y
CONFIG_MODULES_MAVLINK=y
CONFIG_MODULES_MUORB_APPS=y

View File

@ -1,9 +1,10 @@
#!/bin/bash
cd boards/modalai/voxl2/libfc-sensor-api
cd src/modules/muorb/apps/libfc-sensor-api
rm -fR build
mkdir build
cd build
CC=/home/4.1.0.4/tools/linaro64/bin/aarch64-linux-gnu-gcc cmake ..
make
cd ../../../../..
cd ../../../../../..

View File

@ -76,6 +76,7 @@ qshell flight_mode_manager start
# Start all of the processing modules on the applications processor
dataman start
navigator start
load_mon start
# Start microdds_client for ros2 offboard messages from agent over localhost
microdds_client start -t udp -h 127.0.0.1 -p 8888

View File

@ -207,6 +207,7 @@ qshell flight_mode_manager start
# Start all of the processing modules on the applications processor
dataman start
navigator start
load_mon start
# This bridge allows raw data packets to be sent over UART to the ESC
voxl2_io_bridge start

View File

@ -49,6 +49,7 @@ CONFIG_MODULES_FW_POS_CONTROL=y
CONFIG_MODULES_FW_RATE_CONTROL=y
CONFIG_MODULES_GIMBAL=y
CONFIG_MODULES_GYRO_CALIBRATION=y
CONFIG_MODULES_GYRO_FFT=y
CONFIG_MODULES_LAND_DETECTOR=y
CONFIG_MODULES_LANDING_TARGET_ESTIMATOR=y
CONFIG_MODULES_LOAD_MON=y

View File

@ -53,7 +53,7 @@ CONFIG_MODULES_CAMERA_FEEDBACK=y
CONFIG_MODULES_COMMANDER=y
CONFIG_MODULES_CONTROL_ALLOCATOR=y
CONFIG_MODULES_DATAMAN=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE=y
CONFIG_MODULES_DIFFERENTIAL_DRIVE=n
CONFIG_MODULES_EKF2=y
CONFIG_MODULES_ESC_BATTERY=y
CONFIG_MODULES_EVENTS=y
@ -81,6 +81,7 @@ CONFIG_MODULES_NAVIGATOR=y
CONFIG_MODE_NAVIGATOR_VTOL_TAKEOFF=y
CONFIG_MODULES_PAYLOAD_DELIVERER=y
CONFIG_MODULES_RC_UPDATE=y
CONFIG_MODULES_ROVER_POS_CONTROL=y
CONFIG_MODULES_SENSORS=y
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=y
CONFIG_MODULES_TEMPERATURE_COMPENSATION=y
@ -101,7 +102,9 @@ CONFIG_SYSTEMCMDS_NSHTERM=y
CONFIG_SYSTEMCMDS_PARAM=y
CONFIG_SYSTEMCMDS_PERF=y
CONFIG_SYSTEMCMDS_REBOOT=y
CONFIG_SYSTEMCMDS_REFLECT=y
CONFIG_SYSTEMCMDS_SD_BENCH=y
CONFIG_SYSTEMCMDS_SD_STRESS=y
CONFIG_SYSTEMCMDS_SYSTEM_TIME=y
CONFIG_SYSTEMCMDS_TOP=y
CONFIG_SYSTEMCMDS_TOPIC_LISTENER=y

View File

@ -13,7 +13,7 @@ CONFIG_DRIVERS_BAROMETER_BMP388=y
CONFIG_DRIVERS_BAROMETER_INVENSENSE_ICP201XX=y
CONFIG_DRIVERS_BAROMETER_MS5611=y
CONFIG_DRIVERS_CAMERA_CAPTURE=y
CONFIG_DRIVERS_CAMERA_TRIGGER=y
CONFIG_DRIVERS_CAMERA_TRIGGER=n
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
CONFIG_COMMON_DISTANCE_SENSOR=y
CONFIG_DRIVERS_DSHOT=y

17
msg/AutoTrimStatus.msg Normal file
View File

@ -0,0 +1,17 @@
uint64 timestamp # Time since system start (microseconds)
uint64 timestamp_sample
float32[3] trim_estimate # Roll/pitch/yaw trim value obtained from torque setpoints averaged over several seconds
float32[3] trim_estimate_var
float32[3] trim_test # Same as trim_estimate but done on a shorter period. Used to validate the trim estimate.
float32[3] trim_test_var
float32[3] trim_validated # Final roll/pitch/yaw trim estimate, verified by trim_test
uint8 STATE_IDLE = 0
uint8 STATE_SAMPLING = 1
uint8 STATE_SAMPLING_TEST = 2
uint8 STATE_VERIFICATION = 3
uint8 STATE_COMPLETE = 4
uint8 STATE_FAIL = 5
uint8 state

View File

@ -52,13 +52,13 @@ set(msg_files
ArmingCheckReply.msg
ArmingCheckRequest.msg
AutotuneAttitudeControlStatus.msg
AutoTrimStatus.msg
BatteryStatus.msg
Buffer128.msg
ButtonEvent.msg
CameraCapture.msg
CameraStatus.msg
CameraTrigger.msg
CanInterfaceStatus.msg
CellularStatus.msg
CollisionConstraints.msg
CollisionReport.msg

View File

@ -1,6 +0,0 @@
uint64 timestamp # time since system start (microseconds)
uint8 interface
uint64 io_errors
uint64 frames_tx
uint64 frames_rx

View File

@ -52,7 +52,6 @@ add_library(px4_platform STATIC
shutdown.cpp
spi.cpp
pab_manifest.c
Serial.cpp
${SRCS}
)
target_link_libraries(px4_platform prebuild_targets px4_work_queue)

View File

@ -1,138 +0,0 @@
/****************************************************************************
*
* 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 <px4_platform_common/Serial.hpp>
namespace device
{
Serial::Serial(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits,
FlowControl flowcontrol) :
_impl(port, baudrate, bytesize, parity, stopbits, flowcontrol)
{
// If no baudrate was specified then set it to a reasonable default value
if (baudrate == 0) {
(void) _impl.setBaudrate(9600);
}
}
Serial::~Serial()
{
}
bool Serial::open()
{
return _impl.open();
}
bool Serial::isOpen() const
{
return _impl.isOpen();
}
bool Serial::close()
{
return _impl.close();
}
ssize_t Serial::read(uint8_t *buffer, size_t buffer_size)
{
return _impl.read(buffer, buffer_size);
}
ssize_t Serial::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
{
return _impl.readAtLeast(buffer, buffer_size, character_count, timeout_us);
}
ssize_t Serial::write(const void *buffer, size_t buffer_size)
{
return _impl.write(buffer, buffer_size);
}
uint32_t Serial::getBaudrate() const
{
return _impl.getBaudrate();
}
bool Serial::setBaudrate(uint32_t baudrate)
{
return _impl.setBaudrate(baudrate);
}
ByteSize Serial::getBytesize() const
{
return _impl.getBytesize();
}
bool Serial::setBytesize(ByteSize bytesize)
{
return _impl.setBytesize(bytesize);
}
Parity Serial::getParity() const
{
return _impl.getParity();
}
bool Serial::setParity(Parity parity)
{
return _impl.setParity(parity);
}
StopBits Serial::getStopbits() const
{
return _impl.getStopbits();
}
bool Serial::setStopbits(StopBits stopbits)
{
return _impl.setStopbits(stopbits);
}
FlowControl Serial::getFlowcontrol() const
{
return _impl.getFlowcontrol();
}
bool Serial::setFlowcontrol(FlowControl flowcontrol)
{
return _impl.setFlowcontrol(flowcontrol);
}
const char *Serial::getPort() const
{
return _impl.getPort();
}
} // namespace device

View File

@ -1,97 +0,0 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#pragma once
#include <SerialImpl.hpp>
#include <px4_platform_common/SerialCommon.hpp>
using device::SerialConfig::ByteSize;
using device::SerialConfig::Parity;
using device::SerialConfig::StopBits;
using device::SerialConfig::FlowControl;
namespace device __EXPORT
{
class Serial
{
public:
Serial(const char *port, uint32_t baudrate = 57600,
ByteSize bytesize = ByteSize::EightBits, Parity parity = Parity::None,
StopBits stopbits = StopBits::One, FlowControl flowcontrol = FlowControl::Disabled);
virtual ~Serial();
// Open sets up the port and gets it configured based on desired configuration
bool open();
bool isOpen() const;
bool close();
ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
ssize_t write(const void *buffer, size_t buffer_size);
// If port is already open then the following configuration functions
// will reconfigure the port. If the port is not yet open then they will
// simply store the configuration in preparation for the port to be opened.
uint32_t getBaudrate() const;
bool setBaudrate(uint32_t baudrate);
ByteSize getBytesize() const;
bool setBytesize(ByteSize bytesize);
Parity getParity() const;
bool setParity(Parity parity);
StopBits getStopbits() const;
bool setStopbits(StopBits stopbits);
FlowControl getFlowcontrol() const;
bool setFlowcontrol(FlowControl flowcontrol);
const char *getPort() const;
private:
// Disable copy constructors
Serial(const Serial &);
Serial &operator=(const Serial &);
// platform implementation
SerialImpl _impl;
};
} // namespace device

View File

@ -1,70 +0,0 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#pragma once
namespace device
{
namespace SerialConfig
{
// ByteSize: number of data bits
enum class ByteSize {
FiveBits = 5,
SixBits = 6,
SevenBits = 7,
EightBits = 8,
};
// Parity: enable parity checking
enum class Parity {
None = 0,
Odd = 1,
Even = 2,
};
// StopBits: number of stop bits
enum class StopBits {
One = 1,
Two = 2
};
// FlowControl: enable flow control
enum class FlowControl {
Disabled = 0,
Enabled = 1,
};
} // namespace SerialConfig
} // namespace device

View File

@ -13,21 +13,11 @@ __END_DECLS
#define px4_clock_gettime system_clock_gettime
#endif
#if defined(ENABLE_LOCKSTEP_SCHEDULER) || defined(__PX4_QURT)
__BEGIN_DECLS
__EXPORT int px4_clock_settime(clockid_t clk_id, const struct timespec *tp);
__END_DECLS
#else
#define px4_clock_settime system_clock_settime
#endif
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
__BEGIN_DECLS
__EXPORT int px4_clock_settime(clockid_t clk_id, const struct timespec *tp);
__EXPORT int px4_usleep(useconds_t usec);
__EXPORT unsigned int px4_sleep(unsigned int seconds);
__EXPORT int px4_pthread_cond_timedwait(pthread_cond_t *cond,
@ -37,6 +27,7 @@ __END_DECLS
#else
#define px4_clock_settime system_clock_settime
#define px4_usleep system_usleep
#define px4_sleep system_sleep
#define px4_pthread_cond_timedwait system_pthread_cond_timedwait

View File

@ -56,6 +56,31 @@ public:
SubscriptionBlocking(const orb_metadata *meta, uint32_t interval_us = 0, uint8_t instance = 0) :
SubscriptionCallback(meta, interval_us, instance)
{
// pthread_mutexattr_init
pthread_mutexattr_t attr;
int ret_attr_init = pthread_mutexattr_init(&attr);
if (ret_attr_init != 0) {
PX4_ERR("pthread_mutexattr_init failed, status=%d", ret_attr_init);
}
#if defined(PTHREAD_PRIO_NONE)
// pthread_mutexattr_settype
// PTHREAD_PRIO_NONE not available on cygwin
int ret_mutexattr_settype = pthread_mutexattr_settype(&attr, PTHREAD_PRIO_NONE);
if (ret_mutexattr_settype != 0) {
PX4_ERR("pthread_mutexattr_settype failed, status=%d", ret_mutexattr_settype);
}
#endif // PTHREAD_PRIO_NONE
// pthread_mutex_init
int ret_mutex_init = pthread_mutex_init(&_mutex, &attr);
if (ret_mutex_init != 0) {
PX4_ERR("pthread_mutex_init failed, status=%d", ret_mutex_init);
}
}
virtual ~SubscriptionBlocking()

View File

@ -412,10 +412,7 @@ int16_t uORB::DeviceNode::process_add_subscription()
uORBCommunicator::IChannel *ch = uORB::Manager::get_instance()->get_uorb_communicator();
if (_data != nullptr && ch != nullptr) { // _data will not be null if there is a publisher.
// Only send the most recent data to initialize the remote end.
if (_data_valid) {
ch->send_message(_meta->o_name, _meta->o_size, _data + (_meta->o_size * ((_generation.load() - 1) % _meta->o_queue)));
}
ch->send_message(_meta->o_name, _meta->o_size, _data);
}
return PX4_OK;

View File

@ -1,394 +0,0 @@
/****************************************************************************
*
* 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 <SerialImpl.hpp>
#include <string.h> // strncpy
#include <termios.h>
#include <px4_log.h>
#include <fcntl.h>
#include <errno.h>
#include <poll.h>
#include <drivers/drv_hrt.h>
#define MODULE_NAME "SerialImpl"
namespace device
{
SerialImpl::SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits,
FlowControl flowcontrol) :
_baudrate(baudrate),
_bytesize(bytesize),
_parity(parity),
_stopbits(stopbits),
_flowcontrol(flowcontrol)
{
if (port) {
strncpy(_port, port, sizeof(_port) - 1);
_port[sizeof(_port) - 1] = '\0';
} else {
_port[0] = 0;
}
}
SerialImpl::~SerialImpl()
{
if (isOpen()) {
close();
}
}
bool SerialImpl::validateBaudrate(uint32_t baudrate)
{
return ((baudrate == 9600) ||
(baudrate == 19200) ||
(baudrate == 38400) ||
(baudrate == 57600) ||
(baudrate == 115200) ||
(baudrate == 230400) ||
(baudrate == 460800) ||
(baudrate == 921600));
}
bool SerialImpl::configure()
{
/* process baud rate */
int speed;
if (! validateBaudrate(_baudrate)) {
PX4_ERR("ERR: unknown baudrate: %lu", _baudrate);
return false;
}
switch (_baudrate) {
case 9600: speed = B9600; break;
case 19200: speed = B19200; break;
case 38400: speed = B38400; break;
case 57600: speed = B57600; break;
case 115200: speed = B115200; break;
case 230400: speed = B230400; break;
#ifndef B460800
#define B460800 460800
#endif
case 460800: speed = B460800; break;
#ifndef B921600
#define B921600 921600
#endif
case 921600: speed = B921600; break;
default:
PX4_ERR("ERR: unknown baudrate: %lu", _baudrate);
return false;
}
struct termios uart_config;
int termios_state;
/* fill the struct for the new configuration */
if ((termios_state = tcgetattr(_serial_fd, &uart_config)) < 0) {
PX4_ERR("ERR: %d (tcgetattr)", termios_state);
return false;
}
/* properly configure the terminal (see also https://en.wikibooks.org/wiki/Serial_Programming/termios ) */
//
// Input flags - Turn off input processing
//
// convert break to null byte, no CR to NL translation,
// no NL to CR translation, don't mark parity errors or breaks
// no input parity check, don't strip high bit off,
// no XON/XOFF software flow control
//
uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL |
INLCR | PARMRK | INPCK | ISTRIP | IXON);
//
// Output flags - Turn off output processing
//
// no CR to NL translation, no NL to CR-NL translation,
// no NL to CR translation, no column 0 CR suppression,
// no Ctrl-D suppression, no fill characters, no case mapping,
// no local output processing
//
// config.c_oflag &= ~(OCRNL | ONLCR | ONLRET |
// ONOCR | ONOEOT| OFILL | OLCUC | OPOST);
uart_config.c_oflag = 0;
//
// No line processing
//
// echo off, echo newline off, canonical mode off,
// extended input processing off, signal chars off
//
uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
/* no parity, one stop bit, disable flow control */
uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS);
/* set baud rate */
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
PX4_ERR("ERR: %d (cfsetispeed)", termios_state);
return false;
}
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
PX4_ERR("ERR: %d (cfsetospeed)", termios_state);
return false;
}
if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) {
PX4_ERR("ERR: %d (tcsetattr)", termios_state);
return false;
}
return true;
}
bool SerialImpl::open()
{
if (isOpen()) {
return true;
}
// Open the serial port
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
if (serial_fd < 0) {
PX4_ERR("failed to open %s err: %d", _port, errno);
return false;
}
_serial_fd = serial_fd;
// Configure the serial port
if (! configure()) {
PX4_ERR("failed to configure %s err: %d", _port, errno);
return false;
}
_open = true;
return _open;
}
bool SerialImpl::isOpen() const
{
return _open;
}
bool SerialImpl::close()
{
if (_serial_fd >= 0) {
::close(_serial_fd);
}
_serial_fd = -1;
_open = false;
return true;
}
ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
{
if (!_open) {
PX4_ERR("Cannot read from serial device until it has been opened");
return -1;
}
int ret = ::read(_serial_fd, buffer, buffer_size);
if (ret < 0) {
PX4_DEBUG("%s read error %d", _port, ret);
}
return ret;
}
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
{
if (!_open) {
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
return -1;
}
if (buffer_size < character_count) {
PX4_ERR("%s: Buffer not big enough to hold desired amount of read data", __FUNCTION__);
return -1;
}
const hrt_abstime start_time_us = hrt_absolute_time();
int total_bytes_read = 0;
while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) {
// Poll for incoming UART data.
pollfd fds[1];
fds[0].fd = _serial_fd;
fds[0].events = POLLIN;
hrt_abstime remaining_time = timeout_us - hrt_elapsed_time(&start_time_us);
if (remaining_time <= 0) { break; }
int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), remaining_time);
if (ret > 0) {
if (fds[0].revents & POLLIN) {
const unsigned sleeptime = character_count * 1000000 / (_baudrate / 10);
int err = 0;
int bytes_available = 0;
err = ::ioctl(_serial_fd, FIONREAD, (unsigned long)&bytes_available);
if (err != 0 || bytes_available < (int)character_count) {
px4_usleep(sleeptime);
}
ret = read(&buffer[total_bytes_read], buffer_size - total_bytes_read);
if (ret > 0) {
total_bytes_read += ret;
}
} else {
PX4_ERR("Got a poll error");
return -1;
}
}
}
return total_bytes_read;
}
ssize_t SerialImpl::write(const void *buffer, size_t buffer_size)
{
if (!_open) {
PX4_ERR("Cannot write to serial device until it has been opened");
return -1;
}
int written = ::write(_serial_fd, buffer, buffer_size);
::fsync(_serial_fd);
if (written < 0) {
PX4_ERR("%s write error %d", _port, written);
}
return written;
}
const char *SerialImpl::getPort() const
{
return _port;
}
uint32_t SerialImpl::getBaudrate() const
{
return _baudrate;
}
bool SerialImpl::setBaudrate(uint32_t baudrate)
{
if (! validateBaudrate(baudrate)) {
PX4_ERR("ERR: invalid baudrate: %lu", baudrate);
return false;
}
// check if already configured
if ((baudrate == _baudrate) && _open) {
return true;
}
_baudrate = baudrate;
// process baud rate change now if port is already open
if (_open) {
return configure();
}
return true;
}
ByteSize SerialImpl::getBytesize() const
{
return _bytesize;
}
bool SerialImpl::setBytesize(ByteSize bytesize)
{
return bytesize == ByteSize::EightBits;
}
Parity SerialImpl::getParity() const
{
return _parity;
}
bool SerialImpl::setParity(Parity parity)
{
return parity == Parity::None;
}
StopBits SerialImpl::getStopbits() const
{
return _stopbits;
}
bool SerialImpl::setStopbits(StopBits stopbits)
{
return stopbits == StopBits::One;
}
FlowControl SerialImpl::getFlowcontrol() const
{
return _flowcontrol;
}
bool SerialImpl::setFlowcontrol(FlowControl flowcontrol)
{
return flowcontrol == FlowControl::Disabled;
}
} // namespace device

View File

@ -1,104 +0,0 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#pragma once
#include <stdint.h>
#include <unistd.h>
#include <px4_platform_common/SerialCommon.hpp>
using device::SerialConfig::ByteSize;
using device::SerialConfig::Parity;
using device::SerialConfig::StopBits;
using device::SerialConfig::FlowControl;
namespace device
{
class SerialImpl
{
public:
SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits,
FlowControl flowcontrol);
virtual ~SerialImpl();
bool open();
bool isOpen() const;
bool close();
ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
ssize_t write(const void *buffer, size_t buffer_size);
const char *getPort() const;
uint32_t getBaudrate() const;
bool setBaudrate(uint32_t baudrate);
ByteSize getBytesize() const;
bool setBytesize(ByteSize bytesize);
Parity getParity() const;
bool setParity(Parity parity);
StopBits getStopbits() const;
bool setStopbits(StopBits stopbits);
FlowControl getFlowcontrol() const;
bool setFlowcontrol(FlowControl flowcontrol);
private:
int _serial_fd{-1};
bool _open{false};
char _port[32] {};
uint32_t _baudrate{0};
ByteSize _bytesize{ByteSize::EightBits};
Parity _parity{Parity::None};
StopBits _stopbits{StopBits::One};
FlowControl _flowcontrol{FlowControl::Disabled};
bool validateBaudrate(uint32_t baudrate);
bool configure();
};
} // namespace device

View File

@ -3,8 +3,6 @@
add_library(px4_layer
${KERNEL_SRCS}
cdc_acm_check.cpp
${PX4_SOURCE_DIR}/platforms/common/Serial.cpp
SerialImpl.cpp
)
target_link_libraries(px4_layer

View File

@ -15,8 +15,6 @@ add_library(px4_layer
usr_board_ctrl.c
usr_hrt.cpp
usr_mcu_version.cpp
${PX4_SOURCE_DIR}/platforms/common/Serial.cpp
SerialImpl.cpp
)
target_link_libraries(px4_layer

View File

@ -1,103 +0,0 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#pragma once
#include <stdint.h>
#include <unistd.h>
#include <px4_platform_common/SerialCommon.hpp>
using device::SerialConfig::ByteSize;
using device::SerialConfig::Parity;
using device::SerialConfig::StopBits;
using device::SerialConfig::FlowControl;
namespace device
{
class SerialImpl
{
public:
SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits,
FlowControl flowcontrol);
virtual ~SerialImpl();
bool open();
bool isOpen() const;
bool close();
ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
ssize_t write(const void *buffer, size_t buffer_size);
const char *getPort() const;
uint32_t getBaudrate() const;
bool setBaudrate(uint32_t baudrate);
ByteSize getBytesize() const;
bool setBytesize(ByteSize bytesize);
Parity getParity() const;
bool setParity(Parity parity);
StopBits getStopbits() const;
bool setStopbits(StopBits stopbits);
FlowControl getFlowcontrol() const;
bool setFlowcontrol(FlowControl flowcontrol);
private:
int _serial_fd{-1};
bool _open{false};
char _port[32] {};
uint32_t _baudrate{0};
ByteSize _bytesize{ByteSize::EightBits};
Parity _parity{Parity::None};
StopBits _stopbits{StopBits::One};
FlowControl _flowcontrol{FlowControl::Disabled};
bool validateBaudrate(uint32_t baudrate);
bool configure();
};
} // namespace device

View File

@ -46,8 +46,6 @@ add_library(px4_layer
drv_hrt.cpp
cpuload.cpp
print_load.cpp
${PX4_SOURCE_DIR}/platforms/common/Serial.cpp
SerialImpl.cpp
)
target_compile_definitions(px4_layer PRIVATE MODULE_NAME="px4")
target_compile_options(px4_layer PRIVATE -Wno-cast-align) # TODO: fix and enable

View File

@ -1,387 +0,0 @@
/****************************************************************************
*
* 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 <SerialImpl.hpp>
#include <string.h> // strncpy
#include <termios.h>
#include <px4_log.h>
#include <fcntl.h>
#include <errno.h>
#include <poll.h>
#include <drivers/drv_hrt.h>
namespace device
{
SerialImpl::SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits,
FlowControl flowcontrol) :
_baudrate(baudrate),
_bytesize(bytesize),
_parity(parity),
_stopbits(stopbits),
_flowcontrol(flowcontrol)
{
if (port) {
strncpy(_port, port, sizeof(_port) - 1);
_port[sizeof(_port) - 1] = '\0';
} else {
_port[0] = 0;
}
}
SerialImpl::~SerialImpl()
{
if (isOpen()) {
close();
}
}
bool SerialImpl::validateBaudrate(uint32_t baudrate)
{
return ((baudrate == 9600) ||
(baudrate == 19200) ||
(baudrate == 38400) ||
(baudrate == 57600) ||
(baudrate == 115200) ||
(baudrate == 230400) ||
(baudrate == 460800) ||
(baudrate == 921600));
}
bool SerialImpl::configure()
{
/* process baud rate */
int speed;
if (! validateBaudrate(_baudrate)) {
PX4_ERR("ERR: unknown baudrate: %u", _baudrate);
return false;
}
switch (_baudrate) {
case 9600: speed = B9600; break;
case 19200: speed = B19200; break;
case 38400: speed = B38400; break;
case 57600: speed = B57600; break;
case 115200: speed = B115200; break;
case 230400: speed = B230400; break;
#ifndef B460800
#define B460800 460800
#endif
case 460800: speed = B460800; break;
#ifndef B921600
#define B921600 921600
#endif
case 921600: speed = B921600; break;
default:
PX4_ERR("ERR: unknown baudrate: %d", _baudrate);
return false;
}
struct termios uart_config;
int termios_state;
/* fill the struct for the new configuration */
if ((termios_state = tcgetattr(_serial_fd, &uart_config)) < 0) {
PX4_ERR("ERR: %d (tcgetattr)", termios_state);
return false;
}
/* properly configure the terminal (see also https://en.wikibooks.org/wiki/Serial_Programming/termios ) */
//
// Input flags - Turn off input processing
//
// convert break to null byte, no CR to NL translation,
// no NL to CR translation, don't mark parity errors or breaks
// no input parity check, don't strip high bit off,
// no XON/XOFF software flow control
//
uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL |
INLCR | PARMRK | INPCK | ISTRIP | IXON);
//
// Output flags - Turn off output processing
//
// no CR to NL translation, no NL to CR-NL translation,
// no NL to CR translation, no column 0 CR suppression,
// no Ctrl-D suppression, no fill characters, no case mapping,
// no local output processing
//
// config.c_oflag &= ~(OCRNL | ONLCR | ONLRET |
// ONOCR | ONOEOT| OFILL | OLCUC | OPOST);
uart_config.c_oflag = 0;
//
// No line processing
//
// echo off, echo newline off, canonical mode off,
// extended input processing off, signal chars off
//
uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
/* no parity, one stop bit, disable flow control */
uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS);
/* set baud rate */
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
PX4_ERR("ERR: %d (cfsetispeed)", termios_state);
return false;
}
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
PX4_ERR("ERR: %d (cfsetospeed)", termios_state);
return false;
}
if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) {
PX4_ERR("ERR: %d (tcsetattr)", termios_state);
return false;
}
return true;
}
bool SerialImpl::open()
{
if (isOpen()) {
return true;
}
// Open the serial port
int serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
if (serial_fd < 0) {
PX4_ERR("failed to open %s err: %d", _port, errno);
return false;
}
_serial_fd = serial_fd;
// Configure the serial port
if (! configure()) {
PX4_ERR("failed to configure %s err: %d", _port, errno);
return false;
}
_open = true;
return _open;
}
bool SerialImpl::isOpen() const
{
return _open;
}
bool SerialImpl::close()
{
if (_serial_fd >= 0) {
::close(_serial_fd);
}
_serial_fd = -1;
_open = false;
return true;
}
ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
{
if (!_open) {
PX4_ERR("Cannot read from serial device until it has been opened");
return -1;
}
int ret = ::read(_serial_fd, buffer, buffer_size);
if (ret < 0) {
PX4_DEBUG("%s read error %d", _port, ret);
}
return ret;
}
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
{
if (!_open) {
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
return -1;
}
if (buffer_size < character_count) {
PX4_ERR("%s: Buffer not big enough to hold desired amount of read data", __FUNCTION__);
return -1;
}
const hrt_abstime start_time_us = hrt_absolute_time();
int total_bytes_read = 0;
while ((total_bytes_read < (int) character_count) && (hrt_elapsed_time(&start_time_us) < timeout_us)) {
// Poll for incoming UART data.
pollfd fds[1];
fds[0].fd = _serial_fd;
fds[0].events = POLLIN;
hrt_abstime remaining_time = timeout_us - hrt_elapsed_time(&start_time_us);
if (remaining_time <= 0) { break; }
int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), remaining_time);
if (ret > 0) {
if (fds[0].revents & POLLIN) {
const unsigned sleeptime = character_count * 1000000 / (_baudrate / 10);
px4_usleep(sleeptime);
ret = read(&buffer[total_bytes_read], buffer_size - total_bytes_read);
if (ret > 0) {
total_bytes_read += ret;
}
} else {
PX4_ERR("Got a poll error");
return -1;
}
}
}
return total_bytes_read;
}
ssize_t SerialImpl::write(const void *buffer, size_t buffer_size)
{
if (!_open) {
PX4_ERR("Cannot write to serial device until it has been opened");
return -1;
}
int written = ::write(_serial_fd, buffer, buffer_size);
::fsync(_serial_fd);
if (written < 0) {
PX4_ERR("%s write error %d", _port, written);
}
return written;
}
const char *SerialImpl::getPort() const
{
return _port;
}
uint32_t SerialImpl::getBaudrate() const
{
return _baudrate;
}
bool SerialImpl::setBaudrate(uint32_t baudrate)
{
if (! validateBaudrate(baudrate)) {
PX4_ERR("ERR: invalid baudrate: %u", baudrate);
return false;
}
// check if already configured
if ((baudrate == _baudrate) && _open) {
return true;
}
_baudrate = baudrate;
// process baud rate change now if port is already open
if (_open) {
return configure();
}
return true;
}
ByteSize SerialImpl::getBytesize() const
{
return _bytesize;
}
bool SerialImpl::setBytesize(ByteSize bytesize)
{
return bytesize == ByteSize::EightBits;
}
Parity SerialImpl::getParity() const
{
return _parity;
}
bool SerialImpl::setParity(Parity parity)
{
return parity == Parity::None;
}
StopBits SerialImpl::getStopbits() const
{
return _stopbits;
}
bool SerialImpl::setStopbits(StopBits stopbits)
{
return stopbits == StopBits::One;
}
FlowControl SerialImpl::getFlowcontrol() const
{
return _flowcontrol;
}
bool SerialImpl::setFlowcontrol(FlowControl flowcontrol)
{
return flowcontrol == FlowControl::Disabled;
}
} // namespace device

View File

@ -51,11 +51,6 @@
#include <errno.h>
#include "hrt_work.h"
// Voxl2 board specific API definitions to get time offset
#if defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
#include "fc_sensor.h"
#endif
#if defined(ENABLE_LOCKSTEP_SCHEDULER)
#include <lockstep_scheduler/lockstep_scheduler.h>
static LockstepScheduler lockstep_scheduler {true};
@ -112,29 +107,6 @@ hrt_abstime hrt_absolute_time()
#else // defined(ENABLE_LOCKSTEP_SCHEDULER)
struct timespec ts;
px4_clock_gettime(CLOCK_MONOTONIC, &ts);
# if defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
hrt_abstime temp_abstime = ts_to_abstime(&ts);
int apps_time_offset = fc_sensor_get_time_offset();
if (apps_time_offset < 0) {
hrt_abstime temp_offset = -apps_time_offset;
if (temp_offset >= temp_abstime) {
temp_abstime = 0;
} else {
temp_abstime -= temp_offset;
}
} else {
temp_abstime += (hrt_abstime) apps_time_offset;
}
ts.tv_sec = temp_abstime / 1000000;
ts.tv_nsec = (temp_abstime % 1000000) * 1000;
# endif // defined(CONFIG_MUORB_APPS_SYNC_TIMESTAMP)
return ts_to_abstime(&ts);
#endif // defined(ENABLE_LOCKSTEP_SCHEDULER)
}
@ -477,7 +449,6 @@ int px4_clock_gettime(clockid_t clk_id, struct timespec *tp)
#endif // defined(ENABLE_LOCKSTEP_SCHEDULER)
return system_clock_gettime(clk_id, tp);
}
#if defined(ENABLE_LOCKSTEP_SCHEDULER)

View File

@ -50,4 +50,5 @@ add_library(px4 SHARED
target_link_libraries(px4
modules__muorb__slpi
${module_libraries}
px4_layer
)

View File

@ -1,108 +0,0 @@
/****************************************************************************
*
* 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.
*
****************************************************************************/
#pragma once
#include <unistd.h>
#include <px4_platform_common/SerialCommon.hpp>
using device::SerialConfig::ByteSize;
using device::SerialConfig::Parity;
using device::SerialConfig::StopBits;
using device::SerialConfig::FlowControl;
namespace device
{
class SerialImpl
{
public:
SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits,
FlowControl flowcontrol);
virtual ~SerialImpl();
bool open();
bool isOpen() const;
bool close();
ssize_t read(uint8_t *buffer, size_t buffer_size);
ssize_t readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count = 1, uint32_t timeout_us = 0);
ssize_t write(const void *buffer, size_t buffer_size);
const char *getPort() const;
bool setPort(const char *port);
uint32_t getBaudrate() const;
bool setBaudrate(uint32_t baudrate);
ByteSize getBytesize() const;
bool setBytesize(ByteSize bytesize);
Parity getParity() const;
bool setParity(Parity parity);
StopBits getStopbits() const;
bool setStopbits(StopBits stopbits);
FlowControl getFlowcontrol() const;
bool setFlowcontrol(FlowControl flowcontrol);
private:
int _serial_fd{-1};
bool _open{false};
char _port[32] {};
uint32_t _baudrate{0};
ByteSize _bytesize{ByteSize::EightBits};
Parity _parity{Parity::None};
StopBits _stopbits{StopBits::One};
FlowControl _flowcontrol{FlowControl::Disabled};
bool validateBaudrate(uint32_t baudrate);
// Mutex used to lock the read functions
//pthread_mutex_t read_mutex;
// Mutex used to lock the write functions
//pthread_mutex_t write_mutex;
};
} // namespace device

View File

@ -38,7 +38,6 @@ set(QURT_LAYER_SRCS
px4_qurt_impl.cpp
main.cpp
qurt_log.cpp
SerialImpl.cpp
)
add_library(px4_layer

View File

@ -1,326 +0,0 @@
/****************************************************************************
*
* 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 <SerialImpl.hpp>
#include <string.h> // strncpy
#include <px4_log.h>
#include <drivers/device/qurt/uart.h>
#include <drivers/drv_hrt.h>
namespace device
{
SerialImpl::SerialImpl(const char *port, uint32_t baudrate, ByteSize bytesize, Parity parity, StopBits stopbits,
FlowControl flowcontrol) :
_baudrate(baudrate),
_bytesize(bytesize),
_parity(parity),
_stopbits(stopbits),
_flowcontrol(flowcontrol)
{
if (port) {
strncpy(_port, port, sizeof(_port) - 1);
_port[sizeof(_port) - 1] = '\0';
} else {
_port[0] = 0;
}
}
SerialImpl::~SerialImpl()
{
if (isOpen()) {
close();
}
}
bool SerialImpl::validateBaudrate(uint32_t baudrate)
{
if ((baudrate != 9600) &&
(baudrate != 38400) &&
(baudrate != 57600) &&
(baudrate != 115200) &&
(baudrate != 230400) &&
(baudrate != 250000) &&
(baudrate != 420000) &&
(baudrate != 460800) &&
(baudrate != 921600) &&
(baudrate != 1000000) &&
(baudrate != 1843200) &&
(baudrate != 2000000)) {
return false;
}
return true;
}
bool SerialImpl::open()
{
// There's no harm in calling open multiple times on the same port.
// In fact, that's the only way to change the baudrate
_open = false;
_serial_fd = -1;
if (! validateBaudrate(_baudrate)) {
PX4_ERR("Invalid baudrate: %u", _baudrate);
return false;
}
if (_bytesize != ByteSize::EightBits) {
PX4_ERR("Qurt platform only supports ByteSize::EightBits");
return false;
}
if (_parity != Parity::None) {
PX4_ERR("Qurt platform only supports Parity::None");
return false;
}
if (_stopbits != StopBits::One) {
PX4_ERR("Qurt platform only supports StopBits::One");
return false;
}
if (_flowcontrol != FlowControl::Disabled) {
PX4_ERR("Qurt platform only supports FlowControl::Disabled");
return false;
}
// qurt_uart_open will check validity of port and baudrate
int serial_fd = qurt_uart_open(_port, _baudrate);
if (serial_fd < 0) {
PX4_ERR("failed to open %s, fd returned: %d", _port, serial_fd);
return false;
} else {
PX4_INFO("Successfully opened UART %s with baudrate %u", _port, _baudrate);
}
_serial_fd = serial_fd;
_open = true;
return _open;
}
bool SerialImpl::isOpen() const
{
return _open;
}
bool SerialImpl::close()
{
// No close defined for qurt uart yet
// if (_serial_fd >= 0) {
// qurt_uart_close(_serial_fd);
// }
_serial_fd = -1;
_open = false;
return true;
}
ssize_t SerialImpl::read(uint8_t *buffer, size_t buffer_size)
{
if (!_open) {
PX4_ERR("Cannot read from serial device until it has been opened");
return -1;
}
int ret_read = qurt_uart_read(_serial_fd, (char *) buffer, buffer_size, 500);
if (ret_read < 0) {
PX4_DEBUG("%s read error %d", _port, ret_read);
}
return ret_read;
}
ssize_t SerialImpl::readAtLeast(uint8_t *buffer, size_t buffer_size, size_t character_count, uint32_t timeout_us)
{
if (!_open) {
PX4_ERR("Cannot readAtLeast from serial device until it has been opened");
return -1;
}
if (buffer_size < character_count) {
PX4_ERR("%s: Buffer not big enough to hold desired amount of read data", __FUNCTION__);
return -1;
}
const hrt_abstime start_time_us = hrt_absolute_time();
int total_bytes_read = 0;
while (total_bytes_read < (int) character_count) {
if (timeout_us > 0) {
const uint64_t elapsed_us = hrt_elapsed_time(&start_time_us);
if (elapsed_us >= timeout_us) {
// If there was a partial read but not enough to satisfy the minimum then they will be lost
// but this really should never happen when everything is working normally.
// PX4_WARN("%s timeout %d bytes read (%llu us elapsed)", __FUNCTION__, total_bytes_read, elapsed_us);
// Or, instead of returning an error, should we return the number of bytes read (assuming it is greater than zero)?
return total_bytes_read;
}
}
int current_bytes_read = read(&buffer[total_bytes_read], buffer_size - total_bytes_read);
if (current_bytes_read < 0) {
// Again, if there was a partial read but not enough to satisfy the minimum then they will be lost
// but this really should never happen when everything is working normally.
PX4_ERR("%s failed to read uart", __FUNCTION__);
// Or, instead of returning an error, should we return the number of bytes read (assuming it is greater than zero)?
return -1;
}
// Current bytes read could be zero
total_bytes_read += current_bytes_read;
// If we have at least reached our desired minimum number of characters
// then we can return now
if (total_bytes_read >= (int) character_count) {
return total_bytes_read;
}
// Wait a set amount of time before trying again or the remaining time
// until the timeout if we are getting close
const uint64_t elapsed_us = hrt_elapsed_time(&start_time_us);
int64_t time_until_timeout = timeout_us - elapsed_us;
uint64_t time_to_sleep = 5000;
if ((time_until_timeout >= 0) &&
(time_until_timeout < (int64_t) time_to_sleep)) {
time_to_sleep = time_until_timeout;
}
px4_usleep(time_to_sleep);
}
return -1;
}
ssize_t SerialImpl::write(const void *buffer, size_t buffer_size)
{
if (!_open) {
PX4_ERR("Cannot write to serial device until it has been opened");
return -1;
}
int ret_write = qurt_uart_write(_serial_fd, (const char *) buffer, buffer_size);
if (ret_write < 0) {
PX4_ERR("%s write error %d", _port, ret_write);
}
return ret_write;
}
const char *SerialImpl::getPort() const
{
return _port;
}
uint32_t SerialImpl::getBaudrate() const
{
return _baudrate;
}
bool SerialImpl::setBaudrate(uint32_t baudrate)
{
if (! validateBaudrate(baudrate)) {
PX4_ERR("Invalid baudrate: %u", baudrate);
return false;
}
// check if already configured
if (baudrate == _baudrate) {
return true;
}
_baudrate = baudrate;
// process baud rate change now if port is already open
if (_open) {
return open();
}
return true;
}
ByteSize SerialImpl::getBytesize() const
{
return _bytesize;
}
bool SerialImpl::setBytesize(ByteSize bytesize)
{
return bytesize == ByteSize::EightBits;
}
Parity SerialImpl::getParity() const
{
return _parity;
}
bool SerialImpl::setParity(Parity parity)
{
return parity == Parity::None;
}
StopBits SerialImpl::getStopbits() const
{
return _stopbits;
}
bool SerialImpl::setStopbits(StopBits stopbits)
{
return stopbits == StopBits::One;
}
FlowControl SerialImpl::getFlowcontrol() const
{
return _flowcontrol;
}
bool SerialImpl::setFlowcontrol(FlowControl flowcontrol)
{
return flowcontrol == FlowControl::Disabled;
}
} // namespace device

View File

@ -81,7 +81,7 @@ static void hrt_unlock()
px4_sem_post(&_hrt_lock);
}
int px4_clock_settime(clockid_t clk_id, const struct timespec *tp)
int px4_clock_settime(clockid_t clk_id, struct timespec *tp)
{
return 0;
}

View File

@ -162,16 +162,7 @@ static inline void abstime_to_ts(struct timespec *ts, hrt_abstime abstime)
*/
static inline hrt_abstime hrt_elapsed_time(const hrt_abstime *then)
{
hrt_abstime now = hrt_absolute_time();
// Cannot allow a negative elapsed time as this would appear
// to be a huge positive elapsed time when represented as an
// unsigned value!
if (*then > now) {
return 0;
}
return now - *then;
return hrt_absolute_time() - *then;
}
/**

View File

@ -45,6 +45,7 @@
#include <poll.h>
#endif
#include <termios.h>
#include <cstring>
#include <drivers/drv_sensor.h>
@ -56,8 +57,6 @@
#include <px4_platform_common/cli.h>
#include <px4_platform_common/getopt.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/time.h>
#include <px4_platform_common/Serial.hpp>
#include <uORB/Publication.hpp>
#include <uORB/PublicationMulti.hpp>
#include <uORB/Subscription.hpp>
@ -82,7 +81,6 @@
#include <linux/spi/spidev.h>
#endif /* __PX4_LINUX */
using namespace device;
using namespace time_literals;
#define TIMEOUT_1HZ 1300 //!< Timeout time in mS, 1000 mS (1Hz) + 300 mS delta for error
@ -171,10 +169,7 @@ public:
void reset_if_scheduled();
private:
#ifdef __PX4_LINUX
int _spi_fd {-1}; ///< SPI interface to GPS
#endif
Serial *_uart = nullptr; ///< UART interface to GPS
int _serial_fd{-1}; ///< serial interface to GPS
unsigned _baudrate{0}; ///< current baudrate
const unsigned _configured_baudrate{0}; ///< configured baudrate (0=auto-detect)
char _port[20] {}; ///< device / serial port path
@ -334,11 +329,8 @@ GPS::GPS(const char *path, gps_driver_mode_t mode, GPSHelper::Interface interfac
char c = _port[strlen(_port) - 1]; // last digit of path (eg /dev/ttyS2)
set_device_bus(c - 48); // sub 48 to convert char to integer
#ifdef __PX4_LINUX
} else if (_interface == GPSHelper::Interface::SPI) {
set_device_bus_type(device::Device::DeviceBusType::DeviceBusType_SPI);
#endif
}
if (_mode == gps_driver_mode_t::None) {
@ -411,23 +403,10 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user)
return num_read;
}
case GPSCallbackType::writeDeviceData: {
gps->dumpGpsData((uint8_t *)data1, (size_t)data2, gps_dump_comm_mode_t::Full, true);
case GPSCallbackType::writeDeviceData:
gps->dumpGpsData((uint8_t *)data1, (size_t)data2, gps_dump_comm_mode_t::Full, true);
int ret = 0;
if (gps->_uart) {
ret = gps->_uart->write((void *) data1, (size_t) data2);
#ifdef __PX4_LINUX
} else if (gps->_spi_fd >= 0) {
ret = ::write(gps->_spi_fd, data1, (size_t)data2);
#endif
}
return ret;
}
return ::write(gps->_serial_fd, data1, (size_t)data2);
case GPSCallbackType::setBaudrate:
return gps->setBaudrate(data2);
@ -470,64 +449,72 @@ int GPS::callback(GPSCallbackType type, void *data1, int data2, void *user)
int GPS::pollOrRead(uint8_t *buf, size_t buf_length, int timeout)
{
int ret = 0;
const unsigned character_count = 32; // minimum bytes that we want to read
const int max_timeout = 50;
int timeout_adjusted = math::min(max_timeout, timeout);
handleInjectDataTopic();
if ((_interface == GPSHelper::Interface::UART) && (_uart)) {
ret = _uart->readAtLeast(buf, buf_length, character_count, timeout_adjusted);
#if !defined(__PX4_QURT)
// SPI is only supported on LInux
#if defined(__PX4_LINUX)
/* For non QURT, use the usual polling. */
} else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd >= 0)) {
//Poll only for the serial data. In the same thread we also need to handle orb messages,
//so ideally we would poll on both, the serial fd and orb subscription. Unfortunately the
//two pollings use different underlying mechanisms (at least under posix), which makes this
//impossible. Instead we limit the maximum polling interval and regularly check for new orb
//messages.
//FIXME: add a unified poll() API
const int max_timeout = 50;
//Poll only for the SPI data. In the same thread we also need to handle orb messages,
//so ideally we would poll on both, the SPI fd and orb subscription. Unfortunately the
//two pollings use different underlying mechanisms (at least under posix), which makes this
//impossible. Instead we limit the maximum polling interval and regularly check for new orb
//messages.
//FIXME: add a unified poll() API
pollfd fds[1];
fds[0].fd = _serial_fd;
fds[0].events = POLLIN;
pollfd fds[1];
fds[0].fd = _spi_fd;
fds[0].events = POLLIN;
int ret = poll(fds, sizeof(fds) / sizeof(fds[0]), math::min(max_timeout, timeout));
ret = poll(fds, sizeof(fds) / sizeof(fds[0]), timeout_adjusted);
if (ret > 0) {
/* if we have new data from GPS, go handle it */
if (fds[0].revents & POLLIN) {
/*
* We are here because poll says there is some data, so this
* won't block even on a blocking device. But don't read immediately
* by 1-2 bytes, wait for some more data to save expensive read() calls.
* If we have all requested data available, read it without waiting.
* If more bytes are available, we'll go back to poll() again.
*/
const unsigned character_count = 32; // minimum bytes that we want to read
unsigned baudrate = _baudrate == 0 ? 115200 : _baudrate;
const unsigned sleeptime = character_count * 1000000 / (baudrate / 10);
if (ret > 0) {
/* if we have new data from GPS, go handle it */
if (fds[0].revents & POLLIN) {
/*
* We are here because poll says there is some data, so this
* won't block even on a blocking device. But don't read immediately
* by 1-2 bytes, wait for some more data to save expensive read() calls.
* If we have all requested data available, read it without waiting.
* If more bytes are available, we'll go back to poll() again.
*/
unsigned baudrate = _baudrate == 0 ? 115200 : _baudrate;
const unsigned sleeptime = character_count * 1000000 / (baudrate / 10);
#ifdef __PX4_NUTTX
int err = 0;
int bytes_available = 0;
err = ::ioctl(_serial_fd, FIONREAD, (unsigned long)&bytes_available);
if (err != 0 || bytes_available < (int)character_count) {
px4_usleep(sleeptime);
ret = ::read(_spi_fd, buf, buf_length);
if (ret > 0) {
_num_bytes_read += ret;
}
} else {
ret = -1;
}
}
#else
px4_usleep(sleeptime);
#endif
ret = ::read(_serial_fd, buf, buf_length);
if (ret > 0) {
_num_bytes_read += ret;
}
} else {
ret = -1;
}
}
return ret;
#else
/* For QURT, just use read for now, since this doesn't block, we need to slow it down
* just a bit. */
px4_usleep(10000);
return ::read(_serial_fd, buf, buf_length);
#endif
}
void GPS::handleInjectDataTopic()
@ -596,38 +583,105 @@ bool GPS::injectData(uint8_t *data, size_t len)
{
dumpGpsData(data, len, gps_dump_comm_mode_t::Full, true);
size_t written = 0;
if ((_interface == GPSHelper::Interface::UART) && (_uart)) {
written = _uart->write((const void *) data, len);
#ifdef __PX4_LINUX
} else if (_interface == GPSHelper::Interface::SPI) {
written = ::write(_spi_fd, data, len);
::fsync(_spi_fd);
#endif
}
size_t written = ::write(_serial_fd, data, len);
::fsync(_serial_fd);
return written == len;
}
int GPS::setBaudrate(unsigned baud)
{
if (_interface == GPSHelper::Interface::UART) {
if ((_uart) && (_uart->setBaudrate(baud))) {
return 0;
}
/* process baud rate */
int speed;
#ifdef __PX4_LINUX
switch (baud) {
case 9600: speed = B9600; break;
} else if (_interface == GPSHelper::Interface::SPI) {
// Can't set the baudrate on a SPI port but just return a success
return 0;
case 19200: speed = B19200; break;
case 38400: speed = B38400; break;
case 57600: speed = B57600; break;
case 115200: speed = B115200; break;
case 230400: speed = B230400; break;
#ifndef B460800
#define B460800 460800
#endif
case 460800: speed = B460800; break;
#ifndef B921600
#define B921600 921600
#endif
case 921600: speed = B921600; break;
default:
PX4_ERR("ERR: unknown baudrate: %d", baud);
return -EINVAL;
}
return -1;
struct termios uart_config;
int termios_state;
/* fill the struct for the new configuration */
tcgetattr(_serial_fd, &uart_config);
/* properly configure the terminal (see also https://en.wikibooks.org/wiki/Serial_Programming/termios ) */
//
// Input flags - Turn off input processing
//
// convert break to null byte, no CR to NL translation,
// no NL to CR translation, don't mark parity errors or breaks
// no input parity check, don't strip high bit off,
// no XON/XOFF software flow control
//
uart_config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL |
INLCR | PARMRK | INPCK | ISTRIP | IXON);
//
// Output flags - Turn off output processing
//
// no CR to NL translation, no NL to CR-NL translation,
// no NL to CR translation, no column 0 CR suppression,
// no Ctrl-D suppression, no fill characters, no case mapping,
// no local output processing
//
// config.c_oflag &= ~(OCRNL | ONLCR | ONLRET |
// ONOCR | ONOEOT| OFILL | OLCUC | OPOST);
uart_config.c_oflag = 0;
//
// No line processing
//
// echo off, echo newline off, canonical mode off,
// extended input processing off, signal chars off
//
uart_config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
/* no parity, one stop bit, disable flow control */
uart_config.c_cflag &= ~(CSTOPB | PARENB | CRTSCTS);
/* set baud rate */
if ((termios_state = cfsetispeed(&uart_config, speed)) < 0) {
GPS_ERR("ERR: %d (cfsetispeed)", termios_state);
return -1;
}
if ((termios_state = cfsetospeed(&uart_config, speed)) < 0) {
GPS_ERR("ERR: %d (cfsetospeed)", termios_state);
return -1;
}
if ((termios_state = tcsetattr(_serial_fd, TCSANOW, &uart_config)) < 0) {
GPS_ERR("ERR: %d (tcsetattr)", termios_state);
return -1;
}
return 0;
}
void GPS::initializeCommunicationDump()
@ -786,58 +840,31 @@ GPS::run()
_helper = nullptr;
}
if ((_interface == GPSHelper::Interface::UART) && (_uart == nullptr)) {
if (_serial_fd < 0) {
/* open the serial port */
_serial_fd = ::open(_port, O_RDWR | O_NOCTTY);
// Create the UART port instance
_uart = new Serial(_port);
if (_uart == nullptr) {
PX4_ERR("Error creating serial device %s", _port);
px4_sleep(1);
continue;
}
}
if ((_interface == GPSHelper::Interface::UART) && (! _uart->isOpen())) {
// Configure the desired baudrate if one was specified by the user.
// Otherwise the default baudrate will be used.
if (_configured_baudrate) {
if (! _uart->setBaudrate(_configured_baudrate)) {
PX4_ERR("Error setting baudrate to %u on %s", _configured_baudrate, _port);
px4_sleep(1);
continue;
}
}
// Open the UART. If this is successful then the UART is ready to use.
if (! _uart->open()) {
PX4_ERR("Error opening serial device %s", _port);
if (_serial_fd < 0) {
PX4_ERR("failed to open %s err: %d", _port, errno);
px4_sleep(1);
continue;
}
#ifdef __PX4_LINUX
} else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd < 0)) {
_spi_fd = ::open(_port, O_RDWR | O_NOCTTY);
if (_interface == GPSHelper::Interface::SPI) {
int spi_speed = 1000000; // make sure the bus speed is not too high (required on RPi)
int status_value = ::ioctl(_serial_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed);
if (_spi_fd < 0) {
PX4_ERR("failed to open SPI port %s err: %d", _port, errno);
px4_sleep(1);
continue;
}
if (status_value < 0) {
PX4_ERR("SPI_IOC_WR_MAX_SPEED_HZ failed for %s (%d)", _port, errno);
}
int spi_speed = 1000000; // make sure the bus speed is not too high (required on RPi)
int status_value = ::ioctl(_spi_fd, SPI_IOC_WR_MAX_SPEED_HZ, &spi_speed);
status_value = ::ioctl(_serial_fd, SPI_IOC_RD_MAX_SPEED_HZ, &spi_speed);
if (status_value < 0) {
PX4_ERR("SPI_IOC_WR_MAX_SPEED_HZ failed for %s (%d)", _port, errno);
}
status_value = ::ioctl(_spi_fd, SPI_IOC_RD_MAX_SPEED_HZ, &spi_speed);
if (status_value < 0) {
PX4_ERR("SPI_IOC_RD_MAX_SPEED_HZ failed for %s (%d)", _port, errno);
if (status_value < 0) {
PX4_ERR("SPI_IOC_RD_MAX_SPEED_HZ failed for %s (%d)", _port, errno);
}
}
#endif /* __PX4_LINUX */
@ -1029,17 +1056,9 @@ GPS::run()
}
}
if ((_interface == GPSHelper::Interface::UART) && (_uart)) {
(void) _uart->close();
delete _uart;
_uart = nullptr;
#ifdef __PX4_LINUX
} else if ((_interface == GPSHelper::Interface::SPI) && (_spi_fd >= 0)) {
::close(_spi_fd);
_spi_fd = -1;
#endif
if (_serial_fd >= 0) {
::close(_serial_fd);
_serial_fd = -1;
}
if (_mode_auto) {
@ -1387,7 +1406,7 @@ int GPS::task_spawn(int argc, char *argv[], Instance instance)
entry_point, (char *const *)argv);
if (task_id < 0) {
_task_id = -1;
task_id = -1;
return -errno;
}
@ -1458,12 +1477,12 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance)
break;
case 'i':
if (!strcmp(myoptarg, "uart")) {
interface = GPSHelper::Interface::UART;
#ifdef __PX4_LINUX
} else if (!strcmp(myoptarg, "spi")) {
if (!strcmp(myoptarg, "spi")) {
interface = GPSHelper::Interface::SPI;
#endif
} else if (!strcmp(myoptarg, "uart")) {
interface = GPSHelper::Interface::UART;
} else {
PX4_ERR("unknown interface: %s", myoptarg);
error_flag = true;
@ -1471,12 +1490,12 @@ GPS *GPS::instantiate(int argc, char *argv[], Instance instance)
break;
case 'j':
if (!strcmp(myoptarg, "uart")) {
interface_secondary = GPSHelper::Interface::UART;
#ifdef __PX4_LINUX
} else if (!strcmp(myoptarg, "spi")) {
if (!strcmp(myoptarg, "spi")) {
interface_secondary = GPSHelper::Interface::SPI;
#endif
} else if (!strcmp(myoptarg, "uart")) {
interface_secondary = GPSHelper::Interface::UART;
} else {
PX4_ERR("unknown interface for secondary: %s", myoptarg);
error_flag = true;

View File

@ -364,13 +364,6 @@ PX4IO::~PX4IO()
bool PX4IO::updateOutputs(bool stop_motors, uint16_t outputs[MAX_ACTUATORS],
unsigned num_outputs, unsigned num_control_groups_updated)
{
for (size_t i = 0; i < num_outputs; i++) {
if (!_mixing_output.isFunctionSet(i)) {
// do not run any signal on disabled channels
outputs[i] = 0;
}
}
if (!_test_fmu_fail) {
/* output to the servos */
io_reg_set(PX4IO_PAGE_DIRECT_PWM, 0, outputs, num_outputs);

View File

@ -75,7 +75,6 @@ add_definitions(
-DUAVCAN_${UAVCAN_DRIVER_UPPER}_${OS_UPPER}=1
-DUAVCAN_${UAVCAN_DRIVER_UPPER}_NUM_IFACES=${config_uavcan_num_ifaces}
-DUAVCAN_${UAVCAN_DRIVER_UPPER}_TIMER_NUMBER=${UAVCAN_TIMER}
-DUAVCAN_NUM_IFACES=${config_uavcan_num_ifaces}
-DUAVCAN_CPP_VERSION=UAVCAN_CPP03
-DUAVCAN_DRIVER=uavcan_${UAVCAN_DRIVER}
-DUAVCAN_IMPLEMENT_PLACEMENT_NEW=1

View File

@ -744,41 +744,6 @@ UavcanNode::Run()
_node.spinOnce(); // expected to be non-blocking
// Publish status
constexpr hrt_abstime status_pub_interval = 100_ms;
if (hrt_absolute_time() - _last_can_status_pub >= status_pub_interval) {
_last_can_status_pub = hrt_absolute_time();
for (int i = 0; i < _node.getDispatcher().getCanIOManager().getCanDriver().getNumIfaces(); i++) {
if (i > UAVCAN_NUM_IFACES) {
break;
}
auto iface = _node.getDispatcher().getCanIOManager().getCanDriver().getIface(i);
if (!iface) {
continue;
}
auto iface_perf_cnt = _node.getDispatcher().getCanIOManager().getIfacePerfCounters(i);
can_interface_status_s status{
.timestamp = hrt_absolute_time(),
.io_errors = iface_perf_cnt.errors,
.frames_tx = iface_perf_cnt.frames_tx,
.frames_rx = iface_perf_cnt.frames_rx,
.interface = static_cast<uint8_t>(i),
};
if (_can_status_pub_handles[i] == nullptr) {
int instance{0};
_can_status_pub_handles[i] = orb_advertise_multi(ORB_ID(can_interface_status), nullptr, &instance);
}
(void)orb_publish(ORB_ID(can_interface_status), _can_status_pub_handles[i], &status);
}
}
// check for parameter updates
if (_parameter_update_sub.updated()) {
// clear update

View File

@ -96,7 +96,6 @@
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/SubscriptionInterval.hpp>
#include <uORB/topics/can_interface_status.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/uavcan_parameter_request.h>
#include <uORB/topics/uavcan_parameter_value.h>
@ -310,10 +309,6 @@ private:
uORB::Publication<uavcan_parameter_value_s> _param_response_pub{ORB_ID(uavcan_parameter_value)};
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
uORB::PublicationMulti<can_interface_status_s> _can_status_pub{ORB_ID(can_interface_status)};
hrt_abstime _last_can_status_pub{0};
orb_advert_t _can_status_pub_handles[UAVCAN_NUM_IFACES] = {nullptr};
/*
* The MAVLink parameter bridge needs to know the maximum parameter index

View File

@ -364,7 +364,7 @@
},
"1": {
"name": "manual_control_loss",
"description": "Manual control loss"
"description": "manual control loss"
},
"2": {
"name": "gcs_connection_loss",
@ -372,19 +372,19 @@
},
"3": {
"name": "low_battery_level",
"description": "Low battery level"
"description": "low battery level"
},
"4": {
"name": "critical_battery_level",
"description": "Critical battery level"
"description": "critical battery level"
},
"5": {
"name": "emergency_battery_level",
"description": "Emergency battery level"
"description": "emergency battery level"
},
"6": {
"name": "low_remaining_flight_time",
"description": "Remaining flight time low"
"description": "low remaining flight time"
}
}
},
@ -402,19 +402,19 @@
},
"2": {
"name": "fallback_posctrl",
"description": "Position mode"
"description": "fallback to position control"
},
"3": {
"name": "fallback_altctrl",
"description": "Altitude mode"
"description": "fallback to altitude control"
},
"4": {
"name": "fallback_stabilized",
"description": "Stabilized mode"
"description": "fallback to stabilized"
},
"5": {
"name": "hold",
"description": "Hold"
"description": "hold"
},
"6": {
"name": "rtl",
@ -422,11 +422,11 @@
},
"7": {
"name": "land",
"description": "Land"
"description": "land"
},
"8": {
"name": "descend",
"description": "Descend"
"description": "descend"
},
"9": {
"name": "disarm",

View File

@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2020-2024 PX4 Development Team. All rights reserved.
* Copyright (c) 2020-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
@ -51,18 +51,17 @@ static constexpr float sq(float var) { return var * var; }
// rot312(1) - Second rotation is a RH rotation about the X axis (rad)
// rot312(2) - Third rotation is a RH rotation about the Y axis (rad)
// See http://www.atacolorado.com/eulersequences.doc
template<typename T = float>
inline matrix::Dcm<T> taitBryan312ToRotMat(const matrix::Vector3<T> &rot312)
inline matrix::Dcmf taitBryan312ToRotMat(const matrix::Vector3f &rot312)
{
// Calculate the frame2 to frame 1 rotation matrix from a 312 Tait-Bryan rotation sequence
const T c2 = cosf(rot312(2)); // third rotation is pitch
const T s2 = sinf(rot312(2));
const T s1 = sinf(rot312(1)); // second rotation is roll
const T c1 = cosf(rot312(1));
const T s0 = sinf(rot312(0)); // first rotation is yaw
const T c0 = cosf(rot312(0));
const float c2 = cosf(rot312(2)); // third rotation is pitch
const float s2 = sinf(rot312(2));
const float s1 = sinf(rot312(1)); // second rotation is roll
const float c1 = cosf(rot312(1));
const float s0 = sinf(rot312(0)); // first rotation is yaw
const float c0 = cosf(rot312(0));
matrix::Dcm<T> R;
matrix::Dcmf R;
R(0, 0) = c0 * c2 - s0 * s1 * s2;
R(1, 1) = c0 * c1;
R(2, 2) = c2 * c1;
@ -76,21 +75,20 @@ inline matrix::Dcm<T> taitBryan312ToRotMat(const matrix::Vector3<T> &rot312)
return R;
}
template<typename T = float>
inline matrix::Dcm<T> quatToInverseRotMat(const matrix::Quaternion<T> &quat)
inline matrix::Dcmf quatToInverseRotMat(const matrix::Quatf &quat)
{
const T q00 = quat(0) * quat(0);
const T q11 = quat(1) * quat(1);
const T q22 = quat(2) * quat(2);
const T q33 = quat(3) * quat(3);
const T q01 = quat(0) * quat(1);
const T q02 = quat(0) * quat(2);
const T q03 = quat(0) * quat(3);
const T q12 = quat(1) * quat(2);
const T q13 = quat(1) * quat(3);
const T q23 = quat(2) * quat(3);
const float q00 = quat(0) * quat(0);
const float q11 = quat(1) * quat(1);
const float q22 = quat(2) * quat(2);
const float q33 = quat(3) * quat(3);
const float q01 = quat(0) * quat(1);
const float q02 = quat(0) * quat(2);
const float q03 = quat(0) * quat(3);
const float q12 = quat(1) * quat(2);
const float q13 = quat(1) * quat(3);
const float q23 = quat(2) * quat(3);
matrix::Dcm<T> dcm;
matrix::Dcmf dcm;
dcm(0, 0) = q00 + q11 - q22 - q33;
dcm(1, 1) = q00 - q11 + q22 - q33;
dcm(2, 2) = q00 - q11 - q22 + q33;
@ -107,46 +105,40 @@ inline matrix::Dcm<T> quatToInverseRotMat(const matrix::Quaternion<T> &quat)
// We should use a 3-2-1 Tait-Bryan (yaw-pitch-roll) rotation sequence
// when there is more roll than pitch tilt and a 3-1-2 rotation sequence
// when there is more pitch than roll tilt to avoid gimbal lock.
template<typename T = float>
inline bool shouldUse321RotationSequence(const matrix::Dcm<T> &R)
inline bool shouldUse321RotationSequence(const matrix::Dcmf &R)
{
return fabsf(R(2, 0)) < fabsf(R(2, 1));
}
template<typename T = float>
inline float getEuler321Yaw(const matrix::Dcm<T> &R)
inline float getEuler321Yaw(const matrix::Dcmf &R)
{
return atan2f(R(1, 0), R(0, 0));
}
template<typename T = float>
inline float getEuler312Yaw(const matrix::Dcm<T> &R)
inline float getEuler312Yaw(const matrix::Dcmf &R)
{
return atan2f(-R(0, 1), R(1, 1));
}
template<typename T = float>
inline T getEuler321Yaw(const matrix::Quaternion<T> &q)
inline float getEuler321Yaw(const matrix::Quatf &q)
{
// Values from yaw_input_321.c file produced by
// https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/quat2yaw321.m
const T a = static_cast<T>(2.) * (q(0) * q(3) + q(1) * q(2));
const T b = sq(q(0)) + sq(q(1)) - sq(q(2)) - sq(q(3));
const float a = 2.f * (q(0) * q(3) + q(1) * q(2));
const float b = sq(q(0)) + sq(q(1)) - sq(q(2)) - sq(q(3));
return atan2f(a, b);
}
template<typename T = float>
inline T getEuler312Yaw(const matrix::Quaternion<T> &q)
inline float getEuler312Yaw(const matrix::Quatf &q)
{
// Values from yaw_input_312.c file produced by
// https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/quat2yaw312.m
const T a = static_cast<T>(2.) * (q(0) * q(3) - q(1) * q(2));
const T b = sq(q(0)) - sq(q(1)) + sq(q(2)) - sq(q(3));
const float a = 2.f * (q(0) * q(3) - q(1) * q(2));
const float b = sq(q(0)) - sq(q(1)) + sq(q(2)) - sq(q(3));
return atan2f(a, b);
}
template<typename T = float>
inline T getEulerYaw(const matrix::Dcm<T> &R)
inline float getEulerYaw(const matrix::Dcmf &R)
{
if (shouldUse321RotationSequence(R)) {
return getEuler321Yaw(R);
@ -156,32 +148,23 @@ inline T getEulerYaw(const matrix::Dcm<T> &R)
}
}
template<typename T = float>
inline T getEulerYaw(const matrix::Quaternion<T> &q)
inline matrix::Dcmf updateEuler321YawInRotMat(float yaw, const matrix::Dcmf &rot_in)
{
return getEulerYaw(matrix::Dcm<T>(q));
}
template<typename T = float>
inline matrix::Dcm<T> updateEuler321YawInRotMat(T yaw, const matrix::Dcm<T> &rot_in)
{
matrix::Euler<T> euler321(rot_in);
matrix::Eulerf euler321(rot_in);
euler321(2) = yaw;
return matrix::Dcm<T>(euler321);
return matrix::Dcmf(euler321);
}
template<typename T = float>
inline matrix::Dcm<T> updateEuler312YawInRotMat(T yaw, const matrix::Dcm<T> &rot_in)
inline matrix::Dcmf updateEuler312YawInRotMat(float yaw, const matrix::Dcmf &rot_in)
{
const matrix::Vector3<T> rotVec312(yaw, // yaw
asinf(rot_in(2, 1)), // roll
atan2f(-rot_in(2, 0), rot_in(2, 2))); // pitch
const matrix::Vector3f rotVec312(yaw, // yaw
asinf(rot_in(2, 1)), // roll
atan2f(-rot_in(2, 0), rot_in(2, 2))); // pitch
return taitBryan312ToRotMat(rotVec312);
}
// Checks which euler rotation sequence to use and update yaw in rotation matrix
template<typename T = float>
inline matrix::Dcm<T> updateYawInRotMat(T yaw, const matrix::Dcm<T> &rot_in)
inline matrix::Dcmf updateYawInRotMat(float yaw, const matrix::Dcmf &rot_in)
{
if (shouldUse321RotationSequence(rot_in)) {
return updateEuler321YawInRotMat(yaw, rot_in);

View File

@ -39,6 +39,8 @@
#pragma once
#include <lib/mathlib/mathlib.h>
namespace math
{

View File

@ -455,8 +455,7 @@ bool MixingOutput::update()
}
}
// Send output if any function mapped or one last disabling sample
if (!all_disabled || !_was_all_disabled) {
if (!all_disabled) {
if (!_armed.armed && !_armed.manual_lockdown) {
_actuator_test.overrideValues(outputs, _max_num_outputs);
}
@ -464,8 +463,6 @@ bool MixingOutput::update()
limitAndUpdateOutputs(outputs, has_updates);
}
_was_all_disabled = all_disabled;
return true;
}

View File

@ -288,7 +288,6 @@ private:
hrt_abstime _lowrate_schedule_interval{300_ms};
ActuatorTest _actuator_test{_function_assignment};
uint32_t _reversible_mask{0}; ///< per-output bits. If set, the output is configured to be reversible (motors only)
bool _was_all_disabled{false};
uORB::SubscriptionCallbackWorkItem *_subscription_callback{nullptr}; ///< current scheduling callback

View File

@ -191,15 +191,11 @@ TEST_F(MixerModuleTest, basic)
mixing_output.setAllMaxValues(MAX_VALUE);
EXPECT_EQ(test_module.num_updates, 0);
// all functions disabled: expect to get one single update to process disabling the output signal
// all functions disabled: not expected to get an update
mixing_output.update();
mixing_output.updateSubscriptions(false);
mixing_output.update();
EXPECT_EQ(test_module.num_updates, 1);
mixing_output.update();
mixing_output.updateSubscriptions(false);
mixing_output.update();
EXPECT_EQ(test_module.num_updates, 1);
EXPECT_EQ(test_module.num_updates, 0);
test_module.reset();
// configure motor, ensure all still disarmed

View File

@ -56,13 +56,13 @@ public:
* Set maximum rate of change for the value
* @param slew_rate maximum rate of change
*/
void setSlewRate(const Type slew_rate) { _slew_rate = slew_rate; }
void setSlewRate(const Type &slew_rate) { _slew_rate = slew_rate; }
/**
* Set value ignoring slew rate for initialization purpose
* @param value new applied value
*/
void setForcedValue(const Type value) { _value = value; }
void setForcedValue(const Type &value) { _value = value; }
/**
* Get value from last update of the slew rate
@ -76,7 +76,7 @@ public:
* @param deltatime time in seconds since last update
* @return actual value that complies with the slew rate
*/
Type update(const Type new_value, const float deltatime)
Type update(const Type &new_value, const float deltatime)
{
// Limit the rate of change of the value
const Type dvalue_desired = new_value - _value;
@ -90,3 +90,14 @@ protected:
Type _slew_rate{}; ///< maximum rate of change for the value
Type _value{}; ///< state to keep last value of the slew rate
};
template<>
inline matrix::Vector3f SlewRate<matrix::Vector3f>::update(const matrix::Vector3f &new_value, const float deltatime)
{
// Limit the rate of change of the value
const matrix::Vector3f dvalue_desired = new_value - _value;
const matrix::Vector3f dvalue_max = _slew_rate * deltatime;
const matrix::Vector3f dvalue = matrix::constrain(dvalue_desired, -dvalue_max, dvalue_max);
_value += dvalue;
return _value;
}

View File

@ -598,9 +598,6 @@ transition_result_t Commander::arm(arm_disarm_reason_t calling_reason, bool run_
if (!_health_and_arming_checks.canArm(_vehicle_status.nav_state)) {
tune_negative(true);
mavlink_log_critical(&_mavlink_log_pub, "Arming denied: Resolve system health failures first\t");
events::send(events::ID("commander_arm_denied_resolve_failures"), {events::Log::Critical, events::LogInternal::Info},
"Arming denied: Resolve system health failures first");
return TRANSITION_DENIED;
}
}
@ -2422,14 +2419,7 @@ void Commander::control_status_leds(bool changed, const uint8_t battery_warning)
if (_cpuload_sub.copy(&cpuload)) {
const float cpuload_percent = cpuload.load * 100.f;
bool overload = false;
// Only check CPU load if it hasn't been disabled
if (!(_param_com_cpu_max.get() < FLT_EPSILON)) {
overload = (cpuload_percent > _param_com_cpu_max.get());
}
overload = overload || (cpuload.ram_usage > 0.99f);
bool overload = (cpuload_percent > _param_com_cpu_max.get()) || (cpuload.ram_usage > 0.99f);
if (_overload_start == 0 && overload) {
_overload_start = time_now_us;

View File

@ -293,9 +293,7 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor
mavlink_log_warning(reporter.mavlink_log_pub(), "GNSS data fusion stopped\t");
}
// only report this failure as critical if not already in a local position invalid state
events::Log log_level = reporter.failsafeFlags().local_position_invalid ? events::Log::Info : events::Log::Error;
events::send(events::ID("check_estimator_gnss_fusion_stopped"), {log_level, events::LogInternal::Info},
events::send(events::ID("check_estimator_gnss_fusion_stopped"), {events::Log::Error, events::LogInternal::Info},
"GNSS data fusion stopped");
} else if (!_gps_was_fused && ekf_gps_fusion) {

View File

@ -369,7 +369,7 @@ FailsafeBase::ActionOptions Failsafe::fromRemainingFlightTimeLowActParam(int par
{
ActionOptions options{};
options.allow_user_takeover = UserTakeoverAllowed::Auto;
options.allow_user_takeover = UserTakeoverAllowed::Always;
options.cause = Cause::RemainingFlightTimeLow;
switch (command_after_remaining_flight_time_low(param_value)) {

View File

@ -195,7 +195,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
events::send<uint32_t, events::px4::enums::failsafe_action_t, uint16_t>(
events::ID("commander_failsafe_enter_generic_hold"),
{events::Log::Critical, events::LogInternal::Warning},
"Failsafe, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
"Failsafe activated, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
(uint16_t) delay_s);
} else {
@ -204,7 +204,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
events::send<uint32_t, events::px4::enums::failsafe_action_t, uint16_t, events::px4::enums::failsafe_cause_t>(
events::ID("commander_failsafe_enter_hold"),
{events::Log::Critical, events::LogInternal::Warning},
"{4}, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
"Failsafe activated due to {4}, triggering {2} in {3} seconds", mavlink_mode, failsafe_action,
(uint16_t) delay_s, failsafe_cause);
}
@ -231,7 +231,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
events::send<uint32_t, events::px4::enums::failsafe_action_t>(
events::ID("commander_failsafe_enter_generic"),
{events::Log::Critical, events::LogInternal::Warning},
"Failsafe, triggering {2}", mavlink_mode, failsafe_action);
"Failsafe activated, triggering {2}", mavlink_mode, failsafe_action);
}
} else {
@ -272,7 +272,7 @@ void FailsafeBase::notifyUser(uint8_t user_intended_mode, Action action, Action
events::send<uint32_t, events::px4::enums::failsafe_action_t, events::px4::enums::failsafe_cause_t>(
events::ID("commander_failsafe_enter"),
{events::Log::Critical, events::LogInternal::Warning},
"{3}, triggering {2}", mavlink_mode, failsafe_action, failsafe_cause);
"Failsafe activated due to {3}, triggering {2}", mavlink_mode, failsafe_action, failsafe_cause);
}
}
@ -517,8 +517,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
break;
}
returned_state.cause = Cause::Generic;
// fallthrough
case Action::FallbackAltCtrl:
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_ALTCTL)) {
@ -526,8 +524,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
break;
}
returned_state.cause = Cause::Generic;
// fallthrough
case Action::FallbackStab:
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_STAB)) {
@ -535,8 +531,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
break;
} // else: fall through here as well. If stabilized isn't available, we most certainly end up in Terminate
returned_state.cause = Cause::Generic;
// fallthrough
case Action::Hold:
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_LOITER)) {
@ -544,8 +538,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
break;
}
returned_state.cause = Cause::Generic;
// fallthrough
case Action::RTL:
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_RTL)) {
@ -553,8 +545,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
break;
}
returned_state.cause = Cause::Generic;
// fallthrough
case Action::Land:
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_AUTO_LAND)) {
@ -562,8 +552,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
break;
}
returned_state.cause = Cause::Generic;
// fallthrough
case Action::Descend:
if (modeCanRun(status_flags, vehicle_status_s::NAVIGATION_STATE_DESCEND)) {
@ -571,8 +559,6 @@ void FailsafeBase::getSelectedAction(const State &state, const failsafe_flags_s
break;
}
returned_state.cause = Cause::Generic;
// fallthrough
case Action::Terminate:
selected_action = Action::Terminate;

View File

@ -147,7 +147,7 @@ public:
bool rc_sticks_takeover_request,
const failsafe_flags_s &status_flags);
bool inFailsafe() const { return (_selected_action != Action::None && _selected_action != Action::Warn); }
bool inFailsafe() const { return _selected_action != Action::None; }
Action selectedAction() const { return _selected_action; }

View File

@ -485,14 +485,9 @@ public:
#else
// Efficient implementation of the Joseph stabilized covariance update
// Based on "G. J. Bierman. Factorization Methods for Discrete Sequential Estimation. Academic Press, Dover Publications, New York, 1977, 2006"
// P = (I - K * H) * P * (I - K * H).T + K * R * K.T
// = P_temp * (I - H.T * K.T) + K * R * K.T
// = P_temp - P_temp * H.T * K.T + K * R * K.T
// Step 1: conventional update
// Compute P_temp and store it in P to avoid allocating more memory
// P is symmetric, so PH == H.T * P.T == H.T * P. Taking the row is faster as matrices are row-major
VectorState PH = P * H; // H is stored as a column vector. H is in fact H.T
VectorState PH = P * H;
for (unsigned i = 0; i < State::size; i++) {
for (unsigned j = 0; j < State::size; j++) {
@ -501,7 +496,7 @@ public:
}
// Step 2: stabilized update
PH = P * H; // H is stored as a column vector. H is in fact H.T
PH = P * H;
for (unsigned i = 0; i < State::size; i++) {
for (unsigned j = 0; j <= i; j++) {

View File

@ -865,24 +865,18 @@ bool Ekf::fuseDirectStateMeasurement(const float innov, const float innov_var, c
#else
// Efficient implementation of the Joseph stabilized covariance update
// Based on "G. J. Bierman. Factorization Methods for Discrete Sequential Estimation. Academic Press, Dover Publications, New York, 1977, 2006"
// P = (I - K * H) * P * (I - K * H).T + K * R * K.T
// = P_temp * (I - H.T * K.T) + K * R * K.T
// = P_temp - P_temp * H.T * K.T + K * R * K.T
// Step 1: conventional update
// Compute P_temp and store it in P to avoid allocating more memory
// P is symmetric, so PH == H.T * P.T == H.T * P. Taking the row is faster as matrices are row-major
VectorState PH = P.row(state_index);
for (unsigned i = 0; i < State::size; i++) {
for (unsigned j = 0; j < State::size; j++) {
P(i, j) -= K(i) * PH(j); // P is now not symmetric if K is not optimal (e.g.: some gains have been zeroed)
P(i, j) -= K(i) * PH(j); // P is now not symmetrical if K is not optimal (e.g.: some gains have been zeroed)
}
}
// Step 2: stabilized update
// P (or "P_temp") is not symmetric so we must take the column
PH = P.col(state_index);
PH = P.row(state_index);
for (unsigned i = 0; i < State::size; i++) {
for (unsigned j = 0; j <= i; j++) {

View File

@ -246,7 +246,7 @@ bool Ekf::tryYawEmergencyReset()
bool success = false;
/* A rapid reset to the yaw emergency estimate is performed if horizontal velocity innovation checks continuously
* fails while the difference between the yaw emergency estimator and the yaw estimate is large.
* fails while the difference between the yaw emergency estimator and the yas estimate is large.
* This enables recovery from a bad yaw estimate. A reset is not performed if the fault condition was
* present before flight to prevent triggering due to GPS glitches or other sensor errors.
*/

View File

@ -390,20 +390,70 @@ def compute_mag_z_innov_var_and_h(
return (innov_var, H.T)
def compute_yaw_innov_var_and_h(
def compute_yaw_321_innov_var_and_h(
state: VState,
P: MTangent,
R: sf.Scalar
R: sf.Scalar,
epsilon: sf.Scalar
) -> (sf.Scalar, VTangent):
state = vstate_to_state(state)
q = sf.Quaternion.from_storage(state["quat_nominal"].to_storage())
r = sf.Quaternion.symbolic('r')
delta_q = q * r.conj() # create a quaternion error of the measurement at the origin
delta_meas_pred = 2 * delta_q.z # Use small angle approximation to obtain a simpler jacobian
R_to_earth = state["quat_nominal"].to_rotation_matrix()
# Fix the singularity at pi/2 by inserting epsilon
meas_pred = sf.atan2(R_to_earth[1,0], R_to_earth[0,0], epsilon=epsilon)
H = sf.V1(delta_meas_pred).jacobian(state)
H = H.subs({r.w: q.w, r.x: q.x, r.y: q.y, r.z: q.z}) # assume innovation is small
H = sf.V1(meas_pred).jacobian(state)
innov_var = (H * P * H.T + R)[0,0]
return (innov_var, H.T)
def compute_yaw_321_innov_var_and_h_alternate(
state: VState,
P: MTangent,
R: sf.Scalar,
epsilon: sf.Scalar
) -> (sf.Scalar, VTangent):
state = vstate_to_state(state)
R_to_earth = state["quat_nominal"].to_rotation_matrix()
# Alternate form that has a singularity at yaw 0 instead of pi/2
meas_pred = sf.pi/2 - sf.atan2(R_to_earth[0,0], R_to_earth[1,0], epsilon=epsilon)
H = sf.V1(meas_pred).jacobian(state)
innov_var = (H * P * H.T + R)[0,0]
return (innov_var, H.T)
def compute_yaw_312_innov_var_and_h(
state: VState,
P: MTangent,
R: sf.Scalar,
epsilon: sf.Scalar
) -> (sf.Scalar, VTangent):
state = vstate_to_state(state)
R_to_earth = state["quat_nominal"].to_rotation_matrix()
# Alternate form to be used when close to pitch +-pi/2
meas_pred = sf.atan2(-R_to_earth[0,1], R_to_earth[1,1], epsilon=epsilon)
H = sf.V1(meas_pred).jacobian(state)
innov_var = (H * P * H.T + R)[0,0]
return (innov_var, H.T)
def compute_yaw_312_innov_var_and_h_alternate(
state: VState,
P: MTangent,
R: sf.Scalar,
epsilon: sf.Scalar
) -> (sf.Scalar, VTangent):
state = vstate_to_state(state)
R_to_earth = state["quat_nominal"].to_rotation_matrix()
# Alternate form to be used when close to pitch +-pi/2
meas_pred = sf.pi/2 - sf.atan2(-R_to_earth[1,1], R_to_earth[0,1], epsilon=epsilon)
H = sf.V1(meas_pred).jacobian(state)
innov_var = (H * P * H.T + R)[0,0]
return (innov_var, H.T)
@ -628,7 +678,10 @@ if not args.disable_wind:
generate_px4_function(compute_sideslip_innov_and_innov_var, output_names=["innov", "innov_var"])
generate_px4_function(compute_wind_init_and_cov_from_airspeed, output_names=["wind", "P_wind"])
generate_px4_function(compute_yaw_innov_var_and_h, output_names=["innov_var", "H"])
generate_px4_function(compute_yaw_312_innov_var_and_h, output_names=["innov_var", "H"])
generate_px4_function(compute_yaw_312_innov_var_and_h_alternate, output_names=["innov_var", "H"])
generate_px4_function(compute_yaw_321_innov_var_and_h, output_names=["innov_var", "H"])
generate_px4_function(compute_yaw_321_innov_var_and_h_alternate, output_names=["innov_var", "H"])
generate_px4_function(compute_flow_xy_innov_var_and_hx, output_names=["innov_var", "H"])
generate_px4_function(compute_flow_y_innov_var_and_h, output_names=["innov_var", "H"])
generate_px4_function(compute_gnss_yaw_pred_innov_var_and_h, output_names=["meas_pred", "innov_var", "H"])

View File

@ -0,0 +1,76 @@
// -----------------------------------------------------------------------------
// This file was autogenerated by symforce from template:
// function/FUNCTION.h.jinja
// Do NOT modify by hand.
// -----------------------------------------------------------------------------
#pragma once
#include <matrix/math.hpp>
namespace sym {
/**
* This function was autogenerated from a symbolic function. Do not modify by hand.
*
* Symbolic function: compute_yaw_312_innov_var_and_h
*
* Args:
* state: Matrix24_1
* P: Matrix23_23
* R: Scalar
* epsilon: Scalar
*
* Outputs:
* innov_var: Scalar
* H: Matrix23_1
*/
template <typename Scalar>
void ComputeYaw312InnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar R,
const Scalar epsilon, Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 53
// Input arrays
// Intermediate terms (15)
const Scalar _tmp0 = 2 * state(0, 0);
const Scalar _tmp1 = -_tmp0 * state(3, 0);
const Scalar _tmp2 = 2 * state(1, 0);
const Scalar _tmp3 = _tmp2 * state(2, 0);
const Scalar _tmp4 = _tmp1 + _tmp3;
const Scalar _tmp5 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp6 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp7 = -2 * _tmp5 - 2 * _tmp6 + 1;
const Scalar _tmp8 = _tmp7 + epsilon * ((((_tmp7) > 0) - ((_tmp7) < 0)) + Scalar(0.5));
const Scalar _tmp9 = std::pow(_tmp8, Scalar(2));
const Scalar _tmp10 = _tmp4 / _tmp9;
const Scalar _tmp11 = Scalar(1.0) / (_tmp8);
const Scalar _tmp12 = _tmp9 / (std::pow(_tmp4, Scalar(2)) + _tmp9);
const Scalar _tmp13 = _tmp12 * (_tmp10 * (_tmp1 - _tmp3) -
_tmp11 * (_tmp5 - _tmp6 - std::pow(state(0, 0), Scalar(2)) +
std::pow(state(2, 0), Scalar(2))));
const Scalar _tmp14 = _tmp12 * (_tmp10 * (-_tmp2 * state(0, 0) + 2 * state(2, 0) * state(3, 0)) -
_tmp11 * (_tmp0 * state(2, 0) + _tmp2 * state(3, 0)));
// Output terms (2)
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = R + _tmp13 * (P(0, 2) * _tmp14 + P(2, 2) * _tmp13) +
_tmp14 * (P(0, 0) * _tmp14 + P(2, 0) * _tmp13);
}
if (H != nullptr) {
matrix::Matrix<Scalar, 23, 1>& _h = (*H);
_h.setZero();
_h(0, 0) = _tmp14;
_h(2, 0) = _tmp13;
}
} // NOLINT(readability/fn_size)
// NOLINTNEXTLINE(readability/fn_size)
} // namespace sym

View File

@ -0,0 +1,76 @@
// -----------------------------------------------------------------------------
// This file was autogenerated by symforce from template:
// function/FUNCTION.h.jinja
// Do NOT modify by hand.
// -----------------------------------------------------------------------------
#pragma once
#include <matrix/math.hpp>
namespace sym {
/**
* This function was autogenerated from a symbolic function. Do not modify by hand.
*
* Symbolic function: compute_yaw_312_innov_var_and_h_alternate
*
* Args:
* state: Matrix24_1
* P: Matrix23_23
* R: Scalar
* epsilon: Scalar
*
* Outputs:
* innov_var: Scalar
* H: Matrix23_1
*/
template <typename Scalar>
void ComputeYaw312InnovVarAndHAlternate(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar R,
const Scalar epsilon, Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 57
// Input arrays
// Intermediate terms (15)
const Scalar _tmp0 = 2 * state(0, 0);
const Scalar _tmp1 = 2 * state(1, 0);
const Scalar _tmp2 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp3 = std::pow(state(1, 0), Scalar(2));
const Scalar _tmp4 = -2 * _tmp2 - 2 * _tmp3 + 1;
const Scalar _tmp5 = -_tmp0 * state(3, 0);
const Scalar _tmp6 = _tmp1 * state(2, 0);
const Scalar _tmp7 = _tmp5 + _tmp6;
const Scalar _tmp8 = _tmp7 + epsilon * ((((_tmp7) > 0) - ((_tmp7) < 0)) + Scalar(0.5));
const Scalar _tmp9 = std::pow(_tmp8, Scalar(2));
const Scalar _tmp10 = _tmp4 / _tmp9;
const Scalar _tmp11 = Scalar(1.0) / (_tmp8);
const Scalar _tmp12 = _tmp9 / (std::pow(_tmp4, Scalar(2)) + _tmp9);
const Scalar _tmp13 = _tmp12 * (_tmp10 * (_tmp0 * state(2, 0) + _tmp1 * state(3, 0)) -
_tmp11 * (-_tmp1 * state(0, 0) + 2 * state(2, 0) * state(3, 0)));
const Scalar _tmp14 = _tmp12 * (_tmp10 * (_tmp2 - _tmp3 - std::pow(state(0, 0), Scalar(2)) +
std::pow(state(2, 0), Scalar(2))) -
_tmp11 * (_tmp5 - _tmp6));
// Output terms (2)
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = R - _tmp13 * (-P(0, 0) * _tmp13 - P(2, 0) * _tmp14) -
_tmp14 * (-P(0, 2) * _tmp13 - P(2, 2) * _tmp14);
}
if (H != nullptr) {
matrix::Matrix<Scalar, 23, 1>& _h = (*H);
_h.setZero();
_h(0, 0) = -_tmp13;
_h(2, 0) = -_tmp14;
}
} // NOLINT(readability/fn_size)
// NOLINTNEXTLINE(readability/fn_size)
} // namespace sym

View File

@ -0,0 +1,76 @@
// -----------------------------------------------------------------------------
// This file was autogenerated by symforce from template:
// function/FUNCTION.h.jinja
// Do NOT modify by hand.
// -----------------------------------------------------------------------------
#pragma once
#include <matrix/math.hpp>
namespace sym {
/**
* This function was autogenerated from a symbolic function. Do not modify by hand.
*
* Symbolic function: compute_yaw_321_innov_var_and_h
*
* Args:
* state: Matrix24_1
* P: Matrix23_23
* R: Scalar
* epsilon: Scalar
*
* Outputs:
* innov_var: Scalar
* H: Matrix23_1
*/
template <typename Scalar>
void ComputeYaw321InnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar R,
const Scalar epsilon, Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 53
// Input arrays
// Intermediate terms (15)
const Scalar _tmp0 = 2 * state(0, 0);
const Scalar _tmp1 = _tmp0 * state(3, 0);
const Scalar _tmp2 = 2 * state(1, 0);
const Scalar _tmp3 = _tmp2 * state(2, 0);
const Scalar _tmp4 = _tmp1 + _tmp3;
const Scalar _tmp5 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp6 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp7 = -2 * _tmp5 - 2 * _tmp6 + 1;
const Scalar _tmp8 = _tmp7 + epsilon * ((((_tmp7) > 0) - ((_tmp7) < 0)) + Scalar(0.5));
const Scalar _tmp9 = std::pow(_tmp8, Scalar(2));
const Scalar _tmp10 = _tmp4 / _tmp9;
const Scalar _tmp11 = Scalar(1.0) / (_tmp8);
const Scalar _tmp12 = _tmp9 / (std::pow(_tmp4, Scalar(2)) + _tmp9);
const Scalar _tmp13 = _tmp12 * (-_tmp10 * (-_tmp1 + _tmp3) +
_tmp11 * (-_tmp5 + _tmp6 + std::pow(state(0, 0), Scalar(2)) -
std::pow(state(1, 0), Scalar(2))));
const Scalar _tmp14 = _tmp12 * (-_tmp10 * (-_tmp0 * state(2, 0) - _tmp2 * state(3, 0)) +
_tmp11 * (_tmp2 * state(0, 0) - 2 * state(2, 0) * state(3, 0)));
// Output terms (2)
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = R + _tmp13 * (P(1, 2) * _tmp14 + P(2, 2) * _tmp13) +
_tmp14 * (P(1, 1) * _tmp14 + P(2, 1) * _tmp13);
}
if (H != nullptr) {
matrix::Matrix<Scalar, 23, 1>& _h = (*H);
_h.setZero();
_h(1, 0) = _tmp14;
_h(2, 0) = _tmp13;
}
} // NOLINT(readability/fn_size)
// NOLINTNEXTLINE(readability/fn_size)
} // namespace sym

View File

@ -0,0 +1,76 @@
// -----------------------------------------------------------------------------
// This file was autogenerated by symforce from template:
// function/FUNCTION.h.jinja
// Do NOT modify by hand.
// -----------------------------------------------------------------------------
#pragma once
#include <matrix/math.hpp>
namespace sym {
/**
* This function was autogenerated from a symbolic function. Do not modify by hand.
*
* Symbolic function: compute_yaw_321_innov_var_and_h_alternate
*
* Args:
* state: Matrix24_1
* P: Matrix23_23
* R: Scalar
* epsilon: Scalar
*
* Outputs:
* innov_var: Scalar
* H: Matrix23_1
*/
template <typename Scalar>
void ComputeYaw321InnovVarAndHAlternate(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar R,
const Scalar epsilon, Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 57
// Input arrays
// Intermediate terms (15)
const Scalar _tmp0 = 2 * state(2, 0);
const Scalar _tmp1 = 2 * state(1, 0);
const Scalar _tmp2 = 2 * state(0, 0) * state(3, 0);
const Scalar _tmp3 = _tmp1 * state(2, 0);
const Scalar _tmp4 = _tmp2 + _tmp3;
const Scalar _tmp5 = _tmp4 + epsilon * ((((_tmp4) > 0) - ((_tmp4) < 0)) + Scalar(0.5));
const Scalar _tmp6 = Scalar(1.0) / (_tmp5);
const Scalar _tmp7 = std::pow(state(3, 0), Scalar(2));
const Scalar _tmp8 = std::pow(state(2, 0), Scalar(2));
const Scalar _tmp9 = -2 * _tmp7 - 2 * _tmp8 + 1;
const Scalar _tmp10 = std::pow(_tmp5, Scalar(2));
const Scalar _tmp11 = _tmp9 / _tmp10;
const Scalar _tmp12 = _tmp10 / (_tmp10 + std::pow(_tmp9, Scalar(2)));
const Scalar _tmp13 = _tmp12 * (-_tmp11 * (-_tmp0 * state(3, 0) + _tmp1 * state(0, 0)) +
_tmp6 * (-_tmp0 * state(0, 0) - _tmp1 * state(3, 0)));
const Scalar _tmp14 = _tmp12 * (-_tmp11 * (-_tmp7 + _tmp8 + std::pow(state(0, 0), Scalar(2)) -
std::pow(state(1, 0), Scalar(2))) +
_tmp6 * (-_tmp2 + _tmp3));
// Output terms (2)
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = R - _tmp13 * (-P(1, 1) * _tmp13 - P(2, 1) * _tmp14) -
_tmp14 * (-P(1, 2) * _tmp13 - P(2, 2) * _tmp14);
}
if (H != nullptr) {
matrix::Matrix<Scalar, 23, 1>& _h = (*H);
_h.setZero();
_h(1, 0) = -_tmp13;
_h(2, 0) = -_tmp14;
}
} // NOLINT(readability/fn_size)
// NOLINTNEXTLINE(readability/fn_size)
} // namespace sym

View File

@ -1,65 +0,0 @@
// -----------------------------------------------------------------------------
// This file was autogenerated by symforce from template:
// function/FUNCTION.h.jinja
// Do NOT modify by hand.
// -----------------------------------------------------------------------------
#pragma once
#include <matrix/math.hpp>
namespace sym {
/**
* This function was autogenerated from a symbolic function. Do not modify by hand.
*
* Symbolic function: compute_yaw_innov_var_and_h
*
* Args:
* state: Matrix24_1
* P: Matrix23_23
* R: Scalar
*
* Outputs:
* innov_var: Scalar
* H: Matrix23_1
*/
template <typename Scalar>
void ComputeYawInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
const matrix::Matrix<Scalar, 23, 23>& P, const Scalar R,
Scalar* const innov_var = nullptr,
matrix::Matrix<Scalar, 23, 1>* const H = nullptr) {
// Total ops: 36
// Input arrays
// Intermediate terms (5)
const Scalar _tmp0 = 2 * state(2, 0);
const Scalar _tmp1 = 2 * state(1, 0);
const Scalar _tmp2 = -_tmp0 * state(0, 0) + _tmp1 * state(3, 0);
const Scalar _tmp3 = _tmp0 * state(3, 0) + _tmp1 * state(0, 0);
const Scalar _tmp4 = std::pow(state(0, 0), Scalar(2)) - std::pow(state(1, 0), Scalar(2)) -
std::pow(state(2, 0), Scalar(2)) + std::pow(state(3, 0), Scalar(2));
// Output terms (2)
if (innov_var != nullptr) {
Scalar& _innov_var = (*innov_var);
_innov_var = R + _tmp2 * (P(0, 0) * _tmp2 + P(1, 0) * _tmp3 + P(2, 0) * _tmp4) +
_tmp3 * (P(0, 1) * _tmp2 + P(1, 1) * _tmp3 + P(2, 1) * _tmp4) +
_tmp4 * (P(0, 2) * _tmp2 + P(1, 2) * _tmp3 + P(2, 2) * _tmp4);
}
if (H != nullptr) {
matrix::Matrix<Scalar, 23, 1>& _h = (*H);
_h.setZero();
_h(0, 0) = _tmp2;
_h(1, 0) = _tmp3;
_h(2, 0) = _tmp4;
}
} // NOLINT(readability/fn_size)
// NOLINTNEXTLINE(readability/fn_size)
} // namespace sym

View File

@ -45,20 +45,14 @@ import numpy as np
import quaternion
from scipy import optimize
def getAllData(logfile, use_gnss):
def getAllData(logfile):
log = ULog(logfile)
if use_gnss:
v_local = np.array([getData(log, 'vehicle_gps_position', 'vel_n_m_s'),
getData(log, 'vehicle_gps_position', 'vel_e_m_s'),
getData(log, 'vehicle_gps_position', 'vel_d_m_s')])
t_v_local = ms2s(getData(log, 'vehicle_gps_position', 'timestamp'))
v_local = np.matrix([getData(log, 'vehicle_local_position', 'vx'),
getData(log, 'vehicle_local_position', 'vy'),
getData(log, 'vehicle_local_position', 'vz')])
else:
v_local = np.array([getData(log, 'vehicle_local_position', 'vx'),
getData(log, 'vehicle_local_position', 'vy'),
getData(log, 'vehicle_local_position', 'vz')])
t_v_local = ms2s(getData(log, 'vehicle_local_position', 'timestamp'))
t_v_local = ms2s(getData(log, 'vehicle_local_position', 'timestamp'))
accel = np.matrix([getData(log, 'sensor_combined', 'accelerometer_m_s2[0]'),
getData(log, 'sensor_combined', 'accelerometer_m_s2[1]'),
@ -132,8 +126,8 @@ def getData(log, topic_name, variable_name, instance=0):
def ms2s(time_ms):
return time_ms * 1e-6
def run(logfile, use_gnss):
(t, v_body, a_body) = getAllData(logfile, use_gnss)
def run(logfile):
(t, v_body, a_body) = getAllData(logfile)
rho = 1.15 # air densitiy
rho15 = 1.225 # air density at 15 degC
@ -203,10 +197,8 @@ if __name__ == '__main__':
# Provide parameter file path and name
parser.add_argument('logfile', help='Full ulog file path, name and extension', type=str)
parser.add_argument('--gnss', help='Use GNSS velocity instead of local velocity estimate',
action='store_true')
args = parser.parse_args()
logfile = os.path.abspath(args.logfile) # Convert to absolute path
run(logfile, args.gnss)
run(logfile)

View File

@ -33,7 +33,8 @@
#include "ekf.h"
#include <ekf_derivation/generated/compute_yaw_innov_var_and_h.h>
#include <ekf_derivation/generated/compute_yaw_321_innov_var_and_h.h>
#include <ekf_derivation/generated/compute_yaw_312_innov_var_and_h.h>
#include <mathlib/mathlib.h>
@ -41,7 +42,7 @@
bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status)
{
VectorState H_YAW;
sym::ComputeYawInnovVarAndH(_state.vector(), P, aid_src_status.observation_variance, &aid_src_status.innovation_variance, &H_YAW);
computeYawInnovVarAndH(aid_src_status.observation_variance, aid_src_status.innovation_variance, H_YAW);
return fuseYaw(aid_src_status, H_YAW);
}
@ -134,5 +135,10 @@ bool Ekf::fuseYaw(estimator_aid_source1d_s &aid_src_status, const VectorState &H
void Ekf::computeYawInnovVarAndH(float variance, float &innovation_variance, VectorState &H_YAW) const
{
sym::ComputeYawInnovVarAndH(_state.vector(), P, variance, &innovation_variance, &H_YAW);
if (shouldUse321RotationSequence(_R_to_earth)) {
sym::ComputeYaw321InnovVarAndH(_state.vector(), P, variance, FLT_EPSILON, &innovation_variance, &H_YAW);
} else {
sym::ComputeYaw312InnovVarAndH(_state.vector(), P, variance, FLT_EPSILON, &innovation_variance, &H_YAW);
}
}

View File

@ -1,391 +1,391 @@
Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00093,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00053,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00055,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00048,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00038,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00034,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2190000,1,-0.011,-0.014,5.8e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2590000,1,-0.011,-0.013,5.8e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2790000,1,-0.011,-0.013,4.8e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2890000,1,-0.011,-0.013,-1.8e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3090000,1,-0.011,-0.013,4.8e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3190000,1,-0.011,-0.013,-8.9e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0087,0.0087,0.00021,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3290000,1,-0.011,-0.013,3.1e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3390000,1,-0.011,-0.012,2.5e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3490000,1,-0.011,-0.013,-5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3590000,1,-0.011,-0.012,1.8e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00018,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4290000,1,-0.01,-0.012,8.2e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00016,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00017,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4690000,1,-0.01,-0.012,0.0002,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4790000,1,-0.01,-0.012,0.00019,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00015,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00014,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00013,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5690000,1,-0.0096,-0.011,0.00034,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00012,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6090000,1,-0.0094,-0.011,0.00032,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6290000,1,-0.0094,-0.011,0.00022,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6390000,1,-0.0093,-0.011,0.00024,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6590000,1,-0.0094,-0.011,0.00017,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6690000,1,-0.0093,-0.011,9.6e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6790000,0.78,-0.024,0.0049,-0.63,-0.0056,0.0015,-0.11,0.0015,0.00055,-3.7e+02,-0.0014,-0.0057,-8.2e-05,0,0,-5.8e-05,-0.092,-0.02,0.51,-0.00081,-0.075,-0.061,0,0,0.0013,0.0013,0.072,0.18,0.18,0.6,0.11,0.11,0.2,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1
6890000,0.78,-0.025,0.0057,-0.63,-0.03,-0.0077,-0.12,-9e-05,-0.0018,-3.7e+02,-0.0013,-0.0057,-8.3e-05,0,0,-0.00011,-0.1,-0.022,0.51,-0.0011,-0.083,-0.067,0,0,0.0013,0.0013,0.057,0.18,0.18,0.46,0.14,0.14,0.18,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00024,0.0013,0.00094,0.0014,0.0013,1,1
6990000,0.78,-0.025,0.0058,-0.63,-0.059,-0.018,-0.12,-0.0053,-0.0061,-3.7e+02,-0.0012,-0.0057,-8.7e-05,-2.7e-05,-6.9e-05,-0.00041,-0.1,-0.022,0.5,-0.0015,-0.084,-0.067,0,0,0.0013,0.0013,0.053,0.19,0.18,0.36,0.17,0.17,0.16,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.0009,0.0014,0.0013,1,1
7090000,0.78,-0.025,0.0059,-0.63,-0.087,-0.028,-0.12,-0.014,-0.012,-3.7e+02,-0.0011,-0.0057,-9.1e-05,-8.3e-05,-0.00024,-0.00077,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.052,0.19,0.19,0.29,0.2,0.2,0.16,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00015,0.0013,0.00089,0.0013,0.0013,1,1
7190000,0.78,-0.025,0.006,-0.63,-0.11,-0.037,-0.15,-0.024,-0.018,-3.7e+02,-0.001,-0.0057,-9.3e-05,-7.7e-05,-0.00036,-0.00056,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.051,0.21,0.21,0.24,0.23,0.23,0.15,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00088,0.0013,0.0013,1,1
7290000,0.78,-0.025,0.0059,-0.63,-0.14,-0.04,-0.14,-0.035,-0.019,-3.7e+02,-0.0011,-0.0057,-9e-05,-4.6e-05,-0.00024,-0.0012,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.22,0.22,0.2,0.28,0.28,0.14,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00087,0.0013,0.0013,1,1
7390000,0.78,-0.025,0.0059,-0.63,-0.16,-0.048,-0.16,-0.049,-0.025,-3.7e+02,-0.0011,-0.0057,-9e-05,8.1e-07,-0.00028,-0.0014,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.24,0.24,0.18,0.32,0.32,0.13,7.8e-05,7.9e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.00087,0.0013,0.0013,1,1
7490000,0.78,-0.025,0.0059,-0.63,-0.19,-0.061,-0.16,-0.066,-0.038,-3.7e+02,-0.00093,-0.0057,-9.3e-05,1.6e-05,-0.0005,-0.0022,-0.1,-0.023,0.5,-0.0017,-0.085,-0.069,0,0,0.0013,0.0013,0.049,0.27,0.26,0.15,0.37,0.37,0.12,7.8e-05,7.8e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1
7590000,0.78,-0.025,0.0059,-0.63,-0.21,-0.067,-0.16,-0.082,-0.044,-3.7e+02,-0.00093,-0.0056,-9e-05,0.00011,-0.00047,-0.003,-0.1,-0.023,0.5,-0.0016,-0.085,-0.068,0,0,0.0013,0.0013,0.049,0.29,0.29,0.14,0.43,0.43,0.12,7.7e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1
7690000,0.78,-0.025,0.0059,-0.63,-0.24,-0.079,-0.16,-0.1,-0.058,-3.7e+02,-0.00082,-0.0056,-9.3e-05,8.3e-05,-0.00057,-0.005,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.32,0.32,0.13,0.49,0.49,0.11,7.6e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,9.6e-05,0.0013,0.00086,0.0013,0.0013,1,1
7790000,0.78,-0.025,0.006,-0.63,-0.27,-0.088,-0.16,-0.14,-0.072,-3.7e+02,-0.00074,-0.0057,-9.9e-05,-0.00013,-0.00063,-0.007,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.35,0.35,0.12,0.56,0.55,0.11,7.5e-05,7.5e-05,4.9e-06,0.04,0.04,0.038,0.0013,9.3e-05,0.0013,0.00086,0.0013,0.0013,1,1
7890000,0.78,-0.025,0.006,-0.63,-0.29,-0.099,-0.15,-0.16,-0.086,-3.7e+02,-0.00067,-0.0056,-9.8e-05,-8.1e-05,-0.00064,-0.0095,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.39,0.38,0.11,0.63,0.63,0.1,7.4e-05,7.4e-05,4.9e-06,0.04,0.04,0.038,0.0013,9e-05,0.0013,0.00086,0.0013,0.0013,1,1
7990000,0.78,-0.025,0.006,-0.63,-0.32,-0.11,-0.16,-0.19,-0.098,-3.7e+02,-0.00064,-0.0056,-9.7e-05,2.6e-06,-0.00064,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.43,0.42,0.1,0.71,0.71,0.099,7.2e-05,7.3e-05,4.9e-06,0.04,0.04,0.038,0.0013,8.8e-05,0.0013,0.00086,0.0013,0.0013,1,1
8090000,0.78,-0.025,0.006,-0.63,-0.34,-0.12,-0.17,-0.21,-0.11,-3.7e+02,-0.00058,-0.0054,-9.5e-05,0.00017,-0.00074,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.47,0.46,0.1,0.8,0.8,0.097,7e-05,7.1e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.6e-05,0.0013,0.00086,0.0013,0.0013,1,1
8190000,0.78,-0.025,0.0061,-0.63,-0.37,-0.13,-0.17,-0.25,-0.13,-3.7e+02,-0.00056,-0.0055,-9.8e-05,-2.7e-05,-0.00068,-0.013,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.52,0.51,0.099,0.9,0.89,0.094,6.8e-05,6.9e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.5e-05,0.0013,0.00085,0.0013,0.0013,1,1
8290000,0.78,-0.025,0.0061,-0.63,-0.019,-0.0046,-0.17,-0.27,-0.13,-3.7e+02,-0.00042,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.017,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.6e-05,6.7e-05,4.9e-06,0.04,0.04,0.036,0.0013,8.3e-05,0.0013,0.00085,0.0013,0.0013,1,1
8390000,0.78,-0.025,0.0061,-0.63,-0.046,-0.012,-0.17,-0.27,-0.13,-3.7e+02,-0.00038,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.021,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,6.5e-05,4.9e-06,0.04,0.04,0.035,0.0013,8.2e-05,0.0013,0.00085,0.0013,0.0013,1,1
8490000,0.78,-0.026,0.0062,-0.63,-0.073,-0.02,-0.17,-0.27,-0.13,-3.7e+02,-0.00033,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.025,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,51,51,0.089,6.2e-05,6.3e-05,4.9e-06,0.04,0.04,0.034,0.0013,8.1e-05,0.0013,0.00085,0.0013,0.0013,1,1
8590000,0.78,-0.025,0.0062,-0.63,-0.099,-0.028,-0.16,-0.28,-0.14,-3.7e+02,-0.00051,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.029,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.095,52,52,0.088,5.9e-05,6.1e-05,4.9e-06,0.04,0.04,0.034,0.0013,8e-05,0.0013,0.00085,0.0013,0.0013,1,1
8690000,0.78,-0.025,0.0061,-0.63,-0.12,-0.036,-0.16,-0.28,-0.14,-3.7e+02,-0.00047,-0.0055,-9.9e-05,-6.1e-05,-0.00064,-0.034,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.096,35,35,0.088,5.7e-05,5.9e-05,4.9e-06,0.04,0.04,0.033,0.0013,7.9e-05,0.0013,0.00085,0.0013,0.0013,1,1
8790000,0.78,-0.026,0.0062,-0.63,-0.15,-0.044,-0.15,-0.3,-0.14,-3.7e+02,-0.0004,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.04,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,37,37,0.087,5.5e-05,5.6e-05,4.9e-06,0.04,0.04,0.032,0.0013,7.8e-05,0.0013,0.00085,0.0013,0.0013,1,1
8890000,0.78,-0.026,0.0063,-0.63,-0.18,-0.05,-0.15,-0.3,-0.14,-3.7e+02,-0.00037,-0.0056,-0.00011,-6.1e-05,-0.00064,-0.044,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.095,28,28,0.086,5.2e-05,5.4e-05,4.9e-06,0.04,0.04,0.03,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1
8990000,0.78,-0.026,0.0064,-0.63,-0.21,-0.056,-0.14,-0.32,-0.15,-3.7e+02,-0.00029,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.05,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.096,30,30,0.087,5e-05,5.1e-05,4.9e-06,0.04,0.04,0.029,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1
9090000,0.78,-0.026,0.0065,-0.63,-0.23,-0.06,-0.14,-0.33,-0.15,-3.7e+02,-0.00033,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.052,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.095,25,25,0.086,4.7e-05,4.9e-05,4.9e-06,0.04,0.04,0.028,0.0013,7.6e-05,0.0013,0.00085,0.0013,0.0013,1,1
9190000,0.78,-0.026,0.0063,-0.63,-0.25,-0.071,-0.14,-0.35,-0.16,-3.7e+02,-0.00029,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.056,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.094,27,27,0.085,4.5e-05,4.6e-05,4.9e-06,0.04,0.04,0.027,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1
9290000,0.78,-0.026,0.0063,-0.63,-0.27,-0.077,-0.13,-0.35,-0.16,-3.7e+02,-0.00023,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.06,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,23,23,0.085,4.2e-05,4.4e-05,4.9e-06,0.04,0.04,0.025,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1
9390000,0.78,-0.026,0.0065,-0.63,-0.3,-0.086,-0.13,-0.38,-0.17,-3.7e+02,-0.00018,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.063,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,21,21,0.093,25,25,0.086,4e-05,4.2e-05,4.9e-06,0.04,0.04,0.024,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1
9490000,0.78,-0.026,0.0064,-0.63,-0.31,-0.092,-0.13,-0.38,-0.17,-3.7e+02,-0.00011,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.067,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.091,22,22,0.085,3.8e-05,4e-05,4.9e-06,0.04,0.04,0.023,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1
9590000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.18,-3.7e+02,-0.00024,-0.0053,-0.0001,-6.1e-05,-0.00064,-0.07,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.09,25,25,0.085,3.6e-05,3.7e-05,4.9e-06,0.04,0.04,0.022,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1
9690000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.17,-3.7e+02,-0.0003,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.075,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.089,22,22,0.086,3.4e-05,3.6e-05,4.9e-06,0.04,0.04,0.02,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1
9790000,0.78,-0.026,0.0063,-0.63,-0.38,-0.11,-0.1,-0.45,-0.19,-3.7e+02,-0.00026,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.08,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.087,24,24,0.085,3.2e-05,3.4e-05,4.9e-06,0.04,0.04,0.019,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1
9890000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.1,-0.48,-0.2,-3.7e+02,-0.00033,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.083,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.084,28,28,0.085,3e-05,3.2e-05,4.9e-06,0.04,0.04,0.018,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1
9990000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.096,-0.47,-0.19,-3.7e+02,-0.00035,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.086,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.083,24,24,0.086,2.8e-05,3e-05,4.9e-06,0.04,0.04,0.017,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1
10090000,0.78,-0.026,0.0062,-0.63,-0.43,-0.12,-0.092,-0.51,-0.2,-3.7e+02,-0.00043,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.089,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.081,27,27,0.085,2.7e-05,2.8e-05,4.9e-06,0.04,0.04,0.016,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1
10190000,0.78,-0.026,0.0065,-0.63,-0.43,-0.12,-0.092,-0.5,-0.2,-3.7e+02,-0.00044,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.09,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,13,0.078,24,24,0.084,2.5e-05,2.7e-05,4.9e-06,0.04,0.04,0.015,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1
10290000,0.78,-0.026,0.0067,-0.63,-0.46,-0.12,-0.08,-0.55,-0.21,-3.7e+02,-0.00045,-0.0058,-0.00011,-6.1e-05,-0.00064,-0.096,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,14,0.076,27,27,0.085,2.4e-05,2.5e-05,4.9e-06,0.04,0.04,0.014,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1
10390000,0.78,-0.026,0.0068,-0.63,-0.017,-0.027,0.0097,-0.00031,-0.0021,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00013,-0.00061,-0.099,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,4.9e-06,0.04,0.04,0.013,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1
10490000,0.78,-0.026,0.0069,-0.63,-0.047,-0.034,0.023,-0.0035,-0.0051,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00035,-0.00043,-0.1,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.26,0.26,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,4.9e-06,0.04,0.04,0.012,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1
10590000,0.78,-0.026,0.0066,-0.63,-0.045,-0.023,0.026,0.0012,-0.0011,-3.7e+02,-0.00059,-0.0058,-0.00011,-3.5e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.1e-05,4.9e-06,0.04,0.04,0.012,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1
10690000,0.78,-0.026,0.0066,-0.63,-0.073,-0.029,0.03,-0.0048,-0.0037,-3.7e+02,-0.00059,-0.0059,-0.00011,-9.8e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.14,0.14,0.26,0.14,0.14,0.078,1.9e-05,2e-05,4.9e-06,0.04,0.04,0.011,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1
10790000,0.78,-0.025,0.0064,-0.63,-0.069,-0.024,0.024,-0.0001,-0.0015,-3.7e+02,-0.00063,-0.0058,-0.00011,0.00028,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.096,0.096,0.17,0.09,0.09,0.072,1.8e-05,1.9e-05,4.8e-06,0.04,0.039,0.011,0.0013,7e-05,0.0013,0.00084,0.0013,0.0013,1,1
10890000,0.78,-0.025,0.0064,-0.63,-0.097,-0.03,0.02,-0.0084,-0.0042,-3.7e+02,-0.00063,-0.0058,-0.00011,0.0003,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0015,0.048,0.11,0.11,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00084,0.0013,0.0013,1,1
10990000,0.78,-0.025,0.0059,-0.63,-0.085,-0.024,0.014,-0.0037,-0.0024,-3.7e+02,-0.00066,-0.0058,-0.0001,0.0011,-0.009,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.086,0.086,0.12,0.099,0.099,0.071,1.6e-05,1.7e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
11090000,0.78,-0.025,0.0057,-0.63,-0.11,-0.032,0.019,-0.013,-0.0054,-3.7e+02,-0.00069,-0.0057,-9.6e-05,0.0013,-0.0089,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.1,0.1,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
11190000,0.78,-0.024,0.0051,-0.63,-0.095,-0.025,0.0078,-0.0051,-0.0021,-3.7e+02,-0.00079,-0.0057,-9.3e-05,0.0019,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.084,0.084,0.084,0.11,0.11,0.069,1.4e-05,1.5e-05,4.8e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1
11290000,0.78,-0.024,0.0052,-0.63,-0.12,-0.029,0.0076,-0.016,-0.0046,-3.7e+02,-0.00074,-0.0058,-9.7e-05,0.0016,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.099,0.099,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,4.8e-06,0.038,0.038,0.01,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1
11390000,0.78,-0.022,0.0045,-0.63,-0.1,-0.024,0.002,-0.0027,-0.00099,-3.7e+02,-0.00084,-0.0059,-9.5e-05,0.0015,-0.022,-0.11,-0.11,-0.023,0.5,-0.0013,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.08,0.08,0.063,0.082,0.082,0.068,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1
11490000,0.78,-0.022,0.0047,-0.63,-0.12,-0.026,0.0029,-0.014,-0.0031,-3.7e+02,-0.0008,-0.006,-0.0001,0.0009,-0.022,-0.11,-0.11,-0.023,0.5,-0.0014,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.095,0.095,0.058,0.089,0.089,0.069,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1
11590000,0.78,-0.022,0.0041,-0.63,-0.1,-0.022,-0.003,-0.0044,-0.00098,-3.7e+02,-0.00085,-0.006,-9.8e-05,0.00079,-0.029,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.078,0.078,0.049,0.068,0.068,0.066,1.1e-05,1.2e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1
11690000,0.78,-0.022,0.0042,-0.63,-0.12,-0.026,-0.0074,-0.016,-0.0033,-3.7e+02,-0.00079,-0.006,-0.0001,0.00062,-0.03,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.093,0.093,0.046,0.075,0.075,0.066,1.1e-05,1.1e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1
11790000,0.78,-0.021,0.0037,-0.63,-0.1,-0.017,-0.0092,-0.0082,0.00018,-3.7e+02,-0.00082,-0.006,-9.7e-05,0.0012,-0.036,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.077,0.076,0.039,0.06,0.06,0.063,1e-05,1.1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1
11890000,0.78,-0.021,0.0038,-0.63,-0.12,-0.019,-0.01,-0.019,-0.0015,-3.7e+02,-0.0008,-0.0061,-9.9e-05,0.00091,-0.036,-0.11,-0.11,-0.023,0.5,-0.0015,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.09,0.09,0.037,0.067,0.067,0.063,9.5e-06,1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1
11990000,0.78,-0.02,0.003,-0.63,-0.095,-0.012,-0.015,-0.011,0.0012,-3.7e+02,-0.00095,-0.0061,-9.3e-05,0.0013,-0.04,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.074,0.074,0.033,0.055,0.055,0.061,9e-06,9.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1
12090000,0.78,-0.02,0.0029,-0.63,-0.11,-0.016,-0.021,-0.021,-0.00045,-3.7e+02,-0.00099,-0.006,-9e-05,0.0018,-0.04,-0.11,-0.11,-0.023,0.5,-0.0013,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.087,0.086,0.031,0.063,0.063,0.061,8.6e-06,9.2e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1
12190000,0.78,-0.019,0.0023,-0.63,-0.084,-0.015,-0.016,-0.01,0.00028,-3.7e+02,-0.00098,-0.006,-8.9e-05,0.0016,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.071,0.071,0.028,0.052,0.052,0.059,8.1e-06,8.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1
12290000,0.78,-0.019,0.0024,-0.63,-0.092,-0.017,-0.015,-0.019,-0.0014,-3.7e+02,-0.00094,-0.006,-8.9e-05,0.0017,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.082,0.082,0.028,0.06,0.06,0.059,7.8e-06,8.4e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1
12390000,0.78,-0.019,0.0019,-0.63,-0.073,-0.014,-0.013,-0.0094,-0.00012,-3.7e+02,-0.00099,-0.006,-8.8e-05,0.0011,-0.05,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.067,0.067,0.026,0.05,0.05,0.057,7.4e-06,8e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1
12490000,0.78,-0.019,0.0021,-0.63,-0.08,-0.016,-0.016,-0.017,-0.0014,-3.7e+02,-0.00096,-0.0061,-9.1e-05,0.00059,-0.05,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.077,0.076,0.026,0.058,0.058,0.057,7.1e-06,7.6e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1
12590000,0.78,-0.018,0.0018,-0.63,-0.073,-0.014,-0.022,-0.014,-0.00033,-3.7e+02,-0.001,-0.0061,-8.8e-05,0.00072,-0.052,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.063,0.063,0.025,0.049,0.049,0.055,6.8e-06,7.3e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.5e-05,0.0012,0.00072,0.0013,0.0012,1,1
12690000,0.78,-0.018,0.0018,-0.63,-0.079,-0.015,-0.025,-0.021,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.8e-05,0.00038,-0.051,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.071,0.071,0.025,0.057,0.057,0.055,6.5e-06,7e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1
12790000,0.78,-0.018,0.0016,-0.63,-0.072,-0.012,-0.028,-0.018,-0.0006,-3.7e+02,-0.0011,-0.0061,-8.7e-05,0.00058,-0.053,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00054,0.00056,0.046,0.059,0.058,0.024,0.048,0.048,0.053,6.2e-06,6.7e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1
12890000,0.78,-0.018,0.0017,-0.63,-0.079,-0.013,-0.027,-0.026,-0.0019,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00062,-0.054,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00055,0.00056,0.046,0.066,0.066,0.025,0.056,0.056,0.054,6e-06,6.5e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1
12990000,0.78,-0.018,0.0013,-0.63,-0.064,-0.012,-0.028,-0.019,-0.0015,-3.7e+02,-0.0011,-0.006,-8.6e-05,0.0009,-0.056,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.059,0.058,0.025,0.058,0.058,0.052,5.7e-06,6.2e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1
13090000,0.78,-0.018,0.0014,-0.63,-0.069,-0.011,-0.028,-0.026,-0.0023,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00025,-0.057,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.065,0.065,0.025,0.066,0.066,0.052,5.5e-06,6e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1
13190000,0.78,-0.018,0.0011,-0.63,-0.055,-0.011,-0.025,-0.017,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.7e-05,-1.3e-05,-0.058,-0.11,-0.11,-0.024,0.5,-0.0016,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.058,0.058,0.025,0.067,0.067,0.051,5.2e-06,5.7e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1
13290000,0.78,-0.018,0.0011,-0.63,-0.06,-0.013,-0.021,-0.024,-0.003,-3.7e+02,-0.001,-0.006,-8.8e-05,0.00039,-0.059,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.064,0.064,0.027,0.077,0.077,0.051,5.1e-06,5.5e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1
13390000,0.78,-0.017,0.00099,-0.63,-0.049,-0.012,-0.017,-0.016,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00065,-0.06,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.056,0.056,0.026,0.077,0.077,0.05,4.9e-06,5.3e-06,4.8e-06,0.032,0.032,0.0088,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13490000,0.78,-0.017,0.00096,-0.63,-0.053,-0.013,-0.016,-0.022,-0.0034,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00089,-0.061,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.062,0.062,0.028,0.088,0.088,0.05,4.7e-06,5.1e-06,4.8e-06,0.031,0.032,0.0087,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13590000,0.78,-0.017,0.00083,-0.63,-0.043,-0.012,-0.018,-0.014,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00051,-0.062,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.054,0.054,0.028,0.087,0.087,0.05,4.5e-06,5e-06,4.8e-06,0.031,0.032,0.0084,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13690000,0.78,-0.017,0.00081,-0.63,-0.046,-0.015,-0.022,-0.019,-0.0035,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00095,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.06,0.06,0.029,0.098,0.098,0.05,4.3e-06,4.8e-06,4.8e-06,0.031,0.032,0.0083,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13790000,0.78,-0.017,0.00063,-0.63,-0.033,-0.013,-0.024,-0.0063,-0.003,-3.7e+02,-0.0011,-0.006,-8.3e-05,0.00068,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.045,0.045,0.029,0.072,0.072,0.049,4.2e-06,4.6e-06,4.8e-06,0.031,0.031,0.0079,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1
13890000,0.78,-0.017,0.00069,-0.63,-0.037,-0.015,-0.028,-0.01,-0.0045,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00091,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.049,0.049,0.03,0.081,0.081,0.05,4e-06,4.5e-06,4.8e-06,0.031,0.031,0.0078,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1
13990000,0.78,-0.017,0.00054,-0.63,-0.029,-0.014,-0.027,-0.0032,-0.004,-3.7e+02,-0.0011,-0.006,-8.4e-05,0.00078,-0.064,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.04,0.04,0.03,0.063,0.063,0.05,3.9e-06,4.3e-06,4.8e-06,0.031,0.031,0.0074,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
14090000,0.78,-0.017,0.00048,-0.63,-0.03,-0.015,-0.028,-0.006,-0.0056,-3.7e+02,-0.0011,-0.006,-8.1e-05,0.0012,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.044,0.044,0.031,0.07,0.07,0.05,3.8e-06,4.2e-06,4.8e-06,0.031,0.031,0.0073,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
14190000,0.78,-0.017,0.00041,-0.63,-0.024,-0.013,-0.03,-8.4e-05,-0.0036,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0015,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.036,0.036,0.03,0.057,0.057,0.05,3.6e-06,4.1e-06,4.8e-06,0.031,0.031,0.0069,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
14290000,0.78,-0.017,0.00037,-0.63,-0.025,-0.015,-0.029,-0.0025,-0.0051,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0016,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.04,0.04,0.032,0.064,0.064,0.051,3.5e-06,3.9e-06,4.8e-06,0.031,0.031,0.0067,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
14390000,0.78,-0.017,0.00033,-0.63,-0.02,-0.015,-0.031,0.0017,-0.0037,-3.7e+02,-0.0011,-0.0059,-7.8e-05,0.0021,-0.065,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.034,0.034,0.031,0.053,0.053,0.05,3.4e-06,3.8e-06,4.8e-06,0.031,0.031,0.0063,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
14490000,0.78,-0.017,0.0004,-0.63,-0.022,-0.018,-0.034,-0.00071,-0.0054,-3.7e+02,-0.001,-0.0059,-7.9e-05,0.0022,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.037,0.037,0.032,0.06,0.06,0.051,3.3e-06,3.7e-06,4.8e-06,0.031,0.031,0.0062,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
14590000,0.78,-0.017,0.00048,-0.63,-0.023,-0.018,-0.034,-0.0013,-0.0052,-3.7e+02,-0.001,-0.0059,-8e-05,0.0021,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.032,0.032,0.031,0.051,0.051,0.051,3.2e-06,3.6e-06,4.8e-06,0.031,0.031,0.0058,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14690000,0.78,-0.017,0.0005,-0.63,-0.026,-0.017,-0.031,-0.0038,-0.0071,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0024,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.035,0.035,0.032,0.056,0.056,0.051,3.1e-06,3.5e-06,4.8e-06,0.031,0.031,0.0057,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14790000,0.78,-0.017,0.00051,-0.63,-0.025,-0.016,-0.027,-0.0038,-0.0066,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0023,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.03,0.03,0.031,0.049,0.049,0.051,3e-06,3.3e-06,4.8e-06,0.031,0.031,0.0053,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14890000,0.78,-0.017,0.00052,-0.63,-0.028,-0.019,-0.03,-0.0065,-0.0085,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0025,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.033,0.033,0.031,0.054,0.054,0.052,2.9e-06,3.3e-06,4.8e-06,0.031,0.031,0.0051,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14990000,0.78,-0.017,0.00057,-0.63,-0.026,-0.016,-0.026,-0.0049,-0.0065,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.029,0.029,0.03,0.047,0.047,0.051,2.8e-06,3.2e-06,4.8e-06,0.031,0.031,0.0048,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15090000,0.78,-0.017,0.00066,-0.63,-0.028,-0.017,-0.029,-0.0076,-0.0081,-3.7e+02,-0.00097,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.031,0.031,0.031,0.052,0.052,0.052,2.7e-06,3.1e-06,4.8e-06,0.031,0.031,0.0046,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15190000,0.78,-0.017,0.00069,-0.63,-0.026,-0.016,-0.026,-0.006,-0.0064,-3.7e+02,-0.00096,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.00041,0.046,0.027,0.028,0.03,0.046,0.046,0.052,2.6e-06,3e-06,4.8e-06,0.031,0.031,0.0043,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15290000,0.78,-0.017,0.00069,-0.63,-0.028,-0.018,-0.024,-0.0086,-0.0082,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0023,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.03,0.03,0.03,0.051,0.051,0.052,2.5e-06,2.9e-06,4.8e-06,0.031,0.031,0.0042,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15390000,0.78,-0.017,0.00064,-0.63,-0.027,-0.018,-0.022,-0.0082,-0.0083,-3.7e+02,-0.00099,-0.0059,-7.4e-05,0.0028,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.029,0.029,0.029,0.054,0.054,0.051,2.4e-06,2.8e-06,4.8e-06,0.031,0.031,0.0039,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15490000,0.78,-0.017,0.00066,-0.63,-0.03,-0.018,-0.022,-0.011,-0.0098,-3.7e+02,-0.00099,-0.0059,-7.6e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.031,0.031,0.029,0.06,0.06,0.053,2.4e-06,2.7e-06,4.8e-06,0.031,0.031,0.0037,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15590000,0.78,-0.017,0.0007,-0.63,-0.028,-0.017,-0.021,-0.01,-0.0091,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0022,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.029,0.03,0.028,0.062,0.062,0.052,2.3e-06,2.7e-06,4.8e-06,0.031,0.031,0.0035,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15690000,0.78,-0.017,0.00067,-0.63,-0.029,-0.017,-0.021,-0.013,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0021,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.032,0.032,0.028,0.069,0.069,0.052,2.2e-06,2.6e-06,4.8e-06,0.03,0.031,0.0033,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15790000,0.78,-0.017,0.00067,-0.63,-0.026,-0.016,-0.024,-0.009,-0.009,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.026,0.027,0.027,0.056,0.057,0.051,2.2e-06,2.5e-06,4.8e-06,0.03,0.031,0.0031,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
15890000,0.78,-0.017,0.00068,-0.63,-0.028,-0.017,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.028,0.029,0.027,0.063,0.063,0.052,2.1e-06,2.5e-06,4.8e-06,0.03,0.031,0.003,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
15990000,0.78,-0.017,0.00066,-0.63,-0.025,-0.017,-0.017,-0.0084,-0.0095,-3.7e+02,-0.001,-0.0059,-7.3e-05,0.0023,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.026,0.053,0.053,0.051,2e-06,2.4e-06,4.8e-06,0.03,0.031,0.0028,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
16090000,0.78,-0.017,0.00058,-0.63,-0.027,-0.019,-0.014,-0.011,-0.012,-3.7e+02,-0.0011,-0.0059,-7.1e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.026,0.026,0.025,0.058,0.058,0.052,2e-06,2.3e-06,4.8e-06,0.03,0.031,0.0027,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
16190000,0.78,-0.017,0.00056,-0.63,-0.025,-0.017,-0.013,-0.008,-0.009,-3.7e+02,-0.0011,-0.0059,-6.9e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.023,0.025,0.05,0.05,0.051,1.9e-06,2.3e-06,4.8e-06,0.03,0.031,0.0025,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
16290000,0.78,-0.017,0.00049,-0.63,-0.028,-0.019,-0.014,-0.011,-0.011,-3.7e+02,-0.0011,-0.0059,-6.7e-05,0.0031,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.024,0.055,0.055,0.052,1.9e-06,2.2e-06,4.8e-06,0.03,0.031,0.0024,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16390000,0.78,-0.017,0.00051,-0.63,-0.024,-0.015,-0.013,-0.0081,-0.0086,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.022,0.022,0.023,0.047,0.047,0.051,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16490000,0.78,-0.016,0.00047,-0.63,-0.024,-0.017,-0.016,-0.01,-0.01,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.024,0.023,0.052,0.052,0.052,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16590000,0.78,-0.016,0.00043,-0.63,-0.024,-0.013,-0.017,-0.01,-0.0062,-3.7e+02,-0.0011,-0.0059,-5.9e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.00095,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.021,0.022,0.046,0.046,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.002,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16690000,0.78,-0.016,0.00048,-0.63,-0.025,-0.014,-0.013,-0.013,-0.0073,-3.7e+02,-0.0011,-0.0059,-6.1e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.00096,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.022,0.023,0.022,0.05,0.051,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.0019,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16790000,0.78,-0.016,0.00052,-0.63,-0.024,-0.01,-0.012,-0.013,-0.004,-3.7e+02,-0.0011,-0.006,-5.6e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.0009,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.02,0.021,0.044,0.044,0.05,1.6e-06,2e-06,4.8e-06,0.03,0.031,0.0018,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16890000,0.78,-0.016,0.00051,-0.63,-0.025,-0.011,-0.0096,-0.015,-0.0049,-3.7e+02,-0.0011,-0.006,-5.7e-05,0.0027,-0.066,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.022,0.021,0.049,0.049,0.051,1.6e-06,1.9e-06,4.8e-06,0.03,0.031,0.0017,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16990000,0.78,-0.016,0.00055,-0.63,-0.024,-0.011,-0.0091,-0.014,-0.0048,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.019,0.02,0.02,0.043,0.043,0.05,1.5e-06,1.9e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17090000,0.78,-0.016,0.00054,-0.63,-0.025,-0.013,-0.009,-0.016,-0.0059,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.021,0.02,0.048,0.048,0.05,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17190000,0.78,-0.016,0.00048,-0.63,-0.024,-0.015,-0.0099,-0.014,-0.0062,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.019,0.042,0.043,0.049,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0015,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17290000,0.78,-0.016,0.00051,-0.63,-0.027,-0.017,-0.0054,-0.017,-0.0074,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0024,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.019,0.047,0.047,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0014,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17390000,0.78,-0.016,0.00044,-0.63,-0.024,-0.018,-0.0035,-0.014,-0.0076,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.018,0.018,0.042,0.042,0.048,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17490000,0.78,-0.016,0.00046,-0.63,-0.026,-0.019,-0.0018,-0.017,-0.0095,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.018,0.046,0.046,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17590000,0.78,-0.016,0.00047,-0.63,-0.024,-0.019,0.0036,-0.014,-0.0091,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.017,0.041,0.041,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17690000,0.78,-0.016,0.00049,-0.63,-0.026,-0.021,0.003,-0.017,-0.011,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.0027,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.019,0.017,0.045,0.045,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17790000,0.78,-0.016,0.00043,-0.63,-0.024,-0.022,0.0016,-0.015,-0.012,-3.7e+02,-0.0012,-0.0059,-4.8e-05,0.0031,-0.065,-0.13,-0.11,-0.024,0.5,-0.00088,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.016,0.048,0.048,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17890000,0.78,-0.016,0.00042,-0.63,-0.027,-0.023,0.0017,-0.018,-0.015,-3.7e+02,-0.0012,-0.0059,-4.6e-05,0.0033,-0.065,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.016,0.053,0.053,0.048,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17990000,0.78,-0.016,0.00045,-0.63,-0.026,-0.021,0.0029,-0.016,-0.015,-3.7e+02,-0.0012,-0.0059,-4.5e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00086,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.016,0.055,0.055,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.001,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1
18090000,0.78,-0.016,0.00049,-0.63,-0.027,-0.021,0.0053,-0.019,-0.016,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.021,0.021,0.016,0.06,0.061,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.00098,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1
18190000,0.78,-0.016,0.00049,-0.63,-0.024,-0.02,0.0066,-0.014,-0.013,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.015,0.051,0.051,0.047,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00093,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18290000,0.78,-0.016,0.00059,-0.63,-0.025,-0.02,0.0078,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.015,0.056,0.056,0.046,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00089,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18390000,0.78,-0.016,0.00055,-0.63,-0.024,-0.021,0.009,-0.013,-0.012,-3.7e+02,-0.0012,-0.006,-3.8e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.014,0.048,0.048,0.046,1.1e-06,1.4e-06,4.7e-06,0.03,0.03,0.00085,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18490000,0.78,-0.016,0.00051,-0.63,-0.024,-0.023,0.0086,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3.7e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.014,0.053,0.053,0.046,1.1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00082,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18590000,0.78,-0.016,0.00049,-0.63,-0.022,-0.022,0.0067,-0.012,-0.013,-3.7e+02,-0.0013,-0.0059,-2.8e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.016,0.017,0.014,0.046,0.046,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00078,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18690000,0.78,-0.016,0.00055,-0.63,-0.024,-0.023,0.0048,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3e-05,0.0033,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.013,0.05,0.05,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00076,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18790000,0.78,-0.016,0.00057,-0.63,-0.022,-0.021,0.0045,-0.012,-0.012,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.013,0.044,0.044,0.045,1e-06,1.2e-06,4.7e-06,0.03,0.03,0.00073,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18890000,0.78,-0.016,0.00048,-0.63,-0.022,-0.024,0.0051,-0.014,-0.015,-3.7e+02,-0.0013,-0.0059,-2.2e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.013,0.048,0.048,0.045,9.8e-07,1.2e-06,4.7e-06,0.03,0.03,0.0007,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18990000,0.78,-0.016,0.00042,-0.63,-0.019,-0.024,0.0037,-0.0098,-0.013,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.012,0.043,0.043,0.044,9.5e-07,1.2e-06,4.7e-06,0.03,0.03,0.00067,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19090000,0.78,-0.016,0.00041,-0.63,-0.019,-0.025,0.0067,-0.011,-0.015,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.012,0.046,0.047,0.044,9.4e-07,1.2e-06,4.7e-06,0.03,0.03,0.00065,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19190000,0.78,-0.016,0.00036,-0.63,-0.015,-0.024,0.0067,-0.0077,-0.013,-3.7e+02,-0.0013,-0.0059,-8.2e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00068,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.015,0.012,0.041,0.042,0.044,9.1e-07,1.2e-06,4.7e-06,0.03,0.03,0.00063,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19290000,0.78,-0.016,0.00037,-0.63,-0.016,-0.024,0.0094,-0.0095,-0.016,-3.7e+02,-0.0013,-0.006,-1.1e-05,0.0034,-0.065,-0.13,-0.11,-0.024,0.5,-0.00069,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.012,0.045,0.046,0.044,9e-07,1.1e-06,4.7e-06,0.03,0.03,0.00061,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19390000,0.78,-0.016,0.0004,-0.63,-0.015,-0.022,0.013,-0.0084,-0.014,-3.7e+02,-0.0013,-0.006,-2.4e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.012,0.04,0.041,0.043,8.8e-07,1.1e-06,4.6e-06,0.03,0.03,0.00058,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19490000,0.78,-0.016,0.00035,-0.63,-0.015,-0.024,0.0096,-0.01,-0.017,-3.7e+02,-0.0013,-0.0059,1.4e-06,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00064,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.044,0.045,0.043,8.6e-07,1.1e-06,4.6e-06,0.03,0.03,0.00057,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19590000,0.78,-0.015,0.0003,-0.63,-0.013,-0.022,0.0088,-0.0085,-0.015,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.0039,-0.065,-0.13,-0.11,-0.024,0.5,-0.0006,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.04,0.04,0.042,8.4e-07,1.1e-06,4.6e-06,0.03,0.03,0.00055,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19690000,0.78,-0.015,0.00028,-0.63,-0.014,-0.021,0.01,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00061,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.044,0.042,8.3e-07,1.1e-06,4.6e-06,0.03,0.03,0.00053,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19790000,0.78,-0.015,0.00024,-0.63,-0.012,-0.018,0.011,-0.0079,-0.015,-3.7e+02,-0.0013,-0.006,1.8e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00058,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.039,0.039,0.042,8.1e-07,1e-06,4.6e-06,0.03,0.03,0.00051,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19890000,0.78,-0.015,0.00028,-0.63,-0.011,-0.02,0.012,-0.0096,-0.017,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.004,-0.065,-0.13,-0.11,-0.024,0.5,-0.00056,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.043,0.042,8e-07,1e-06,4.6e-06,0.03,0.03,0.0005,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19990000,0.78,-0.016,0.00028,-0.63,-0.0096,-0.02,0.015,-0.0084,-0.016,-3.7e+02,-0.0013,-0.0059,3.9e-05,0.0043,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.039,0.039,0.041,7.7e-07,9.9e-07,4.6e-06,0.03,0.03,0.00048,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
20090000,0.78,-0.016,0.00023,-0.63,-0.0096,-0.02,0.015,-0.0091,-0.019,-3.7e+02,-0.0013,-0.0059,4.7e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.01,0.042,0.043,0.042,7.7e-07,9.8e-07,4.6e-06,0.03,0.03,0.00047,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
20190000,0.78,-0.016,0.00019,-0.63,-0.01,-0.019,0.017,-0.0092,-0.017,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00046,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.038,0.039,0.041,7.4e-07,9.5e-07,4.6e-06,0.03,0.03,0.00045,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20290000,0.78,-0.016,0.00019,-0.63,-0.0089,-0.019,0.015,-0.0096,-0.019,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00047,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0099,0.042,0.042,0.041,7.4e-07,9.4e-07,4.6e-06,0.03,0.03,0.00044,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20390000,0.78,-0.016,0.00024,-0.63,-0.0085,-0.016,0.017,-0.0095,-0.017,-3.7e+02,-0.0013,-0.0059,6.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0097,0.038,0.038,0.041,7.2e-07,9.2e-07,4.5e-06,0.03,0.03,0.00043,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20490000,0.78,-0.016,0.0002,-0.63,-0.0087,-0.016,0.017,-0.01,-0.018,-3.7e+02,-0.0013,-0.0059,6.5e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0096,0.041,0.042,0.041,7.1e-07,9.1e-07,4.5e-06,0.03,0.03,0.00042,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20590000,0.78,-0.016,0.0002,-0.63,-0.0081,-0.014,0.014,-0.0089,-0.016,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0093,0.038,0.038,0.04,6.9e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20690000,0.78,-0.016,0.00015,-0.63,-0.0089,-0.014,0.015,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,7.2e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0093,0.041,0.042,0.04,6.8e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20790000,0.78,-0.016,0.00013,-0.63,-0.0065,-0.013,0.016,-0.0082,-0.015,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0091,0.037,0.038,0.04,6.6e-07,8.5e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20890000,0.78,-0.016,0.00011,-0.63,-0.0067,-0.013,0.015,-0.0088,-0.017,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.009,0.041,0.041,0.04,6.6e-07,8.4e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20990000,0.78,-0.016,9.5e-05,-0.63,-0.0051,-0.011,0.015,-0.0084,-0.018,-3.7e+02,-0.0013,-0.0059,9e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00038,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0088,0.043,0.044,0.039,6.4e-07,8.3e-07,4.4e-06,0.03,0.03,0.00037,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21090000,0.78,-0.016,8.8e-05,-0.63,-0.0062,-0.011,0.016,-0.0094,-0.019,-3.7e+02,-0.0013,-0.0059,9.3e-05,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00037,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0088,0.047,0.048,0.039,6.4e-07,8.2e-07,4.4e-06,0.03,0.03,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21190000,0.78,-0.016,8.4e-05,-0.63,-0.0063,-0.011,0.015,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,9.4e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00036,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0086,0.049,0.05,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00035,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21290000,0.78,-0.016,-6.5e-06,-0.63,-0.0059,-0.011,0.017,-0.0099,-0.021,-3.7e+02,-0.0013,-0.0059,0.0001,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00035,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0085,0.054,0.055,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00034,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21390000,0.78,-0.016,4.3e-05,-0.63,-0.0052,-0.0064,0.016,-0.0087,-0.016,-3.7e+02,-0.0013,-0.0059,0.00011,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0084,0.046,0.047,0.039,6e-07,7.7e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21490000,0.78,-0.016,3.3e-05,-0.63,-0.0059,-0.0073,0.016,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,0.00011,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0083,0.05,0.052,0.038,5.9e-07,7.6e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21590000,0.78,-0.016,7.2e-05,-0.63,-0.0045,-0.0056,0.016,-0.0082,-0.013,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00029,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0081,0.044,0.045,0.038,5.8e-07,7.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21690000,0.78,-0.016,6.5e-05,-0.63,-0.0061,-0.0065,0.017,-0.0095,-0.015,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0081,0.048,0.049,0.038,5.7e-07,7.4e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21790000,0.78,-0.016,0.00016,-0.63,-0.0051,-0.0043,0.016,-0.0083,-0.0092,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.008,0.042,0.043,0.038,5.6e-07,7.1e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21890000,0.78,-0.015,0.00016,-0.63,-0.0058,-0.005,0.016,-0.009,-0.0097,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0079,0.046,0.047,0.038,5.5e-07,7.1e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21990000,0.78,-0.015,0.00019,-0.63,-0.0057,-0.0022,0.017,-0.0084,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0078,0.041,0.042,0.038,5.4e-07,6.9e-07,4.3e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
22090000,0.78,-0.015,0.00018,-0.63,-0.0054,-0.0037,0.015,-0.0088,-0.006,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0078,0.045,0.046,0.037,5.4e-07,6.9e-07,4.2e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
22190000,0.78,-0.015,0.00019,-0.63,-0.004,-0.0043,0.016,-0.0073,-0.0054,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0076,0.04,0.041,0.037,5.2e-07,6.7e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
22290000,0.78,-0.015,0.00016,-0.63,-0.0036,-0.0039,0.016,-0.008,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0076,0.043,0.045,0.037,5.2e-07,6.6e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
22390000,0.78,-0.015,0.00015,-0.63,-0.0011,-0.0039,0.017,-0.0062,-0.0051,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.012,0.014,0.0075,0.039,0.04,0.037,5.1e-07,6.5e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22490000,0.78,-0.015,0.00013,-0.63,7e-05,-0.0045,0.018,-0.0056,-0.0054,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0074,0.042,0.044,0.037,5e-07,6.4e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22590000,0.78,-0.015,0.00013,-0.63,0.0019,-0.0034,0.018,-0.0039,-0.0047,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0073,0.045,0.046,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22690000,0.78,-0.015,6.1e-05,-0.63,0.0035,-0.0046,0.019,-0.0032,-0.0056,-3.7e+02,-0.0014,-0.0059,0.00016,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0073,0.048,0.05,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22790000,0.78,-0.015,0.0001,-0.63,0.0045,-0.004,0.02,-0.0026,-0.0042,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0072,0.051,0.052,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22890000,0.78,-0.015,0.00011,-0.63,0.0052,-0.0049,0.021,-0.0028,-0.0048,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0072,0.055,0.057,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22990000,0.78,-0.015,0.00012,-0.63,0.0049,-0.0049,0.022,-0.0029,-0.0055,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0071,0.058,0.06,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23090000,0.78,-0.015,0.00018,-0.63,0.0051,-0.0046,0.023,-0.0027,-0.0052,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.007,0.062,0.065,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23190000,0.78,-0.015,0.00017,-0.63,0.0027,-0.0034,0.024,-0.0055,-0.005,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0069,0.065,0.067,0.035,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23290000,0.78,-0.015,0.00023,-0.63,0.0023,-0.0031,0.025,-0.0058,-0.0057,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.017,0.019,0.0069,0.07,0.073,0.036,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23390000,0.78,-0.015,0.00021,-0.63,-0.0011,-0.0028,0.022,-0.01,-0.0058,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.0068,0.072,0.075,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23490000,0.78,-0.013,-0.0019,-0.63,0.0044,-0.0021,-0.011,-0.011,-0.007,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00014,-0.091,-0.068,0,0,0.00036,0.00036,0.046,0.017,0.019,0.0068,0.078,0.081,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23590000,0.78,-0.0042,-0.0062,-0.63,0.015,0.0017,-0.043,-0.0099,-0.0038,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.066,-0.13,-0.11,-0.024,0.5,-0.00012,-0.091,-0.068,0,0,0.00035,0.00034,0.046,0.014,0.016,0.0067,0.062,0.064,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23690000,0.78,0.0014,-0.0052,-0.63,0.042,0.016,-0.093,-0.0075,-0.0033,-3.7e+02,-0.0013,-0.0059,0.00018,0.0046,-0.066,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00034,0.00034,0.046,0.015,0.017,0.0067,0.067,0.069,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23790000,0.78,-0.0022,-0.0027,-0.63,0.063,0.033,-0.15,-0.0074,-0.0017,-3.7e+02,-0.0013,-0.0059,0.00018,0.0049,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.014,0.015,0.0066,0.055,0.056,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23890000,0.78,-0.0085,-0.0007,-0.63,0.077,0.045,-0.2,2.8e-05,0.0023,-3.7e+02,-0.0013,-0.0059,0.00019,0.005,-0.066,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00034,0.00035,0.046,0.014,0.016,0.0066,0.059,0.061,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23990000,0.78,-0.013,0.00021,-0.63,0.072,0.045,-0.25,-0.0055,0.00083,-3.7e+02,-0.0013,-0.0059,0.00018,0.0052,-0.067,-0.13,-0.11,-0.024,0.5,-0.00029,-0.09,-0.067,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0066,0.062,0.063,0.035,4.1e-07,5.2e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
24090000,0.78,-0.012,-0.00093,-0.63,0.072,0.044,-0.3,0.00081,0.0045,-3.7e+02,-0.0013,-0.0059,0.00019,0.0053,-0.067,-0.13,-0.11,-0.024,0.5,-0.00034,-0.09,-0.067,0,0,0.00035,0.00036,0.046,0.015,0.017,0.0065,0.066,0.069,0.035,4.1e-07,5.2e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
24190000,0.78,-0.0097,-0.0017,-0.63,0.069,0.043,-0.35,-0.0065,0.0022,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00031,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.015,0.017,0.0065,0.069,0.071,0.034,4.1e-07,5.1e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24290000,0.78,-0.0089,-0.0021,-0.63,0.077,0.048,-0.4,-0.00011,0.0069,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0065,0.074,0.077,0.034,4e-07,5.1e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24390000,0.78,-0.0093,-0.0022,-0.63,0.074,0.047,-0.46,-0.013,0.00027,-3.7e+02,-0.0012,-0.0059,0.00015,0.0062,-0.069,-0.13,-0.11,-0.024,0.5,-0.0003,-0.089,-0.068,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0064,0.076,0.079,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24490000,0.78,-0.0051,-0.0026,-0.63,0.085,0.054,-0.51,-0.0046,0.0052,-3.7e+02,-0.0012,-0.0059,0.00015,0.0063,-0.069,-0.13,-0.11,-0.024,0.5,-0.00033,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.02,0.0064,0.082,0.085,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24590000,0.78,-0.0016,-0.0027,-0.63,0.089,0.057,-0.56,-0.018,-0.0039,-3.7e+02,-0.0012,-0.0059,0.00014,0.0069,-0.071,-0.13,-0.11,-0.024,0.5,-0.00037,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.019,0.0063,0.084,0.088,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24690000,0.78,-0.00074,-0.0027,-0.63,0.11,0.073,-0.64,-0.0089,0.0014,-3.7e+02,-0.0012,-0.0059,0.00015,0.0072,-0.071,-0.13,-0.11,-0.024,0.5,-0.00055,-0.089,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0063,0.09,0.094,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24790000,0.78,-0.0023,-0.0024,-0.63,0.11,0.082,-0.73,-0.028,-0.0034,-3.7e+02,-0.0012,-0.0059,0.00013,0.0079,-0.073,-0.13,-0.11,-0.025,0.5,-0.00036,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0062,0.093,0.096,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1
24890000,0.78,-0.00046,-0.004,-0.63,0.13,0.097,-0.75,-0.017,0.0055,-3.7e+02,-0.0012,-0.0059,0.00012,0.0081,-0.074,-0.13,-0.11,-0.025,0.5,-0.00045,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.099,0.1,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00062,0.0012,0.0012,1,1
24990000,0.78,0.0012,-0.0055,-0.63,0.13,0.1,-0.81,-0.039,-0.001,-3.7e+02,-0.0011,-0.0059,9e-05,0.0092,-0.076,-0.13,-0.11,-0.025,0.5,-0.00024,-0.087,-0.069,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.1,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1
25090000,0.78,0.00063,-0.0059,-0.63,0.16,0.12,-0.86,-0.025,0.011,-3.7e+02,-0.0011,-0.0059,8.4e-05,0.0094,-0.076,-0.13,-0.11,-0.025,0.5,-0.00025,-0.087,-0.068,0,0,0.00034,0.00034,0.044,0.02,0.023,0.0062,0.11,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0011,0.0012,1,1
25190000,0.78,-0.0015,-0.0054,-0.62,0.15,0.11,-0.91,-0.069,-0.012,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00022,-0.086,-0.069,0,0,0.00034,0.00033,0.044,0.02,0.023,0.0061,0.11,0.11,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1
25290000,0.78,0.0055,-0.0066,-0.62,0.17,0.13,-0.96,-0.053,-0.00075,-3.7e+02,-0.0011,-0.0059,4.8e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00034,-0.086,-0.069,0,0,0.00033,0.00034,0.044,0.021,0.024,0.0061,0.12,0.12,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.0006,0.0011,0.0012,1,1
25390000,0.78,0.011,-0.0071,-0.62,0.18,0.13,-1,-0.1,-0.025,-3.7e+02,-0.001,-0.0058,8.1e-06,0.014,-0.086,-0.13,-0.11,-0.025,0.5,-0.00037,-0.085,-0.069,0,0,0.00033,0.00036,0.043,0.021,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.00059,0.0011,0.0012,1,1
25490000,0.78,0.013,-0.0072,-0.63,0.22,0.16,-1.1,-0.082,-0.012,-3.7e+02,-0.001,-0.0058,2.3e-05,0.014,-0.087,-0.13,-0.11,-0.025,0.5,-0.00072,-0.084,-0.069,0,0,0.00033,0.00036,0.042,0.022,0.026,0.0061,0.13,0.13,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0012,0.00058,0.0011,0.0012,1,1
25590000,0.78,0.011,-0.007,-0.63,0.25,0.19,-1.1,-0.059,0.0041,-3.7e+02,-0.001,-0.0058,3.2e-05,0.014,-0.087,-0.13,-0.12,-0.025,0.5,-0.00098,-0.084,-0.068,0,0,0.00033,0.00035,0.042,0.024,0.028,0.0061,0.14,0.14,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0011,0.00058,0.0011,0.0011,1,1
25690000,0.78,0.018,-0.0099,-0.63,0.29,0.21,-1.2,-0.032,0.022,-3.7e+02,-0.001,-0.0058,4.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0013,-0.082,-0.068,0,0,0.00034,0.00039,0.042,0.025,0.03,0.0061,0.14,0.15,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00017,0.001,5.2e-05,0.0011,0.00057,0.0011,0.0011,1,1
25790000,0.78,0.024,-0.012,-0.63,0.35,0.25,-1.2,-0.00023,0.043,-3.7e+02,-0.00099,-0.0058,6.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0019,-0.081,-0.067,0,0,0.00034,0.00043,0.041,0.027,0.033,0.0061,0.15,0.16,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5.1e-05,0.0011,0.00057,0.0011,0.0011,1,1
25890000,0.77,0.025,-0.012,-0.63,0.41,0.28,-1.3,0.039,0.066,-3.7e+02,-0.00099,-0.0058,8.6e-05,0.015,-0.089,-0.13,-0.12,-0.026,0.5,-0.0025,-0.079,-0.066,0,0,0.00034,0.00043,0.04,0.029,0.037,0.0061,0.17,0.17,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5e-05,0.0011,0.00056,0.0011,0.0011,1,1
25990000,0.77,0.021,-0.012,-0.63,0.47,0.31,-1.3,0.083,0.093,-3.7e+02,-0.00099,-0.0058,9.9e-05,0.015,-0.089,-0.13,-0.12,-0.027,0.5,-0.0029,-0.078,-0.065,0,0,0.00034,0.00041,0.04,0.032,0.04,0.0061,0.18,0.19,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00099,5e-05,0.0011,0.00055,0.001,0.0011,1,1
26090000,0.78,0.032,-0.016,-0.63,0.52,0.35,-1.3,0.13,0.13,-3.7e+02,-0.00098,-0.0058,8.8e-05,0.016,-0.089,-0.13,-0.12,-0.027,0.5,-0.0028,-0.077,-0.065,0,0,0.00035,0.00049,0.039,0.034,0.043,0.0061,0.19,0.2,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00097,4.8e-05,0.0011,0.00054,0.001,0.0011,1,1
26190000,0.78,0.041,-0.017,-0.63,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,9.6e-05,0.018,-0.09,-0.13,-0.13,-0.028,0.5,-0.0035,-0.074,-0.063,0,0,0.00036,0.00058,0.037,0.036,0.047,0.0061,0.2,0.22,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00093,4.7e-05,0.001,0.00053,0.00098,0.001,1,1
26290000,0.78,0.044,-0.018,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,9.2e-05,0.019,-0.091,-0.13,-0.13,-0.028,0.49,-0.0037,-0.071,-0.061,0,0,0.00036,0.0006,0.036,0.039,0.052,0.0061,0.21,0.23,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00091,4.6e-05,0.001,0.00052,0.00094,0.001,1,1
26390000,0.77,0.04,-0.018,-0.63,0.76,0.5,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,0.0001,0.02,-0.091,-0.13,-0.13,-0.028,0.49,-0.0042,-0.069,-0.06,0,0,0.00036,0.00055,0.034,0.042,0.056,0.0061,0.23,0.25,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00088,4.4e-05,0.00098,0.0005,0.00091,0.00097,1,1
26490000,0.77,0.056,-0.024,-0.63,0.84,0.55,-1.3,0.4,0.3,-3.7e+02,-0.00096,-0.0058,0.0001,0.02,-0.092,-0.13,-0.13,-0.029,0.49,-0.0043,-0.067,-0.058,0,0,0.00038,0.00075,0.033,0.044,0.061,0.0061,0.24,0.27,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00084,4.2e-05,0.00094,0.00048,0.00088,0.00094,1,1
26590000,0.77,0.073,-0.029,-0.63,0.95,0.63,-1.3,0.48,0.36,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.023,-0.092,-0.13,-0.13,-0.03,0.49,-0.0039,-0.064,-0.057,0,0,0.00041,0.00098,0.031,0.048,0.067,0.0061,0.26,0.29,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0008,4e-05,0.00089,0.00046,0.00083,0.00089,1,1
26690000,0.77,0.076,-0.03,-0.64,1.1,0.71,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.024,-0.093,-0.13,-0.14,-0.031,0.49,-0.0049,-0.059,-0.052,0,0,0.00041,0.00097,0.028,0.052,0.073,0.0061,0.28,0.31,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00074,3.8e-05,0.00083,0.00044,0.00077,0.00083,1,1
26790000,0.77,0.07,-0.029,-0.64,1.2,0.79,-1.3,0.7,0.5,-3.7e+02,-0.00095,-0.0058,6.9e-05,0.025,-0.093,-0.13,-0.14,-0.032,0.48,-0.0047,-0.055,-0.049,0,0,0.00039,0.00084,0.026,0.055,0.079,0.0061,0.3,0.33,0.033,3.7e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0007,3.6e-05,0.00079,0.00041,0.00073,0.00078,1,1
26890000,0.76,0.093,-0.036,-0.64,1.3,0.86,-1.3,0.83,0.58,-3.7e+02,-0.00095,-0.0058,7.2e-05,0.026,-0.093,-0.13,-0.15,-0.032,0.48,-0.0052,-0.052,-0.047,0,0,0.00044,0.0011,0.024,0.058,0.085,0.0061,0.32,0.35,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00066,3.4e-05,0.00074,0.00039,0.00068,0.00074,1,1
26990000,0.76,0.12,-0.041,-0.64,1.5,0.97,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,6.1e-05,0.029,-0.094,-0.13,-0.15,-0.034,0.48,-0.0055,-0.046,-0.043,0,0,0.00049,0.0014,0.021,0.061,0.091,0.0061,0.34,0.37,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.0006,3.1e-05,0.00067,0.00036,0.00062,0.00067,1,1
27090000,0.76,0.12,-0.041,-0.64,1.7,1.1,-1.2,1.1,0.78,-3.7e+02,-0.00095,-0.0058,4.5e-05,0.03,-0.093,-0.13,-0.16,-0.035,0.47,-0.0055,-0.041,-0.038,0,0,0.00049,0.0013,0.018,0.065,0.098,0.0061,0.36,0.4,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00055,2.8e-05,0.0006,0.00033,0.00056,0.0006,1,1
27190000,0.76,0.11,-0.039,-0.64,1.9,1.2,-1.2,1.3,0.9,-3.7e+02,-0.00096,-0.0058,2.8e-05,0.032,-0.092,-0.13,-0.16,-0.035,0.47,-0.0053,-0.038,-0.035,0,0,0.00045,0.0011,0.017,0.068,0.1,0.0062,0.38,0.43,0.034,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00051,2.6e-05,0.00056,0.00031,0.00052,0.00056,1,1
27290000,0.76,0.093,-0.035,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,2.2e-05,0.032,-0.091,-0.13,-0.16,-0.036,0.47,-0.0054,-0.035,-0.033,0,0,0.00041,0.00083,0.015,0.07,0.11,0.0062,0.4,0.46,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00048,2.5e-05,0.00053,0.00029,0.00049,0.00052,1,1
27390000,0.76,0.077,-0.03,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00095,-0.0058,1.7e-05,0.033,-0.089,-0.13,-0.17,-0.036,0.47,-0.0054,-0.033,-0.032,0,0,0.00038,0.00064,0.014,0.071,0.11,0.0062,0.43,0.49,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00046,2.4e-05,0.00051,0.00027,0.00047,0.00051,1,1
27490000,0.76,0.061,-0.025,-0.64,2.2,1.4,-1.2,1.9,1.3,-3.7e+02,-0.00095,-0.0058,9e-06,0.033,-0.087,-0.13,-0.17,-0.037,0.47,-0.0052,-0.032,-0.032,0,0,0.00036,0.00052,0.012,0.072,0.11,0.0062,0.46,0.52,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00044,2.3e-05,0.0005,0.00025,0.00046,0.0005,1,1
27590000,0.77,0.049,-0.022,-0.64,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,-8.8e-07,0.034,-0.084,-0.13,-0.17,-0.037,0.47,-0.0048,-0.031,-0.031,0,0,0.00035,0.00045,0.012,0.073,0.11,0.0062,0.48,0.55,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.3e-05,0.00049,0.00024,0.00045,0.00049,1,1
27690000,0.77,0.047,-0.021,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,-9.9e-06,0.034,-0.083,-0.13,-0.17,-0.037,0.47,-0.0044,-0.031,-0.031,0,0,0.00035,0.00044,0.011,0.073,0.11,0.0063,0.51,0.59,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.2e-05,0.00049,0.00023,0.00045,0.00049,1,1
27790000,0.77,0.049,-0.021,-0.64,2.3,1.5,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,-2.3e-05,0.035,-0.081,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.031,0,0,0.00035,0.00044,0.0098,0.074,0.1,0.0063,0.54,0.62,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00042,2.2e-05,0.00049,0.00022,0.00044,0.00048,1,1
27890000,0.77,0.047,-0.021,-0.64,2.4,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,-2.4e-05,0.034,-0.079,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00043,0.0093,0.075,0.1,0.0063,0.58,0.66,0.034,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00041,2.2e-05,0.00048,0.00022,0.00044,0.00048,1,1
27990000,0.77,0.043,-0.02,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,-2.7e-05,0.034,-0.078,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00041,0.0087,0.076,0.1,0.0064,0.61,0.7,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00041,2.1e-05,0.00048,0.00021,0.00043,0.00048,1,1
28090000,0.77,0.057,-0.025,-0.64,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,-3.8e-05,0.035,-0.076,-0.13,-0.17,-0.038,0.47,-0.0035,-0.029,-0.03,0,0,0.00035,0.00045,0.0081,0.077,0.1,0.0064,0.65,0.74,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.0004,2.1e-05,0.00048,0.00021,0.00042,0.00048,1,1
28190000,0.77,0.071,-0.028,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,-4e-05,0.035,-0.074,-0.13,-0.17,-0.038,0.46,-0.0035,-0.029,-0.03,0,0,0.00036,0.00049,0.0077,0.078,0.1,0.0065,0.68,0.79,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00039,2.1e-05,0.00047,0.0002,0.00042,0.00047,1,1
28290000,0.77,0.053,-0.022,-0.64,2.5,1.7,-0.065,3.8,2.6,-3.7e+02,-0.00095,-0.0058,-4.9e-05,0.035,-0.071,-0.13,-0.17,-0.038,0.46,-0.0033,-0.028,-0.029,0,0,0.00035,0.00043,0.0074,0.077,0.1,0.0066,0.72,0.83,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.0002,0.00041,0.00046,1,1
28390000,0.77,0.02,-0.0094,-0.64,2.5,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,-5.7e-05,0.035,-0.068,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00035,0.00037,0.0071,0.076,0.1,0.0066,0.76,0.88,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1
28490000,0.77,0.0014,-0.0026,-0.64,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,-6.3e-05,0.035,-0.065,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0068,0.077,0.099,0.0067,0.8,0.93,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1
28590000,0.77,-0.0022,-0.0011,-0.64,2.4,1.6,0.99,4.5,3.1,-3.7e+02,-0.00096,-0.0058,-6.4e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0065,0.077,0.098,0.0067,0.84,0.98,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1
28690000,0.77,-0.0032,-0.00057,-0.64,2.3,1.6,0.99,4.8,3.3,-3.7e+02,-0.00097,-0.0058,-7.1e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.003,-0.027,-0.029,0,0,0.00034,0.00036,0.0063,0.078,0.098,0.0067,0.88,1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00018,0.0004,0.00046,1,1
28790000,0.77,-0.0034,-0.00035,-0.63,2.2,1.6,1,5,3.4,-3.7e+02,-0.00098,-0.0058,-7.9e-05,0.034,-0.061,-0.12,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00034,0.00037,0.0061,0.079,0.098,0.0068,0.92,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
28890000,0.77,-0.0032,-0.00036,-0.63,2.2,1.5,0.99,5.2,3.6,-3.7e+02,-0.00099,-0.0058,-8.6e-05,0.033,-0.06,-0.12,-0.17,-0.038,0.46,-0.0028,-0.027,-0.029,0,0,0.00034,0.00037,0.0059,0.08,0.1,0.0068,0.97,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
28990000,0.77,-0.0027,-0.00054,-0.63,2.1,1.5,0.98,5.5,3.8,-3.7e+02,-0.001,-0.0058,-9.8e-05,0.033,-0.058,-0.12,-0.17,-0.038,0.46,-0.0026,-0.027,-0.028,0,0,0.00034,0.00037,0.0057,0.081,0.1,0.0069,1,1.2,0.034,3.6e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
29090000,0.78,-0.0022,-0.0007,-0.63,2.1,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.056,-0.12,-0.17,-0.038,0.46,-0.0025,-0.027,-0.028,0,0,0.00034,0.00037,0.0055,0.083,0.1,0.0069,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00037,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
29190000,0.77,-0.0019,-0.00078,-0.63,2,1.5,0.97,5.9,4.1,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.055,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.028,0,0,0.00034,0.00037,0.0054,0.084,0.1,0.007,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1
29290000,0.78,-0.00093,-0.0011,-0.63,1.9,1.4,1,6.1,4.2,-3.7e+02,-0.001,-0.0058,-0.00011,0.031,-0.053,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.028,0,0,0.00033,0.00037,0.0053,0.086,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00044,1,1
29390000,0.78,0.00051,-0.0014,-0.63,1.9,1.4,1,6.3,4.4,-3.7e+02,-0.001,-0.0058,-0.00012,0.03,-0.051,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.0051,0.087,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29490000,0.78,0.0017,-0.0018,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,-0.00013,0.03,-0.05,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.005,0.089,0.11,0.0071,1.3,1.5,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29590000,0.78,0.0028,-0.002,-0.63,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,-0.00013,0.028,-0.048,-0.12,-0.17,-0.038,0.46,-0.002,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.091,0.12,0.0071,1.3,1.6,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29690000,0.78,0.0036,-0.0023,-0.63,1.8,1.4,0.99,6.8,4.8,-3.7e+02,-0.001,-0.0058,-0.00014,0.028,-0.045,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.093,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29790000,0.78,0.0041,-0.0025,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0058,-0.00014,0.027,-0.042,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0048,0.095,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29890000,0.78,0.0045,-0.0026,-0.63,1.7,1.3,0.97,7.2,5.1,-3.7e+02,-0.001,-0.0058,-0.00015,0.026,-0.038,-0.12,-0.17,-0.038,0.46,-0.0017,-0.028,-0.028,0,0,0.00033,0.00038,0.0047,0.097,0.13,0.0072,1.5,1.8,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1
29990000,0.78,0.0046,-0.0027,-0.63,1.7,1.3,0.95,7.3,5.2,-3.7e+02,-0.001,-0.0058,-0.00015,0.025,-0.035,-0.12,-0.17,-0.038,0.46,-0.0016,-0.028,-0.028,0,0,0.00033,0.00038,0.0046,0.099,0.13,0.0072,1.6,1.9,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1
30090000,0.78,0.0046,-0.0027,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0058,-0.00016,0.024,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0046,0.1,0.14,0.0072,1.6,2,0.034,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
30190000,0.78,0.0043,-0.0026,-0.63,1.6,1.3,0.93,7.7,5.5,-3.7e+02,-0.001,-0.0058,-0.00016,0.023,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0045,0.1,0.14,0.0072,1.7,2.1,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
30290000,0.78,0.0042,-0.0026,-0.63,1.5,1.3,0.92,7.8,5.6,-3.7e+02,-0.0011,-0.0058,-0.00016,0.022,-0.031,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.028,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.2,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
30390000,0.78,0.0041,-0.0026,-0.63,1.5,1.2,0.9,8,5.7,-3.7e+02,-0.0011,-0.0058,-0.00017,0.021,-0.028,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.3,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30490000,0.78,0.0039,-0.0025,-0.63,1.5,1.2,0.89,8.2,5.8,-3.7e+02,-0.0011,-0.0058,-0.00017,0.02,-0.026,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.16,0.0072,1.9,2.4,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30590000,0.78,0.0036,-0.0025,-0.63,1.5,1.2,0.85,8.3,6,-3.7e+02,-0.0011,-0.0058,-0.00017,0.019,-0.022,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0043,0.11,0.16,0.0072,2,2.5,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30690000,0.78,0.0034,-0.0024,-0.63,1.4,1.2,0.84,8.5,6.1,-3.7e+02,-0.0011,-0.0058,-0.00017,0.018,-0.019,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00039,0.0043,0.11,0.17,0.0072,2.1,2.6,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30790000,0.78,0.0031,-0.0023,-0.63,1.4,1.2,0.83,8.6,6.2,-3.7e+02,-0.0011,-0.0058,-0.00017,0.017,-0.018,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.8,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30890000,0.78,0.0027,-0.0022,-0.63,1.4,1.2,0.82,8.8,6.3,-3.7e+02,-0.0011,-0.0058,-0.00018,0.016,-0.016,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.9,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30990000,0.78,0.0023,-0.0022,-0.63,1.3,1.2,0.81,8.9,6.4,-3.7e+02,-0.0011,-0.0058,-0.00018,0.015,-0.012,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.19,0.0072,2.3,3,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
31090000,0.78,0.0019,-0.0021,-0.63,1.3,1.1,0.8,9,6.6,-3.7e+02,-0.0011,-0.0058,-0.00018,0.014,-0.0094,-0.12,-0.17,-0.038,0.46,-0.00097,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.12,0.2,0.0072,2.4,3.2,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
31190000,0.78,0.0016,-0.002,-0.63,1.3,1.1,0.79,9.2,6.7,-3.7e+02,-0.0011,-0.0058,-0.00019,0.012,-0.0056,-0.12,-0.17,-0.038,0.46,-0.00088,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.2,0.0072,2.5,3.3,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
31290000,0.78,0.0012,-0.0018,-0.63,1.2,1.1,0.79,9.3,6.8,-3.7e+02,-0.0011,-0.0058,-0.00019,0.011,-0.0028,-0.12,-0.17,-0.038,0.46,-0.00081,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.21,0.0071,2.6,3.5,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
31390000,0.78,0.00059,-0.0016,-0.63,1.2,1.1,0.79,9.4,6.9,-3.7e+02,-0.0011,-0.0058,-0.00019,0.0099,0.0002,-0.12,-0.17,-0.038,0.46,-0.00074,-0.029,-0.027,0,0,0.0003,0.0004,0.0041,0.13,0.22,0.0071,2.7,3.6,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1
31490000,0.78,8.5e-05,-0.0015,-0.63,1.2,1.1,0.79,9.5,7,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0086,0.0029,-0.12,-0.17,-0.038,0.46,-0.00061,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.23,0.0071,2.8,3.8,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1
31590000,0.78,-0.00021,-0.0014,-0.63,1.1,1.1,0.78,9.7,7.1,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0073,0.005,-0.11,-0.17,-0.038,0.46,-0.00056,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.0071,2.9,3.9,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.0001,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1
31690000,0.78,-0.00082,-0.0013,-0.63,1.1,1.1,0.79,9.8,7.2,-3.7e+02,-0.0011,-0.0058,-0.0002,0.006,0.0077,-0.11,-0.17,-0.038,0.46,-0.00049,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.007,3,4.1,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
31790000,0.78,-0.0014,-0.0011,-0.63,1.1,1,0.79,9.9,7.3,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0047,0.011,-0.11,-0.17,-0.038,0.46,-0.00042,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.25,0.007,3.1,4.3,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
31890000,0.78,-0.002,-0.001,-0.63,1.1,1,0.78,10,7.4,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0033,0.014,-0.11,-0.17,-0.038,0.46,-0.00033,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.15,0.26,0.007,3.2,4.5,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
31990000,0.78,-0.0024,-0.0009,-0.63,1,1,0.78,10,7.6,-3.7e+02,-0.0011,-0.0058,-0.00021,0.0018,0.017,-0.11,-0.17,-0.038,0.46,-0.00022,-0.029,-0.027,0,0,0.00029,0.00041,0.004,0.15,0.27,0.007,3.3,4.7,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32090000,0.78,-0.003,-0.0007,-0.63,1,0.99,0.79,10,7.7,-3.7e+02,-0.0012,-0.0058,-0.00021,0.00019,0.02,-0.11,-0.17,-0.038,0.46,-0.00011,-0.029,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.28,0.007,3.5,4.9,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32190000,0.78,-0.0038,-0.00051,-0.63,0.97,0.98,0.78,10,7.8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0015,0.024,-0.11,-0.18,-0.038,0.46,3.2e-05,-0.03,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.29,0.0069,3.6,5.1,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.9e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32290000,0.78,-0.0044,-0.00042,-0.63,0.94,0.96,0.78,11,7.9,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0032,0.028,-0.11,-0.18,-0.038,0.46,0.00014,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.3,0.0069,3.7,5.4,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.8e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32390000,0.78,-0.0049,-0.00032,-0.63,0.91,0.94,0.78,11,8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0041,0.03,-0.11,-0.18,-0.038,0.46,0.00019,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.31,0.0069,3.8,5.6,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32490000,0.78,-0.0051,-0.00027,-0.63,0.88,0.92,0.78,11,8.1,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0056,0.032,-0.11,-0.18,-0.038,0.46,0.00028,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.16,0.32,0.0068,4,5.8,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1
32590000,0.78,-0.0053,-0.00021,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0064,0.033,-0.11,-0.18,-0.038,0.46,0.00034,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.56,0.25,0.25,0.037,3e-07,5.1e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1
32690000,0.78,-0.0053,-0.00025,-0.63,-1.6,-0.85,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0073,0.035,-0.11,-0.18,-0.038,0.46,0.00041,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.55,0.26,0.26,0.048,2.9e-07,5.1e-07,3.2e-06,0.029,0.023,9.5e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
32790000,0.78,-0.0052,-0.00026,-0.63,-1.5,-0.83,0.62,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0081,0.036,-0.11,-0.18,-0.038,0.46,0.00047,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.27,0.26,0.26,0.049,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
32890000,0.78,-0.005,-0.00039,-0.63,-1.6,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0089,0.038,-0.11,-0.18,-0.038,0.46,0.00057,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.26,0.27,0.27,0.059,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
32990000,0.78,-0.0049,-0.0005,-0.63,-1.5,-0.84,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0098,0.04,-0.11,-0.18,-0.038,0.46,0.00059,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.085,0.17,0.27,0.27,0.057,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33090000,0.78,-0.005,-0.00048,-0.63,-1.6,-0.86,0.58,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.038,0.46,0.00061,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.086,0.16,0.28,0.28,0.065,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33190000,0.78,-0.0036,-0.0037,-0.62,-1.5,-0.84,0.53,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.01,0.041,-0.11,-0.18,-0.038,0.46,0.0006,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.063,0.065,0.11,0.28,0.28,0.062,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33290000,0.82,-0.0015,-0.016,-0.57,-1.5,-0.86,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.039,0.46,0.00058,-0.03,-0.025,0,0,0.00027,0.00042,0.0038,0.064,0.066,0.11,0.29,0.29,0.067,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00035,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33390000,0.89,-0.0018,-0.013,-0.46,-1.5,-0.85,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.015,0.038,-0.11,-0.18,-0.039,0.46,0.0012,-0.028,-0.025,0,0,0.00028,0.0004,0.0037,0.051,0.053,0.083,0.29,0.29,0.065,2.9e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00033,1.7e-05,0.00041,0.00015,0.00035,0.00041,1,1
33490000,0.95,-0.00026,-0.0052,-0.31,-1.5,-0.86,0.72,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.018,0.037,-0.11,-0.18,-0.04,0.46,0.0017,-0.02,-0.025,0,0,0.00031,0.00036,0.0034,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00025,1.4e-05,0.00041,0.00013,0.00026,0.00041,1,1
33590000,0.99,-0.003,0.0015,-0.14,-1.5,-0.84,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.0002,-0.018,0.037,-0.11,-0.19,-0.042,0.46,0.0025,-0.013,-0.026,0,0,0.00035,0.00031,0.003,0.044,0.047,0.061,0.3,0.3,0.065,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00017,1e-05,0.00041,9.5e-05,0.00016,0.0004,1,1
33690000,1,-0.0064,0.005,0.024,-1.6,-0.86,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.018,0.037,-0.11,-0.19,-0.043,0.46,0.0018,-0.0093,-0.026,0,0,0.00037,0.00028,0.0026,0.045,0.05,0.056,0.31,0.31,0.068,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00013,7.8e-06,0.0004,6.9e-05,0.0001,0.0004,1,1
33790000,0.98,-0.0073,0.0069,0.19,-1.6,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.002,-0.0068,-0.027,0,0,0.00037,0.00026,0.0023,0.04,0.045,0.047,0.31,0.31,0.064,2.8e-07,4.9e-07,3.1e-06,0.028,0.022,9.3e-05,9.7e-05,6.4e-06,0.0004,4.8e-05,6.3e-05,0.0004,1,1
33890000,0.94,-0.0075,0.0082,0.35,-1.7,-0.9,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.0019,-0.0054,-0.027,0,0,0.00036,0.00026,0.0022,0.044,0.051,0.043,0.32,0.32,0.065,2.8e-07,4.9e-07,3e-06,0.028,0.022,9.3e-05,8.1e-05,5.6e-06,0.0004,3.4e-05,4.2e-05,0.0004,1,1
33990000,0.87,-0.0095,0.0057,0.49,-1.7,-0.91,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.015,0.036,-0.11,-0.2,-0.044,0.46,0.0017,-0.004,-0.027,0,0,0.00032,0.00027,0.002,0.041,0.049,0.036,0.32,0.32,0.062,2.8e-07,4.8e-07,3e-06,0.028,0.022,9.3e-05,7.1e-05,5.1e-06,0.0004,2.6e-05,3e-05,0.0004,1,1
34090000,0.81,-0.011,0.0044,0.59,-1.7,-0.97,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.01,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0034,-0.027,0,0,0.0003,0.00028,0.002,0.047,0.057,0.034,0.33,0.33,0.063,2.8e-07,4.9e-07,3e-06,0.027,0.022,9.3e-05,6.6e-05,4.9e-06,0.0004,2.1e-05,2.4e-05,0.0004,1,1
34190000,0.76,-0.0081,0.0029,0.65,-1.7,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.039,0.052,-0.11,-0.2,-0.044,0.46,0.0012,-0.0028,-0.027,0,0,0.00026,0.00028,0.0018,0.045,0.054,0.029,0.33,0.33,0.06,2.8e-07,4.7e-07,3e-06,0.026,0.021,9.3e-05,6e-05,4.6e-06,0.0004,1.7e-05,1.9e-05,0.0004,1,1
34290000,0.72,-0.0052,0.0041,0.69,-1.7,-1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.038,0.051,-0.11,-0.2,-0.044,0.46,0.0011,-0.0024,-0.027,0,0,0.00025,0.00029,0.0018,0.053,0.064,0.027,0.34,0.34,0.06,2.8e-07,4.7e-07,3e-06,0.025,0.021,9.3e-05,5.7e-05,4.5e-06,0.0004,1.4e-05,1.6e-05,0.0004,1,1
34390000,0.7,-0.0024,0.0054,0.71,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.036,0.05,-0.11,-0.2,-0.044,0.46,0.00092,-0.0022,-0.027,0,0,0.00025,0.00029,0.0018,0.062,0.075,0.025,0.35,0.35,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.5e-05,4.4e-06,0.0004,1.3e-05,1.4e-05,0.0004,1,1
34490000,0.69,-0.00036,0.0066,0.73,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.049,-0.11,-0.2,-0.044,0.46,0.0008,-0.0021,-0.027,0,0,0.00024,0.0003,0.0017,0.073,0.088,0.023,0.36,0.36,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.4e-05,4.3e-06,0.0004,1.1e-05,1.2e-05,0.0004,1,1
34590000,0.68,0.00092,0.0074,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.05,-0.11,-0.2,-0.044,0.46,0.00064,-0.002,-0.027,0,0,0.00024,0.0003,0.0017,0.085,0.1,0.021,0.38,0.38,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.2e-05,4.3e-06,0.0004,1e-05,1.1e-05,0.0004,1,1
34690000,0.67,0.0017,0.0079,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.034,0.049,-0.11,-0.2,-0.044,0.46,0.00068,-0.0018,-0.027,0,0,0.00024,0.0003,0.0017,0.098,0.12,0.019,0.39,0.4,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,9.6e-06,1e-05,0.0004,1,1
34790000,0.67,0.0024,0.0081,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.036,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00024,0.0003,0.0017,0.11,0.14,0.018,0.41,0.42,0.058,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,8.9e-06,9.2e-06,0.0004,1,1
34890000,0.66,0.0025,0.0082,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00069,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.13,0.16,0.017,0.43,0.44,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5e-05,4.1e-06,0.0004,8.4e-06,8.5e-06,0.0004,1,1
34990000,0.66,-0.00086,0.016,0.75,-3,-2.2,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00079,-0.0017,-0.027,0,0,0.00024,0.00031,0.0017,0.16,0.22,0.016,0.46,0.47,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.9e-06,8e-06,0.0004,1,1
35090000,0.66,-0.00092,0.016,0.75,-3.1,-2.3,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.18,0.25,0.015,0.49,0.51,0.055,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.5e-06,7.5e-06,0.0004,1,1
35190000,0.66,-0.001,0.015,0.75,-3.1,-2.3,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00081,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.2,0.28,0.014,0.52,0.55,0.054,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,7.2e-06,7.1e-06,0.0004,1,1
35290000,0.66,-0.0012,0.015,0.75,-3.2,-2.3,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00084,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.23,0.31,0.013,0.56,0.6,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,6.9e-06,6.7e-06,0.0004,1,1
35390000,0.66,-0.0011,0.015,0.75,-3.2,-2.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00091,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.25,0.34,0.013,0.61,0.66,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.6e-06,6.4e-06,0.0004,1,1
35490000,0.66,-0.0012,0.016,0.75,-3.2,-2.4,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.28,0.37,0.012,0.66,0.73,0.051,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.4e-06,6.2e-06,0.0004,1,1
35590000,0.66,-0.0012,0.016,0.75,-3.3,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00092,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.31,0.4,0.011,0.72,0.81,0.05,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,4e-06,0.0004,6.2e-06,5.9e-06,0.0004,1,1
35690000,0.66,-0.0011,0.016,0.75,-3.3,-2.5,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.046,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.33,0.44,0.011,0.79,0.9,0.049,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.1e-06,5.7e-06,0.0004,1,1
35790000,0.66,-0.0012,0.016,0.75,-3.3,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.36,0.48,0.01,0.86,1,0.048,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,5.9e-06,5.5e-06,0.0004,1,1
35890000,0.66,-0.0013,0.016,0.75,-3.4,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.4,0.52,0.01,0.95,1.1,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,5.7e-06,5.3e-06,0.0004,1,1
35990000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.045,-0.11,-0.2,-0.044,0.46,0.00094,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.43,0.56,0.0097,1,1.2,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.6e-06,5.1e-06,0.0004,1,1
36090000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.044,-0.11,-0.2,-0.044,0.46,0.00096,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.46,0.6,0.0093,1.2,1.4,0.046,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.5e-06,5e-06,0.0004,1,1
36190000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.034,0.043,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.5,0.65,0.009,1.3,1.5,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.4e-06,4.8e-06,0.0004,1,1
36290000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.53,0.69,0.0088,1.4,1.7,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.3e-06,4.7e-06,0.0004,1,1
36390000,0.66,-0.0013,0.016,0.75,-3.5,-2.9,-0.097,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.57,0.74,0.0086,1.6,1.9,0.044,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.2e-06,4.6e-06,0.0004,1,1
36490000,0.66,-0.0014,0.016,0.75,-3.6,-2.9,-0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.032,0.041,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.61,0.79,0.0083,1.7,2.1,0.043,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.0004,5.2e-06,4.5e-06,0.0004,1,1
36590000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.08,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.032,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.65,0.84,0.0082,1.9,2.4,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5.1e-06,4.4e-06,0.0004,1,1
36690000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.031,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.69,0.89,0.0081,2.1,2.6,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.3e-06,0.0004,1,1
36790000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00024,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.74,0.94,0.0079,2.3,2.9,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.2e-06,0.0004,1,1
36890000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.78,1,0.0078,2.6,3.2,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4.1e-06,0.0004,1,1
36990000,0.66,-0.0014,0.016,0.75,-3.7,-3.2,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.82,1.1,0.0077,2.8,3.6,0.04,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4e-06,0.0004,1,1
37090000,0.66,-0.0014,0.016,0.75,-3.8,-3.2,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.87,1.1,0.0076,3.1,4,0.04,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1
37190000,0.66,-0.0014,0.016,0.75,-3.8,-3.3,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.92,1.2,0.0076,3.4,4.4,0.039,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1
37290000,0.66,-0.0015,0.017,0.75,-3.8,-3.3,-0.026,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.97,1.2,0.0075,3.7,4.8,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.8e-06,0.0004,1,1
37390000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.029,0.036,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,1,1.3,0.0075,4.1,5.3,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1
37490000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.029,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.4,5.8,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1
37590000,0.66,-0.0014,0.017,0.75,-3.9,-3.5,-0.0032,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.028,0.034,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.9,6.3,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1
37690000,0.66,-0.0015,0.017,0.75,-4,-3.5,0.0061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.033,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.2,1.5,0.0074,5.3,6.9,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.6e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1
37790000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.2,1.5,0.0074,5.8,7.5,0.037,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.5e-06,0.0004,1,1
37890000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.022,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.6,0.0074,6.3,8.2,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1
37990000,0.66,-0.0016,0.017,0.75,-4.1,-3.7,0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.026,0.031,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.7,0.0074,6.8,8.9,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1
38090000,0.66,-0.0017,0.017,0.75,-4.1,-3.8,0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.7,0.0074,7.4,9.6,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.5e-06,3.4e-06,0.0004,1,1
38190000,0.66,-0.0016,0.017,0.75,-4.2,-3.8,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.8,0.0074,8,10,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1
38290000,0.66,-0.0017,0.017,0.75,-4.2,-3.9,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,8.6,11,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1
38390000,0.66,-0.0016,0.017,0.75,-4.2,-3.9,0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,9.3,12,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1
38490000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.07,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,10,13,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1
38590000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.076,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.1,0.0075,11,14,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1
38690000,0.66,-0.0016,0.017,0.75,-4.3,-4.1,0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.2,0.0075,12,15,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1
38790000,0.66,-0.0016,0.017,0.75,-4.4,-4.1,0.089,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00026,0.0016,1.8,2.3,0.0075,12,16,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1
38890000,0.66,-0.0017,0.017,0.75,-4.4,-4.1,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.9,2.3,0.0075,13,17,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1
190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.9e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00093,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-2.8e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.011,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,7.7e-11,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,1.4e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,1.4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,1.1e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00062,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,1.1e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.00079,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,3.3e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00053,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,3.3e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1090000,1,-0.01,-0.014,0.00012,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,9.3e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00046,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1190000,1,-0.01,-0.014,9.8e-05,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,9.3e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00054,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1290000,1,-0.01,-0.014,0.00015,0.02,0.0044,-0.14,0.0027,0.00088,-0.064,8.5e-05,-0.00019,2.3e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00041,0.88,0.88,2,0.15,0.15,1.4,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1390000,1,-0.01,-0.014,0.00016,0.026,0.0042,-0.15,0.005,0.0013,-0.078,8.5e-05,-0.00019,2.3e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00047,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1490000,1,-0.01,-0.014,0.00014,0.024,0.0029,-0.16,0.0037,0.00083,-0.093,0.00015,-0.00045,4.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00036,0.95,0.95,2,0.14,0.14,2.1,0.0089,0.0089,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1590000,1,-0.01,-0.014,0.00013,0.03,0.0035,-0.18,0.0064,0.0012,-0.11,0.00015,-0.00045,4.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00042,1.3,1.3,2,0.21,0.21,2.6,0.0089,0.0089,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1690000,1,-0.011,-0.014,9.6e-05,0.028,-0.0001,-0.19,0.0045,0.00062,-0.13,0.0002,-0.00087,7.7e-06,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.00033,1,1,2,0.14,0.14,3,0.0079,0.0079,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1790000,1,-0.011,-0.014,6.5e-05,0.035,-0.002,-0.2,0.0075,0.00054,-0.15,0.0002,-0.00087,7.7e-06,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00037,1.3,1.3,2,0.21,0.21,3.5,0.0079,0.0079,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1890000,1,-0.011,-0.015,4.4e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00087,7.7e-06,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00042,1.7,1.7,2,0.31,0.31,4.1,0.0079,0.0079,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1990000,1,-0.011,-0.014,3.6e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,1.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00033,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2090000,1,-0.011,-0.014,-4.3e-06,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,1.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00037,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2190000,1,-0.011,-0.014,-1.3e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,1.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.021,0.0003,1.2,1.2,2.1,0.2,0.2,6,0.0056,0.0055,8.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2290000,1,-0.011,-0.014,-2.9e-05,0.039,-0.0093,-0.27,0.012,-0.0017,-0.27,0.00017,-0.002,1.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00033,1.5,1.5,2.1,0.3,0.3,6.7,0.0056,0.0055,8.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2390000,1,-0.011,-0.013,-3.1e-05,0.03,-0.0086,-0.29,0.0075,-0.0015,-0.3,9e-05,-0.0025,2.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00027,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2490000,1,-0.011,-0.013,-5.3e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,2.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.0003,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2590000,1,-0.011,-0.013,-5.6e-05,0.027,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.3e-05,-0.0029,2.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00025,0.88,0.88,2.1,0.18,0.18,9.1,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2690000,1,-0.011,-0.013,-6.4e-05,0.031,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.3e-05,-0.0029,2.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00027,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2790000,1,-0.011,-0.013,-8.5e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,2.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.012,0.012,0.00023,0.76,0.76,2.2,0.16,0.16,11,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2890000,1,-0.011,-0.013,-0.00014,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,2.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00025,0.93,0.94,2.2,0.23,0.23,12,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2990000,1,-0.011,-0.013,-0.00011,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.01,0.01,0.00022,0.66,0.66,2.2,0.15,0.15,13,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3090000,1,-0.011,-0.013,-0.00011,0.025,-0.011,-0.38,0.0081,-0.0031,-0.53,-0.00023,-0.0036,3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.81,0.81,2.2,0.22,0.22,14,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3190000,1,-0.011,-0.013,-0.00018,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,3.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0089,0.0088,0.0002,0.58,0.58,2.3,0.14,0.14,15,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3290000,1,-0.011,-0.013,-0.00014,0.023,-0.01,-0.4,0.0074,-0.0031,-0.61,-0.00034,-0.0039,3.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0097,0.0097,0.00022,0.71,0.72,2.3,0.2,0.2,16,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3390000,1,-0.011,-0.012,-0.00018,0.018,-0.0091,-0.42,0.005,-0.0021,-0.65,-0.00045,-0.0041,3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0079,0.0079,0.00019,0.52,0.52,2.3,0.14,0.14,18,0.002,0.002,2.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3490000,1,-0.011,-0.013,-0.0002,0.022,-0.012,-0.43,0.007,-0.0031,-0.69,-0.00045,-0.0041,3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.0002,0.64,0.64,2.3,0.19,0.19,19,0.002,0.002,2.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3590000,1,-0.011,-0.012,-0.00019,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,3.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.48,0.48,2.4,0.13,0.13,20,0.0017,0.0017,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3690000,1,-0.011,-0.012,-6.8e-05,0.02,-0.014,-0.46,0.0066,-0.0035,-0.78,-0.00055,-0.0044,3.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.58,0.58,2.4,0.17,0.17,22,0.0017,0.0017,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3790000,1,-0.011,-0.012,-3.4e-05,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,3.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.44,0.44,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3890000,1,-0.011,-0.012,-7.2e-05,0.017,-0.014,-0.48,0.0061,-0.004,-0.87,-0.00067,-0.0046,3.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00018,0.54,0.54,2.4,0.16,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3990000,1,-0.011,-0.012,-7.4e-05,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,3.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0074,0.0074,0.00019,0.65,0.65,2.5,0.22,0.22,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4090000,1,-0.011,-0.012,-9e-05,0.017,-0.014,-0.51,0.0057,-0.0041,-0.97,-0.0008,-0.0048,3.8e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0061,0.006,0.00017,0.5,0.5,2.5,0.16,0.16,28,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4190000,1,-0.011,-0.012,-0.00012,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.0008,-0.0048,3.8e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0066,0.0066,0.00018,0.6,0.6,2.5,0.21,0.21,29,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4290000,1,-0.01,-0.012,-0.00018,0.016,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00092,-0.0049,4e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00016,0.46,0.46,2.6,0.15,0.15,31,0.00094,0.00094,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4390000,1,-0.01,-0.012,-0.00016,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00092,-0.0049,4e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0058,0.0057,0.00017,0.55,0.55,2.6,0.2,0.2,33,0.00094,0.00094,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4490000,1,-0.01,-0.012,-0.00011,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.0051,4.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0046,0.00015,0.43,0.43,2.6,0.14,0.14,34,0.00077,0.00076,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4590000,1,-0.01,-0.012,-8.6e-05,0.017,-0.011,-0.58,0.0066,-0.0047,-1.2,-0.001,-0.0051,4.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.51,0.51,2.7,0.19,0.19,36,0.00077,0.00076,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4690000,1,-0.01,-0.012,-9.4e-05,0.013,-0.0095,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,4.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.004,0.004,0.00015,0.4,0.4,2.7,0.14,0.14,38,0.00062,0.00061,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4790000,1,-0.01,-0.012,-0.00011,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,4.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0043,0.0043,0.00015,0.47,0.47,2.7,0.18,0.18,40,0.00062,0.00061,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4890000,1,-0.01,-0.011,-0.00013,0.012,-0.0095,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,4.5e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0035,0.0035,0.00014,0.37,0.37,2.8,0.13,0.13,42,0.00049,0.00049,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4990000,1,-0.01,-0.011,-0.00016,0.014,-0.01,-0.64,0.0057,-0.0041,-1.5,-0.0012,-0.0053,4.5e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00015,0.43,0.43,2.8,0.17,0.17,44,0.00049,0.00049,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5090000,1,-0.01,-0.011,-0.00012,0.011,-0.0078,-0.66,0.0041,-0.0029,-1.6,-0.0013,-0.0054,4.6e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.34,0.34,2.8,0.12,0.12,47,0.00039,0.00039,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5190000,1,-0.01,-0.011,-0.0001,0.012,-0.0091,-0.67,0.0052,-0.0038,-1.6,-0.0013,-0.0054,4.6e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.4,0.4,2.9,0.16,0.16,49,0.00039,0.00039,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5290000,1,-0.0099,-0.011,-0.00012,0.0079,-0.0066,-0.68,0.0036,-0.0027,-1.7,-0.0013,-0.0055,4.7e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.31,0.31,2.9,0.12,0.12,51,0.00031,0.00031,9.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5390000,1,-0.0099,-0.011,-6.8e-05,0.0073,-0.0074,-0.7,0.0044,-0.0034,-1.8,-0.0013,-0.0055,4.7e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00014,0.36,0.36,3,0.15,0.15,54,0.00031,0.00031,9.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5490000,1,-0.0097,-0.011,-6.5e-05,0.0047,-0.0055,-0.71,0.0029,-0.0024,-1.8,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.28,0.28,3,0.11,0.11,56,0.00024,0.00024,8.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5590000,1,-0.0097,-0.011,-9.2e-05,0.0053,-0.0058,-0.73,0.0034,-0.0029,-1.9,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.33,0.33,3,0.15,0.15,59,0.00024,0.00024,8.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5690000,1,-0.0096,-0.011,-2.7e-05,0.0034,-0.0032,-0.74,0.0023,-0.002,-2,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.26,0.26,3.1,0.11,0.11,61,0.00019,0.00019,7.5e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5790000,1,-0.0095,-0.011,-3.6e-05,0.0036,-0.0021,-0.75,0.0026,-0.0023,-2,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.002,0.002,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00019,0.00019,7.5e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5890000,1,-0.0095,-0.011,-6.6e-05,0.0031,-0.0004,0.0028,0.0018,-0.0015,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.24,0.24,9.8,0.1,0.1,0.52,0.00015,0.00015,6.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5990000,1,-0.0094,-0.011,-4.9e-05,0.0033,0.0011,0.015,0.0021,-0.0014,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00012,0.28,0.28,8.8,0.13,0.13,0.33,0.00015,0.00015,6.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6090000,1,-0.0094,-0.011,-7e-05,0.0042,0.0023,-0.011,0.0024,-0.0012,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00013,0.32,0.32,7,0.17,0.17,0.33,0.00015,0.00015,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6190000,1,-0.0094,-0.011,-0.00015,0.003,0.0046,-0.005,0.0017,-0.00033,-3.7e+02,-0.0015,-0.0057,4.9e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.25,0.25,4.9,0.13,0.13,0.32,0.00012,0.00012,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6290000,1,-0.0094,-0.011,-0.00018,0.0042,0.0047,-0.012,0.0021,0.00013,-3.7e+02,-0.0015,-0.0057,4.9e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.29,0.29,3.2,0.16,0.16,0.3,0.00012,0.00012,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6390000,0.77,-0.024,0.0046,-0.63,-0.012,-0.0013,-0.05,0.0011,-0.001,-3.7e+02,-0.0014,-0.0057,4.7e-05,0,0,-0.0001,-0.097,-0.021,0.51,-0.00012,-0.08,-0.061,0,0,0.0012,0.0012,0.065,0.21,0.21,2.3,0.12,0.12,0.29,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0014,0.00038,0.0014,0.001,0.0014,0.0014,1,1
6490000,0.78,-0.024,0.005,-0.63,-0.038,-0.012,-0.052,-0.0019,-0.0044,-3.7e+02,-0.0013,-0.0057,4.3e-05,0,0,-0.00015,-0.1,-0.022,0.51,-0.00039,-0.084,-0.064,0,0,0.0012,0.0012,0.056,0.21,0.21,1.5,0.15,0.15,0.26,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00022,0.0013,0.00092,0.0014,0.0013,1,1
6590000,0.78,-0.024,0.0052,-0.63,-0.064,-0.021,-0.098,-0.0077,-0.0087,-3.7e+02,-0.0012,-0.0057,4e-05,-3.5e-05,0.00025,2.5e-05,-0.1,-0.023,0.51,-0.00086,-0.085,-0.066,0,0,0.0012,0.0012,0.053,0.22,0.22,1.1,0.18,0.18,0.23,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00017,0.0013,0.00088,0.0013,0.0013,1,1
6690000,0.78,-0.024,0.0053,-0.63,-0.091,-0.035,-0.075,-0.017,-0.017,-3.7e+02,-0.001,-0.0057,3.5e-05,9.4e-05,0.00099,-0.0003,-0.1,-0.023,0.5,-0.001,-0.086,-0.067,0,0,0.0012,0.0012,0.051,0.23,0.23,0.78,0.22,0.22,0.21,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00014,0.0013,0.00087,0.0013,0.0013,1,1
6790000,0.78,-0.024,0.0054,-0.63,-0.12,-0.045,-0.11,-0.026,-0.026,-3.7e+02,-0.00088,-0.0057,3.2e-05,-9.9e-06,0.0015,-6.5e-05,-0.1,-0.023,0.5,-0.00099,-0.086,-0.068,0,0,0.0012,0.0012,0.051,0.25,0.25,0.6,0.26,0.26,0.2,9.8e-05,9.7e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00086,0.0013,0.0013,1,1
6890000,0.78,-0.024,0.0054,-0.63,-0.14,-0.053,-0.12,-0.038,-0.033,-3.7e+02,-0.00083,-0.0057,3.1e-05,-7e-05,0.0017,-0.00011,-0.1,-0.023,0.5,-0.001,-0.086,-0.068,0,0,0.0012,0.0012,0.05,0.26,0.26,0.46,0.31,0.31,0.18,9.7e-05,9.7e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00086,0.0013,0.0013,1,1
6990000,0.78,-0.024,0.0054,-0.63,-0.17,-0.065,-0.12,-0.059,-0.045,-3.7e+02,-0.00069,-0.0058,2.4e-05,0.00036,0.0023,-0.00042,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0012,0.0012,0.05,0.28,0.28,0.36,0.36,0.36,0.16,9.6e-05,9.6e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00011,0.0013,0.00085,0.0013,0.0013,1,1
7090000,0.78,-0.024,0.0056,-0.63,-0.2,-0.077,-0.12,-0.084,-0.062,-3.7e+02,-0.0005,-0.0059,1.6e-05,0.00085,0.0031,-0.00078,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0012,0.0013,0.049,0.31,0.31,0.29,0.42,0.42,0.16,9.5e-05,9.6e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.0001,0.0013,0.00085,0.0013,0.0013,1,1
7190000,0.78,-0.024,0.0056,-0.63,-0.23,-0.085,-0.14,-0.11,-0.073,-3.7e+02,-0.00044,-0.006,1.3e-05,0.001,0.0033,-0.00056,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.34,0.33,0.24,0.49,0.48,0.15,9.4e-05,9.4e-05,5.8e-06,0.04,0.04,0.04,0.0013,9.9e-05,0.0013,0.00085,0.0013,0.0013,1,1
7290000,0.78,-0.024,0.0056,-0.63,-0.25,-0.081,-0.14,-0.13,-0.068,-3.7e+02,-0.00066,-0.006,2e-05,0.00095,0.0024,-0.0012,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.37,0.36,0.2,0.56,0.55,0.14,9.2e-05,9.3e-05,5.8e-06,0.04,0.04,0.04,0.0013,9.5e-05,0.0013,0.00085,0.0013,0.0013,1,1
7390000,0.78,-0.024,0.0056,-0.63,-0.28,-0.086,-0.16,-0.16,-0.075,-3.7e+02,-0.0007,-0.0059,2.2e-05,0.00083,0.0023,-0.0014,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.4,0.39,0.18,0.63,0.63,0.13,9.1e-05,9.1e-05,5.8e-06,0.04,0.04,0.039,0.0013,9.2e-05,0.0013,0.00084,0.0013,0.0013,1,1
7490000,0.78,-0.024,0.0057,-0.63,-0.3,-0.1,-0.16,-0.19,-0.096,-3.7e+02,-0.00051,-0.0059,1.6e-05,0.0008,0.0031,-0.0021,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.44,0.43,0.15,0.72,0.71,0.12,8.9e-05,9e-05,5.8e-06,0.04,0.04,0.039,0.0013,9e-05,0.0013,0.00084,0.0013,0.0013,1,1
7590000,0.78,-0.024,0.0056,-0.63,-0.32,-0.1,-0.16,-0.21,-0.1,-3.7e+02,-0.00059,-0.0058,2.1e-05,0.00036,0.0028,-0.003,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0013,0.0013,0.048,0.47,0.47,0.14,0.81,0.8,0.12,8.6e-05,8.7e-05,5.8e-06,0.04,0.04,0.039,0.0013,8.7e-05,0.0013,0.00084,0.0013,0.0013,1,1
7690000,0.78,-0.024,0.0056,-0.63,-0.35,-0.11,-0.16,-0.24,-0.12,-3.7e+02,-0.00048,-0.0058,1.8e-05,0.00033,0.0033,-0.005,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0013,0.0014,0.048,0.52,0.51,0.13,0.91,0.9,0.11,8.4e-05,8.5e-05,5.8e-06,0.04,0.04,0.039,0.0013,8.6e-05,0.0013,0.00084,0.0013,0.0013,1,1
7790000,0.78,-0.024,0.0058,-0.63,-0.39,-0.12,-0.16,-0.3,-0.14,-3.7e+02,-0.00042,-0.006,1.2e-05,0.001,0.0036,-0.007,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0014,0.0014,0.048,0.56,0.55,0.12,1,1,0.11,8.1e-05,8.2e-05,5.7e-06,0.04,0.04,0.038,0.0013,8.4e-05,0.0013,0.00084,0.0013,0.0013,1,1
7890000,0.78,-0.025,0.0058,-0.63,-0.41,-0.13,-0.15,-0.33,-0.15,-3.7e+02,-0.00039,-0.0059,1.3e-05,0.00063,0.0039,-0.0095,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0014,0.0014,0.048,0.61,0.6,0.11,1.1,1.1,0.1,7.8e-05,8e-05,5.7e-06,0.04,0.04,0.038,0.0013,8.3e-05,0.0013,0.00084,0.0013,0.0013,1,1
7990000,0.78,-0.025,0.0057,-0.63,-0.43,-0.14,-0.16,-0.37,-0.16,-3.7e+02,-0.00041,-0.0058,1.6e-05,0.00027,0.0038,-0.011,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.66,0.65,0.1,1.3,1.2,0.099,7.5e-05,7.6e-05,5.7e-06,0.04,0.04,0.038,0.0013,8.1e-05,0.0013,0.00084,0.0013,0.0013,1,1
8090000,0.78,-0.025,0.0057,-0.63,-0.45,-0.15,-0.17,-0.4,-0.18,-3.7e+02,-0.00037,-0.0057,1.8e-05,-0.00027,0.004,-0.011,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.72,0.71,0.1,1.4,1.4,0.097,7.2e-05,7.4e-05,5.7e-06,0.04,0.04,0.037,0.0013,8e-05,0.0013,0.00084,0.0013,0.0013,1,1
8190000,0.78,-0.025,0.0058,-0.63,-0.48,-0.15,-0.17,-0.46,-0.19,-3.7e+02,-0.0004,-0.0058,1.5e-05,0.00019,0.004,-0.013,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.78,0.76,0.099,1.6,1.5,0.094,6.8e-05,7e-05,5.7e-06,0.04,0.04,0.037,0.0013,7.9e-05,0.0013,0.00084,0.0013,0.0013,1,1
8290000,0.78,-0.025,0.006,-0.63,-0.022,-0.005,-0.17,-0.47,-0.2,-3.7e+02,-0.00028,-0.0059,1e-05,0.00027,0.0041,-0.017,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.092,6.5e-05,6.7e-05,5.7e-06,0.04,0.04,0.036,0.0013,7.8e-05,0.0013,0.00084,0.0013,0.0013,1,1
8390000,0.78,-0.025,0.0059,-0.63,-0.048,-0.012,-0.17,-0.47,-0.2,-3.7e+02,-0.00026,-0.0058,1.3e-05,0.00027,0.0041,-0.021,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.2e-05,6.4e-05,5.7e-06,0.04,0.04,0.035,0.0013,7.8e-05,0.0013,0.00084,0.0013,0.0013,1,1
8490000,0.78,-0.025,0.006,-0.63,-0.075,-0.019,-0.17,-0.48,-0.2,-3.7e+02,-0.00026,-0.0058,1.1e-05,0.00027,0.0041,-0.025,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,51,51,0.089,5.8e-05,6.1e-05,5.7e-06,0.04,0.04,0.034,0.0013,7.7e-05,0.0013,0.00084,0.0013,0.0013,1,1
8590000,0.78,-0.025,0.0059,-0.63,-0.099,-0.026,-0.16,-0.48,-0.2,-3.7e+02,-0.0005,-0.006,1.5e-05,0.00027,0.0041,-0.029,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.095,52,52,0.088,5.5e-05,5.7e-05,5.7e-06,0.04,0.04,0.034,0.0013,7.6e-05,0.0013,0.00084,0.0013,0.0013,1,1
8690000,0.78,-0.025,0.0058,-0.63,-0.12,-0.034,-0.16,-0.49,-0.21,-3.7e+02,-0.00048,-0.0058,1.9e-05,0.00027,0.0041,-0.034,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,35,35,0.088,5.2e-05,5.5e-05,5.7e-06,0.04,0.04,0.033,0.0013,7.6e-05,0.0013,0.00084,0.0013,0.0013,1,1
8790000,0.78,-0.025,0.006,-0.63,-0.15,-0.04,-0.15,-0.5,-0.21,-3.7e+02,-0.00044,-0.0059,1.6e-05,0.00027,0.0041,-0.04,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,37,37,0.087,4.9e-05,5.1e-05,5.7e-06,0.04,0.04,0.032,0.0013,7.5e-05,0.0013,0.00084,0.0013,0.0013,1,1
8890000,0.78,-0.025,0.0061,-0.63,-0.17,-0.045,-0.15,-0.51,-0.21,-3.7e+02,-0.00043,-0.0059,1.4e-05,0.00027,0.0041,-0.044,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.095,28,28,0.086,4.6e-05,4.8e-05,5.7e-06,0.04,0.04,0.03,0.0013,7.4e-05,0.0013,0.00084,0.0013,0.0013,1,1
8990000,0.78,-0.025,0.0062,-0.63,-0.2,-0.05,-0.14,-0.53,-0.21,-3.7e+02,-0.00036,-0.006,9.8e-06,0.00027,0.0041,-0.05,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.096,30,30,0.087,4.4e-05,4.6e-05,5.7e-06,0.04,0.04,0.029,0.0013,7.4e-05,0.0013,0.00084,0.0013,0.0013,1,1
9090000,0.78,-0.025,0.0062,-0.63,-0.22,-0.053,-0.14,-0.53,-0.21,-3.7e+02,-0.00043,-0.0061,1e-05,0.00027,0.0041,-0.052,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.095,25,25,0.086,4.1e-05,4.3e-05,5.7e-06,0.04,0.04,0.028,0.0013,7.4e-05,0.0013,0.00084,0.0013,0.0013,1,1
9190000,0.78,-0.025,0.006,-0.63,-0.25,-0.065,-0.14,-0.55,-0.22,-3.7e+02,-0.0004,-0.0058,1.5e-05,0.00027,0.0041,-0.055,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.094,27,27,0.085,3.8e-05,4.1e-05,5.7e-06,0.04,0.04,0.027,0.0013,7.3e-05,0.0013,0.00084,0.0013,0.0013,1,1
9290000,0.78,-0.025,0.0061,-0.63,-0.27,-0.071,-0.13,-0.56,-0.22,-3.7e+02,-0.00036,-0.0058,1.5e-05,0.00027,0.0041,-0.06,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,23,23,0.085,3.6e-05,3.8e-05,5.7e-06,0.04,0.04,0.025,0.0013,7.3e-05,0.0013,0.00084,0.0013,0.0013,1,1
9390000,0.78,-0.025,0.0062,-0.63,-0.3,-0.079,-0.13,-0.59,-0.23,-3.7e+02,-0.00032,-0.0058,1.3e-05,0.00027,0.0041,-0.063,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,26,26,0.086,3.4e-05,3.6e-05,5.7e-06,0.04,0.04,0.024,0.0013,7.2e-05,0.0013,0.00084,0.0013,0.0013,1,1
9490000,0.78,-0.026,0.0061,-0.63,-0.31,-0.086,-0.13,-0.59,-0.23,-3.7e+02,-0.00027,-0.0057,1.6e-05,0.00027,0.0041,-0.067,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,19,19,0.091,22,22,0.085,3.2e-05,3.4e-05,5.7e-06,0.04,0.04,0.023,0.0013,7.2e-05,0.0013,0.00083,0.0013,0.0013,1,1
9590000,0.78,-0.025,0.0059,-0.63,-0.33,-0.095,-0.12,-0.62,-0.24,-3.7e+02,-0.0004,-0.0056,2e-05,0.00027,0.0041,-0.07,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,19,19,0.09,25,25,0.085,3e-05,3.2e-05,5.7e-06,0.04,0.04,0.022,0.0013,7.2e-05,0.0013,0.00083,0.0013,0.0013,1,1
9690000,0.78,-0.025,0.006,-0.63,-0.33,-0.091,-0.12,-0.61,-0.24,-3.7e+02,-0.00046,-0.0058,1.8e-05,0.00027,0.0041,-0.075,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,17,17,0.089,22,22,0.086,2.8e-05,3e-05,5.7e-06,0.04,0.04,0.02,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1
9790000,0.78,-0.025,0.006,-0.63,-0.36,-0.1,-0.11,-0.65,-0.25,-3.7e+02,-0.00043,-0.0057,1.9e-05,0.00027,0.0041,-0.08,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,17,17,0.087,25,25,0.085,2.6e-05,2.8e-05,5.7e-06,0.04,0.04,0.019,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1
9890000,0.78,-0.025,0.0059,-0.63,-0.36,-0.1,-0.1,-0.64,-0.25,-3.7e+02,-0.0005,-0.0057,2.1e-05,0.00027,0.0041,-0.083,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,15,15,0.084,22,22,0.085,2.5e-05,2.6e-05,5.7e-06,0.04,0.04,0.018,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1
9990000,0.78,-0.025,0.006,-0.63,-0.39,-0.11,-0.097,-0.67,-0.26,-3.7e+02,-0.00052,-0.0058,2e-05,0.00027,0.0041,-0.086,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,15,15,0.083,25,25,0.086,2.3e-05,2.5e-05,5.7e-06,0.04,0.04,0.017,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1
10090000,0.78,-0.025,0.0059,-0.63,-0.41,-0.11,-0.093,-0.71,-0.27,-3.7e+02,-0.0006,-0.0057,2.3e-05,0.00027,0.0041,-0.089,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,15,15,0.081,28,28,0.085,2.2e-05,2.4e-05,5.7e-06,0.04,0.04,0.016,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1
10190000,0.78,-0.025,0.0061,-0.63,-0.41,-0.11,-0.093,-0.7,-0.26,-3.7e+02,-0.00061,-0.0059,1.9e-05,0.00027,0.0041,-0.09,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,14,14,0.078,24,24,0.084,2.1e-05,2.2e-05,5.7e-06,0.04,0.04,0.015,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1
10290000,0.78,-0.025,0.0063,-0.63,-0.44,-0.11,-0.08,-0.74,-0.27,-3.7e+02,-0.00062,-0.006,1.7e-05,0.00027,0.0041,-0.096,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0015,0.0015,0.048,14,14,0.076,27,27,0.085,1.9e-05,2.1e-05,5.7e-06,0.04,0.04,0.014,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1
10390000,0.78,-0.025,0.0064,-0.63,-0.016,-0.026,0.0097,-0.00026,-0.0021,-3.7e+02,-0.00059,-0.006,1.7e-05,0.00022,0.0044,-0.099,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0015,0.0015,0.048,0.25,0.25,0.56,0.25,0.25,0.078,1.8e-05,2e-05,5.7e-06,0.04,0.039,0.013,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1
10490000,0.78,-0.025,0.0065,-0.63,-0.044,-0.032,0.023,-0.0033,-0.0049,-3.7e+02,-0.00059,-0.0061,1.5e-05,0.00043,0.0046,-0.1,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0015,0.0015,0.048,0.26,0.26,0.55,0.26,0.26,0.08,1.7e-05,1.9e-05,5.7e-06,0.04,0.039,0.012,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
10590000,0.78,-0.025,0.0062,-0.63,-0.042,-0.021,0.026,0.0012,-0.001,-3.7e+02,-0.00075,-0.006,2e-05,0.00066,0.0031,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.13,0.13,0.27,0.13,0.13,0.073,1.6e-05,1.8e-05,5.7e-06,0.039,0.039,0.012,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
10690000,0.78,-0.025,0.0063,-0.63,-0.069,-0.026,0.03,-0.0044,-0.0034,-3.7e+02,-0.00074,-0.0061,1.9e-05,0.00069,0.0031,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.14,0.14,0.26,0.14,0.14,0.078,1.5e-05,1.7e-05,5.7e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
10790000,0.78,-0.024,0.006,-0.63,-0.065,-0.021,0.024,4.9e-05,-0.0014,-3.7e+02,-0.00079,-0.006,2.2e-05,0.00087,0.00042,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.096,0.096,0.17,0.09,0.09,0.072,1.4e-05,1.6e-05,5.7e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
10890000,0.78,-0.024,0.0061,-0.63,-0.092,-0.026,0.02,-0.0078,-0.0038,-3.7e+02,-0.00079,-0.006,2.3e-05,0.00083,0.00041,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.11,0.11,0.16,0.096,0.096,0.075,1.4e-05,1.5e-05,5.7e-06,0.039,0.039,0.011,0.0013,6.8e-05,0.0013,0.00083,0.0013,0.0013,1,1
10990000,0.78,-0.024,0.0055,-0.63,-0.08,-0.021,0.014,-0.0033,-0.0021,-3.7e+02,-0.00081,-0.0059,2.7e-05,0.0011,-0.0047,-0.11,-0.1,-0.023,0.5,-0.001,-0.087,-0.069,0,0,0.0013,0.0014,0.048,0.086,0.086,0.12,0.099,0.099,0.071,1.3e-05,1.4e-05,5.7e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1
11090000,0.78,-0.024,0.0054,-0.63,-0.1,-0.028,0.019,-0.012,-0.0047,-3.7e+02,-0.00084,-0.0059,3e-05,0.00085,-0.0047,-0.11,-0.1,-0.023,0.5,-0.00099,-0.087,-0.069,0,0,0.0013,0.0014,0.048,0.099,0.1,0.11,0.11,0.11,0.074,1.2e-05,1.3e-05,5.7e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1
11190000,0.78,-0.023,0.0048,-0.63,-0.09,-0.021,0.0078,-0.0044,-0.0017,-3.7e+02,-0.00094,-0.0059,3.4e-05,0.0015,-0.012,-0.11,-0.11,-0.023,0.5,-0.00094,-0.087,-0.069,0,0,0.0012,0.0013,0.048,0.083,0.083,0.084,0.11,0.11,0.069,1.1e-05,1.2e-05,5.7e-06,0.037,0.037,0.011,0.0013,6.8e-05,0.0013,0.00081,0.0013,0.0013,1,1
11290000,0.78,-0.023,0.0049,-0.63,-0.11,-0.025,0.0076,-0.015,-0.0037,-3.7e+02,-0.00089,-0.006,3.1e-05,0.0016,-0.011,-0.11,-0.11,-0.023,0.5,-0.00098,-0.087,-0.069,0,0,0.0012,0.0013,0.047,0.098,0.098,0.078,0.12,0.12,0.072,1.1e-05,1.2e-05,5.7e-06,0.037,0.037,0.01,0.0013,6.7e-05,0.0013,0.00081,0.0013,0.0013,1,1
11390000,0.78,-0.022,0.0042,-0.63,-0.098,-0.02,0.002,-0.0023,-0.00073,-3.7e+02,-0.00099,-0.006,3.4e-05,0.0016,-0.018,-0.11,-0.11,-0.023,0.5,-0.001,-0.088,-0.069,0,0,0.0011,0.0011,0.047,0.079,0.079,0.063,0.082,0.082,0.068,1e-05,1.1e-05,5.7e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.0008,0.0013,0.0013,1,1
11490000,0.78,-0.022,0.0045,-0.63,-0.12,-0.022,0.0029,-0.013,-0.0024,-3.7e+02,-0.00095,-0.0061,3e-05,0.0016,-0.018,-0.11,-0.11,-0.023,0.5,-0.0011,-0.088,-0.069,0,0,0.0011,0.0011,0.047,0.094,0.094,0.058,0.089,0.089,0.069,9.6e-06,1e-05,5.7e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1
11590000,0.78,-0.021,0.0038,-0.63,-0.098,-0.018,-0.003,-0.0042,-0.00071,-3.7e+02,-0.00099,-0.0061,3.3e-05,0.0013,-0.025,-0.11,-0.11,-0.023,0.5,-0.0012,-0.088,-0.069,0,0,0.00095,0.00099,0.047,0.078,0.078,0.049,0.068,0.068,0.066,9.1e-06,9.9e-06,5.7e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00078,0.0013,0.0013,1,1
11690000,0.78,-0.021,0.004,-0.63,-0.11,-0.022,-0.0074,-0.015,-0.0026,-3.7e+02,-0.00094,-0.0061,3.1e-05,0.0013,-0.025,-0.11,-0.11,-0.023,0.5,-0.0012,-0.088,-0.069,0,0,0.00095,0.00099,0.047,0.092,0.092,0.046,0.075,0.075,0.066,8.6e-06,9.4e-06,5.7e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00078,0.0013,0.0013,1,1
11790000,0.78,-0.02,0.0034,-0.63,-0.096,-0.014,-0.0092,-0.008,0.00046,-3.7e+02,-0.00097,-0.0061,3.4e-05,0.0018,-0.031,-0.11,-0.11,-0.023,0.5,-0.0011,-0.089,-0.069,0,0,0.00084,0.00087,0.047,0.076,0.076,0.039,0.06,0.06,0.063,8.1e-06,8.8e-06,5.7e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1
11890000,0.78,-0.02,0.0035,-0.63,-0.11,-0.015,-0.01,-0.019,-0.00079,-3.7e+02,-0.00095,-0.0062,3.2e-05,0.0017,-0.031,-0.11,-0.11,-0.023,0.5,-0.0012,-0.089,-0.069,0,0,0.00084,0.00087,0.047,0.089,0.089,0.037,0.067,0.067,0.063,7.8e-06,8.5e-06,5.7e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1
11990000,0.78,-0.019,0.0029,-0.63,-0.092,-0.0092,-0.015,-0.011,0.0015,-3.7e+02,-0.0011,-0.0062,3.8e-05,0.0018,-0.036,-0.11,-0.11,-0.023,0.5,-0.0011,-0.089,-0.069,0,0,0.00074,0.00077,0.047,0.074,0.073,0.033,0.055,0.055,0.061,7.4e-06,8e-06,5.7e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0013,0.00075,0.0013,0.0013,1,1
12090000,0.78,-0.019,0.0027,-0.63,-0.1,-0.012,-0.021,-0.02,0.00017,-3.7e+02,-0.0011,-0.0061,4e-05,0.0021,-0.036,-0.11,-0.11,-0.023,0.5,-0.001,-0.089,-0.069,0,0,0.00075,0.00077,0.047,0.086,0.086,0.031,0.063,0.063,0.061,7e-06,7.7e-06,5.7e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0013,0.00075,0.0013,0.0013,1,1
12190000,0.78,-0.019,0.0022,-0.63,-0.081,-0.012,-0.016,-0.01,0.00056,-3.7e+02,-0.0011,-0.0061,4.1e-05,0.0016,-0.041,-0.11,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00067,0.00069,0.046,0.07,0.07,0.028,0.052,0.052,0.059,6.7e-06,7.3e-06,5.7e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1
12290000,0.78,-0.019,0.0022,-0.63,-0.09,-0.014,-0.015,-0.019,-0.00089,-3.7e+02,-0.0011,-0.0061,4.1e-05,0.0017,-0.042,-0.11,-0.11,-0.024,0.5,-0.001,-0.09,-0.069,0,0,0.00067,0.00069,0.046,0.081,0.081,0.028,0.06,0.06,0.059,6.4e-06,7e-06,5.7e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1
12390000,0.78,-0.018,0.0018,-0.63,-0.07,-0.011,-0.013,-0.0093,0.00016,-3.7e+02,-0.0011,-0.0061,4.1e-05,0.0011,-0.046,-0.11,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.0006,0.00062,0.046,0.066,0.066,0.026,0.05,0.05,0.057,6.1e-06,6.7e-06,5.7e-06,0.032,0.032,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1
12490000,0.78,-0.018,0.0019,-0.63,-0.078,-0.013,-0.016,-0.017,-0.00083,-3.7e+02,-0.0011,-0.0061,3.9e-05,0.00083,-0.046,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.0006,0.00062,0.046,0.076,0.076,0.026,0.058,0.058,0.057,5.9e-06,6.4e-06,5.7e-06,0.032,0.032,0.01,0.0012,6.4e-05,0.0012,0.00073,0.0013,0.0012,1,1
12590000,0.78,-0.018,0.0017,-0.63,-0.071,-0.011,-0.022,-0.014,-3.2e-05,-3.7e+02,-0.0012,-0.0061,4.2e-05,0.00089,-0.048,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.00055,0.00057,0.046,0.062,0.062,0.025,0.049,0.049,0.055,5.6e-06,6.2e-06,5.7e-06,0.031,0.032,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1
12690000,0.78,-0.018,0.0016,-0.63,-0.076,-0.012,-0.025,-0.021,-0.00096,-3.7e+02,-0.0012,-0.0062,4.2e-05,0.00068,-0.047,-0.11,-0.11,-0.024,0.5,-0.0013,-0.09,-0.069,0,0,0.00056,0.00057,0.046,0.071,0.071,0.025,0.057,0.057,0.055,5.4e-06,5.9e-06,5.7e-06,0.031,0.032,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1
12790000,0.78,-0.018,0.0014,-0.63,-0.07,-0.01,-0.028,-0.018,-0.0003,-3.7e+02,-0.0012,-0.0062,4.3e-05,0.00079,-0.049,-0.11,-0.11,-0.024,0.5,-0.0013,-0.09,-0.069,0,0,0.00052,0.00053,0.046,0.058,0.058,0.024,0.048,0.048,0.053,5.1e-06,5.7e-06,5.7e-06,0.031,0.031,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1
12890000,0.78,-0.018,0.0015,-0.63,-0.077,-0.011,-0.027,-0.026,-0.0014,-3.7e+02,-0.0011,-0.0062,4.1e-05,0.00082,-0.05,-0.11,-0.11,-0.024,0.5,-0.0013,-0.09,-0.069,0,0,0.00052,0.00053,0.046,0.066,0.066,0.025,0.056,0.056,0.054,5e-06,5.5e-06,5.7e-06,0.031,0.031,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1
12990000,0.78,-0.018,0.0012,-0.63,-0.062,-0.0094,-0.028,-0.019,-0.0011,-3.7e+02,-0.0012,-0.0061,4.3e-05,0.00087,-0.052,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.00049,0.0005,0.046,0.058,0.058,0.025,0.058,0.058,0.052,4.8e-06,5.3e-06,5.7e-06,0.031,0.031,0.0094,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1
13090000,0.78,-0.018,0.0013,-0.63,-0.068,-0.0091,-0.028,-0.026,-0.0017,-3.7e+02,-0.0011,-0.0062,4.1e-05,0.00044,-0.053,-0.11,-0.11,-0.024,0.5,-0.0013,-0.09,-0.069,0,0,0.00049,0.0005,0.046,0.065,0.065,0.025,0.066,0.066,0.052,4.6e-06,5.1e-06,5.7e-06,0.031,0.031,0.0094,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1
13190000,0.78,-0.017,0.00099,-0.63,-0.054,-0.0086,-0.025,-0.017,-0.0011,-3.7e+02,-0.0012,-0.0062,4.2e-05,0.00013,-0.055,-0.11,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00047,0.00048,0.046,0.057,0.057,0.025,0.067,0.067,0.051,4.4e-06,4.9e-06,5.7e-06,0.031,0.031,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1
13290000,0.78,-0.017,0.001,-0.63,-0.059,-0.011,-0.021,-0.023,-0.0024,-3.7e+02,-0.0011,-0.0061,4.2e-05,0.00041,-0.055,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00047,0.00048,0.046,0.064,0.064,0.027,0.077,0.077,0.051,4.3e-06,4.8e-06,5.7e-06,0.031,0.031,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1
13390000,0.78,-0.017,0.00086,-0.63,-0.048,-0.0099,-0.017,-0.016,-0.0017,-3.7e+02,-0.0011,-0.0061,4.3e-05,0.00052,-0.056,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00045,0.00046,0.046,0.056,0.056,0.026,0.077,0.077,0.05,4.1e-06,4.6e-06,5.7e-06,0.03,0.03,0.0088,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13490000,0.78,-0.017,0.00083,-0.63,-0.051,-0.011,-0.016,-0.022,-0.0029,-3.7e+02,-0.0011,-0.0061,4.4e-05,0.0007,-0.057,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00045,0.00046,0.046,0.062,0.062,0.028,0.088,0.088,0.05,3.9e-06,4.4e-06,5.7e-06,0.03,0.03,0.0087,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13590000,0.78,-0.017,0.00071,-0.63,-0.041,-0.0099,-0.018,-0.014,-0.0017,-3.7e+02,-0.0011,-0.0061,4.4e-05,0.00039,-0.058,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00043,0.00045,0.046,0.054,0.054,0.028,0.087,0.087,0.05,3.8e-06,4.3e-06,5.7e-06,0.03,0.03,0.0084,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13690000,0.78,-0.017,0.0007,-0.63,-0.044,-0.013,-0.022,-0.019,-0.003,-3.7e+02,-0.0011,-0.0061,4.5e-05,0.00072,-0.058,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00043,0.00045,0.046,0.059,0.059,0.029,0.098,0.098,0.05,3.7e-06,4.2e-06,5.7e-06,0.03,0.03,0.0083,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
13790000,0.78,-0.017,0.00052,-0.63,-0.032,-0.011,-0.024,-0.0065,-0.0028,-3.7e+02,-0.0012,-0.0061,4.5e-05,0.00044,-0.059,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.045,0.045,0.029,0.072,0.072,0.049,3.5e-06,4e-06,5.7e-06,0.03,0.03,0.0079,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
13890000,0.78,-0.017,0.00058,-0.63,-0.036,-0.013,-0.028,-0.01,-0.0042,-3.7e+02,-0.0011,-0.0061,4.4e-05,0.00062,-0.059,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.049,0.049,0.03,0.081,0.081,0.05,3.4e-06,3.9e-06,5.7e-06,0.03,0.03,0.0078,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
13990000,0.78,-0.017,0.00043,-0.63,-0.028,-0.012,-0.027,-0.0033,-0.0039,-3.7e+02,-0.0011,-0.0061,4.4e-05,0.00048,-0.06,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.04,0.04,0.03,0.063,0.063,0.05,3.3e-06,3.8e-06,5.7e-06,0.03,0.03,0.0074,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
14090000,0.78,-0.017,0.00038,-0.63,-0.029,-0.013,-0.028,-0.006,-0.0053,-3.7e+02,-0.0012,-0.006,4.6e-05,0.00081,-0.06,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.043,0.043,0.031,0.07,0.07,0.05,3.2e-06,3.7e-06,5.7e-06,0.03,0.03,0.0073,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
14190000,0.78,-0.017,0.00032,-0.63,-0.023,-0.011,-0.03,-0.00018,-0.0036,-3.7e+02,-0.0012,-0.006,4.7e-05,0.001,-0.061,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.6e-06,5.7e-06,0.03,0.03,0.0069,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
14290000,0.78,-0.017,0.00028,-0.63,-0.024,-0.013,-0.029,-0.0025,-0.0048,-3.7e+02,-0.0012,-0.006,4.8e-05,0.0011,-0.06,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.04,0.04,0.032,0.064,0.064,0.051,3e-06,3.5e-06,5.7e-06,0.03,0.03,0.0067,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
14390000,0.78,-0.016,0.00024,-0.63,-0.019,-0.013,-0.031,0.0017,-0.0035,-3.7e+02,-0.0012,-0.006,4.9e-05,0.0015,-0.061,-0.12,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.034,0.034,0.031,0.053,0.053,0.05,2.9e-06,3.4e-06,5.7e-06,0.03,0.03,0.0063,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14490000,0.78,-0.017,0.00031,-0.63,-0.021,-0.016,-0.034,-0.00065,-0.0051,-3.7e+02,-0.0011,-0.006,4.8e-05,0.0016,-0.062,-0.12,-0.11,-0.024,0.5,-0.00098,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.037,0.037,0.032,0.06,0.06,0.051,2.8e-06,3.3e-06,5.7e-06,0.03,0.03,0.0062,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14590000,0.78,-0.016,0.00038,-0.63,-0.022,-0.016,-0.034,-0.0013,-0.005,-3.7e+02,-0.0011,-0.006,4.8e-05,0.0016,-0.062,-0.12,-0.11,-0.024,0.5,-0.00097,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.032,0.032,0.031,0.051,0.051,0.051,2.7e-06,3.2e-06,5.7e-06,0.03,0.03,0.0058,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14690000,0.78,-0.017,0.0004,-0.63,-0.025,-0.015,-0.031,-0.0037,-0.0067,-3.7e+02,-0.0011,-0.006,4.8e-05,0.0017,-0.062,-0.12,-0.11,-0.024,0.5,-0.00095,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.035,0.035,0.032,0.056,0.056,0.051,2.6e-06,3.1e-06,5.7e-06,0.03,0.03,0.0056,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
14790000,0.78,-0.016,0.00042,-0.63,-0.024,-0.014,-0.027,-0.0037,-0.0063,-3.7e+02,-0.0011,-0.006,4.8e-05,0.0017,-0.063,-0.12,-0.11,-0.024,0.5,-0.00094,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.03,0.03,0.031,0.048,0.049,0.051,2.6e-06,3e-06,5.7e-06,0.03,0.03,0.0053,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
14890000,0.78,-0.016,0.00042,-0.63,-0.027,-0.017,-0.03,-0.0064,-0.008,-3.7e+02,-0.0011,-0.006,4.8e-05,0.0018,-0.063,-0.12,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.033,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,5.7e-06,0.03,0.03,0.0051,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
14990000,0.78,-0.016,0.00047,-0.63,-0.025,-0.014,-0.026,-0.0048,-0.0062,-3.7e+02,-0.001,-0.006,4.9e-05,0.0018,-0.063,-0.12,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,5.7e-06,0.03,0.03,0.0048,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15090000,0.78,-0.016,0.00056,-0.63,-0.027,-0.015,-0.029,-0.0074,-0.0076,-3.7e+02,-0.001,-0.006,4.8e-05,0.0017,-0.063,-0.12,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.031,0.031,0.031,0.052,0.052,0.052,2.3e-06,2.8e-06,5.7e-06,0.03,0.03,0.0046,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15190000,0.78,-0.016,0.00059,-0.63,-0.025,-0.014,-0.026,-0.0059,-0.0061,-3.7e+02,-0.001,-0.006,4.9e-05,0.0017,-0.064,-0.12,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.027,0.028,0.03,0.046,0.046,0.052,2.3e-06,2.7e-06,5.7e-06,0.03,0.03,0.0043,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15290000,0.78,-0.016,0.00059,-0.63,-0.026,-0.016,-0.024,-0.0083,-0.0076,-3.7e+02,-0.001,-0.006,5e-05,0.0018,-0.063,-0.12,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,5.7e-06,0.029,0.03,0.0042,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15390000,0.78,-0.016,0.00055,-0.63,-0.026,-0.016,-0.022,-0.0079,-0.0078,-3.7e+02,-0.0011,-0.006,5.3e-05,0.0022,-0.063,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.028,0.029,0.029,0.054,0.054,0.051,2.1e-06,2.6e-06,5.7e-06,0.029,0.03,0.0039,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15490000,0.78,-0.016,0.00057,-0.63,-0.028,-0.016,-0.022,-0.011,-0.009,-3.7e+02,-0.0011,-0.006,5.1e-05,0.0019,-0.063,-0.12,-0.11,-0.024,0.5,-0.00088,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.5e-06,5.7e-06,0.029,0.03,0.0037,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
15590000,0.78,-0.016,0.00061,-0.63,-0.026,-0.014,-0.021,-0.01,-0.0084,-3.7e+02,-0.0011,-0.006,5.1e-05,0.0017,-0.064,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.029,0.03,0.028,0.062,0.062,0.052,2e-06,2.4e-06,5.7e-06,0.029,0.03,0.0035,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
15690000,0.78,-0.016,0.00059,-0.63,-0.027,-0.015,-0.021,-0.012,-0.0097,-3.7e+02,-0.0011,-0.006,5.1e-05,0.0017,-0.063,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.4e-06,5.7e-06,0.029,0.03,0.0033,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
15790000,0.78,-0.016,0.00058,-0.63,-0.025,-0.014,-0.024,-0.0088,-0.0084,-3.7e+02,-0.0011,-0.006,5.1e-05,0.0017,-0.064,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.026,0.027,0.027,0.056,0.057,0.051,1.9e-06,2.3e-06,5.7e-06,0.029,0.03,0.0031,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
15890000,0.78,-0.016,0.0006,-0.63,-0.027,-0.014,-0.022,-0.011,-0.0098,-3.7e+02,-0.0011,-0.006,5.1e-05,0.0016,-0.064,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.028,0.029,0.027,0.063,0.063,0.052,1.9e-06,2.3e-06,5.7e-06,0.029,0.03,0.003,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
15990000,0.78,-0.016,0.00058,-0.63,-0.024,-0.014,-0.017,-0.0082,-0.0089,-3.7e+02,-0.0011,-0.006,5.3e-05,0.0019,-0.064,-0.13,-0.11,-0.024,0.5,-0.00085,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.024,0.025,0.026,0.052,0.053,0.051,1.8e-06,2.2e-06,5.7e-06,0.029,0.03,0.0028,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
16090000,0.78,-0.016,0.00051,-0.63,-0.026,-0.016,-0.014,-0.01,-0.011,-3.7e+02,-0.0011,-0.006,5.6e-05,0.0022,-0.064,-0.13,-0.11,-0.024,0.5,-0.00083,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.2e-06,5.7e-06,0.029,0.03,0.0027,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
16190000,0.78,-0.016,0.00049,-0.63,-0.024,-0.015,-0.013,-0.0078,-0.0083,-3.7e+02,-0.0011,-0.006,5.8e-05,0.0022,-0.064,-0.13,-0.11,-0.024,0.5,-0.00081,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.023,0.023,0.025,0.05,0.05,0.051,1.7e-06,2.1e-06,5.7e-06,0.029,0.03,0.0025,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16290000,0.78,-0.016,0.00043,-0.63,-0.027,-0.016,-0.014,-0.01,-0.01,-3.7e+02,-0.0011,-0.006,6e-05,0.0025,-0.064,-0.13,-0.11,-0.024,0.5,-0.00079,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2.1e-06,5.7e-06,0.029,0.03,0.0024,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16390000,0.78,-0.016,0.00045,-0.63,-0.023,-0.013,-0.013,-0.0078,-0.008,-3.7e+02,-0.0012,-0.006,6.2e-05,0.0024,-0.063,-0.13,-0.11,-0.024,0.5,-0.00078,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.021,0.022,0.023,0.047,0.047,0.051,1.6e-06,2e-06,5.7e-06,0.029,0.03,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16490000,0.78,-0.016,0.00041,-0.63,-0.023,-0.014,-0.016,-0.0099,-0.0093,-3.7e+02,-0.0012,-0.006,6.2e-05,0.0024,-0.063,-0.13,-0.11,-0.024,0.5,-0.00079,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,2e-06,5.7e-06,0.029,0.03,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16590000,0.78,-0.016,0.00038,-0.63,-0.023,-0.01,-0.017,-0.01,-0.0055,-3.7e+02,-0.0012,-0.006,6.8e-05,0.0026,-0.063,-0.13,-0.11,-0.024,0.5,-0.00073,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.021,0.022,0.046,0.046,0.051,1.5e-06,1.9e-06,5.6e-06,0.029,0.03,0.002,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16690000,0.78,-0.016,0.00042,-0.63,-0.024,-0.011,-0.013,-0.013,-0.0064,-3.7e+02,-0.0012,-0.006,6.6e-05,0.0023,-0.063,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.022,0.022,0.022,0.05,0.051,0.051,1.5e-06,1.9e-06,5.6e-06,0.029,0.03,0.0019,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16790000,0.78,-0.016,0.00046,-0.63,-0.023,-0.0077,-0.012,-0.013,-0.0032,-3.7e+02,-0.0012,-0.006,7.2e-05,0.0024,-0.063,-0.13,-0.11,-0.024,0.5,-0.00068,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,5.6e-06,0.029,0.03,0.0018,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16890000,0.78,-0.016,0.00045,-0.63,-0.024,-0.0087,-0.0097,-0.015,-0.0039,-3.7e+02,-0.0012,-0.006,7.1e-05,0.0023,-0.063,-0.13,-0.11,-0.024,0.5,-0.0007,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.021,0.022,0.021,0.049,0.049,0.051,1.4e-06,1.8e-06,5.6e-06,0.029,0.03,0.0017,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
16990000,0.78,-0.016,0.0005,-0.63,-0.023,-0.0085,-0.0092,-0.013,-0.004,-3.7e+02,-0.0012,-0.006,6.8e-05,0.0021,-0.063,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,5.6e-06,0.029,0.029,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17090000,0.78,-0.016,0.00049,-0.63,-0.024,-0.01,-0.0092,-0.016,-0.0049,-3.7e+02,-0.0012,-0.006,6.9e-05,0.0021,-0.063,-0.13,-0.11,-0.024,0.5,-0.00072,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,5.6e-06,0.029,0.029,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17190000,0.78,-0.016,0.00043,-0.63,-0.023,-0.013,-0.01,-0.014,-0.0053,-3.7e+02,-0.0012,-0.006,7e-05,0.0022,-0.063,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.018,0.019,0.019,0.042,0.043,0.049,1.3e-06,1.7e-06,5.6e-06,0.029,0.029,0.0015,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17290000,0.78,-0.016,0.00047,-0.63,-0.026,-0.014,-0.0055,-0.016,-0.0063,-3.7e+02,-0.0012,-0.006,6.8e-05,0.0021,-0.063,-0.13,-0.11,-0.024,0.5,-0.00073,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.7e-06,5.6e-06,0.029,0.029,0.0014,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17390000,0.78,-0.016,0.0004,-0.63,-0.023,-0.015,-0.0036,-0.014,-0.0066,-3.7e+02,-0.0012,-0.006,7e-05,0.0022,-0.063,-0.13,-0.11,-0.024,0.5,-0.00072,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.6e-06,5.6e-06,0.029,0.029,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17490000,0.78,-0.016,0.00042,-0.63,-0.025,-0.016,-0.0019,-0.016,-0.0083,-3.7e+02,-0.0012,-0.006,7e-05,0.0022,-0.063,-0.13,-0.11,-0.024,0.5,-0.00072,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.02,0.018,0.046,0.046,0.049,1.2e-06,1.6e-06,5.6e-06,0.029,0.029,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
17590000,0.78,-0.016,0.00043,-0.63,-0.024,-0.016,0.0035,-0.014,-0.0081,-3.7e+02,-0.0012,-0.006,7.1e-05,0.0022,-0.063,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,5.6e-06,0.029,0.029,0.0012,0.0012,6e-05,0.0012,0.00065,0.0012,0.0012,1,1
17690000,0.78,-0.016,0.00045,-0.63,-0.025,-0.018,0.0029,-0.016,-0.0099,-3.7e+02,-0.0012,-0.006,7.2e-05,0.0023,-0.063,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.018,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.5e-06,5.6e-06,0.029,0.029,0.0012,0.0012,6e-05,0.0012,0.00065,0.0012,0.0012,1,1
17790000,0.78,-0.016,0.00041,-0.63,-0.023,-0.019,0.0016,-0.014,-0.011,-3.7e+02,-0.0013,-0.006,7.9e-05,0.0026,-0.063,-0.13,-0.11,-0.024,0.5,-0.00067,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.5e-06,5.6e-06,0.029,0.029,0.0011,0.0012,6e-05,0.0012,0.00065,0.0012,0.0012,1,1
17890000,0.78,-0.016,0.00039,-0.63,-0.026,-0.02,0.0017,-0.017,-0.013,-3.7e+02,-0.0012,-0.006,8e-05,0.0028,-0.063,-0.13,-0.11,-0.024,0.5,-0.00066,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.02,0.016,0.052,0.053,0.048,1.1e-06,1.5e-06,5.6e-06,0.029,0.029,0.0011,0.0012,6e-05,0.0012,0.00065,0.0012,0.0012,1,1
17990000,0.78,-0.016,0.00042,-0.63,-0.025,-0.018,0.0029,-0.015,-0.013,-3.7e+02,-0.0013,-0.006,8.1e-05,0.0027,-0.063,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,5.6e-06,0.029,0.029,0.001,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18090000,0.78,-0.016,0.00046,-0.63,-0.027,-0.018,0.0052,-0.018,-0.014,-3.7e+02,-0.0012,-0.006,7.8e-05,0.0025,-0.063,-0.13,-0.11,-0.024,0.5,-0.00066,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.4e-06,5.6e-06,0.029,0.029,0.00098,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18190000,0.78,-0.016,0.00047,-0.63,-0.023,-0.017,0.0065,-0.013,-0.011,-3.7e+02,-0.0013,-0.006,8.3e-05,0.0026,-0.063,-0.13,-0.11,-0.024,0.5,-0.00063,-0.091,-0.069,0,0,0.00035,0.00038,0.046,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.4e-06,5.5e-06,0.029,0.029,0.00092,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18290000,0.78,-0.016,0.00056,-0.63,-0.024,-0.017,0.0077,-0.016,-0.013,-3.7e+02,-0.0013,-0.006,8.1e-05,0.0025,-0.063,-0.13,-0.11,-0.024,0.5,-0.00063,-0.091,-0.069,0,0,0.00035,0.00038,0.046,0.019,0.02,0.015,0.056,0.056,0.046,1e-06,1.3e-06,5.5e-06,0.029,0.029,0.00089,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18390000,0.78,-0.016,0.00052,-0.63,-0.023,-0.018,0.0089,-0.012,-0.011,-3.7e+02,-0.0013,-0.006,8.8e-05,0.0026,-0.063,-0.13,-0.11,-0.024,0.5,-0.0006,-0.091,-0.069,0,0,0.00035,0.00038,0.046,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.3e-06,5.5e-06,0.029,0.029,0.00085,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18490000,0.78,-0.016,0.00048,-0.63,-0.024,-0.02,0.0085,-0.014,-0.013,-3.7e+02,-0.0013,-0.006,8.9e-05,0.0027,-0.063,-0.13,-0.11,-0.024,0.5,-0.0006,-0.091,-0.069,0,0,0.00035,0.00038,0.046,0.018,0.019,0.014,0.052,0.053,0.046,9.9e-07,1.3e-06,5.5e-06,0.029,0.029,0.00082,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18590000,0.78,-0.016,0.00047,-0.63,-0.022,-0.02,0.0066,-0.012,-0.011,-3.7e+02,-0.0013,-0.006,9.8e-05,0.0029,-0.063,-0.13,-0.11,-0.024,0.5,-0.00055,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.016,0.017,0.014,0.046,0.046,0.045,9.6e-07,1.3e-06,5.5e-06,0.029,0.029,0.00078,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18690000,0.78,-0.016,0.00053,-0.63,-0.024,-0.02,0.0047,-0.014,-0.013,-3.7e+02,-0.0013,-0.006,9.6e-05,0.0028,-0.063,-0.13,-0.11,-0.024,0.5,-0.00055,-0.091,-0.068,0,0,0.00035,0.00038,0.046,0.017,0.018,0.013,0.05,0.05,0.045,9.5e-07,1.2e-06,5.5e-06,0.029,0.029,0.00076,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18790000,0.78,-0.016,0.00055,-0.63,-0.022,-0.018,0.0044,-0.012,-0.011,-3.7e+02,-0.0013,-0.006,0.0001,0.0027,-0.063,-0.13,-0.11,-0.024,0.5,-0.00054,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.013,0.044,0.044,0.045,9.2e-07,1.2e-06,5.5e-06,0.029,0.029,0.00072,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18890000,0.78,-0.016,0.00047,-0.63,-0.022,-0.021,0.005,-0.014,-0.013,-3.7e+02,-0.0013,-0.006,0.0001,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.00053,-0.091,-0.068,0,0,0.00035,0.00038,0.046,0.016,0.017,0.013,0.048,0.048,0.045,9.1e-07,1.2e-06,5.5e-06,0.029,0.029,0.0007,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
18990000,0.78,-0.016,0.00041,-0.63,-0.018,-0.021,0.0036,-0.0097,-0.012,-3.7e+02,-0.0013,-0.006,0.00011,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.0005,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.012,0.042,0.043,0.044,8.8e-07,1.2e-06,5.5e-06,0.029,0.029,0.00067,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19090000,0.78,-0.016,0.0004,-0.63,-0.018,-0.022,0.0066,-0.011,-0.014,-3.7e+02,-0.0013,-0.006,0.00011,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.0005,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.016,0.017,0.012,0.046,0.047,0.044,8.7e-07,1.2e-06,5.5e-06,0.029,0.029,0.00065,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19190000,0.78,-0.015,0.00036,-0.63,-0.015,-0.021,0.0066,-0.0076,-0.012,-3.7e+02,-0.0013,-0.006,0.00012,0.0031,-0.063,-0.13,-0.11,-0.024,0.5,-0.00047,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.012,0.041,0.042,0.044,8.5e-07,1.1e-06,5.4e-06,0.029,0.029,0.00062,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19290000,0.78,-0.015,0.00036,-0.63,-0.016,-0.021,0.0093,-0.0093,-0.014,-3.7e+02,-0.0013,-0.006,0.00012,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.00048,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.012,0.045,0.046,0.044,8.4e-07,1.1e-06,5.4e-06,0.029,0.029,0.00061,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19390000,0.78,-0.015,0.00039,-0.63,-0.015,-0.02,0.013,-0.0084,-0.012,-3.7e+02,-0.0013,-0.006,0.00012,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.00044,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.012,0.04,0.041,0.043,8.2e-07,1.1e-06,5.4e-06,0.029,0.029,0.00058,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19490000,0.78,-0.015,0.00034,-0.63,-0.015,-0.021,0.0095,-0.0099,-0.015,-3.7e+02,-0.0013,-0.006,0.00013,0.0032,-0.063,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.011,0.044,0.045,0.043,8.1e-07,1.1e-06,5.4e-06,0.029,0.029,0.00057,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19590000,0.78,-0.015,0.0003,-0.63,-0.013,-0.019,0.0088,-0.0084,-0.013,-3.7e+02,-0.0013,-0.006,0.00014,0.0033,-0.063,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.011,0.04,0.04,0.042,7.8e-07,1e-06,5.4e-06,0.029,0.029,0.00054,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19690000,0.78,-0.015,0.00028,-0.63,-0.013,-0.018,0.01,-0.0093,-0.015,-3.7e+02,-0.0013,-0.006,0.00014,0.0032,-0.063,-0.13,-0.11,-0.024,0.5,-0.0004,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.011,0.043,0.044,0.042,7.7e-07,1e-06,5.4e-06,0.029,0.029,0.00053,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19790000,0.78,-0.015,0.00024,-0.63,-0.012,-0.015,0.011,-0.0079,-0.013,-3.7e+02,-0.0013,-0.006,0.00014,0.0032,-0.063,-0.13,-0.11,-0.024,0.5,-0.00037,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.011,0.039,0.039,0.042,7.6e-07,1e-06,5.3e-06,0.029,0.029,0.00051,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19890000,0.78,-0.015,0.00028,-0.63,-0.011,-0.017,0.012,-0.0095,-0.015,-3.7e+02,-0.0013,-0.006,0.00015,0.0034,-0.063,-0.13,-0.11,-0.024,0.5,-0.00035,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.011,0.043,0.043,0.042,7.5e-07,1e-06,5.3e-06,0.029,0.029,0.0005,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
19990000,0.78,-0.015,0.00028,-0.63,-0.0095,-0.016,0.015,-0.0083,-0.014,-3.7e+02,-0.0013,-0.006,0.00017,0.0037,-0.063,-0.13,-0.11,-0.024,0.5,-0.00031,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.01,0.038,0.039,0.041,7.3e-07,9.7e-07,5.3e-06,0.029,0.029,0.00048,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
20090000,0.78,-0.015,0.00024,-0.63,-0.0095,-0.017,0.015,-0.009,-0.017,-3.7e+02,-0.0013,-0.0059,0.00018,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-0.0003,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.01,0.042,0.043,0.042,7.2e-07,9.7e-07,5.3e-06,0.029,0.029,0.00047,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
20190000,0.78,-0.015,0.0002,-0.63,-0.01,-0.016,0.017,-0.0092,-0.015,-3.7e+02,-0.0013,-0.0059,0.00019,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-0.00026,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.01,0.038,0.039,0.041,7e-07,9.4e-07,5.3e-06,0.029,0.029,0.00045,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
20290000,0.78,-0.015,0.00021,-0.63,-0.0088,-0.015,0.015,-0.0097,-0.017,-3.7e+02,-0.0013,-0.0059,0.00019,0.0041,-0.063,-0.13,-0.11,-0.024,0.5,-0.00026,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.0099,0.042,0.042,0.041,6.9e-07,9.3e-07,5.3e-06,0.029,0.029,0.00044,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
20390000,0.78,-0.015,0.00025,-0.63,-0.0084,-0.013,0.017,-0.0095,-0.015,-3.7e+02,-0.0013,-0.0059,0.0002,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-0.00022,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,9.1e-07,5.2e-06,0.029,0.029,0.00043,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20490000,0.78,-0.015,0.00021,-0.63,-0.0086,-0.013,0.017,-0.01,-0.016,-3.7e+02,-0.0013,-0.006,0.00019,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-0.00023,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0096,0.041,0.042,0.041,6.7e-07,9e-07,5.2e-06,0.029,0.029,0.00042,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20590000,0.78,-0.015,0.0002,-0.63,-0.0081,-0.011,0.014,-0.0089,-0.014,-3.7e+02,-0.0013,-0.006,0.0002,0.0038,-0.063,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0093,0.037,0.038,0.04,6.5e-07,8.7e-07,5.2e-06,0.029,0.029,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20690000,0.78,-0.015,0.00017,-0.63,-0.0089,-0.011,0.015,-0.0098,-0.015,-3.7e+02,-0.0013,-0.006,0.0002,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0093,0.041,0.042,0.04,6.4e-07,8.7e-07,5.2e-06,0.029,0.029,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20790000,0.78,-0.015,0.00014,-0.63,-0.0065,-0.0099,0.015,-0.0082,-0.013,-3.7e+02,-0.0013,-0.006,0.00021,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0091,0.037,0.038,0.04,6.3e-07,8.4e-07,5.1e-06,0.029,0.029,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20890000,0.78,-0.015,0.00013,-0.63,-0.0068,-0.0097,0.015,-0.0088,-0.015,-3.7e+02,-0.0013,-0.006,0.00021,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.009,0.041,0.041,0.04,6.2e-07,8.4e-07,5.1e-06,0.029,0.029,0.00037,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
20990000,0.78,-0.015,0.00011,-0.63,-0.0052,-0.0078,0.015,-0.0085,-0.015,-3.7e+02,-0.0014,-0.006,0.00022,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0088,0.043,0.044,0.039,6.1e-07,8.2e-07,5.1e-06,0.029,0.029,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21090000,0.78,-0.015,0.00011,-0.63,-0.0063,-0.0073,0.016,-0.0095,-0.016,-3.7e+02,-0.0013,-0.0059,0.00022,0.0041,-0.063,-0.13,-0.11,-0.024,0.5,-0.00017,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0088,0.047,0.048,0.039,6e-07,8.2e-07,5.1e-06,0.029,0.029,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21190000,0.78,-0.015,0.0001,-0.63,-0.0064,-0.007,0.015,-0.01,-0.016,-3.7e+02,-0.0013,-0.006,0.00022,0.0041,-0.063,-0.13,-0.11,-0.024,0.5,-0.00016,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0086,0.049,0.05,0.039,5.9e-07,8e-07,5.1e-06,0.029,0.029,0.00035,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21290000,0.78,-0.015,1.4e-05,-0.63,-0.006,-0.0072,0.017,-0.01,-0.018,-3.7e+02,-0.0013,-0.0059,0.00023,0.0042,-0.063,-0.13,-0.11,-0.024,0.5,-0.00016,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.016,0.017,0.0085,0.053,0.055,0.039,5.9e-07,7.9e-07,5.1e-06,0.029,0.029,0.00034,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21390000,0.78,-0.015,5.9e-05,-0.63,-0.0053,-0.003,0.016,-0.0088,-0.013,-3.7e+02,-0.0013,-0.006,0.00024,0.0041,-0.063,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.0084,0.046,0.047,0.039,5.7e-07,7.7e-07,5e-06,0.029,0.029,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21490000,0.78,-0.015,5.1e-05,-0.63,-0.006,-0.0037,0.016,-0.0099,-0.014,-3.7e+02,-0.0013,-0.0059,0.00024,0.0042,-0.063,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.017,0.0083,0.05,0.052,0.038,5.6e-07,7.6e-07,5e-06,0.029,0.029,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21590000,0.78,-0.015,8.7e-05,-0.63,-0.0046,-0.0023,0.016,-0.0083,-0.011,-3.7e+02,-0.0013,-0.006,0.00025,0.0041,-0.063,-0.13,-0.11,-0.024,0.5,-0.00011,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.0081,0.044,0.045,0.038,5.5e-07,7.4e-07,5e-06,0.029,0.029,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21690000,0.78,-0.015,8.1e-05,-0.63,-0.0062,-0.003,0.017,-0.0096,-0.012,-3.7e+02,-0.0013,-0.0059,0.00025,0.0042,-0.063,-0.13,-0.11,-0.024,0.5,-0.0001,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.0081,0.048,0.049,0.038,5.5e-07,7.4e-07,5e-06,0.029,0.029,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
21790000,0.78,-0.015,0.00017,-0.63,-0.0053,-0.001,0.016,-0.0084,-0.0066,-3.7e+02,-0.0013,-0.006,0.00026,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-6.7e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.008,0.042,0.043,0.038,5.3e-07,7.1e-07,4.9e-06,0.029,0.029,0.0003,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
21890000,0.78,-0.015,0.00018,-0.63,-0.0059,-0.0016,0.016,-0.0091,-0.0069,-3.7e+02,-0.0013,-0.006,0.00026,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-6.4e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,7.1e-07,4.9e-06,0.029,0.029,0.0003,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
21990000,0.78,-0.015,0.00021,-0.63,-0.0058,0.001,0.017,-0.0085,-0.0033,-3.7e+02,-0.0013,-0.006,0.00027,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-3.4e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0078,0.041,0.042,0.038,5.2e-07,6.9e-07,4.8e-06,0.029,0.029,0.00029,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22090000,0.78,-0.015,0.00019,-0.63,-0.0055,-0.00036,0.015,-0.0089,-0.0032,-3.7e+02,-0.0013,-0.006,0.00027,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-3.4e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.0078,0.044,0.046,0.037,5.1e-07,6.9e-07,4.8e-06,0.029,0.029,0.00029,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22190000,0.78,-0.015,0.00021,-0.63,-0.0042,-0.0012,0.016,-0.0075,-0.003,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-2.8e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.046,0.012,0.014,0.0076,0.04,0.041,0.037,5e-07,6.7e-07,4.8e-06,0.029,0.029,0.00028,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22290000,0.78,-0.015,0.00018,-0.63,-0.0038,-0.00059,0.016,-0.0082,-0.0029,-3.7e+02,-0.0013,-0.006,0.00027,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-2.8e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.047,0.013,0.015,0.0076,0.043,0.045,0.037,5e-07,6.7e-07,4.8e-06,0.029,0.029,0.00028,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22390000,0.78,-0.015,0.00017,-0.63,-0.0013,-0.00078,0.017,-0.0064,-0.0026,-3.7e+02,-0.0014,-0.006,0.00028,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-3.2e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.012,0.014,0.0075,0.039,0.04,0.037,4.9e-07,6.5e-07,4.7e-06,0.029,0.029,0.00027,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22490000,0.78,-0.015,0.00015,-0.63,-0.00017,-0.0012,0.018,-0.0058,-0.0026,-3.7e+02,-0.0014,-0.006,0.00028,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-3.3e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.013,0.015,0.0074,0.042,0.044,0.037,4.8e-07,6.5e-07,4.7e-06,0.029,0.029,0.00027,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22590000,0.78,-0.015,0.00014,-0.63,0.0017,-0.0001,0.018,-0.0041,-0.0018,-3.7e+02,-0.0014,-0.006,0.00028,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-3.1e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.013,0.015,0.0073,0.045,0.046,0.036,4.8e-07,6.3e-07,4.7e-06,0.029,0.029,0.00026,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22690000,0.78,-0.015,8.2e-05,-0.63,0.0032,-0.0012,0.019,-0.0035,-0.0023,-3.7e+02,-0.0014,-0.006,0.00029,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-3.1e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.047,0.014,0.016,0.0073,0.048,0.05,0.036,4.7e-07,6.3e-07,4.7e-06,0.029,0.029,0.00026,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22790000,0.78,-0.015,0.00012,-0.63,0.0042,-0.00062,0.02,-0.0029,-0.001,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-4.1e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.014,0.016,0.0072,0.051,0.053,0.036,4.6e-07,6.2e-07,4.7e-06,0.029,0.029,0.00025,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22890000,0.78,-0.015,0.00013,-0.63,0.0049,-0.0013,0.021,-0.0031,-0.0012,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-3.5e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.047,0.015,0.017,0.0072,0.055,0.057,0.036,4.6e-07,6.2e-07,4.7e-06,0.029,0.029,0.00025,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
22990000,0.78,-0.015,0.00014,-0.63,0.0046,-0.0014,0.022,-0.0033,-0.0019,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-2.9e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.015,0.017,0.0071,0.057,0.06,0.036,4.5e-07,6.1e-07,4.6e-06,0.029,0.029,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23090000,0.78,-0.015,0.0002,-0.63,0.0048,-0.00096,0.023,-0.003,-0.0012,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-2.7e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.016,0.018,0.007,0.062,0.065,0.036,4.5e-07,6e-07,4.6e-06,0.029,0.029,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23190000,0.78,-0.015,0.00018,-0.63,0.0024,0.00015,0.024,-0.0058,-0.0011,-3.7e+02,-0.0014,-0.006,0.00028,0.0038,-0.063,-0.13,-0.11,-0.024,0.5,-1e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.015,0.018,0.0069,0.064,0.067,0.035,4.4e-07,5.9e-07,4.6e-06,0.029,0.029,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23290000,0.78,-0.015,0.00025,-0.63,0.002,0.00067,0.025,-0.0061,-0.0014,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-6.5e-06,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.016,0.019,0.0069,0.07,0.073,0.036,4.4e-07,5.9e-07,4.6e-06,0.029,0.029,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23390000,0.78,-0.015,0.00022,-0.63,-0.0013,0.00086,0.022,-0.01,-0.0015,-3.7e+02,-0.0014,-0.006,0.00028,0.0038,-0.063,-0.13,-0.11,-0.024,0.5,7.1e-06,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.016,0.018,0.0068,0.072,0.075,0.035,4.3e-07,5.8e-07,4.5e-06,0.029,0.029,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23490000,0.78,-0.012,-0.0019,-0.63,0.0041,0.0017,-0.011,-0.011,-0.0023,-3.7e+02,-0.0014,-0.006,0.00029,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,1.3e-06,-0.091,-0.068,0,0,0.00034,0.00036,0.047,0.017,0.02,0.0068,0.078,0.082,0.035,4.3e-07,5.8e-07,4.5e-06,0.029,0.029,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
23590000,0.78,-0.0041,-0.0062,-0.63,0.015,0.0051,-0.043,-0.01,-0.00031,-3.7e+02,-0.0013,-0.006,0.00029,0.0039,-0.064,-0.13,-0.11,-0.024,0.5,5.1e-06,-0.091,-0.068,0,0,0.00034,0.00033,0.047,0.014,0.016,0.0067,0.062,0.064,0.035,4.2e-07,5.5e-07,4.4e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23690000,0.78,0.0016,-0.0052,-0.63,0.042,0.019,-0.093,-0.0078,0.0005,-3.7e+02,-0.0013,-0.006,0.00029,0.004,-0.064,-0.13,-0.11,-0.024,0.5,-5.7e-05,-0.091,-0.068,0,0,0.00033,0.00033,0.047,0.015,0.017,0.0067,0.066,0.069,0.035,4.2e-07,5.5e-07,4.4e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23790000,0.78,-0.0021,-0.0027,-0.63,0.063,0.036,-0.15,-0.0076,0.0013,-3.7e+02,-0.0013,-0.006,0.0003,0.0042,-0.064,-0.13,-0.11,-0.024,0.5,-0.00016,-0.09,-0.067,0,0,0.00033,0.00033,0.047,0.013,0.015,0.0066,0.055,0.057,0.035,4.1e-07,5.3e-07,4.4e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23890000,0.78,-0.0084,-0.00069,-0.63,0.077,0.048,-0.2,-0.00014,0.0056,-3.7e+02,-0.0013,-0.006,0.0003,0.0043,-0.064,-0.13,-0.11,-0.024,0.5,-0.00021,-0.09,-0.067,0,0,0.00033,0.00034,0.047,0.014,0.016,0.0066,0.059,0.061,0.035,4.1e-07,5.3e-07,4.3e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
23990000,0.78,-0.013,0.00022,-0.63,0.072,0.048,-0.25,-0.0055,0.0042,-3.7e+02,-0.0013,-0.006,0.0003,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.09,-0.067,0,0,0.00034,0.00036,0.047,0.014,0.016,0.0066,0.061,0.064,0.035,4e-07,5.2e-07,4.3e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
24090000,0.78,-0.012,-0.00092,-0.63,0.072,0.047,-0.3,0.00074,0.0082,-3.7e+02,-0.0013,-0.006,0.0003,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.09,-0.067,0,0,0.00034,0.00035,0.047,0.015,0.017,0.0065,0.066,0.069,0.035,4e-07,5.2e-07,4.3e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
24190000,0.78,-0.0095,-0.0017,-0.63,0.069,0.046,-0.35,-0.0064,0.006,-3.7e+02,-0.0013,-0.0059,0.00029,0.0049,-0.066,-0.13,-0.11,-0.024,0.5,-0.00023,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.015,0.017,0.0065,0.068,0.071,0.034,3.9e-07,5.1e-07,4.3e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.00063,0.0012,0.0012,1,1
24290000,0.78,-0.0087,-0.0021,-0.63,0.077,0.052,-0.4,-4.6e-05,0.011,-3.7e+02,-0.0013,-0.006,0.00029,0.005,-0.066,-0.13,-0.11,-0.024,0.5,-0.00024,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.016,0.019,0.0065,0.074,0.077,0.034,3.9e-07,5.1e-07,4.3e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.00063,0.0012,0.0012,1,1
24390000,0.78,-0.0091,-0.0022,-0.63,0.074,0.05,-0.46,-0.012,0.0043,-3.7e+02,-0.0013,-0.0059,0.00026,0.0056,-0.067,-0.13,-0.11,-0.024,0.5,-0.00024,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.016,0.018,0.0064,0.076,0.079,0.034,3.9e-07,5e-07,4.2e-06,0.029,0.029,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24490000,0.78,-0.0049,-0.0026,-0.63,0.085,0.057,-0.51,-0.0043,0.0096,-3.7e+02,-0.0013,-0.0059,0.00026,0.0057,-0.067,-0.13,-0.11,-0.024,0.5,-0.00026,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.017,0.02,0.0064,0.082,0.086,0.034,3.9e-07,5e-07,4.2e-06,0.029,0.029,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24590000,0.78,-0.0014,-0.0027,-0.63,0.089,0.061,-0.56,-0.018,0.00042,-3.7e+02,-0.0012,-0.0059,0.00024,0.0063,-0.068,-0.13,-0.11,-0.024,0.5,-0.00033,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.017,0.019,0.0063,0.084,0.088,0.034,3.8e-07,4.9e-07,4.2e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24690000,0.78,-0.00055,-0.0027,-0.63,0.11,0.077,-0.64,-0.0084,0.0062,-3.7e+02,-0.0012,-0.0059,0.00025,0.0065,-0.069,-0.13,-0.11,-0.024,0.5,-0.0005,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.018,0.021,0.0063,0.09,0.095,0.034,3.8e-07,4.9e-07,4.2e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
24790000,0.78,-0.0021,-0.0024,-0.63,0.11,0.086,-0.73,-0.028,0.0011,-3.7e+02,-0.0012,-0.0059,0.00023,0.0072,-0.071,-0.13,-0.11,-0.025,0.5,-0.00035,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.018,0.021,0.0062,0.092,0.097,0.034,3.7e-07,4.8e-07,4.1e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1
24890000,0.78,-0.00027,-0.004,-0.63,0.13,0.1,-0.75,-0.016,0.01,-3.7e+02,-0.0012,-0.0059,0.00022,0.0075,-0.071,-0.13,-0.11,-0.025,0.5,-0.00043,-0.088,-0.068,0,0,0.00033,0.00033,0.046,0.019,0.022,0.0062,0.099,0.1,0.034,3.7e-07,4.8e-07,4.1e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1
24990000,0.78,0.0014,-0.0056,-0.63,0.13,0.11,-0.81,-0.038,0.0037,-3.7e+02,-0.0012,-0.0059,0.00019,0.0086,-0.073,-0.13,-0.11,-0.025,0.5,-0.00026,-0.087,-0.069,0,0,0.00033,0.00033,0.045,0.019,0.022,0.0062,0.1,0.11,0.034,3.7e-07,4.7e-07,4.1e-06,0.029,0.029,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1
25090000,0.78,0.00082,-0.0059,-0.63,0.16,0.12,-0.86,-0.024,0.016,-3.7e+02,-0.0012,-0.0059,0.00018,0.0087,-0.074,-0.13,-0.11,-0.025,0.5,-0.00026,-0.087,-0.068,0,0,0.00033,0.00033,0.045,0.02,0.023,0.0062,0.11,0.11,0.034,3.7e-07,4.7e-07,4.1e-06,0.029,0.029,0.00018,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1
25190000,0.78,-0.0013,-0.0055,-0.63,0.15,0.12,-0.91,-0.067,-0.0074,-3.7e+02,-0.0011,-0.0059,0.00013,0.011,-0.078,-0.13,-0.11,-0.025,0.5,-0.00027,-0.086,-0.069,0,0,0.00033,0.00033,0.044,0.019,0.023,0.0061,0.11,0.12,0.033,3.6e-07,4.6e-07,4e-06,0.029,0.029,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1
25290000,0.78,0.0057,-0.0066,-0.63,0.18,0.13,-0.96,-0.051,0.0044,-3.7e+02,-0.0011,-0.0059,0.00013,0.011,-0.078,-0.13,-0.11,-0.025,0.5,-0.00038,-0.086,-0.069,0,0,0.00032,0.00033,0.044,0.021,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.6e-07,4e-06,0.029,0.029,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1
25390000,0.78,0.012,-0.0071,-0.63,0.18,0.13,-1,-0.098,-0.02,-3.7e+02,-0.001,-0.0058,8.8e-05,0.013,-0.083,-0.13,-0.11,-0.025,0.5,-0.00046,-0.085,-0.069,0,0,0.00032,0.00035,0.043,0.02,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.5e-07,4e-06,0.029,0.029,0.00018,0.0011,5.4e-05,0.0012,0.00059,0.0011,0.0012,1,1
25490000,0.78,0.013,-0.0072,-0.63,0.22,0.16,-1.1,-0.079,-0.0069,-3.7e+02,-0.001,-0.0058,0.0001,0.013,-0.083,-0.13,-0.12,-0.025,0.5,-0.00079,-0.084,-0.069,0,0,0.00032,0.00035,0.043,0.022,0.026,0.0061,0.13,0.13,0.033,3.5e-07,4.5e-07,4e-06,0.029,0.029,0.00018,0.0011,5.3e-05,0.0012,0.00058,0.0011,0.0012,1,1
25590000,0.78,0.011,-0.0071,-0.63,0.25,0.19,-1.1,-0.057,0.0099,-3.7e+02,-0.001,-0.0058,0.00011,0.013,-0.084,-0.13,-0.12,-0.025,0.5,-0.001,-0.084,-0.068,0,0,0.00032,0.00034,0.043,0.023,0.028,0.0061,0.14,0.14,0.033,3.5e-07,4.5e-07,4e-06,0.029,0.029,0.00018,0.0011,5.3e-05,0.0011,0.00058,0.0011,0.0011,1,1
25690000,0.78,0.018,-0.0099,-0.63,0.3,0.22,-1.2,-0.03,0.029,-3.7e+02,-0.001,-0.0058,0.00012,0.014,-0.084,-0.13,-0.12,-0.026,0.5,-0.0014,-0.083,-0.067,0,0,0.00032,0.00038,0.042,0.025,0.03,0.0061,0.14,0.15,0.033,3.5e-07,4.5e-07,3.9e-06,0.029,0.029,0.00017,0.001,5.2e-05,0.0011,0.00058,0.0011,0.0011,1,1
25790000,0.78,0.024,-0.012,-0.63,0.35,0.25,-1.2,0.0026,0.049,-3.7e+02,-0.001,-0.0058,0.00015,0.014,-0.085,-0.13,-0.12,-0.026,0.5,-0.0019,-0.081,-0.067,0,0,0.00033,0.00042,0.042,0.027,0.033,0.0061,0.15,0.16,0.033,3.5e-07,4.5e-07,3.9e-06,0.029,0.029,0.00017,0.001,5.1e-05,0.0011,0.00057,0.0011,0.0011,1,1
25890000,0.77,0.025,-0.012,-0.63,0.41,0.29,-1.3,0.042,0.073,-3.7e+02,-0.001,-0.0058,0.00017,0.014,-0.085,-0.13,-0.12,-0.026,0.5,-0.0026,-0.08,-0.066,0,0,0.00033,0.00043,0.041,0.029,0.037,0.0061,0.16,0.18,0.033,3.5e-07,4.6e-07,3.9e-06,0.029,0.029,0.00017,0.001,5.1e-05,0.0011,0.00056,0.0011,0.0011,1,1
25990000,0.77,0.022,-0.012,-0.63,0.47,0.32,-1.3,0.086,0.1,-3.7e+02,-0.001,-0.0058,0.00019,0.014,-0.085,-0.13,-0.12,-0.027,0.5,-0.0029,-0.079,-0.065,0,0,0.00033,0.0004,0.04,0.031,0.04,0.0061,0.18,0.19,0.033,3.5e-07,4.6e-07,3.9e-06,0.029,0.029,0.00017,0.00099,5e-05,0.0011,0.00055,0.001,0.0011,1,1
26090000,0.78,0.032,-0.016,-0.63,0.53,0.36,-1.3,0.13,0.14,-3.7e+02,-0.001,-0.0058,0.00017,0.015,-0.086,-0.13,-0.12,-0.027,0.5,-0.0028,-0.077,-0.065,0,0,0.00033,0.00049,0.039,0.033,0.043,0.0061,0.19,0.2,0.033,3.5e-07,4.6e-07,3.9e-06,0.029,0.029,0.00017,0.00097,4.9e-05,0.0011,0.00054,0.001,0.0011,1,1
26190000,0.78,0.042,-0.017,-0.63,0.6,0.4,-1.3,0.19,0.17,-3.7e+02,-0.00099,-0.0058,0.00018,0.017,-0.087,-0.13,-0.13,-0.028,0.5,-0.0034,-0.074,-0.062,0,0,0.00035,0.00057,0.038,0.036,0.047,0.0061,0.2,0.22,0.033,3.5e-07,4.6e-07,3.8e-06,0.029,0.029,0.00017,0.00094,4.7e-05,0.001,0.00053,0.00098,0.001,1,1
26290000,0.77,0.044,-0.018,-0.63,0.68,0.46,-1.3,0.25,0.21,-3.7e+02,-0.00098,-0.0058,0.00018,0.018,-0.087,-0.13,-0.13,-0.028,0.49,-0.0037,-0.071,-0.061,0,0,0.00035,0.00059,0.036,0.038,0.052,0.0061,0.21,0.23,0.033,3.5e-07,4.6e-07,3.8e-06,0.029,0.029,0.00016,0.00091,4.6e-05,0.001,0.00052,0.00095,0.001,1,1
26390000,0.77,0.04,-0.018,-0.63,0.76,0.51,-1.3,0.32,0.26,-3.7e+02,-0.00098,-0.0058,0.00018,0.018,-0.088,-0.13,-0.13,-0.028,0.49,-0.0041,-0.07,-0.06,0,0,0.00034,0.00054,0.035,0.041,0.056,0.0061,0.23,0.25,0.033,3.6e-07,4.6e-07,3.8e-06,0.029,0.029,0.00016,0.00088,4.4e-05,0.00098,0.0005,0.00091,0.00098,1,1
26490000,0.77,0.057,-0.024,-0.63,0.84,0.56,-1.3,0.4,0.31,-3.7e+02,-0.00098,-0.0058,0.00018,0.019,-0.088,-0.13,-0.13,-0.029,0.49,-0.0043,-0.068,-0.058,0,0,0.00037,0.00074,0.033,0.044,0.061,0.0061,0.24,0.27,0.033,3.6e-07,4.6e-07,3.8e-06,0.029,0.029,0.00016,0.00084,4.2e-05,0.00094,0.00048,0.00088,0.00094,1,1
26590000,0.77,0.074,-0.029,-0.63,0.96,0.64,-1.3,0.49,0.38,-3.7e+02,-0.00097,-0.0058,0.00015,0.021,-0.089,-0.13,-0.13,-0.03,0.49,-0.0038,-0.064,-0.056,0,0,0.0004,0.00097,0.031,0.047,0.067,0.0061,0.26,0.29,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.0008,4e-05,0.00089,0.00046,0.00083,0.00089,1,1
26690000,0.77,0.076,-0.03,-0.64,1.1,0.71,-1.3,0.59,0.44,-3.7e+02,-0.00097,-0.0058,0.00016,0.023,-0.09,-0.13,-0.14,-0.031,0.49,-0.0048,-0.059,-0.052,0,0,0.0004,0.00097,0.029,0.051,0.074,0.0061,0.28,0.31,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.00074,3.8e-05,0.00083,0.00044,0.00077,0.00083,1,1
26790000,0.77,0.071,-0.029,-0.64,1.2,0.8,-1.3,0.7,0.51,-3.7e+02,-0.00096,-0.0058,0.00014,0.024,-0.089,-0.13,-0.14,-0.032,0.48,-0.0046,-0.056,-0.049,0,0,0.00038,0.00084,0.026,0.054,0.079,0.0061,0.29,0.33,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.0007,3.6e-05,0.00079,0.00041,0.00073,0.00078,1,1
26890000,0.76,0.093,-0.036,-0.64,1.4,0.87,-1.3,0.83,0.59,-3.7e+02,-0.00096,-0.0058,0.00015,0.025,-0.089,-0.13,-0.15,-0.032,0.48,-0.0051,-0.052,-0.047,0,0,0.00043,0.0011,0.024,0.057,0.085,0.0061,0.31,0.35,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.00066,3.4e-05,0.00074,0.00039,0.00068,0.00074,1,1
26990000,0.76,0.12,-0.041,-0.64,1.5,0.98,-1.3,0.98,0.69,-3.7e+02,-0.00096,-0.0059,0.00013,0.027,-0.09,-0.13,-0.15,-0.034,0.48,-0.0054,-0.046,-0.043,0,0,0.00048,0.0014,0.021,0.06,0.092,0.0061,0.33,0.38,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.0006,3.1e-05,0.00067,0.00036,0.00062,0.00067,1,1
27090000,0.76,0.12,-0.042,-0.64,1.7,1.1,-1.2,1.1,0.79,-3.7e+02,-0.00096,-0.0059,0.00011,0.029,-0.09,-0.13,-0.16,-0.035,0.47,-0.0054,-0.041,-0.038,0,0,0.00048,0.0013,0.019,0.064,0.098,0.0061,0.36,0.4,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00055,2.8e-05,0.0006,0.00033,0.00056,0.0006,1,1
27190000,0.76,0.11,-0.039,-0.64,1.9,1.2,-1.2,1.3,0.92,-3.7e+02,-0.00097,-0.0059,9.3e-05,0.03,-0.089,-0.13,-0.16,-0.035,0.47,-0.0051,-0.038,-0.035,0,0,0.00044,0.0011,0.017,0.067,0.1,0.0062,0.38,0.43,0.034,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00051,2.6e-05,0.00056,0.00031,0.00052,0.00056,1,1
27290000,0.76,0.093,-0.035,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00097,-0.0059,8.5e-05,0.031,-0.087,-0.13,-0.16,-0.036,0.47,-0.0053,-0.035,-0.033,0,0,0.0004,0.00083,0.015,0.069,0.11,0.0062,0.4,0.46,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00048,2.5e-05,0.00053,0.00029,0.00049,0.00052,1,1
27390000,0.76,0.077,-0.03,-0.64,2.2,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00097,-0.0059,7.9e-05,0.032,-0.085,-0.13,-0.17,-0.036,0.47,-0.0053,-0.033,-0.032,0,0,0.00037,0.00064,0.014,0.07,0.11,0.0062,0.43,0.49,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00046,2.4e-05,0.00051,0.00027,0.00047,0.00051,1,1
27490000,0.76,0.062,-0.025,-0.64,2.2,1.5,-1.2,1.9,1.3,-3.7e+02,-0.00097,-0.0059,7e-05,0.032,-0.083,-0.13,-0.17,-0.037,0.47,-0.005,-0.032,-0.031,0,0,0.00035,0.00051,0.013,0.071,0.11,0.0062,0.45,0.52,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00044,2.3e-05,0.0005,0.00025,0.00046,0.0005,1,1
27590000,0.77,0.049,-0.022,-0.64,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00096,-0.0059,5.9e-05,0.032,-0.081,-0.13,-0.17,-0.037,0.47,-0.0046,-0.031,-0.031,0,0,0.00034,0.00044,0.012,0.072,0.11,0.0062,0.48,0.56,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00043,2.3e-05,0.00049,0.00024,0.00045,0.00049,1,1
27690000,0.77,0.047,-0.021,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00096,-0.0059,4.8e-05,0.033,-0.079,-0.13,-0.17,-0.037,0.47,-0.0043,-0.031,-0.031,0,0,0.00034,0.00043,0.011,0.072,0.11,0.0063,0.51,0.59,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00043,2.2e-05,0.00049,0.00023,0.00045,0.00049,1,1
27790000,0.77,0.049,-0.021,-0.64,2.3,1.6,-1.2,2.6,1.8,-3.7e+02,-0.00097,-0.0059,3.3e-05,0.033,-0.078,-0.13,-0.17,-0.037,0.47,-0.0038,-0.03,-0.03,0,0,0.00034,0.00043,0.0099,0.073,0.11,0.0063,0.54,0.63,0.033,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00015,0.00042,2.2e-05,0.00048,0.00022,0.00044,0.00048,1,1
27890000,0.77,0.047,-0.021,-0.64,2.4,1.6,-1.2,2.8,2,-3.7e+02,-0.00096,-0.0059,3.2e-05,0.033,-0.076,-0.13,-0.17,-0.037,0.47,-0.0038,-0.03,-0.03,0,0,0.00034,0.00042,0.0093,0.074,0.11,0.0063,0.57,0.67,0.034,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.00041,2.2e-05,0.00048,0.00022,0.00043,0.00048,1,1
27990000,0.77,0.043,-0.02,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00097,-0.0059,2.9e-05,0.033,-0.075,-0.13,-0.17,-0.037,0.47,-0.0038,-0.03,-0.03,0,0,0.00034,0.0004,0.0087,0.075,0.11,0.0064,0.61,0.71,0.033,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.00041,2.1e-05,0.00048,0.00021,0.00043,0.00048,1,1
28090000,0.77,0.057,-0.025,-0.64,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00096,-0.0059,1.6e-05,0.034,-0.073,-0.13,-0.17,-0.038,0.47,-0.0033,-0.029,-0.03,0,0,0.00034,0.00044,0.0082,0.076,0.11,0.0064,0.64,0.75,0.033,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.0004,2.1e-05,0.00048,0.0002,0.00042,0.00047,1,1
28190000,0.77,0.071,-0.028,-0.63,2.5,1.7,-0.93,3.6,2.5,-3.7e+02,-0.00096,-0.0059,1.4e-05,0.033,-0.071,-0.13,-0.17,-0.038,0.46,-0.0033,-0.029,-0.03,0,0,0.00035,0.00048,0.0077,0.077,0.11,0.0065,0.68,0.8,0.034,3.7e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.00039,2.1e-05,0.00047,0.0002,0.00042,0.00047,1,1
28290000,0.77,0.053,-0.022,-0.64,2.5,1.7,-0.065,3.8,2.6,-3.7e+02,-0.00096,-0.0059,3.6e-06,0.034,-0.068,-0.13,-0.17,-0.038,0.46,-0.0031,-0.028,-0.029,0,0,0.00034,0.00042,0.0074,0.076,0.1,0.0065,0.72,0.85,0.034,3.7e-07,4.8e-07,3.6e-06,0.028,0.029,0.00014,0.00038,2e-05,0.00046,0.0002,0.00041,0.00046,1,1
28390000,0.77,0.021,-0.0094,-0.64,2.5,1.7,0.79,4,2.8,-3.7e+02,-0.00096,-0.0059,-5.4e-06,0.034,-0.065,-0.13,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00033,0.00036,0.0071,0.075,0.1,0.0066,0.75,0.89,0.033,3.7e-07,4.8e-07,3.6e-06,0.028,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.0004,0.00046,1,1
28490000,0.77,0.0017,-0.0025,-0.64,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00097,-0.0059,-1.2e-05,0.034,-0.063,-0.13,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00033,0.00035,0.0068,0.076,0.1,0.0066,0.79,0.94,0.034,3.6e-07,4.8e-07,3.6e-06,0.028,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.0004,0.00046,1,1
28590000,0.77,-0.002,-0.0011,-0.64,2.4,1.6,0.99,4.5,3.1,-3.7e+02,-0.00097,-0.0059,-1.3e-05,0.033,-0.061,-0.12,-0.17,-0.038,0.46,-0.003,-0.027,-0.029,0,0,0.00033,0.00036,0.0065,0.077,0.1,0.0067,0.83,0.99,0.034,3.6e-07,4.8e-07,3.6e-06,0.028,0.028,0.00014,0.00038,2e-05,0.00046,0.00019,0.0004,0.00046,1,1
28690000,0.77,-0.0029,-0.00054,-0.64,2.3,1.6,0.99,4.8,3.3,-3.7e+02,-0.00098,-0.0059,-2.1e-05,0.033,-0.061,-0.12,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00033,0.00036,0.0063,0.077,0.1,0.0067,0.87,1,0.034,3.6e-07,4.8e-07,3.6e-06,0.028,0.028,0.00014,0.00038,2e-05,0.00046,0.00018,0.0004,0.00046,1,1
28790000,0.77,-0.0032,-0.00032,-0.63,2.2,1.6,1,5,3.5,-3.7e+02,-0.00099,-0.0059,-3e-05,0.033,-0.059,-0.12,-0.17,-0.038,0.46,-0.0027,-0.027,-0.029,0,0,0.00033,0.00036,0.0061,0.078,0.1,0.0067,0.91,1.1,0.034,3.6e-07,4.8e-07,3.6e-06,0.028,0.028,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
28890000,0.77,-0.0029,-0.00033,-0.63,2.2,1.6,0.99,5.2,3.6,-3.7e+02,-0.001,-0.0058,-3.7e-05,0.032,-0.057,-0.12,-0.17,-0.038,0.46,-0.0027,-0.027,-0.028,0,0,0.00033,0.00036,0.0059,0.079,0.1,0.0068,0.96,1.2,0.034,3.5e-07,4.8e-07,3.6e-06,0.028,0.028,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
28990000,0.77,-0.0024,-0.00051,-0.63,2.1,1.5,0.98,5.5,3.8,-3.7e+02,-0.001,-0.0058,-5e-05,0.032,-0.055,-0.12,-0.17,-0.038,0.46,-0.0025,-0.027,-0.028,0,0,0.00033,0.00036,0.0057,0.08,0.1,0.0068,1,1.2,0.034,3.5e-07,4.8e-07,3.6e-06,0.028,0.028,0.00013,0.00037,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
29090000,0.78,-0.0019,-0.00067,-0.63,2.1,1.5,0.97,5.7,4,-3.7e+02,-0.001,-0.0058,-5.8e-05,0.031,-0.054,-0.12,-0.17,-0.038,0.46,-0.0024,-0.027,-0.028,0,0,0.00033,0.00036,0.0055,0.082,0.11,0.0069,1,1.3,0.034,3.5e-07,4.8e-07,3.5e-06,0.028,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1
29190000,0.77,-0.0016,-0.00075,-0.63,2,1.5,0.97,5.9,4.1,-3.7e+02,-0.001,-0.0058,-5.6e-05,0.031,-0.053,-0.12,-0.17,-0.038,0.46,-0.0024,-0.027,-0.028,0,0,0.00033,0.00036,0.0054,0.083,0.11,0.0069,1.1,1.3,0.034,3.5e-07,4.8e-07,3.5e-06,0.028,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1
29290000,0.78,-0.00068,-0.001,-0.63,1.9,1.4,1,6.1,4.3,-3.7e+02,-0.001,-0.0058,-6.5e-05,0.03,-0.051,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.028,0,0,0.00032,0.00036,0.0053,0.085,0.11,0.0069,1.1,1.4,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29390000,0.78,0.00075,-0.0014,-0.63,1.9,1.4,1,6.3,4.4,-3.7e+02,-0.001,-0.0058,-7.8e-05,0.029,-0.049,-0.12,-0.17,-0.038,0.46,-0.002,-0.027,-0.028,0,0,0.00032,0.00036,0.0051,0.086,0.11,0.007,1.2,1.5,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29490000,0.78,0.002,-0.0018,-0.63,1.8,1.4,1,6.5,4.6,-3.7e+02,-0.001,-0.0058,-8.1e-05,0.029,-0.048,-0.12,-0.17,-0.038,0.46,-0.0019,-0.027,-0.028,0,0,0.00032,0.00036,0.005,0.088,0.12,0.007,1.3,1.5,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29590000,0.78,0.0031,-0.002,-0.63,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,-8.6e-05,0.028,-0.046,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00032,0.00037,0.0049,0.09,0.12,0.007,1.3,1.6,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
29690000,0.78,0.0038,-0.0023,-0.63,1.8,1.4,0.99,6.8,4.8,-3.7e+02,-0.001,-0.0058,-9.3e-05,0.027,-0.043,-0.12,-0.17,-0.038,0.46,-0.0018,-0.028,-0.028,0,0,0.00032,0.00037,0.0048,0.092,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1
29790000,0.78,0.0044,-0.0025,-0.63,1.7,1.4,0.98,7,5,-3.7e+02,-0.0011,-0.0058,-9.6e-05,0.026,-0.04,-0.12,-0.17,-0.038,0.46,-0.0018,-0.028,-0.028,0,0,0.00032,0.00037,0.0048,0.094,0.13,0.0071,1.4,1.8,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1
29890000,0.78,0.0047,-0.0026,-0.63,1.7,1.3,0.97,7.2,5.1,-3.7e+02,-0.0011,-0.0058,-0.0001,0.025,-0.036,-0.12,-0.17,-0.038,0.46,-0.0016,-0.028,-0.028,0,0,0.00032,0.00037,0.0047,0.096,0.13,0.0071,1.5,1.9,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00044,1,1
29990000,0.78,0.0049,-0.0027,-0.63,1.7,1.3,0.95,7.3,5.2,-3.7e+02,-0.0011,-0.0058,-0.00011,0.024,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.027,0,0,0.00032,0.00037,0.0046,0.098,0.14,0.0071,1.5,2,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00044,1,1
30090000,0.78,0.0048,-0.0026,-0.63,1.6,1.3,0.94,7.5,5.4,-3.7e+02,-0.0011,-0.0058,-0.00012,0.023,-0.031,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.028,0,0,0.00031,0.00037,0.0046,0.1,0.14,0.0071,1.6,2.1,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
30190000,0.78,0.0046,-0.0026,-0.63,1.6,1.3,0.93,7.7,5.5,-3.7e+02,-0.0011,-0.0058,-0.00011,0.022,-0.031,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.028,0,0,0.00031,0.00037,0.0045,0.1,0.15,0.0072,1.7,2.2,0.035,3.3e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
30290000,0.78,0.0044,-0.0025,-0.63,1.5,1.3,0.92,7.8,5.6,-3.7e+02,-0.0011,-0.0058,-0.00012,0.021,-0.029,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.028,0,0,0.00031,0.00037,0.0044,0.1,0.15,0.0072,1.8,2.3,0.035,3.3e-07,5e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
30390000,0.78,0.0043,-0.0026,-0.63,1.5,1.3,0.9,8,5.8,-3.7e+02,-0.0011,-0.0058,-0.00012,0.02,-0.026,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00031,0.00037,0.0044,0.11,0.16,0.0072,1.8,2.4,0.034,3.2e-07,5e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30490000,0.78,0.0041,-0.0025,-0.63,1.5,1.2,0.89,8.2,5.9,-3.7e+02,-0.0011,-0.0058,-0.00012,0.02,-0.025,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00038,0.0043,0.11,0.16,0.0072,1.9,2.5,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.026,0.00011,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30590000,0.78,0.0038,-0.0024,-0.63,1.5,1.2,0.85,8.3,6,-3.7e+02,-0.0011,-0.0058,-0.00012,0.019,-0.021,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00038,0.0043,0.11,0.17,0.0072,2,2.6,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30690000,0.78,0.0036,-0.0023,-0.63,1.4,1.2,0.84,8.5,6.1,-3.7e+02,-0.0011,-0.0058,-0.00013,0.018,-0.018,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00038,0.0043,0.11,0.18,0.0072,2.1,2.7,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30790000,0.78,0.0032,-0.0022,-0.63,1.4,1.2,0.83,8.6,6.3,-3.7e+02,-0.0011,-0.0058,-0.00013,0.017,-0.017,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00038,0.0042,0.12,0.18,0.0072,2.1,2.8,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30890000,0.78,0.0029,-0.0022,-0.63,1.4,1.2,0.82,8.8,6.4,-3.7e+02,-0.0011,-0.0058,-0.00013,0.016,-0.014,-0.12,-0.17,-0.038,0.46,-0.001,-0.028,-0.027,0,0,0.0003,0.00038,0.0042,0.12,0.19,0.0072,2.2,3,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
30990000,0.78,0.0025,-0.0021,-0.63,1.3,1.2,0.81,8.9,6.5,-3.7e+02,-0.0011,-0.0058,-0.00014,0.015,-0.011,-0.12,-0.17,-0.038,0.46,-0.00097,-0.028,-0.027,0,0,0.0003,0.00038,0.0042,0.12,0.2,0.0071,2.3,3.1,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00043,1,1
31090000,0.78,0.002,-0.002,-0.63,1.3,1.2,0.8,9,6.6,-3.7e+02,-0.0011,-0.0058,-0.00014,0.014,-0.0083,-0.12,-0.17,-0.038,0.46,-0.00088,-0.028,-0.027,0,0,0.0003,0.00038,0.0041,0.12,0.2,0.0072,2.4,3.3,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00043,1,1
31190000,0.78,0.0018,-0.0019,-0.63,1.3,1.1,0.79,9.2,6.7,-3.7e+02,-0.0011,-0.0058,-0.00014,0.012,-0.0047,-0.12,-0.17,-0.038,0.46,-0.00079,-0.029,-0.027,0,0,0.0003,0.00039,0.0041,0.13,0.21,0.0071,2.5,3.4,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00043,1,1
31290000,0.78,0.0013,-0.0017,-0.63,1.2,1.1,0.79,9.3,6.8,-3.7e+02,-0.0011,-0.0058,-0.00014,0.011,-0.0019,-0.12,-0.17,-0.038,0.46,-0.00072,-0.029,-0.027,0,0,0.0003,0.00039,0.0041,0.13,0.22,0.0071,2.6,3.6,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.024,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00043,1,1
31390000,0.78,0.00075,-0.0015,-0.63,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0058,-0.00014,0.0096,0.001,-0.12,-0.17,-0.038,0.46,-0.00065,-0.029,-0.027,0,0,0.0003,0.00039,0.004,0.13,0.23,0.0071,2.7,3.7,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.024,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00042,1,1
31490000,0.78,0.00024,-0.0014,-0.63,1.2,1.1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0058,-0.00015,0.0084,0.0036,-0.12,-0.17,-0.038,0.46,-0.00052,-0.029,-0.027,0,0,0.00029,0.00039,0.004,0.13,0.23,0.0071,2.8,3.9,0.035,3.1e-07,5.1e-07,3.5e-06,0.028,0.024,0.0001,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00042,1,1
31590000,0.78,-6.9e-05,-0.0014,-0.63,1.1,1.1,0.78,9.7,7.2,-3.7e+02,-0.0011,-0.0058,-0.00015,0.0071,0.0057,-0.11,-0.17,-0.038,0.46,-0.00047,-0.029,-0.027,0,0,0.00029,0.00039,0.004,0.14,0.24,0.007,2.9,4.1,0.035,3.1e-07,5.1e-07,3.5e-06,0.028,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
31690000,0.78,-0.00067,-0.0012,-0.63,1.1,1.1,0.79,9.8,7.3,-3.7e+02,-0.0011,-0.0058,-0.00015,0.0058,0.0083,-0.11,-0.17,-0.038,0.46,-0.0004,-0.029,-0.027,0,0,0.00029,0.00039,0.004,0.14,0.25,0.007,3,4.3,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
31790000,0.78,-0.0013,-0.001,-0.63,1.1,1.1,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0058,-0.00015,0.0045,0.011,-0.11,-0.17,-0.038,0.46,-0.00034,-0.029,-0.027,0,0,0.00029,0.0004,0.004,0.14,0.26,0.007,3.1,4.4,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
31890000,0.78,-0.0019,-0.00091,-0.63,1.1,1,0.78,10,7.5,-3.7e+02,-0.0011,-0.0058,-0.00016,0.0032,0.014,-0.11,-0.17,-0.038,0.46,-0.00025,-0.029,-0.027,0,0,0.00029,0.0004,0.004,0.14,0.27,0.007,3.2,4.6,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
31990000,0.78,-0.0022,-0.00081,-0.63,1,1,0.78,10,7.6,-3.7e+02,-0.0012,-0.0058,-0.00016,0.0017,0.018,-0.11,-0.17,-0.038,0.46,-0.00014,-0.029,-0.027,0,0,0.00029,0.0004,0.0039,0.15,0.28,0.0069,3.3,4.8,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32090000,0.78,-0.0029,-0.00061,-0.63,1,1,0.79,10,7.7,-3.7e+02,-0.0012,-0.0058,-0.00017,0.00018,0.02,-0.11,-0.18,-0.038,0.46,-3.6e-05,-0.029,-0.027,0,0,0.00028,0.0004,0.0039,0.15,0.29,0.0069,3.4,5.1,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,9.9e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32190000,0.78,-0.0037,-0.00041,-0.63,0.97,1,0.78,10,7.8,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.0014,0.024,-0.11,-0.18,-0.038,0.46,0.00011,-0.029,-0.026,0,0,0.00028,0.0004,0.0039,0.15,0.3,0.0069,3.5,5.3,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,9.8e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32290000,0.78,-0.0043,-0.00032,-0.63,0.94,0.98,0.78,11,7.9,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.0031,0.028,-0.11,-0.18,-0.038,0.46,0.00021,-0.03,-0.026,0,0,0.00028,0.0004,0.0039,0.16,0.31,0.0068,3.7,5.5,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32390000,0.78,-0.0048,-0.00023,-0.63,0.91,0.96,0.78,11,8,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.004,0.03,-0.11,-0.18,-0.038,0.46,0.00026,-0.03,-0.026,0,0,0.00028,0.00041,0.0039,0.16,0.32,0.0068,3.8,5.8,0.035,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
32490000,0.78,-0.005,-0.00017,-0.63,0.88,0.94,0.78,11,8.1,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.0054,0.032,-0.11,-0.18,-0.038,0.46,0.00035,-0.03,-0.026,0,0,0.00028,0.00041,0.0039,0.16,0.33,0.0068,3.9,6,0.035,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1
32590000,0.78,-0.0052,-0.00011,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0062,0.033,-0.11,-0.18,-0.039,0.46,0.00041,-0.03,-0.026,0,0,0.00028,0.00041,0.0039,0.25,0.25,0.56,0.25,0.25,0.037,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.5e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1
32690000,0.78,-0.0052,-0.00014,-0.63,-1.6,-0.85,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0071,0.035,-0.11,-0.18,-0.038,0.46,0.00048,-0.03,-0.026,0,0,0.00027,0.00041,0.0039,0.25,0.25,0.55,0.26,0.26,0.048,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.5e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
32790000,0.78,-0.0051,-0.00016,-0.63,-1.5,-0.83,0.62,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0079,0.036,-0.11,-0.18,-0.038,0.46,0.00053,-0.03,-0.026,0,0,0.00027,0.00041,0.0039,0.13,0.13,0.27,0.26,0.26,0.048,2.9e-07,5.2e-07,3.5e-06,0.028,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
32890000,0.78,-0.0049,-0.00028,-0.63,-1.6,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.0002,-0.0086,0.038,-0.11,-0.18,-0.039,0.46,0.00063,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.13,0.13,0.26,0.27,0.27,0.059,2.9e-07,5.2e-07,3.5e-06,0.028,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
32990000,0.78,-0.0048,-0.0004,-0.63,-1.5,-0.84,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0095,0.039,-0.11,-0.18,-0.038,0.46,0.00066,-0.03,-0.025,0,0,0.00027,0.00042,0.0038,0.084,0.085,0.17,0.27,0.27,0.057,2.9e-07,5.2e-07,3.5e-06,0.028,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33090000,0.78,-0.0049,-0.00037,-0.63,-1.6,-0.86,0.58,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0099,0.04,-0.11,-0.18,-0.038,0.46,0.00067,-0.03,-0.025,0,0,0.00027,0.00042,0.0038,0.084,0.086,0.16,0.28,0.28,0.065,2.9e-07,5.2e-07,3.5e-06,0.028,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33190000,0.78,-0.0035,-0.0036,-0.62,-1.5,-0.84,0.53,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.01,0.04,-0.11,-0.18,-0.038,0.46,0.00067,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,5.1e-07,3.5e-06,0.028,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
33290000,0.82,-0.0014,-0.015,-0.57,-1.5,-0.86,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0098,0.04,-0.11,-0.18,-0.039,0.46,0.00065,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.064,0.066,0.11,0.29,0.29,0.067,2.8e-07,5.2e-07,3.5e-06,0.028,0.021,9.3e-05,0.00035,1.9e-05,0.00041,0.00015,0.00039,0.00041,1,1
33390000,0.89,-0.0017,-0.013,-0.46,-1.5,-0.85,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.015,0.037,-0.11,-0.18,-0.039,0.46,0.0012,-0.028,-0.025,0,0,0.00028,0.0004,0.0037,0.051,0.053,0.083,0.29,0.29,0.065,2.8e-07,5.1e-07,3.4e-06,0.027,0.021,9.3e-05,0.00033,1.7e-05,0.00041,0.00015,0.00035,0.00041,1,1
33490000,0.95,-0.00015,-0.0052,-0.31,-1.5,-0.86,0.72,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.017,0.037,-0.11,-0.18,-0.04,0.46,0.0018,-0.02,-0.025,0,0,0.00031,0.00036,0.0034,0.052,0.055,0.075,0.3,0.3,0.068,2.8e-07,5.1e-07,3.4e-06,0.027,0.021,9.3e-05,0.00025,1.4e-05,0.00041,0.00013,0.00026,0.00041,1,1
33590000,0.99,-0.0028,0.0015,-0.14,-1.5,-0.84,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.017,0.037,-0.11,-0.19,-0.042,0.46,0.0026,-0.013,-0.026,0,0,0.00034,0.00031,0.0029,0.044,0.047,0.061,0.3,0.3,0.065,2.8e-07,5.1e-07,3.4e-06,0.027,0.021,9.3e-05,0.00017,9.9e-06,0.00041,9.4e-05,0.00016,0.0004,1,1
33690000,1,-0.0063,0.005,0.024,-1.6,-0.86,0.69,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00018,-0.017,0.037,-0.11,-0.19,-0.043,0.46,0.0018,-0.0093,-0.026,0,0,0.00037,0.00027,0.0026,0.045,0.05,0.056,0.31,0.31,0.068,2.8e-07,5.1e-07,3.3e-06,0.027,0.021,9.3e-05,0.00013,7.8e-06,0.0004,6.9e-05,0.0001,0.0004,1,1
33790000,0.98,-0.0072,0.0069,0.19,-1.6,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.017,0.037,-0.11,-0.2,-0.043,0.46,0.002,-0.0067,-0.027,0,0,0.00037,0.00025,0.0023,0.04,0.045,0.047,0.31,0.31,0.064,2.8e-07,5e-07,3.3e-06,0.027,0.021,9.3e-05,9.6e-05,6.3e-06,0.0004,4.8e-05,6.3e-05,0.0004,1,1
33890000,0.94,-0.0075,0.0081,0.35,-1.7,-0.9,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.017,0.037,-0.11,-0.2,-0.043,0.46,0.0019,-0.0054,-0.027,0,0,0.00036,0.00026,0.0022,0.044,0.051,0.043,0.32,0.32,0.065,2.8e-07,5e-07,3.3e-06,0.027,0.021,9.3e-05,8e-05,5.6e-06,0.0004,3.4e-05,4.2e-05,0.0004,1,1
33990000,0.87,-0.0095,0.0056,0.49,-1.7,-0.91,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.015,0.036,-0.11,-0.2,-0.044,0.46,0.0017,-0.004,-0.027,0,0,0.00032,0.00026,0.002,0.041,0.049,0.036,0.32,0.32,0.062,2.8e-07,4.9e-07,3.3e-06,0.027,0.021,9.3e-05,7e-05,5.1e-06,0.0004,2.6e-05,3e-05,0.0004,1,1
34090000,0.81,-0.011,0.0043,0.59,-1.7,-0.97,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00017,-0.0095,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0034,-0.027,0,0,0.0003,0.00028,0.002,0.047,0.057,0.033,0.33,0.33,0.063,2.8e-07,4.9e-07,3.2e-06,0.026,0.021,9.3e-05,6.5e-05,4.8e-06,0.0004,2.1e-05,2.4e-05,0.0004,1,1
34190000,0.76,-0.0081,0.0029,0.65,-1.7,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00016,-0.038,0.052,-0.11,-0.2,-0.044,0.46,0.0012,-0.0028,-0.027,0,0,0.00026,0.00027,0.0018,0.045,0.054,0.029,0.33,0.33,0.06,2.8e-07,4.8e-07,3.2e-06,0.025,0.02,9.2e-05,5.9e-05,4.5e-06,0.0004,1.7e-05,1.9e-05,0.0004,1,1
34290000,0.72,-0.0052,0.0041,0.69,-1.7,-1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00016,-0.037,0.05,-0.11,-0.2,-0.044,0.46,0.0011,-0.0024,-0.027,0,0,0.00025,0.00028,0.0018,0.053,0.064,0.027,0.34,0.34,0.06,2.8e-07,4.8e-07,3.2e-06,0.025,0.02,9.2e-05,5.6e-05,4.4e-06,0.0004,1.5e-05,1.6e-05,0.0004,1,1
34390000,0.7,-0.0024,0.0054,0.71,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.036,0.049,-0.11,-0.2,-0.044,0.46,0.00092,-0.0022,-0.027,0,0,0.00024,0.00029,0.0018,0.062,0.075,0.025,0.35,0.35,0.06,2.8e-07,4.8e-07,3.2e-06,0.024,0.02,9.2e-05,5.4e-05,4.3e-06,0.0004,1.3e-05,1.4e-05,0.0004,1,1
34490000,0.69,-0.00035,0.0065,0.73,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.035,0.049,-0.11,-0.2,-0.044,0.46,0.0008,-0.0021,-0.027,0,0,0.00024,0.0003,0.0017,0.072,0.088,0.023,0.36,0.36,0.06,2.8e-07,4.8e-07,3.2e-06,0.024,0.02,9.3e-05,5.3e-05,4.2e-06,0.0004,1.1e-05,1.2e-05,0.0004,1,1
34590000,0.68,0.00093,0.0074,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.033,0.049,-0.11,-0.2,-0.044,0.46,0.00064,-0.002,-0.027,0,0,0.00024,0.0003,0.0017,0.084,0.1,0.021,0.38,0.38,0.059,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,1e-05,1.1e-05,0.0004,1,1
34690000,0.67,0.0018,0.0078,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.034,0.048,-0.11,-0.2,-0.044,0.46,0.00068,-0.0018,-0.027,0,0,0.00023,0.0003,0.0017,0.097,0.12,0.019,0.39,0.4,0.059,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,5.1e-05,4.1e-06,0.0004,9.7e-06,1e-05,0.0004,1,1
34790000,0.67,0.0024,0.0081,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00014,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.11,0.14,0.018,0.41,0.42,0.058,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,5e-05,4.1e-06,0.0004,9e-06,9.2e-06,0.0004,1,1
34890000,0.66,0.0025,0.0081,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00014,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00069,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.13,0.16,0.017,0.43,0.44,0.056,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,8.4e-06,8.5e-06,0.0004,1,1
34990000,0.66,-0.00085,0.015,0.75,-3,-2.2,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00014,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00079,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.16,0.22,0.016,0.46,0.47,0.056,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.8e-05,4e-06,0.0004,8e-06,8e-06,0.0004,1,1
35090000,0.66,-0.00091,0.016,0.75,-3.1,-2.3,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00079,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.18,0.25,0.015,0.49,0.51,0.055,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.8e-05,4e-06,0.0004,7.6e-06,7.5e-06,0.0004,1,1
35190000,0.66,-0.001,0.015,0.75,-3.1,-2.3,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00081,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.2,0.27,0.014,0.52,0.55,0.054,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.7e-05,4e-06,0.0004,7.2e-06,7.1e-06,0.0004,1,1
35290000,0.66,-0.0011,0.015,0.75,-3.2,-2.3,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00015,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00085,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.22,0.3,0.013,0.56,0.6,0.052,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.9e-06,6.7e-06,0.0004,1,1
35390000,0.66,-0.0011,0.015,0.75,-3.2,-2.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00015,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00091,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.25,0.33,0.013,0.61,0.66,0.052,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.7e-06,6.4e-06,0.0004,1,1
35490000,0.66,-0.0012,0.015,0.75,-3.2,-2.4,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.27,0.37,0.012,0.66,0.73,0.051,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.5e-06,6.1e-06,0.0004,1,1
35590000,0.66,-0.0012,0.015,0.75,-3.3,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00015,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00093,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.3,0.4,0.011,0.72,0.81,0.05,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,6.3e-06,5.9e-06,0.0004,1,1
35690000,0.66,-0.0011,0.016,0.75,-3.3,-2.5,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.33,0.44,0.011,0.78,0.89,0.049,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,6.1e-06,5.7e-06,0.0004,1,1
35790000,0.66,-0.0012,0.016,0.75,-3.3,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.36,0.47,0.01,0.86,0.99,0.048,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.5e-05,3.9e-06,0.0004,5.9e-06,5.5e-06,0.0004,1,1
35890000,0.66,-0.0012,0.016,0.75,-3.4,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.034,0.045,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.39,0.51,0.0099,0.94,1.1,0.047,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.8e-06,5.3e-06,0.0004,1,1
35990000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.034,0.044,-0.11,-0.2,-0.044,0.46,0.00095,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.42,0.55,0.0096,1,1.2,0.047,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.7e-06,5.1e-06,0.0004,1,1
36090000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.033,0.044,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.46,0.59,0.0093,1.1,1.4,0.046,2.9e-07,5e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.6e-06,5e-06,0.0004,1,1
36190000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00018,-0.034,0.043,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.49,0.64,0.009,1.3,1.5,0.045,2.9e-07,5e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.5e-06,4.8e-06,0.0004,1,1
36290000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00018,-0.033,0.041,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.53,0.68,0.0088,1.4,1.7,0.045,2.9e-07,5e-07,3.2e-06,0.024,0.019,9.3e-05,4.3e-05,3.8e-06,0.0004,5.4e-06,4.7e-06,0.0004,1,1
36390000,0.66,-0.0013,0.016,0.75,-3.5,-2.9,-0.097,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00018,-0.033,0.041,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.56,0.73,0.0085,1.5,1.9,0.044,2.9e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.3e-05,3.8e-06,0.00039,5.3e-06,4.6e-06,0.0004,1,1
36490000,0.66,-0.0014,0.016,0.75,-3.6,-2.9,-0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00017,-0.032,0.041,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.6,0.78,0.0083,1.7,2.1,0.043,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.3e-05,3.7e-06,0.00039,5.2e-06,4.5e-06,0.0004,1,1
36590000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.08,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00018,-0.032,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.64,0.83,0.0081,1.9,2.4,0.042,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5.1e-06,4.3e-06,0.0004,1,1
36690000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.031,0.04,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.68,0.88,0.008,2.1,2.6,0.042,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5.1e-06,4.3e-06,0.0004,1,1
36790000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.72,0.93,0.0079,2.3,2.9,0.041,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5e-06,4.2e-06,0.0004,1,1
36890000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.77,0.98,0.0078,2.5,3.2,0.041,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5e-06,4.1e-06,0.0004,1,1
36990000,0.66,-0.0014,0.016,0.75,-3.7,-3.2,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.03,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.81,1,0.0077,2.8,3.6,0.04,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.9e-06,4e-06,0.0004,1,1
37090000,0.66,-0.0014,0.016,0.75,-3.8,-3.2,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.03,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.86,1.1,0.0076,3.1,3.9,0.04,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.9e-06,3.9e-06,0.0004,1,1
37190000,0.66,-0.0015,0.016,0.75,-3.8,-3.3,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.9,1.2,0.0075,3.4,4.3,0.039,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.8e-06,3.8e-06,0.0004,1,1
37290000,0.66,-0.0015,0.016,0.75,-3.8,-3.3,-0.026,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.95,1.2,0.0075,3.7,4.8,0.039,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.6e-06,0.00039,4.8e-06,3.8e-06,0.0004,1,1
37390000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.029,0.036,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.0002,0.00028,0.0017,1,1.3,0.0074,4,5.2,0.039,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.6e-06,0.00039,4.8e-06,3.7e-06,0.0004,1,1
37490000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.012,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00024,-0.029,0.035,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1,1.3,0.0074,4.4,5.7,0.038,3e-07,4.9e-07,3.1e-06,0.024,0.019,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1
37590000,0.66,-0.0014,0.017,0.75,-3.9,-3.5,-0.0033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.028,0.034,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.1,1.4,0.0074,4.8,6.3,0.038,3e-07,4.9e-07,3.1e-06,0.024,0.018,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.6e-06,0.0004,1,1
37690000,0.66,-0.0015,0.017,0.75,-4,-3.5,0.0059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.027,0.033,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.1,1.5,0.0074,5.2,6.8,0.038,3.1e-07,4.9e-07,3.1e-06,0.024,0.018,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.5e-06,0.0004,1,1
37790000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0017,1.2,1.5,0.0073,5.7,7.4,0.037,3.1e-07,4.9e-07,3.1e-06,0.024,0.018,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.5e-06,0.0004,1,1
37890000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.022,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0017,1.3,1.6,0.0073,6.2,8.1,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1
37990000,0.66,-0.0016,0.017,0.75,-4.1,-3.7,0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.026,0.031,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0017,1.3,1.7,0.0074,6.7,8.8,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1
38090000,0.66,-0.0017,0.017,0.75,-4.1,-3.8,0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0017,1.4,1.7,0.0073,7.3,9.5,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1
38190000,0.66,-0.0017,0.017,0.75,-4.2,-3.8,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.8,0.0073,7.9,10,0.036,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.6e-06,3.3e-06,0.0004,1,1
38290000,0.66,-0.0017,0.017,0.75,-4.2,-3.9,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,8.5,11,0.036,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.6e-06,3.3e-06,0.0004,1,1
38390000,0.66,-0.0016,0.017,0.75,-4.2,-3.9,0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.024,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,9.2,12,0.036,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.6e-06,3.2e-06,0.0004,1,1
38490000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.069,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.6,2,0.0074,9.9,13,0.036,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.6e-06,3.2e-06,0.0004,1,1
38590000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.076,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.024,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.7,2.1,0.0074,11,14,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.6e-06,3.2e-06,0.0004,1,1
38690000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.00019,0.00026,0.0016,1.7,2.1,0.0074,11,15,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1
38790000,0.66,-0.0016,0.017,0.75,-4.4,-4.1,0.089,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.00019,0.00026,0.0016,1.8,2.2,0.0075,12,16,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.7e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1
38890000,0.66,-0.0017,0.017,0.75,-4.4,-4.1,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.8,2.3,0.0075,13,17,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.7e-05,3.4e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1

1 Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
2 10000,1,-0.0094,-0.01,-3.2e-06,0.00023,7.3e-05,-0.011,7.2e-06,2.2e-06,-0.00045,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3 90000,1,-0.0094,-0.011,6.9e-05,-0.00047,0.0026,-0.026,-1.6e-05,0.00011,-0.0023,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4 190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.6e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00093,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 190000,1,-0.0094,-0.011,2.8e-05,6.9e-05,0.004,-0.041,-5.9e-06,0.00043,-0.0044,-3e-11,-2.7e-12,5.9e-13,0,0,-5e-08,0,0,0,0,0,0,0,0,0.011,0.011,0.00093,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5 290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-1.7e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 290000,1,-0.0094,-0.011,6.3e-05,0.001,0.0064,-0.053,3.8e-05,0.00036,-0.007,9.1e-10,1e-10,-2.8e-11,0,0,-2.5e-06,0,0,0,0,0,0,0,0,0.012,0.011,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6 390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,2.9e-10,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 390000,1,-0.0094,-0.011,7e-05,0.0024,0.0083,-0.059,0.00021,0.0011,-0.0094,-1.1e-08,2.8e-09,7.7e-11,0,0,-1.5e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
7 490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,-4.2e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 490000,1,-0.0095,-0.012,2e-05,0.0039,0.0048,-0.06,0.00024,0.00049,-0.011,1.6e-06,-3.7e-07,1.4e-08,0,0,-4.1e-05,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8 590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,-4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 590000,1,-0.0095,-0.012,2.6e-05,0.006,0.0073,-0.059,0.00074,0.0011,-0.012,1.6e-06,-3.4e-07,1.4e-08,0,0,-7.3e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9 690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,-1.8e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 690000,1,-0.0096,-0.012,8.6e-05,0.0063,0.0052,-0.059,0.0005,0.00055,-0.013,5.5e-06,-3.2e-06,1.1e-07,0,0,-0.00012,0,0,0,0,0,0,0,0,0.016,0.016,0.00062,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10 790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,-1.8e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 790000,1,-0.0097,-0.013,9.9e-05,0.0086,0.0073,-0.063,0.0012,0.0012,-0.014,5.4e-06,-3.1e-06,1.1e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.018,0.018,0.00079,2.8,2.8,2,0.42,0.42,0.28,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11 890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00053,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 890000,1,-0.0098,-0.013,0.00012,0.01,0.006,-0.077,0.00096,0.00072,-0.021,1.6e-05,-1.5e-05,3.3e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.019,0.019,0.00053,1.3,1.3,2,0.2,0.2,0.43,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
12 990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,-6.5e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 990000,1,-0.0099,-0.013,0.00013,0.015,0.0064,-0.092,0.0022,0.0014,-0.029,1.6e-05,-1.5e-05,3.3e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.021,0.021,0.00065,1.5,1.5,2,0.3,0.3,0.61,0.0099,0.01,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13 1090000,1,-0.01,-0.014,0.00013,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1090000,1,-0.01,-0.014,0.00012,0.016,0.0051,-0.11,0.0018,0.00086,-0.039,4.1e-05,-6.2e-05,9.3e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.023,0.023,0.00046,0.93,0.93,2,0.17,0.17,0.84,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14 1190000,1,-0.01,-0.014,0.0001,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,-2.1e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00055,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1190000,1,-0.01,-0.014,9.8e-05,0.02,0.0053,-0.12,0.0035,0.0014,-0.051,4.1e-05,-6.2e-05,9.3e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.025,0.025,0.00054,1.1,1.1,2,0.24,0.24,1.1,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15 1290000,1,-0.01,-0.014,0.00016,0.02,0.0044,-0.14,0.0027,0.00089,-0.064,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,2,0.15,0.15,1.4,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1290000,1,-0.01,-0.014,0.00015,0.02,0.0044,-0.14,0.0027,0.00088,-0.064,8.5e-05,-0.00019,2.3e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.026,0.026,0.00041,0.88,0.88,2,0.15,0.15,1.4,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16 1390000,1,-0.01,-0.014,0.00017,0.026,0.0042,-0.15,0.0051,0.0013,-0.078,8.5e-05,-0.00019,-5.6e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00048,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1390000,1,-0.01,-0.014,0.00016,0.026,0.0042,-0.15,0.005,0.0013,-0.078,8.5e-05,-0.00019,2.3e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.028,0.028,0.00047,1.2,1.2,2,0.21,0.21,1.7,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17 1490000,1,-0.01,-0.014,0.00015,0.024,0.0029,-0.16,0.0038,0.00083,-0.093,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,2,0.14,0.14,2.1,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1490000,1,-0.01,-0.014,0.00014,0.024,0.0029,-0.16,0.0037,0.00083,-0.093,0.00015,-0.00045,4.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.027,0.027,0.00036,0.95,0.95,2,0.14,0.14,2.1,0.0089,0.0089,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18 1590000,1,-0.01,-0.014,0.00015,0.03,0.0035,-0.18,0.0065,0.0012,-0.11,0.00015,-0.00045,-1.2e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,2,0.2,0.2,2.6,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1590000,1,-0.01,-0.014,0.00013,0.03,0.0035,-0.18,0.0064,0.0012,-0.11,0.00015,-0.00045,4.5e-06,0,0,-0.00016,0,0,0,0,0,0,0,0,0.03,0.03,0.00042,1.3,1.3,2,0.21,0.21,2.6,0.0089,0.0089,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19 1690000,1,-0.011,-0.014,0.00012,0.028,-9.5e-05,-0.19,0.0045,0.00063,-0.13,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,2,0.14,0.14,3,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1690000,1,-0.011,-0.014,9.6e-05,0.028,-0.0001,-0.19,0.0045,0.00062,-0.13,0.0002,-0.00087,7.7e-06,0,0,-0.00017,0,0,0,0,0,0,0,0,0.026,0.026,0.00033,1,1,2,0.14,0.14,3,0.0079,0.0079,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20 1790000,1,-0.011,-0.014,9.5e-05,0.035,-0.0019,-0.2,0.0076,0.00054,-0.15,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00038,1.3,1.3,2,0.2,0.2,3.5,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1790000,1,-0.011,-0.014,6.5e-05,0.035,-0.002,-0.2,0.0075,0.00054,-0.15,0.0002,-0.00087,7.7e-06,0,0,-0.00017,0,0,0,0,0,0,0,0,0.028,0.028,0.00037,1.3,1.3,2,0.21,0.21,3.5,0.0079,0.0079,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21 1890000,1,-0.011,-0.015,7.5e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00088,-2.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,2,0.31,0.31,4.1,0.0078,0.0078,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1890000,1,-0.011,-0.015,4.4e-05,0.043,-0.0032,-0.22,0.011,0.00029,-0.17,0.0002,-0.00087,7.7e-06,0,0,-0.00017,0,0,0,0,0,0,0,0,0.031,0.031,0.00042,1.7,1.7,2,0.31,0.31,4.1,0.0079,0.0079,0.00015,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22 1990000,1,-0.011,-0.014,8.5e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00034,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1990000,1,-0.011,-0.014,3.6e-05,0.036,-0.0046,-0.23,0.0082,-0.00027,-0.19,0.00022,-0.0014,1.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.025,0.025,0.00033,1.3,1.3,2.1,0.2,0.2,4.7,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23 2090000,1,-0.011,-0.014,4.7e-05,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,-3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2090000,1,-0.011,-0.014,-4.3e-06,0.041,-0.0071,-0.24,0.012,-0.00085,-0.22,0.00022,-0.0014,1.2e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.027,0.027,0.00037,1.7,1.7,2.1,0.31,0.31,5.3,0.0067,0.0067,0.00011,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24 2190000,1,-0.011,-0.014,5.8e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,2.1,0.2,0.2,6,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2190000,1,-0.011,-0.014,-1.3e-05,0.033,-0.0068,-0.26,0.0079,-0.00096,-0.24,0.00017,-0.002,1.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.02,0.021,0.0003,1.2,1.2,2.1,0.2,0.2,6,0.0056,0.0055,8.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25 2290000,1,-0.011,-0.014,4.5e-05,0.039,-0.0093,-0.27,0.011,-0.0017,-0.27,0.00017,-0.002,-4.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,2.1,0.3,0.3,6.7,0.0055,0.0055,8.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2290000,1,-0.011,-0.014,-2.9e-05,0.039,-0.0093,-0.27,0.012,-0.0017,-0.27,0.00017,-0.002,1.7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.022,0.022,0.00033,1.5,1.5,2.1,0.3,0.3,6.7,0.0056,0.0055,8.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26 2390000,1,-0.011,-0.013,6.2e-05,0.03,-0.0087,-0.29,0.0074,-0.0015,-0.3,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2390000,1,-0.011,-0.013,-3.1e-05,0.03,-0.0086,-0.29,0.0075,-0.0015,-0.3,9e-05,-0.0025,2.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.017,0.017,0.00027,1,1,2.1,0.19,0.19,7.4,0.0046,0.0046,7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27 2490000,1,-0.011,-0.013,4.4e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,-5.2e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,7.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2490000,1,-0.011,-0.013,-5.3e-05,0.035,-0.011,-0.3,0.011,-0.0024,-0.32,9e-05,-0.0025,2.1e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.018,0.018,0.0003,1.3,1.3,2.1,0.28,0.28,8.2,0.0046,0.0046,7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28 2590000,1,-0.011,-0.013,5.8e-05,0.026,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,2.1,0.18,0.18,9.1,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2590000,1,-0.011,-0.013,-5.6e-05,0.027,-0.009,-0.31,0.0068,-0.0018,-0.36,-1.3e-05,-0.0029,2.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.014,0.014,0.00025,0.88,0.88,2.1,0.18,0.18,9.1,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29 2690000,1,-0.011,-0.013,5.5e-05,0.03,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.4e-05,-0.0029,-5.8e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2690000,1,-0.011,-0.013,-6.4e-05,0.031,-0.01,-0.33,0.0097,-0.0028,-0.39,-1.3e-05,-0.0029,2.4e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.015,0.015,0.00027,1.1,1.1,2.2,0.25,0.25,10,0.0038,0.0038,5.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30 2790000,1,-0.011,-0.013,4.8e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,2.2,0.16,0.16,11,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2790000,1,-0.011,-0.013,-8.5e-05,0.023,-0.0093,-0.34,0.0062,-0.0019,-0.42,-0.00012,-0.0033,2.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.012,0.012,0.00023,0.76,0.76,2.2,0.16,0.16,11,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31 2890000,1,-0.011,-0.013,-1.8e-06,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,-6.3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,2.2,0.23,0.23,12,0.0032,0.0032,4.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2890000,1,-0.011,-0.013,-0.00014,0.027,-0.011,-0.35,0.0087,-0.0029,-0.46,-0.00012,-0.0033,2.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.013,0.013,0.00025,0.93,0.94,2.2,0.23,0.23,12,0.0032,0.0032,4.7e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32 2990000,1,-0.011,-0.013,4.6e-05,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,2.2,0.15,0.15,13,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2990000,1,-0.011,-0.013,-0.00011,0.022,-0.0095,-0.36,0.0057,-0.0021,-0.49,-0.00023,-0.0036,3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.01,0.01,0.00022,0.66,0.66,2.2,0.15,0.15,13,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33 3090000,1,-0.011,-0.013,4.8e-05,0.025,-0.011,-0.38,0.008,-0.0031,-0.53,-0.00023,-0.0036,-6.7e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,2.2,0.22,0.22,14,0.0027,0.0027,4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3090000,1,-0.011,-0.013,-0.00011,0.025,-0.011,-0.38,0.0081,-0.0031,-0.53,-0.00023,-0.0036,3e-05,0,0,-0.00018,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.81,0.81,2.2,0.22,0.22,14,0.0027,0.0027,3.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34 3190000,1,-0.011,-0.013,-8.9e-06,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0087,0.0087,0.00021,0.59,0.59,2.3,0.14,0.14,15,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3190000,1,-0.011,-0.013,-0.00018,0.02,-0.0086,-0.39,0.0053,-0.0021,-0.57,-0.00034,-0.0039,3.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0089,0.0088,0.0002,0.58,0.58,2.3,0.14,0.14,15,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
35 3290000,1,-0.011,-0.013,3.1e-05,0.023,-0.01,-0.4,0.0074,-0.003,-0.61,-0.00034,-0.0039,-7e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,2.3,0.2,0.2,16,0.0023,0.0023,3.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3290000,1,-0.011,-0.013,-0.00014,0.023,-0.01,-0.4,0.0074,-0.0031,-0.61,-0.00034,-0.0039,3.1e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0097,0.0097,0.00022,0.71,0.72,2.3,0.2,0.2,16,0.0023,0.0023,3.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
36 3390000,1,-0.011,-0.012,2.5e-06,0.018,-0.0091,-0.42,0.0049,-0.0021,-0.65,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,2.3,0.14,0.14,18,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3390000,1,-0.011,-0.012,-0.00018,0.018,-0.0091,-0.42,0.005,-0.0021,-0.65,-0.00045,-0.0041,3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0079,0.0079,0.00019,0.52,0.52,2.3,0.14,0.14,18,0.002,0.002,2.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
37 3490000,1,-0.011,-0.013,-5e-06,0.022,-0.012,-0.43,0.0069,-0.0031,-0.69,-0.00044,-0.0041,-7.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,2.3,0.19,0.19,19,0.002,0.002,2.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3490000,1,-0.011,-0.013,-0.0002,0.022,-0.012,-0.43,0.007,-0.0031,-0.69,-0.00045,-0.0041,3.3e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0086,0.0086,0.0002,0.64,0.64,2.3,0.19,0.19,19,0.002,0.002,2.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
38 3590000,1,-0.011,-0.012,1.8e-05,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.49,0.49,2.4,0.13,0.13,20,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3590000,1,-0.011,-0.012,-0.00019,0.017,-0.011,-0.44,0.0047,-0.0023,-0.73,-0.00055,-0.0044,3.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.48,0.48,2.4,0.13,0.13,20,0.0017,0.0017,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
39 3690000,1,-0.011,-0.012,0.00014,0.019,-0.014,-0.46,0.0065,-0.0035,-0.78,-0.00055,-0.0044,-7.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,2.4,0.18,0.18,22,0.0017,0.0017,2.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3690000,1,-0.011,-0.012,-6.8e-05,0.02,-0.014,-0.46,0.0066,-0.0035,-0.78,-0.00055,-0.0044,3.5e-05,0,0,-0.00017,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.58,0.58,2.4,0.17,0.17,22,0.0017,0.0017,2.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
40 3790000,1,-0.011,-0.012,0.00019,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.45,0.45,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3790000,1,-0.011,-0.012,-3.4e-05,0.016,-0.013,-0.47,0.0044,-0.0026,-0.82,-0.00067,-0.0046,3.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.44,0.44,2.4,0.12,0.12,23,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
41 3890000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.48,0.006,-0.0039,-0.87,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,2.4,0.17,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3890000,1,-0.011,-0.012,-7.2e-05,0.017,-0.014,-0.48,0.0061,-0.004,-0.87,-0.00067,-0.0046,3.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00018,0.54,0.54,2.4,0.16,0.17,24,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
42 3990000,1,-0.011,-0.012,0.00016,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,-7.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.67,0.67,2.5,0.23,0.23,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3990000,1,-0.011,-0.012,-7.4e-05,0.02,-0.016,-0.5,0.0079,-0.0055,-0.92,-0.00067,-0.0046,3.6e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0074,0.0074,0.00019,0.65,0.65,2.5,0.22,0.22,26,0.0014,0.0014,2.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
43 4090000,1,-0.011,-0.012,0.00015,0.017,-0.014,-0.51,0.0056,-0.0041,-0.97,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.51,0.51,2.5,0.16,0.16,28,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4090000,1,-0.011,-0.012,-9e-05,0.017,-0.014,-0.51,0.0057,-0.0041,-0.97,-0.0008,-0.0048,3.8e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0061,0.006,0.00017,0.5,0.5,2.5,0.16,0.16,28,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
44 4190000,1,-0.011,-0.012,0.00013,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.00079,-0.0047,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0067,0.0067,0.00018,0.61,0.61,2.5,0.21,0.21,29,0.0012,0.0012,1.9e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4190000,1,-0.011,-0.012,-0.00012,0.02,-0.016,-0.53,0.0075,-0.0056,-1,-0.0008,-0.0048,3.8e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0066,0.0066,0.00018,0.6,0.6,2.5,0.21,0.21,29,0.0012,0.0011,1.8e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
45 4290000,1,-0.01,-0.012,8.2e-05,0.017,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,2.6,0.15,0.15,31,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4290000,1,-0.01,-0.012,-0.00018,0.016,-0.012,-0.54,0.0054,-0.0041,-1.1,-0.00092,-0.0049,4e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00016,0.46,0.46,2.6,0.15,0.15,31,0.00094,0.00094,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
46 4390000,1,-0.01,-0.012,0.0001,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00091,-0.0049,-7.7e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,2.6,0.2,0.2,33,0.00097,0.00097,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4390000,1,-0.01,-0.012,-0.00016,0.018,-0.013,-0.55,0.0071,-0.0053,-1.1,-0.00092,-0.0049,4e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0058,0.0057,0.00017,0.55,0.55,2.6,0.2,0.2,33,0.00094,0.00094,1.6e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
47 4490000,1,-0.01,-0.012,0.00016,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0049,0.0049,0.00016,0.43,0.43,2.6,0.14,0.14,34,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4490000,1,-0.01,-0.012,-0.00011,0.014,-0.0097,-0.57,0.0051,-0.0037,-1.2,-0.001,-0.0051,4.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0046,0.00015,0.43,0.43,2.6,0.14,0.14,34,0.00077,0.00076,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
48 4590000,1,-0.01,-0.012,0.00019,0.017,-0.011,-0.58,0.0067,-0.0047,-1.2,-0.001,-0.005,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00017,0.52,0.52,2.7,0.19,0.19,36,0.0008,0.0008,1.5e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4590000,1,-0.01,-0.012,-8.6e-05,0.017,-0.011,-0.58,0.0066,-0.0047,-1.2,-0.001,-0.0051,4.2e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.51,0.51,2.7,0.19,0.19,36,0.00077,0.00076,1.4e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
49 4690000,1,-0.01,-0.012,0.0002,0.014,-0.0096,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,2.7,0.14,0.14,38,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4690000,1,-0.01,-0.012,-9.4e-05,0.013,-0.0095,-0.6,0.0048,-0.0033,-1.3,-0.0011,-0.0052,4.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.004,0.004,0.00015,0.4,0.4,2.7,0.14,0.14,38,0.00062,0.00061,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
50 4790000,1,-0.01,-0.012,0.00019,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,-7.8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.48,0.48,2.7,0.18,0.18,40,0.00065,0.00065,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4790000,1,-0.01,-0.012,-0.00011,0.015,-0.011,-0.61,0.0062,-0.0043,-1.4,-0.0011,-0.0052,4.4e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0043,0.0043,0.00015,0.47,0.47,2.7,0.18,0.18,40,0.00062,0.00061,1.3e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
51 4890000,1,-0.01,-0.011,0.00017,0.012,-0.0097,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.37,0.37,2.8,0.13,0.13,42,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4890000,1,-0.01,-0.011,-0.00013,0.012,-0.0095,-0.63,0.0044,-0.0031,-1.4,-0.0012,-0.0053,4.5e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0035,0.0035,0.00014,0.37,0.37,2.8,0.13,0.13,42,0.00049,0.00049,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
52 4990000,1,-0.01,-0.012,0.00015,0.015,-0.01,-0.64,0.0058,-0.0041,-1.5,-0.0012,-0.0053,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0041,0.0041,0.00015,0.44,0.44,2.8,0.17,0.17,44,0.00053,0.00053,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4990000,1,-0.01,-0.011,-0.00016,0.014,-0.01,-0.64,0.0057,-0.0041,-1.5,-0.0012,-0.0053,4.5e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00015,0.43,0.43,2.8,0.17,0.17,44,0.00049,0.00049,1.1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
53 5090000,1,-0.01,-0.011,0.0002,0.011,-0.0081,-0.66,0.0041,-0.003,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.34,0.34,2.8,0.12,0.12,47,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5090000,1,-0.01,-0.011,-0.00012,0.011,-0.0078,-0.66,0.0041,-0.0029,-1.6,-0.0013,-0.0054,4.6e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.34,0.34,2.8,0.12,0.12,47,0.00039,0.00039,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
54 5190000,1,-0.01,-0.011,0.00022,0.013,-0.0095,-0.67,0.0053,-0.0039,-1.6,-0.0013,-0.0054,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0036,0.0036,0.00014,0.4,0.4,2.9,0.16,0.16,49,0.00043,0.00043,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5190000,1,-0.01,-0.011,-0.0001,0.012,-0.0091,-0.67,0.0052,-0.0038,-1.6,-0.0013,-0.0054,4.6e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.4,0.4,2.9,0.16,0.16,49,0.00039,0.00039,1e-05,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
55 5290000,1,-0.0099,-0.011,0.00021,0.0086,-0.007,-0.68,0.0037,-0.0027,-1.7,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.31,0.31,2.9,0.12,0.12,51,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5290000,1,-0.0099,-0.011,-0.00012,0.0079,-0.0066,-0.68,0.0036,-0.0027,-1.7,-0.0013,-0.0055,4.7e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.31,0.31,2.9,0.12,0.12,51,0.00031,0.00031,9.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
56 5390000,1,-0.0099,-0.011,0.00027,0.0081,-0.0078,-0.7,0.0045,-0.0035,-1.8,-0.0013,-0.0055,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,3,0.16,0.16,54,0.00034,0.00034,9.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5390000,1,-0.0099,-0.011,-6.8e-05,0.0073,-0.0074,-0.7,0.0044,-0.0034,-1.8,-0.0013,-0.0055,4.7e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00014,0.36,0.36,3,0.15,0.15,54,0.00031,0.00031,9.1e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
57 5490000,1,-0.0098,-0.011,0.00028,0.0055,-0.0059,-0.71,0.0031,-0.0025,-1.8,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00013,0.28,0.28,3,0.11,0.11,56,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5490000,1,-0.0097,-0.011,-6.5e-05,0.0047,-0.0055,-0.71,0.0029,-0.0024,-1.8,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.28,0.28,3,0.11,0.11,56,0.00024,0.00024,8.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
58 5590000,1,-0.0097,-0.011,0.00026,0.0061,-0.0063,-0.73,0.0036,-0.003,-1.9,-0.0014,-0.0055,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,3,0.15,0.15,59,0.00028,0.00028,8.4e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5590000,1,-0.0097,-0.011,-9.2e-05,0.0053,-0.0058,-0.73,0.0034,-0.0029,-1.9,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.33,0.33,3,0.15,0.15,59,0.00024,0.00024,8.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
59 5690000,1,-0.0096,-0.011,0.00034,0.0041,-0.0036,-0.74,0.0025,-0.0021,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00012,0.26,0.26,3.1,0.11,0.11,61,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5690000,1,-0.0096,-0.011,-2.7e-05,0.0034,-0.0032,-0.74,0.0023,-0.002,-2,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.26,0.26,3.1,0.11,0.11,61,0.00019,0.00019,7.5e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
60 5790000,1,-0.0095,-0.011,0.00033,0.0044,-0.0026,-0.75,0.0029,-0.0024,-2,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00022,0.00022,7.6e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5790000,1,-0.0095,-0.011,-3.6e-05,0.0036,-0.0021,-0.75,0.0026,-0.0023,-2,-0.0014,-0.0056,4.8e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.002,0.002,0.00013,0.3,0.3,3.1,0.14,0.14,64,0.00019,0.00019,7.5e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
61 5890000,1,-0.0095,-0.011,0.00031,0.0038,-0.00081,0.0028,0.002,-0.0016,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,9.8,0.1,0.1,0.52,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5890000,1,-0.0095,-0.011,-6.6e-05,0.0031,-0.0004,0.0028,0.0018,-0.0015,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.24,0.24,9.8,0.1,0.1,0.52,0.00015,0.00015,6.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
62 5990000,1,-0.0094,-0.011,0.00033,0.0041,0.00065,0.015,0.0023,-0.0015,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,8.8,0.13,0.13,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5990000,1,-0.0094,-0.011,-4.9e-05,0.0033,0.0011,0.015,0.0021,-0.0014,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.00014,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00012,0.28,0.28,8.8,0.13,0.13,0.33,0.00015,0.00015,6.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
63 6090000,1,-0.0094,-0.011,0.00032,0.0051,0.0018,-0.011,0.0028,-0.0014,-3.7e+02,-0.0014,-0.0056,-7.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,7,0.17,0.17,0.33,0.00018,0.00018,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6090000,1,-0.0094,-0.011,-7e-05,0.0042,0.0023,-0.011,0.0024,-0.0012,-3.7e+02,-0.0015,-0.0056,4.9e-05,0,0,-0.00013,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00013,0.32,0.32,7,0.17,0.17,0.33,0.00015,0.00015,6.9e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
64 6190000,1,-0.0094,-0.011,0.00024,0.0038,0.0042,-0.005,0.002,-0.00048,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.25,0.25,4.9,0.13,0.13,0.32,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6190000,1,-0.0094,-0.011,-0.00015,0.003,0.0046,-0.005,0.0017,-0.00033,-3.7e+02,-0.0015,-0.0057,4.9e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.25,0.25,4.9,0.13,0.13,0.32,0.00012,0.00012,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
65 6290000,1,-0.0094,-0.011,0.00022,0.005,0.0042,-0.012,0.0025,-6.7e-05,-3.7e+02,-0.0015,-0.0056,-7.9e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.28,0.28,3.2,0.16,0.16,0.3,0.00015,0.00015,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6290000,1,-0.0094,-0.011,-0.00018,0.0042,0.0047,-0.012,0.0021,0.00013,-3.7e+02,-0.0015,-0.0057,4.9e-05,0,0,-0.00016,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.29,0.29,3.2,0.16,0.16,0.3,0.00012,0.00012,6.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
66 6390000,1,-0.0093,-0.011,0.00024,0.0043,0.0052,-0.05,0.0019,0.0004,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.0001,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,2.3,0.12,0.12,0.29,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6390000,0.77,-0.024,0.0046,-0.63,-0.012,-0.0013,-0.05,0.0011,-0.001,-3.7e+02,-0.0014,-0.0057,4.7e-05,0,0,-0.0001,-0.097,-0.021,0.51,-0.00012,-0.08,-0.061,0,0,0.0012,0.0012,0.065,0.21,0.21,2.3,0.12,0.12,0.29,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0014,0.00038,0.0014,0.001,0.0014,0.0014,1,1
67 6490000,1,-0.0093,-0.011,0.00023,0.0049,0.0053,-0.052,0.0023,0.00093,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00015,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.26,0.26,1.5,0.15,0.15,0.26,0.00012,0.00012,5.8e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6490000,0.78,-0.024,0.005,-0.63,-0.038,-0.012,-0.052,-0.0019,-0.0044,-3.7e+02,-0.0013,-0.0057,4.3e-05,0,0,-0.00015,-0.1,-0.022,0.51,-0.00039,-0.084,-0.064,0,0,0.0012,0.0012,0.056,0.21,0.21,1.5,0.15,0.15,0.26,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00022,0.0013,0.00092,0.0014,0.0013,1,1
68 6590000,1,-0.0094,-0.011,0.00017,0.0037,0.0053,-0.099,0.0018,0.00099,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,2.9e-05,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.2,0.2,1.1,0.12,0.12,0.23,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6590000,0.78,-0.024,0.0052,-0.63,-0.064,-0.021,-0.098,-0.0077,-0.0087,-3.7e+02,-0.0012,-0.0057,4e-05,-3.5e-05,0.00025,2.5e-05,-0.1,-0.023,0.51,-0.00086,-0.085,-0.066,0,0,0.0012,0.0012,0.053,0.22,0.22,1.1,0.18,0.18,0.23,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00017,0.0013,0.00088,0.0013,0.0013,1,1
69 6690000,1,-0.0093,-0.011,9.6e-05,0.0046,0.0047,-0.076,0.0022,0.0015,-3.7e+02,-0.0015,-0.0057,-8e-05,0,0,-0.00029,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.78,0.14,0.14,0.21,9.7e-05,9.7e-05,5.3e-06,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6690000,0.78,-0.024,0.0053,-0.63,-0.091,-0.035,-0.075,-0.017,-0.017,-3.7e+02,-0.001,-0.0057,3.5e-05,9.4e-05,0.00099,-0.0003,-0.1,-0.023,0.5,-0.001,-0.086,-0.067,0,0,0.0012,0.0012,0.051,0.23,0.23,0.78,0.22,0.22,0.21,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00014,0.0013,0.00087,0.0013,0.0013,1,1
70 6790000,0.78,-0.024,0.0049,-0.63,-0.0056,0.0015,-0.11,0.0015,0.00055,-3.7e+02,-0.0014,-0.0057,-8.2e-05,0,0,-5.8e-05,-0.092,-0.02,0.51,-0.00081,-0.075,-0.061,0,0,0.0013,0.0013,0.072,0.18,0.18,0.6,0.11,0.11,0.2,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0014,0.0005,0.0014,0.0011,0.0015,0.0014,1,1 6790000,0.78,-0.024,0.0054,-0.63,-0.12,-0.045,-0.11,-0.026,-0.026,-3.7e+02,-0.00088,-0.0057,3.2e-05,-9.9e-06,0.0015,-6.5e-05,-0.1,-0.023,0.5,-0.00099,-0.086,-0.068,0,0,0.0012,0.0012,0.051,0.25,0.25,0.6,0.26,0.26,0.2,9.8e-05,9.7e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00086,0.0013,0.0013,1,1
71 6890000,0.78,-0.025,0.0057,-0.63,-0.03,-0.0077,-0.12,-9e-05,-0.0018,-3.7e+02,-0.0013,-0.0057,-8.3e-05,0,0,-0.00011,-0.1,-0.022,0.51,-0.0011,-0.083,-0.067,0,0,0.0013,0.0013,0.057,0.18,0.18,0.46,0.14,0.14,0.18,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00024,0.0013,0.00094,0.0014,0.0013,1,1 6890000,0.78,-0.024,0.0054,-0.63,-0.14,-0.053,-0.12,-0.038,-0.033,-3.7e+02,-0.00083,-0.0057,3.1e-05,-7e-05,0.0017,-0.00011,-0.1,-0.023,0.5,-0.001,-0.086,-0.068,0,0,0.0012,0.0012,0.05,0.26,0.26,0.46,0.31,0.31,0.18,9.7e-05,9.7e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00086,0.0013,0.0013,1,1
72 6990000,0.78,-0.025,0.0058,-0.63,-0.059,-0.018,-0.12,-0.0053,-0.0061,-3.7e+02,-0.0012,-0.0057,-8.7e-05,-2.7e-05,-6.9e-05,-0.00041,-0.1,-0.022,0.5,-0.0015,-0.084,-0.067,0,0,0.0013,0.0013,0.053,0.19,0.18,0.36,0.17,0.17,0.16,8e-05,8e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00018,0.0013,0.0009,0.0014,0.0013,1,1 6990000,0.78,-0.024,0.0054,-0.63,-0.17,-0.065,-0.12,-0.059,-0.045,-3.7e+02,-0.00069,-0.0058,2.4e-05,0.00036,0.0023,-0.00042,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0012,0.0012,0.05,0.28,0.28,0.36,0.36,0.36,0.16,9.6e-05,9.6e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.00011,0.0013,0.00085,0.0013,0.0013,1,1
73 7090000,0.78,-0.025,0.0059,-0.63,-0.087,-0.028,-0.12,-0.014,-0.012,-3.7e+02,-0.0011,-0.0057,-9.1e-05,-8.3e-05,-0.00024,-0.00077,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.052,0.19,0.19,0.29,0.2,0.2,0.16,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00015,0.0013,0.00089,0.0013,0.0013,1,1 7090000,0.78,-0.024,0.0056,-0.63,-0.2,-0.077,-0.12,-0.084,-0.062,-3.7e+02,-0.0005,-0.0059,1.6e-05,0.00085,0.0031,-0.00078,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0012,0.0013,0.049,0.31,0.31,0.29,0.42,0.42,0.16,9.5e-05,9.6e-05,5.8e-06,0.04,0.04,0.04,0.0013,0.0001,0.0013,0.00085,0.0013,0.0013,1,1
74 7190000,0.78,-0.025,0.006,-0.63,-0.11,-0.037,-0.15,-0.024,-0.018,-3.7e+02,-0.001,-0.0057,-9.3e-05,-7.7e-05,-0.00036,-0.00056,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.051,0.21,0.21,0.24,0.23,0.23,0.15,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00013,0.0013,0.00088,0.0013,0.0013,1,1 7190000,0.78,-0.024,0.0056,-0.63,-0.23,-0.085,-0.14,-0.11,-0.073,-3.7e+02,-0.00044,-0.006,1.3e-05,0.001,0.0033,-0.00056,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.34,0.33,0.24,0.49,0.48,0.15,9.4e-05,9.4e-05,5.8e-06,0.04,0.04,0.04,0.0013,9.9e-05,0.0013,0.00085,0.0013,0.0013,1,1
75 7290000,0.78,-0.025,0.0059,-0.63,-0.14,-0.04,-0.14,-0.035,-0.019,-3.7e+02,-0.0011,-0.0057,-9e-05,-4.6e-05,-0.00024,-0.0012,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.22,0.22,0.2,0.28,0.28,0.14,7.9e-05,7.9e-05,4.9e-06,0.04,0.04,0.04,0.0013,0.00012,0.0013,0.00087,0.0013,0.0013,1,1 7290000,0.78,-0.024,0.0056,-0.63,-0.25,-0.081,-0.14,-0.13,-0.068,-3.7e+02,-0.00066,-0.006,2e-05,0.00095,0.0024,-0.0012,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.37,0.36,0.2,0.56,0.55,0.14,9.2e-05,9.3e-05,5.8e-06,0.04,0.04,0.04,0.0013,9.5e-05,0.0013,0.00085,0.0013,0.0013,1,1
76 7390000,0.78,-0.025,0.0059,-0.63,-0.16,-0.048,-0.16,-0.049,-0.025,-3.7e+02,-0.0011,-0.0057,-9e-05,8.1e-07,-0.00028,-0.0014,-0.1,-0.023,0.5,-0.0017,-0.085,-0.068,0,0,0.0013,0.0013,0.05,0.24,0.24,0.18,0.32,0.32,0.13,7.8e-05,7.9e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.00011,0.0013,0.00087,0.0013,0.0013,1,1 7390000,0.78,-0.024,0.0056,-0.63,-0.28,-0.086,-0.16,-0.16,-0.075,-3.7e+02,-0.0007,-0.0059,2.2e-05,0.00083,0.0023,-0.0014,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.4,0.39,0.18,0.63,0.63,0.13,9.1e-05,9.1e-05,5.8e-06,0.04,0.04,0.039,0.0013,9.2e-05,0.0013,0.00084,0.0013,0.0013,1,1
77 7490000,0.78,-0.025,0.0059,-0.63,-0.19,-0.061,-0.16,-0.066,-0.038,-3.7e+02,-0.00093,-0.0057,-9.3e-05,1.6e-05,-0.0005,-0.0022,-0.1,-0.023,0.5,-0.0017,-0.085,-0.069,0,0,0.0013,0.0013,0.049,0.27,0.26,0.15,0.37,0.37,0.12,7.8e-05,7.8e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1 7490000,0.78,-0.024,0.0057,-0.63,-0.3,-0.1,-0.16,-0.19,-0.096,-3.7e+02,-0.00051,-0.0059,1.6e-05,0.0008,0.0031,-0.0021,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0013,0.0013,0.049,0.44,0.43,0.15,0.72,0.71,0.12,8.9e-05,9e-05,5.8e-06,0.04,0.04,0.039,0.0013,9e-05,0.0013,0.00084,0.0013,0.0013,1,1
78 7590000,0.78,-0.025,0.0059,-0.63,-0.21,-0.067,-0.16,-0.082,-0.044,-3.7e+02,-0.00093,-0.0056,-9e-05,0.00011,-0.00047,-0.003,-0.1,-0.023,0.5,-0.0016,-0.085,-0.068,0,0,0.0013,0.0013,0.049,0.29,0.29,0.14,0.43,0.43,0.12,7.7e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,0.0001,0.0013,0.00086,0.0013,0.0013,1,1 7590000,0.78,-0.024,0.0056,-0.63,-0.32,-0.1,-0.16,-0.21,-0.1,-3.7e+02,-0.00059,-0.0058,2.1e-05,0.00036,0.0028,-0.003,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0013,0.0013,0.048,0.47,0.47,0.14,0.81,0.8,0.12,8.6e-05,8.7e-05,5.8e-06,0.04,0.04,0.039,0.0013,8.7e-05,0.0013,0.00084,0.0013,0.0013,1,1
79 7690000,0.78,-0.025,0.0059,-0.63,-0.24,-0.079,-0.16,-0.1,-0.058,-3.7e+02,-0.00082,-0.0056,-9.3e-05,8.3e-05,-0.00057,-0.005,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.32,0.32,0.13,0.49,0.49,0.11,7.6e-05,7.7e-05,4.9e-06,0.04,0.04,0.039,0.0013,9.6e-05,0.0013,0.00086,0.0013,0.0013,1,1 7690000,0.78,-0.024,0.0056,-0.63,-0.35,-0.11,-0.16,-0.24,-0.12,-3.7e+02,-0.00048,-0.0058,1.8e-05,0.00033,0.0033,-0.005,-0.1,-0.023,0.5,-0.0011,-0.086,-0.068,0,0,0.0013,0.0014,0.048,0.52,0.51,0.13,0.91,0.9,0.11,8.4e-05,8.5e-05,5.8e-06,0.04,0.04,0.039,0.0013,8.6e-05,0.0013,0.00084,0.0013,0.0013,1,1
80 7790000,0.78,-0.025,0.006,-0.63,-0.27,-0.088,-0.16,-0.14,-0.072,-3.7e+02,-0.00074,-0.0057,-9.9e-05,-0.00013,-0.00063,-0.007,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.35,0.35,0.12,0.56,0.55,0.11,7.5e-05,7.5e-05,4.9e-06,0.04,0.04,0.038,0.0013,9.3e-05,0.0013,0.00086,0.0013,0.0013,1,1 7790000,0.78,-0.024,0.0058,-0.63,-0.39,-0.12,-0.16,-0.3,-0.14,-3.7e+02,-0.00042,-0.006,1.2e-05,0.001,0.0036,-0.007,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0014,0.0014,0.048,0.56,0.55,0.12,1,1,0.11,8.1e-05,8.2e-05,5.7e-06,0.04,0.04,0.038,0.0013,8.4e-05,0.0013,0.00084,0.0013,0.0013,1,1
81 7890000,0.78,-0.025,0.006,-0.63,-0.29,-0.099,-0.15,-0.16,-0.086,-3.7e+02,-0.00067,-0.0056,-9.8e-05,-8.1e-05,-0.00064,-0.0095,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.39,0.38,0.11,0.63,0.63,0.1,7.4e-05,7.4e-05,4.9e-06,0.04,0.04,0.038,0.0013,9e-05,0.0013,0.00086,0.0013,0.0013,1,1 7890000,0.78,-0.025,0.0058,-0.63,-0.41,-0.13,-0.15,-0.33,-0.15,-3.7e+02,-0.00039,-0.0059,1.3e-05,0.00063,0.0039,-0.0095,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0014,0.0014,0.048,0.61,0.6,0.11,1.1,1.1,0.1,7.8e-05,8e-05,5.7e-06,0.04,0.04,0.038,0.0013,8.3e-05,0.0013,0.00084,0.0013,0.0013,1,1
82 7990000,0.78,-0.025,0.006,-0.63,-0.32,-0.11,-0.16,-0.19,-0.098,-3.7e+02,-0.00064,-0.0056,-9.7e-05,2.6e-06,-0.00064,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.049,0.43,0.42,0.1,0.71,0.71,0.099,7.2e-05,7.3e-05,4.9e-06,0.04,0.04,0.038,0.0013,8.8e-05,0.0013,0.00086,0.0013,0.0013,1,1 7990000,0.78,-0.025,0.0057,-0.63,-0.43,-0.14,-0.16,-0.37,-0.16,-3.7e+02,-0.00041,-0.0058,1.6e-05,0.00027,0.0038,-0.011,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.66,0.65,0.1,1.3,1.2,0.099,7.5e-05,7.6e-05,5.7e-06,0.04,0.04,0.038,0.0013,8.1e-05,0.0013,0.00084,0.0013,0.0013,1,1
83 8090000,0.78,-0.025,0.006,-0.63,-0.34,-0.12,-0.17,-0.21,-0.11,-3.7e+02,-0.00058,-0.0054,-9.5e-05,0.00017,-0.00074,-0.011,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.47,0.46,0.1,0.8,0.8,0.097,7e-05,7.1e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.6e-05,0.0013,0.00086,0.0013,0.0013,1,1 8090000,0.78,-0.025,0.0057,-0.63,-0.45,-0.15,-0.17,-0.4,-0.18,-3.7e+02,-0.00037,-0.0057,1.8e-05,-0.00027,0.004,-0.011,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.72,0.71,0.1,1.4,1.4,0.097,7.2e-05,7.4e-05,5.7e-06,0.04,0.04,0.037,0.0013,8e-05,0.0013,0.00084,0.0013,0.0013,1,1
84 8190000,0.78,-0.025,0.0061,-0.63,-0.37,-0.13,-0.17,-0.25,-0.13,-3.7e+02,-0.00056,-0.0055,-9.8e-05,-2.7e-05,-0.00068,-0.013,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0014,0.048,0.52,0.51,0.099,0.9,0.89,0.094,6.8e-05,6.9e-05,4.9e-06,0.04,0.04,0.037,0.0013,8.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 8190000,0.78,-0.025,0.0058,-0.63,-0.48,-0.15,-0.17,-0.46,-0.19,-3.7e+02,-0.0004,-0.0058,1.5e-05,0.00019,0.004,-0.013,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.78,0.76,0.099,1.6,1.5,0.094,6.8e-05,7e-05,5.7e-06,0.04,0.04,0.037,0.0013,7.9e-05,0.0013,0.00084,0.0013,0.0013,1,1
85 8290000,0.78,-0.025,0.0061,-0.63,-0.019,-0.0046,-0.17,-0.27,-0.13,-3.7e+02,-0.00042,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.017,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.6e-05,6.7e-05,4.9e-06,0.04,0.04,0.036,0.0013,8.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 8290000,0.78,-0.025,0.006,-0.63,-0.022,-0.005,-0.17,-0.47,-0.2,-3.7e+02,-0.00028,-0.0059,1e-05,0.00027,0.0041,-0.017,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.092,6.5e-05,6.7e-05,5.7e-06,0.04,0.04,0.036,0.0013,7.8e-05,0.0013,0.00084,0.0013,0.0013,1,1
86 8390000,0.78,-0.025,0.0061,-0.63,-0.046,-0.012,-0.17,-0.27,-0.13,-3.7e+02,-0.00038,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.021,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.4e-05,6.5e-05,4.9e-06,0.04,0.04,0.035,0.0013,8.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 8390000,0.78,-0.025,0.0059,-0.63,-0.048,-0.012,-0.17,-0.47,-0.2,-3.7e+02,-0.00026,-0.0058,1.3e-05,0.00027,0.0041,-0.021,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0014,0.0015,0.048,25,25,0.097,1e+02,1e+02,0.091,6.2e-05,6.4e-05,5.7e-06,0.04,0.04,0.035,0.0013,7.8e-05,0.0013,0.00084,0.0013,0.0013,1,1
87 8490000,0.78,-0.026,0.0062,-0.63,-0.073,-0.02,-0.17,-0.27,-0.13,-3.7e+02,-0.00033,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.025,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,51,51,0.089,6.2e-05,6.3e-05,4.9e-06,0.04,0.04,0.034,0.0013,8.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 8490000,0.78,-0.025,0.006,-0.63,-0.075,-0.019,-0.17,-0.48,-0.2,-3.7e+02,-0.00026,-0.0058,1.1e-05,0.00027,0.0041,-0.025,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,51,51,0.089,5.8e-05,6.1e-05,5.7e-06,0.04,0.04,0.034,0.0013,7.7e-05,0.0013,0.00084,0.0013,0.0013,1,1
88 8590000,0.78,-0.025,0.0062,-0.63,-0.099,-0.028,-0.16,-0.28,-0.14,-3.7e+02,-0.00051,-0.0056,-0.0001,-6.1e-05,-0.00064,-0.029,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.095,52,52,0.088,5.9e-05,6.1e-05,4.9e-06,0.04,0.04,0.034,0.0013,8e-05,0.0013,0.00085,0.0013,0.0013,1,1 8590000,0.78,-0.025,0.0059,-0.63,-0.099,-0.026,-0.16,-0.48,-0.2,-3.7e+02,-0.0005,-0.006,1.5e-05,0.00027,0.0041,-0.029,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.095,52,52,0.088,5.5e-05,5.7e-05,5.7e-06,0.04,0.04,0.034,0.0013,7.6e-05,0.0013,0.00084,0.0013,0.0013,1,1
89 8690000,0.78,-0.025,0.0061,-0.63,-0.12,-0.036,-0.16,-0.28,-0.14,-3.7e+02,-0.00047,-0.0055,-9.9e-05,-6.1e-05,-0.00064,-0.034,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.096,35,35,0.088,5.7e-05,5.9e-05,4.9e-06,0.04,0.04,0.033,0.0013,7.9e-05,0.0013,0.00085,0.0013,0.0013,1,1 8690000,0.78,-0.025,0.0058,-0.63,-0.12,-0.034,-0.16,-0.49,-0.21,-3.7e+02,-0.00048,-0.0058,1.9e-05,0.00027,0.0041,-0.034,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,35,35,0.088,5.2e-05,5.5e-05,5.7e-06,0.04,0.04,0.033,0.0013,7.6e-05,0.0013,0.00084,0.0013,0.0013,1,1
90 8790000,0.78,-0.026,0.0062,-0.63,-0.15,-0.044,-0.15,-0.3,-0.14,-3.7e+02,-0.0004,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.04,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,37,37,0.087,5.5e-05,5.6e-05,4.9e-06,0.04,0.04,0.032,0.0013,7.8e-05,0.0013,0.00085,0.0013,0.0013,1,1 8790000,0.78,-0.025,0.006,-0.63,-0.15,-0.04,-0.15,-0.5,-0.21,-3.7e+02,-0.00044,-0.0059,1.6e-05,0.00027,0.0041,-0.04,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,25,25,0.096,37,37,0.087,4.9e-05,5.1e-05,5.7e-06,0.04,0.04,0.032,0.0013,7.5e-05,0.0013,0.00084,0.0013,0.0013,1,1
91 8890000,0.78,-0.026,0.0063,-0.63,-0.18,-0.05,-0.15,-0.3,-0.14,-3.7e+02,-0.00037,-0.0056,-0.00011,-6.1e-05,-0.00064,-0.044,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.095,28,28,0.086,5.2e-05,5.4e-05,4.9e-06,0.04,0.04,0.03,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1 8890000,0.78,-0.025,0.0061,-0.63,-0.17,-0.045,-0.15,-0.51,-0.21,-3.7e+02,-0.00043,-0.0059,1.4e-05,0.00027,0.0041,-0.044,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.095,28,28,0.086,4.6e-05,4.8e-05,5.7e-06,0.04,0.04,0.03,0.0013,7.4e-05,0.0013,0.00084,0.0013,0.0013,1,1
92 8990000,0.78,-0.026,0.0064,-0.63,-0.21,-0.056,-0.14,-0.32,-0.15,-3.7e+02,-0.00029,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.05,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,24,24,0.096,30,30,0.087,5e-05,5.1e-05,4.9e-06,0.04,0.04,0.029,0.0013,7.7e-05,0.0013,0.00085,0.0013,0.0013,1,1 8990000,0.78,-0.025,0.0062,-0.63,-0.2,-0.05,-0.14,-0.53,-0.21,-3.7e+02,-0.00036,-0.006,9.8e-06,0.00027,0.0041,-0.05,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0015,0.0015,0.048,24,24,0.096,30,30,0.087,4.4e-05,4.6e-05,5.7e-06,0.04,0.04,0.029,0.0013,7.4e-05,0.0013,0.00084,0.0013,0.0013,1,1
93 9090000,0.78,-0.026,0.0065,-0.63,-0.23,-0.06,-0.14,-0.33,-0.15,-3.7e+02,-0.00033,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.052,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.095,25,25,0.086,4.7e-05,4.9e-05,4.9e-06,0.04,0.04,0.028,0.0013,7.6e-05,0.0013,0.00085,0.0013,0.0013,1,1 9090000,0.78,-0.025,0.0062,-0.63,-0.22,-0.053,-0.14,-0.53,-0.21,-3.7e+02,-0.00043,-0.0061,1e-05,0.00027,0.0041,-0.052,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.095,25,25,0.086,4.1e-05,4.3e-05,5.7e-06,0.04,0.04,0.028,0.0013,7.4e-05,0.0013,0.00084,0.0013,0.0013,1,1
94 9190000,0.78,-0.026,0.0063,-0.63,-0.25,-0.071,-0.14,-0.35,-0.16,-3.7e+02,-0.00029,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.056,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.094,27,27,0.085,4.5e-05,4.6e-05,4.9e-06,0.04,0.04,0.027,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 9190000,0.78,-0.025,0.006,-0.63,-0.25,-0.065,-0.14,-0.55,-0.22,-3.7e+02,-0.0004,-0.0058,1.5e-05,0.00027,0.0041,-0.055,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,23,23,0.094,27,27,0.085,3.8e-05,4.1e-05,5.7e-06,0.04,0.04,0.027,0.0013,7.3e-05,0.0013,0.00084,0.0013,0.0013,1,1
95 9290000,0.78,-0.026,0.0063,-0.63,-0.27,-0.077,-0.13,-0.35,-0.16,-3.7e+02,-0.00023,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.06,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,23,23,0.085,4.2e-05,4.4e-05,4.9e-06,0.04,0.04,0.025,0.0013,7.5e-05,0.0013,0.00085,0.0013,0.0013,1,1 9290000,0.78,-0.025,0.0061,-0.63,-0.27,-0.071,-0.13,-0.56,-0.22,-3.7e+02,-0.00036,-0.0058,1.5e-05,0.00027,0.0041,-0.06,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,23,23,0.085,3.6e-05,3.8e-05,5.7e-06,0.04,0.04,0.025,0.0013,7.3e-05,0.0013,0.00084,0.0013,0.0013,1,1
96 9390000,0.78,-0.026,0.0065,-0.63,-0.3,-0.086,-0.13,-0.38,-0.17,-3.7e+02,-0.00018,-0.0055,-0.00011,-6.1e-05,-0.00064,-0.063,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,21,21,0.093,25,25,0.086,4e-05,4.2e-05,4.9e-06,0.04,0.04,0.024,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1 9390000,0.78,-0.025,0.0062,-0.63,-0.3,-0.079,-0.13,-0.59,-0.23,-3.7e+02,-0.00032,-0.0058,1.3e-05,0.00027,0.0041,-0.063,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,21,21,0.093,26,26,0.086,3.4e-05,3.6e-05,5.7e-06,0.04,0.04,0.024,0.0013,7.2e-05,0.0013,0.00084,0.0013,0.0013,1,1
97 9490000,0.78,-0.026,0.0064,-0.63,-0.31,-0.092,-0.13,-0.38,-0.17,-3.7e+02,-0.00011,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.067,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.091,22,22,0.085,3.8e-05,4e-05,4.9e-06,0.04,0.04,0.023,0.0013,7.4e-05,0.0013,0.00085,0.0013,0.0013,1,1 9490000,0.78,-0.026,0.0061,-0.63,-0.31,-0.086,-0.13,-0.59,-0.23,-3.7e+02,-0.00027,-0.0057,1.6e-05,0.00027,0.0041,-0.067,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,19,19,0.091,22,22,0.085,3.2e-05,3.4e-05,5.7e-06,0.04,0.04,0.023,0.0013,7.2e-05,0.0013,0.00083,0.0013,0.0013,1,1
98 9590000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.18,-3.7e+02,-0.00024,-0.0053,-0.0001,-6.1e-05,-0.00064,-0.07,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,19,19,0.09,25,25,0.085,3.6e-05,3.7e-05,4.9e-06,0.04,0.04,0.022,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 9590000,0.78,-0.025,0.0059,-0.63,-0.33,-0.095,-0.12,-0.62,-0.24,-3.7e+02,-0.0004,-0.0056,2e-05,0.00027,0.0041,-0.07,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,19,19,0.09,25,25,0.085,3e-05,3.2e-05,5.7e-06,0.04,0.04,0.022,0.0013,7.2e-05,0.0013,0.00083,0.0013,0.0013,1,1
99 9690000,0.78,-0.026,0.0063,-0.63,-0.34,-0.1,-0.12,-0.41,-0.17,-3.7e+02,-0.0003,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.075,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.089,22,22,0.086,3.4e-05,3.6e-05,4.9e-06,0.04,0.04,0.02,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 9690000,0.78,-0.025,0.006,-0.63,-0.33,-0.091,-0.12,-0.61,-0.24,-3.7e+02,-0.00046,-0.0058,1.8e-05,0.00027,0.0041,-0.075,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,17,17,0.089,22,22,0.086,2.8e-05,3e-05,5.7e-06,0.04,0.04,0.02,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1
100 9790000,0.78,-0.026,0.0063,-0.63,-0.38,-0.11,-0.1,-0.45,-0.19,-3.7e+02,-0.00026,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.08,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.087,24,24,0.085,3.2e-05,3.4e-05,4.9e-06,0.04,0.04,0.019,0.0013,7.3e-05,0.0013,0.00085,0.0013,0.0013,1,1 9790000,0.78,-0.025,0.006,-0.63,-0.36,-0.1,-0.11,-0.65,-0.25,-3.7e+02,-0.00043,-0.0057,1.9e-05,0.00027,0.0041,-0.08,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,17,17,0.087,25,25,0.085,2.6e-05,2.8e-05,5.7e-06,0.04,0.04,0.019,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1
101 9890000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.1,-0.48,-0.2,-3.7e+02,-0.00033,-0.0054,-0.0001,-6.1e-05,-0.00064,-0.083,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,17,17,0.084,28,28,0.085,3e-05,3.2e-05,4.9e-06,0.04,0.04,0.018,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 9890000,0.78,-0.025,0.0059,-0.63,-0.36,-0.1,-0.1,-0.64,-0.25,-3.7e+02,-0.0005,-0.0057,2.1e-05,0.00027,0.0041,-0.083,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,15,15,0.084,22,22,0.085,2.5e-05,2.6e-05,5.7e-06,0.04,0.04,0.018,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1
102 9990000,0.78,-0.026,0.0063,-0.63,-0.4,-0.12,-0.096,-0.47,-0.19,-3.7e+02,-0.00035,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.086,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.083,24,24,0.086,2.8e-05,3e-05,4.9e-06,0.04,0.04,0.017,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 9990000,0.78,-0.025,0.006,-0.63,-0.39,-0.11,-0.097,-0.67,-0.26,-3.7e+02,-0.00052,-0.0058,2e-05,0.00027,0.0041,-0.086,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,15,15,0.083,25,25,0.086,2.3e-05,2.5e-05,5.7e-06,0.04,0.04,0.017,0.0013,7.1e-05,0.0013,0.00083,0.0013,0.0013,1,1
103 10090000,0.78,-0.026,0.0062,-0.63,-0.43,-0.12,-0.092,-0.51,-0.2,-3.7e+02,-0.00043,-0.0055,-0.0001,-6.1e-05,-0.00064,-0.089,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,15,15,0.081,27,27,0.085,2.7e-05,2.8e-05,4.9e-06,0.04,0.04,0.016,0.0013,7.2e-05,0.0013,0.00085,0.0013,0.0013,1,1 10090000,0.78,-0.025,0.0059,-0.63,-0.41,-0.11,-0.093,-0.71,-0.27,-3.7e+02,-0.0006,-0.0057,2.3e-05,0.00027,0.0041,-0.089,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0016,0.048,15,15,0.081,28,28,0.085,2.2e-05,2.4e-05,5.7e-06,0.04,0.04,0.016,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1
104 10190000,0.78,-0.026,0.0065,-0.63,-0.43,-0.12,-0.092,-0.5,-0.2,-3.7e+02,-0.00044,-0.0057,-0.00011,-6.1e-05,-0.00064,-0.09,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,13,0.078,24,24,0.084,2.5e-05,2.7e-05,4.9e-06,0.04,0.04,0.015,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 10190000,0.78,-0.025,0.0061,-0.63,-0.41,-0.11,-0.093,-0.7,-0.26,-3.7e+02,-0.00061,-0.0059,1.9e-05,0.00027,0.0041,-0.09,-0.1,-0.023,0.5,-0.0012,-0.086,-0.069,0,0,0.0015,0.0015,0.048,14,14,0.078,24,24,0.084,2.1e-05,2.2e-05,5.7e-06,0.04,0.04,0.015,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1
105 10290000,0.78,-0.026,0.0067,-0.63,-0.46,-0.12,-0.08,-0.55,-0.21,-3.7e+02,-0.00045,-0.0058,-0.00011,-6.1e-05,-0.00064,-0.096,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,14,14,0.076,27,27,0.085,2.4e-05,2.5e-05,4.9e-06,0.04,0.04,0.014,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 10290000,0.78,-0.025,0.0063,-0.63,-0.44,-0.11,-0.08,-0.74,-0.27,-3.7e+02,-0.00062,-0.006,1.7e-05,0.00027,0.0041,-0.096,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0015,0.0015,0.048,14,14,0.076,27,27,0.085,1.9e-05,2.1e-05,5.7e-06,0.04,0.04,0.014,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1
106 10390000,0.78,-0.026,0.0068,-0.63,-0.017,-0.027,0.0097,-0.00031,-0.0021,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00013,-0.00061,-0.099,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.25,0.25,0.56,0.25,0.25,0.078,2.2e-05,2.4e-05,4.9e-06,0.04,0.04,0.013,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 10390000,0.78,-0.025,0.0064,-0.63,-0.016,-0.026,0.0097,-0.00026,-0.0021,-3.7e+02,-0.00059,-0.006,1.7e-05,0.00022,0.0044,-0.099,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0015,0.0015,0.048,0.25,0.25,0.56,0.25,0.25,0.078,1.8e-05,2e-05,5.7e-06,0.04,0.039,0.013,0.0013,7e-05,0.0013,0.00083,0.0013,0.0013,1,1
107 10490000,0.78,-0.026,0.0069,-0.63,-0.047,-0.034,0.023,-0.0035,-0.0051,-3.7e+02,-0.00042,-0.0058,-0.00011,-0.00035,-0.00043,-0.1,-0.1,-0.023,0.5,-0.0016,-0.086,-0.069,0,0,0.0016,0.0016,0.048,0.26,0.26,0.55,0.26,0.26,0.08,2.1e-05,2.3e-05,4.9e-06,0.04,0.04,0.012,0.0013,7.1e-05,0.0013,0.00085,0.0013,0.0013,1,1 10490000,0.78,-0.025,0.0065,-0.63,-0.044,-0.032,0.023,-0.0033,-0.0049,-3.7e+02,-0.00059,-0.0061,1.5e-05,0.00043,0.0046,-0.1,-0.1,-0.023,0.5,-0.0012,-0.086,-0.068,0,0,0.0015,0.0015,0.048,0.26,0.26,0.55,0.26,0.26,0.08,1.7e-05,1.9e-05,5.7e-06,0.04,0.039,0.012,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
108 10590000,0.78,-0.026,0.0066,-0.63,-0.045,-0.023,0.026,0.0012,-0.0011,-3.7e+02,-0.00059,-0.0058,-0.00011,-3.5e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.13,0.13,0.27,0.13,0.13,0.073,2e-05,2.1e-05,4.9e-06,0.04,0.04,0.012,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1 10590000,0.78,-0.025,0.0062,-0.63,-0.042,-0.021,0.026,0.0012,-0.001,-3.7e+02,-0.00075,-0.006,2e-05,0.00066,0.0031,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.13,0.13,0.27,0.13,0.13,0.073,1.6e-05,1.8e-05,5.7e-06,0.039,0.039,0.012,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
109 10690000,0.78,-0.026,0.0066,-0.63,-0.073,-0.029,0.03,-0.0048,-0.0037,-3.7e+02,-0.00059,-0.0059,-0.00011,-9.8e-05,-0.0011,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.14,0.14,0.26,0.14,0.14,0.078,1.9e-05,2e-05,4.9e-06,0.04,0.04,0.011,0.0013,7e-05,0.0013,0.00085,0.0013,0.0013,1,1 10690000,0.78,-0.025,0.0063,-0.63,-0.069,-0.026,0.03,-0.0044,-0.0034,-3.7e+02,-0.00074,-0.0061,1.9e-05,0.00069,0.0031,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.14,0.14,0.26,0.14,0.14,0.078,1.5e-05,1.7e-05,5.7e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
110 10790000,0.78,-0.025,0.0064,-0.63,-0.069,-0.024,0.024,-0.0001,-0.0015,-3.7e+02,-0.00063,-0.0058,-0.00011,0.00028,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0016,0.048,0.096,0.096,0.17,0.09,0.09,0.072,1.8e-05,1.9e-05,4.8e-06,0.04,0.039,0.011,0.0013,7e-05,0.0013,0.00084,0.0013,0.0013,1,1 10790000,0.78,-0.024,0.006,-0.63,-0.065,-0.021,0.024,4.9e-05,-0.0014,-3.7e+02,-0.00079,-0.006,2.2e-05,0.00087,0.00042,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.096,0.096,0.17,0.09,0.09,0.072,1.4e-05,1.6e-05,5.7e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1
111 10890000,0.78,-0.025,0.0064,-0.63,-0.097,-0.03,0.02,-0.0084,-0.0042,-3.7e+02,-0.00063,-0.0058,-0.00011,0.0003,-0.0037,-0.1,-0.1,-0.023,0.5,-0.0015,-0.086,-0.069,0,0,0.0015,0.0015,0.048,0.11,0.11,0.16,0.096,0.096,0.075,1.7e-05,1.8e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00084,0.0013,0.0013,1,1 10890000,0.78,-0.024,0.0061,-0.63,-0.092,-0.026,0.02,-0.0078,-0.0038,-3.7e+02,-0.00079,-0.006,2.3e-05,0.00083,0.00041,-0.1,-0.1,-0.023,0.5,-0.0011,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.11,0.11,0.16,0.096,0.096,0.075,1.4e-05,1.5e-05,5.7e-06,0.039,0.039,0.011,0.0013,6.8e-05,0.0013,0.00083,0.0013,0.0013,1,1
112 10990000,0.78,-0.025,0.0059,-0.63,-0.085,-0.024,0.014,-0.0037,-0.0024,-3.7e+02,-0.00066,-0.0058,-0.0001,0.0011,-0.009,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.086,0.086,0.12,0.099,0.099,0.071,1.6e-05,1.7e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 10990000,0.78,-0.024,0.0055,-0.63,-0.08,-0.021,0.014,-0.0033,-0.0021,-3.7e+02,-0.00081,-0.0059,2.7e-05,0.0011,-0.0047,-0.11,-0.1,-0.023,0.5,-0.001,-0.087,-0.069,0,0,0.0013,0.0014,0.048,0.086,0.086,0.12,0.099,0.099,0.071,1.3e-05,1.4e-05,5.7e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1
113 11090000,0.78,-0.025,0.0057,-0.63,-0.11,-0.032,0.019,-0.013,-0.0054,-3.7e+02,-0.00069,-0.0057,-9.6e-05,0.0013,-0.0089,-0.11,-0.1,-0.023,0.5,-0.0014,-0.086,-0.069,0,0,0.0014,0.0015,0.048,0.1,0.1,0.11,0.11,0.11,0.074,1.5e-05,1.6e-05,4.8e-06,0.039,0.039,0.011,0.0013,6.9e-05,0.0013,0.00083,0.0013,0.0013,1,1 11090000,0.78,-0.024,0.0054,-0.63,-0.1,-0.028,0.019,-0.012,-0.0047,-3.7e+02,-0.00084,-0.0059,3e-05,0.00085,-0.0047,-0.11,-0.1,-0.023,0.5,-0.00099,-0.087,-0.069,0,0,0.0013,0.0014,0.048,0.099,0.1,0.11,0.11,0.11,0.074,1.2e-05,1.3e-05,5.7e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1
114 11190000,0.78,-0.024,0.0051,-0.63,-0.095,-0.025,0.0078,-0.0051,-0.0021,-3.7e+02,-0.00079,-0.0057,-9.3e-05,0.0019,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.084,0.084,0.084,0.11,0.11,0.069,1.4e-05,1.5e-05,4.8e-06,0.038,0.038,0.011,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1 11190000,0.78,-0.023,0.0048,-0.63,-0.09,-0.021,0.0078,-0.0044,-0.0017,-3.7e+02,-0.00094,-0.0059,3.4e-05,0.0015,-0.012,-0.11,-0.11,-0.023,0.5,-0.00094,-0.087,-0.069,0,0,0.0012,0.0013,0.048,0.083,0.083,0.084,0.11,0.11,0.069,1.1e-05,1.2e-05,5.7e-06,0.037,0.037,0.011,0.0013,6.8e-05,0.0013,0.00081,0.0013,0.0013,1,1
115 11290000,0.78,-0.024,0.0052,-0.63,-0.12,-0.029,0.0076,-0.016,-0.0046,-3.7e+02,-0.00074,-0.0058,-9.7e-05,0.0016,-0.016,-0.11,-0.1,-0.023,0.5,-0.0013,-0.087,-0.069,0,0,0.0013,0.0013,0.048,0.099,0.099,0.078,0.12,0.12,0.072,1.3e-05,1.4e-05,4.8e-06,0.038,0.038,0.01,0.0013,6.8e-05,0.0013,0.00082,0.0013,0.0013,1,1 11290000,0.78,-0.023,0.0049,-0.63,-0.11,-0.025,0.0076,-0.015,-0.0037,-3.7e+02,-0.00089,-0.006,3.1e-05,0.0016,-0.011,-0.11,-0.11,-0.023,0.5,-0.00098,-0.087,-0.069,0,0,0.0012,0.0013,0.047,0.098,0.098,0.078,0.12,0.12,0.072,1.1e-05,1.2e-05,5.7e-06,0.037,0.037,0.01,0.0013,6.7e-05,0.0013,0.00081,0.0013,0.0013,1,1
116 11390000,0.78,-0.022,0.0045,-0.63,-0.1,-0.024,0.002,-0.0027,-0.00099,-3.7e+02,-0.00084,-0.0059,-9.5e-05,0.0015,-0.022,-0.11,-0.11,-0.023,0.5,-0.0013,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.08,0.08,0.063,0.082,0.082,0.068,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1 11390000,0.78,-0.022,0.0042,-0.63,-0.098,-0.02,0.002,-0.0023,-0.00073,-3.7e+02,-0.00099,-0.006,3.4e-05,0.0016,-0.018,-0.11,-0.11,-0.023,0.5,-0.001,-0.088,-0.069,0,0,0.0011,0.0011,0.047,0.079,0.079,0.063,0.082,0.082,0.068,1e-05,1.1e-05,5.7e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.0008,0.0013,0.0013,1,1
117 11490000,0.78,-0.022,0.0047,-0.63,-0.12,-0.026,0.0029,-0.014,-0.0031,-3.7e+02,-0.0008,-0.006,-0.0001,0.0009,-0.022,-0.11,-0.11,-0.023,0.5,-0.0014,-0.088,-0.069,0,0,0.0011,0.0012,0.047,0.095,0.095,0.058,0.089,0.089,0.069,1.2e-05,1.3e-05,4.8e-06,0.037,0.037,0.01,0.0013,6.8e-05,0.0013,0.0008,0.0013,0.0013,1,1 11490000,0.78,-0.022,0.0045,-0.63,-0.12,-0.022,0.0029,-0.013,-0.0024,-3.7e+02,-0.00095,-0.0061,3e-05,0.0016,-0.018,-0.11,-0.11,-0.023,0.5,-0.0011,-0.088,-0.069,0,0,0.0011,0.0011,0.047,0.094,0.094,0.058,0.089,0.089,0.069,9.6e-06,1e-05,5.7e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1
118 11590000,0.78,-0.022,0.0041,-0.63,-0.1,-0.022,-0.003,-0.0044,-0.00098,-3.7e+02,-0.00085,-0.006,-9.8e-05,0.00079,-0.029,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.078,0.078,0.049,0.068,0.068,0.066,1.1e-05,1.2e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1 11590000,0.78,-0.021,0.0038,-0.63,-0.098,-0.018,-0.003,-0.0042,-0.00071,-3.7e+02,-0.00099,-0.0061,3.3e-05,0.0013,-0.025,-0.11,-0.11,-0.023,0.5,-0.0012,-0.088,-0.069,0,0,0.00095,0.00099,0.047,0.078,0.078,0.049,0.068,0.068,0.066,9.1e-06,9.9e-06,5.7e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00078,0.0013,0.0013,1,1
119 11690000,0.78,-0.022,0.0042,-0.63,-0.12,-0.026,-0.0074,-0.016,-0.0033,-3.7e+02,-0.00079,-0.006,-0.0001,0.00062,-0.03,-0.11,-0.11,-0.023,0.5,-0.0015,-0.088,-0.069,0,0,0.001,0.001,0.047,0.093,0.093,0.046,0.075,0.075,0.066,1.1e-05,1.1e-05,4.8e-06,0.036,0.036,0.01,0.0012,6.7e-05,0.0013,0.00079,0.0013,0.0013,1,1 11690000,0.78,-0.021,0.004,-0.63,-0.11,-0.022,-0.0074,-0.015,-0.0026,-3.7e+02,-0.00094,-0.0061,3.1e-05,0.0013,-0.025,-0.11,-0.11,-0.023,0.5,-0.0012,-0.088,-0.069,0,0,0.00095,0.00099,0.047,0.092,0.092,0.046,0.075,0.075,0.066,8.6e-06,9.4e-06,5.7e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00078,0.0013,0.0013,1,1
120 11790000,0.78,-0.021,0.0037,-0.63,-0.1,-0.017,-0.0092,-0.0082,0.00018,-3.7e+02,-0.00082,-0.006,-9.7e-05,0.0012,-0.036,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.077,0.076,0.039,0.06,0.06,0.063,1e-05,1.1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 11790000,0.78,-0.02,0.0034,-0.63,-0.096,-0.014,-0.0092,-0.008,0.00046,-3.7e+02,-0.00097,-0.0061,3.4e-05,0.0018,-0.031,-0.11,-0.11,-0.023,0.5,-0.0011,-0.089,-0.069,0,0,0.00084,0.00087,0.047,0.076,0.076,0.039,0.06,0.06,0.063,8.1e-06,8.8e-06,5.7e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1
121 11890000,0.78,-0.021,0.0038,-0.63,-0.12,-0.019,-0.01,-0.019,-0.0015,-3.7e+02,-0.0008,-0.0061,-9.9e-05,0.00091,-0.036,-0.11,-0.11,-0.023,0.5,-0.0015,-0.089,-0.069,0,0,0.00089,0.00092,0.047,0.09,0.09,0.037,0.067,0.067,0.063,9.5e-06,1e-05,4.8e-06,0.035,0.035,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1 11890000,0.78,-0.02,0.0035,-0.63,-0.11,-0.015,-0.01,-0.019,-0.00079,-3.7e+02,-0.00095,-0.0062,3.2e-05,0.0017,-0.031,-0.11,-0.11,-0.023,0.5,-0.0012,-0.089,-0.069,0,0,0.00084,0.00087,0.047,0.089,0.089,0.037,0.067,0.067,0.063,7.8e-06,8.5e-06,5.7e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00077,0.0013,0.0013,1,1
122 11990000,0.78,-0.02,0.003,-0.63,-0.095,-0.012,-0.015,-0.011,0.0012,-3.7e+02,-0.00095,-0.0061,-9.3e-05,0.0013,-0.04,-0.11,-0.11,-0.023,0.5,-0.0014,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.074,0.074,0.033,0.055,0.055,0.061,9e-06,9.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1 11990000,0.78,-0.019,0.0029,-0.63,-0.092,-0.0092,-0.015,-0.011,0.0015,-3.7e+02,-0.0011,-0.0062,3.8e-05,0.0018,-0.036,-0.11,-0.11,-0.023,0.5,-0.0011,-0.089,-0.069,0,0,0.00074,0.00077,0.047,0.074,0.073,0.033,0.055,0.055,0.061,7.4e-06,8e-06,5.7e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0013,0.00075,0.0013,0.0013,1,1
123 12090000,0.78,-0.02,0.0029,-0.63,-0.11,-0.016,-0.021,-0.021,-0.00045,-3.7e+02,-0.00099,-0.006,-9e-05,0.0018,-0.04,-0.11,-0.11,-0.023,0.5,-0.0013,-0.089,-0.07,0,0,0.00079,0.00082,0.047,0.087,0.086,0.031,0.063,0.063,0.061,8.6e-06,9.2e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.6e-05,0.0013,0.00076,0.0013,0.0013,1,1 12090000,0.78,-0.019,0.0027,-0.63,-0.1,-0.012,-0.021,-0.02,0.00017,-3.7e+02,-0.0011,-0.0061,4e-05,0.0021,-0.036,-0.11,-0.11,-0.023,0.5,-0.001,-0.089,-0.069,0,0,0.00075,0.00077,0.047,0.086,0.086,0.031,0.063,0.063,0.061,7e-06,7.7e-06,5.7e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0013,0.00075,0.0013,0.0013,1,1
124 12190000,0.78,-0.019,0.0023,-0.63,-0.084,-0.015,-0.016,-0.01,0.00028,-3.7e+02,-0.00098,-0.006,-8.9e-05,0.0016,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.071,0.071,0.028,0.052,0.052,0.059,8.1e-06,8.7e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1 12190000,0.78,-0.019,0.0022,-0.63,-0.081,-0.012,-0.016,-0.01,0.00056,-3.7e+02,-0.0011,-0.0061,4.1e-05,0.0016,-0.041,-0.11,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00067,0.00069,0.046,0.07,0.07,0.028,0.052,0.052,0.059,6.7e-06,7.3e-06,5.7e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1
125 12290000,0.78,-0.019,0.0024,-0.63,-0.092,-0.017,-0.015,-0.019,-0.0014,-3.7e+02,-0.00094,-0.006,-8.9e-05,0.0017,-0.046,-0.11,-0.11,-0.023,0.5,-0.0013,-0.09,-0.07,0,0,0.00071,0.00073,0.046,0.082,0.082,0.028,0.06,0.06,0.059,7.8e-06,8.4e-06,4.8e-06,0.034,0.034,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1 12290000,0.78,-0.019,0.0022,-0.63,-0.09,-0.014,-0.015,-0.019,-0.00089,-3.7e+02,-0.0011,-0.0061,4.1e-05,0.0017,-0.042,-0.11,-0.11,-0.024,0.5,-0.001,-0.09,-0.069,0,0,0.00067,0.00069,0.046,0.081,0.081,0.028,0.06,0.06,0.059,6.4e-06,7e-06,5.7e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00074,0.0013,0.0012,1,1
126 12390000,0.78,-0.019,0.0019,-0.63,-0.073,-0.014,-0.013,-0.0094,-0.00012,-3.7e+02,-0.00099,-0.006,-8.8e-05,0.0011,-0.05,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.067,0.067,0.026,0.05,0.05,0.057,7.4e-06,8e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1 12390000,0.78,-0.018,0.0018,-0.63,-0.07,-0.011,-0.013,-0.0093,0.00016,-3.7e+02,-0.0011,-0.0061,4.1e-05,0.0011,-0.046,-0.11,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.0006,0.00062,0.046,0.066,0.066,0.026,0.05,0.05,0.057,6.1e-06,6.7e-06,5.7e-06,0.032,0.032,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1
127 12490000,0.78,-0.019,0.0021,-0.63,-0.08,-0.016,-0.016,-0.017,-0.0014,-3.7e+02,-0.00096,-0.0061,-9.1e-05,0.00059,-0.05,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00064,0.00066,0.046,0.077,0.076,0.026,0.058,0.058,0.057,7.1e-06,7.6e-06,4.8e-06,0.033,0.033,0.01,0.0012,6.5e-05,0.0012,0.00073,0.0013,0.0012,1,1 12490000,0.78,-0.018,0.0019,-0.63,-0.078,-0.013,-0.016,-0.017,-0.00083,-3.7e+02,-0.0011,-0.0061,3.9e-05,0.00083,-0.046,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.0006,0.00062,0.046,0.076,0.076,0.026,0.058,0.058,0.057,5.9e-06,6.4e-06,5.7e-06,0.032,0.032,0.01,0.0012,6.4e-05,0.0012,0.00073,0.0013,0.0012,1,1
128 12590000,0.78,-0.018,0.0018,-0.63,-0.073,-0.014,-0.022,-0.014,-0.00033,-3.7e+02,-0.001,-0.0061,-8.8e-05,0.00072,-0.052,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.063,0.063,0.025,0.049,0.049,0.055,6.8e-06,7.3e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.5e-05,0.0012,0.00072,0.0013,0.0012,1,1 12590000,0.78,-0.018,0.0017,-0.63,-0.071,-0.011,-0.022,-0.014,-3.2e-05,-3.7e+02,-0.0012,-0.0061,4.2e-05,0.00089,-0.048,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.00055,0.00057,0.046,0.062,0.062,0.025,0.049,0.049,0.055,5.6e-06,6.2e-06,5.7e-06,0.031,0.032,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1
129 12690000,0.78,-0.018,0.0018,-0.63,-0.079,-0.015,-0.025,-0.021,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.8e-05,0.00038,-0.051,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00059,0.0006,0.046,0.071,0.071,0.025,0.057,0.057,0.055,6.5e-06,7e-06,4.8e-06,0.033,0.033,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1 12690000,0.78,-0.018,0.0016,-0.63,-0.076,-0.012,-0.025,-0.021,-0.00096,-3.7e+02,-0.0012,-0.0062,4.2e-05,0.00068,-0.047,-0.11,-0.11,-0.024,0.5,-0.0013,-0.09,-0.069,0,0,0.00056,0.00057,0.046,0.071,0.071,0.025,0.057,0.057,0.055,5.4e-06,5.9e-06,5.7e-06,0.031,0.032,0.0099,0.0012,6.4e-05,0.0012,0.00072,0.0013,0.0012,1,1
130 12790000,0.78,-0.018,0.0016,-0.63,-0.072,-0.012,-0.028,-0.018,-0.0006,-3.7e+02,-0.0011,-0.0061,-8.7e-05,0.00058,-0.053,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00054,0.00056,0.046,0.059,0.058,0.024,0.048,0.048,0.053,6.2e-06,6.7e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 12790000,0.78,-0.018,0.0014,-0.63,-0.07,-0.01,-0.028,-0.018,-0.0003,-3.7e+02,-0.0012,-0.0062,4.3e-05,0.00079,-0.049,-0.11,-0.11,-0.024,0.5,-0.0013,-0.09,-0.069,0,0,0.00052,0.00053,0.046,0.058,0.058,0.024,0.048,0.048,0.053,5.1e-06,5.7e-06,5.7e-06,0.031,0.031,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1
131 12890000,0.78,-0.018,0.0017,-0.63,-0.079,-0.013,-0.027,-0.026,-0.0019,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00062,-0.054,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00055,0.00056,0.046,0.066,0.066,0.025,0.056,0.056,0.054,6e-06,6.5e-06,4.8e-06,0.032,0.032,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 12890000,0.78,-0.018,0.0015,-0.63,-0.077,-0.011,-0.027,-0.026,-0.0014,-3.7e+02,-0.0011,-0.0062,4.1e-05,0.00082,-0.05,-0.11,-0.11,-0.024,0.5,-0.0013,-0.09,-0.069,0,0,0.00052,0.00053,0.046,0.066,0.066,0.025,0.056,0.056,0.054,5e-06,5.5e-06,5.7e-06,0.031,0.031,0.0097,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1
132 12990000,0.78,-0.018,0.0013,-0.63,-0.064,-0.012,-0.028,-0.019,-0.0015,-3.7e+02,-0.0011,-0.006,-8.6e-05,0.0009,-0.056,-0.11,-0.11,-0.024,0.5,-0.0014,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.059,0.058,0.025,0.058,0.058,0.052,5.7e-06,6.2e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.00071,0.0013,0.0012,1,1 12990000,0.78,-0.018,0.0012,-0.63,-0.062,-0.0094,-0.028,-0.019,-0.0011,-3.7e+02,-0.0012,-0.0061,4.3e-05,0.00087,-0.052,-0.11,-0.11,-0.024,0.5,-0.0012,-0.09,-0.069,0,0,0.00049,0.0005,0.046,0.058,0.058,0.025,0.058,0.058,0.052,4.8e-06,5.3e-06,5.7e-06,0.031,0.031,0.0094,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1
133 13090000,0.78,-0.018,0.0014,-0.63,-0.069,-0.011,-0.028,-0.026,-0.0023,-3.7e+02,-0.001,-0.0061,-8.9e-05,0.00025,-0.057,-0.11,-0.11,-0.024,0.5,-0.0015,-0.09,-0.07,0,0,0.00052,0.00053,0.046,0.065,0.065,0.025,0.066,0.066,0.052,5.5e-06,6e-06,4.8e-06,0.032,0.032,0.0094,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1 13090000,0.78,-0.018,0.0013,-0.63,-0.068,-0.0091,-0.028,-0.026,-0.0017,-3.7e+02,-0.0011,-0.0062,4.1e-05,0.00044,-0.053,-0.11,-0.11,-0.024,0.5,-0.0013,-0.09,-0.069,0,0,0.00049,0.0005,0.046,0.065,0.065,0.025,0.066,0.066,0.052,4.6e-06,5.1e-06,5.7e-06,0.031,0.031,0.0094,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1
134 13190000,0.78,-0.018,0.0011,-0.63,-0.055,-0.011,-0.025,-0.017,-0.0015,-3.7e+02,-0.0011,-0.0061,-8.7e-05,-1.3e-05,-0.058,-0.11,-0.11,-0.024,0.5,-0.0016,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.058,0.058,0.025,0.067,0.067,0.051,5.2e-06,5.7e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.4e-05,0.0012,0.0007,0.0013,0.0012,1,1 13190000,0.78,-0.017,0.00099,-0.63,-0.054,-0.0086,-0.025,-0.017,-0.0011,-3.7e+02,-0.0012,-0.0062,4.2e-05,0.00013,-0.055,-0.11,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00047,0.00048,0.046,0.057,0.057,0.025,0.067,0.067,0.051,4.4e-06,4.9e-06,5.7e-06,0.031,0.031,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1
135 13290000,0.78,-0.018,0.0011,-0.63,-0.06,-0.013,-0.021,-0.024,-0.003,-3.7e+02,-0.001,-0.006,-8.8e-05,0.00039,-0.059,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00049,0.00051,0.046,0.064,0.064,0.027,0.077,0.077,0.051,5.1e-06,5.5e-06,4.8e-06,0.032,0.032,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1 13290000,0.78,-0.017,0.001,-0.63,-0.059,-0.011,-0.021,-0.023,-0.0024,-3.7e+02,-0.0011,-0.0061,4.2e-05,0.00041,-0.055,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00047,0.00048,0.046,0.064,0.064,0.027,0.077,0.077,0.051,4.3e-06,4.8e-06,5.7e-06,0.031,0.031,0.0091,0.0012,6.3e-05,0.0012,0.0007,0.0013,0.0012,1,1
136 13390000,0.78,-0.017,0.00099,-0.63,-0.049,-0.012,-0.017,-0.016,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00065,-0.06,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.056,0.056,0.026,0.077,0.077,0.05,4.9e-06,5.3e-06,4.8e-06,0.032,0.032,0.0088,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 13390000,0.78,-0.017,0.00086,-0.63,-0.048,-0.0099,-0.017,-0.016,-0.0017,-3.7e+02,-0.0011,-0.0061,4.3e-05,0.00052,-0.056,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00045,0.00046,0.046,0.056,0.056,0.026,0.077,0.077,0.05,4.1e-06,4.6e-06,5.7e-06,0.03,0.03,0.0088,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
137 13490000,0.78,-0.017,0.00096,-0.63,-0.053,-0.013,-0.016,-0.022,-0.0034,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00089,-0.061,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00047,0.00049,0.046,0.062,0.062,0.028,0.088,0.088,0.05,4.7e-06,5.1e-06,4.8e-06,0.031,0.032,0.0087,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 13490000,0.78,-0.017,0.00083,-0.63,-0.051,-0.011,-0.016,-0.022,-0.0029,-3.7e+02,-0.0011,-0.0061,4.4e-05,0.0007,-0.057,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00045,0.00046,0.046,0.062,0.062,0.028,0.088,0.088,0.05,3.9e-06,4.4e-06,5.7e-06,0.03,0.03,0.0087,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
138 13590000,0.78,-0.017,0.00083,-0.63,-0.043,-0.012,-0.018,-0.014,-0.002,-3.7e+02,-0.001,-0.006,-8.5e-05,0.00051,-0.062,-0.12,-0.11,-0.024,0.5,-0.0015,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.054,0.054,0.028,0.087,0.087,0.05,4.5e-06,5e-06,4.8e-06,0.031,0.032,0.0084,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 13590000,0.78,-0.017,0.00071,-0.63,-0.041,-0.0099,-0.018,-0.014,-0.0017,-3.7e+02,-0.0011,-0.0061,4.4e-05,0.00039,-0.058,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00043,0.00045,0.046,0.054,0.054,0.028,0.087,0.087,0.05,3.8e-06,4.3e-06,5.7e-06,0.03,0.03,0.0084,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
139 13690000,0.78,-0.017,0.00081,-0.63,-0.046,-0.015,-0.022,-0.019,-0.0035,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00095,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00046,0.00047,0.046,0.06,0.06,0.029,0.098,0.098,0.05,4.3e-06,4.8e-06,4.8e-06,0.031,0.032,0.0083,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1 13690000,0.78,-0.017,0.0007,-0.63,-0.044,-0.013,-0.022,-0.019,-0.003,-3.7e+02,-0.0011,-0.0061,4.5e-05,0.00072,-0.058,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00043,0.00045,0.046,0.059,0.059,0.029,0.098,0.098,0.05,3.7e-06,4.2e-06,5.7e-06,0.03,0.03,0.0083,0.0012,6.3e-05,0.0012,0.00069,0.0013,0.0012,1,1
140 13790000,0.78,-0.017,0.00063,-0.63,-0.033,-0.013,-0.024,-0.0063,-0.003,-3.7e+02,-0.0011,-0.006,-8.3e-05,0.00068,-0.062,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.045,0.045,0.029,0.072,0.072,0.049,4.2e-06,4.6e-06,4.8e-06,0.031,0.031,0.0079,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1 13790000,0.78,-0.017,0.00052,-0.63,-0.032,-0.011,-0.024,-0.0065,-0.0028,-3.7e+02,-0.0012,-0.0061,4.5e-05,0.00044,-0.059,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.045,0.045,0.029,0.072,0.072,0.049,3.5e-06,4e-06,5.7e-06,0.03,0.03,0.0079,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
141 13890000,0.78,-0.017,0.00069,-0.63,-0.037,-0.015,-0.028,-0.01,-0.0045,-3.7e+02,-0.001,-0.006,-8.4e-05,0.00091,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00044,0.00045,0.046,0.049,0.049,0.03,0.081,0.081,0.05,4e-06,4.5e-06,4.8e-06,0.031,0.031,0.0078,0.0012,6.3e-05,0.0012,0.00068,0.0013,0.0012,1,1 13890000,0.78,-0.017,0.00058,-0.63,-0.036,-0.013,-0.028,-0.01,-0.0042,-3.7e+02,-0.0011,-0.0061,4.4e-05,0.00062,-0.059,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.049,0.049,0.03,0.081,0.081,0.05,3.4e-06,3.9e-06,5.7e-06,0.03,0.03,0.0078,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
142 13990000,0.78,-0.017,0.00054,-0.63,-0.029,-0.014,-0.027,-0.0032,-0.004,-3.7e+02,-0.0011,-0.006,-8.4e-05,0.00078,-0.064,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.04,0.04,0.03,0.063,0.063,0.05,3.9e-06,4.3e-06,4.8e-06,0.031,0.031,0.0074,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 13990000,0.78,-0.017,0.00043,-0.63,-0.028,-0.012,-0.027,-0.0033,-0.0039,-3.7e+02,-0.0011,-0.0061,4.4e-05,0.00048,-0.06,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.04,0.04,0.03,0.063,0.063,0.05,3.3e-06,3.8e-06,5.7e-06,0.03,0.03,0.0074,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
143 14090000,0.78,-0.017,0.00048,-0.63,-0.03,-0.015,-0.028,-0.006,-0.0056,-3.7e+02,-0.0011,-0.006,-8.1e-05,0.0012,-0.063,-0.12,-0.11,-0.024,0.5,-0.0014,-0.091,-0.07,0,0,0.00043,0.00044,0.046,0.044,0.044,0.031,0.07,0.07,0.05,3.8e-06,4.2e-06,4.8e-06,0.031,0.031,0.0073,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1 14090000,0.78,-0.017,0.00038,-0.63,-0.029,-0.013,-0.028,-0.006,-0.0053,-3.7e+02,-0.0012,-0.006,4.6e-05,0.00081,-0.06,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.043,0.043,0.031,0.07,0.07,0.05,3.2e-06,3.7e-06,5.7e-06,0.03,0.03,0.0073,0.0012,6.2e-05,0.0012,0.00068,0.0013,0.0012,1,1
144 14190000,0.78,-0.017,0.00041,-0.63,-0.024,-0.013,-0.03,-8.4e-05,-0.0036,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0015,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.036,0.036,0.03,0.057,0.057,0.05,3.6e-06,4.1e-06,4.8e-06,0.031,0.031,0.0069,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 14190000,0.78,-0.017,0.00032,-0.63,-0.023,-0.011,-0.03,-0.00018,-0.0036,-3.7e+02,-0.0012,-0.006,4.7e-05,0.001,-0.061,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.036,0.036,0.03,0.057,0.057,0.05,3.1e-06,3.6e-06,5.7e-06,0.03,0.03,0.0069,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
145 14290000,0.78,-0.017,0.00037,-0.63,-0.025,-0.015,-0.029,-0.0025,-0.0051,-3.7e+02,-0.0011,-0.0059,-8e-05,0.0016,-0.064,-0.12,-0.11,-0.024,0.5,-0.0013,-0.091,-0.069,0,0,0.00042,0.00043,0.046,0.04,0.04,0.032,0.064,0.064,0.051,3.5e-06,3.9e-06,4.8e-06,0.031,0.031,0.0067,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 14290000,0.78,-0.017,0.00028,-0.63,-0.024,-0.013,-0.029,-0.0025,-0.0048,-3.7e+02,-0.0012,-0.006,4.8e-05,0.0011,-0.06,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.04,0.04,0.032,0.064,0.064,0.051,3e-06,3.5e-06,5.7e-06,0.03,0.03,0.0067,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1
146 14390000,0.78,-0.017,0.00033,-0.63,-0.02,-0.015,-0.031,0.0017,-0.0037,-3.7e+02,-0.0011,-0.0059,-7.8e-05,0.0021,-0.065,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.034,0.034,0.031,0.053,0.053,0.05,3.4e-06,3.8e-06,4.8e-06,0.031,0.031,0.0063,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 14390000,0.78,-0.016,0.00024,-0.63,-0.019,-0.013,-0.031,0.0017,-0.0035,-3.7e+02,-0.0012,-0.006,4.9e-05,0.0015,-0.061,-0.12,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.034,0.034,0.031,0.053,0.053,0.05,2.9e-06,3.4e-06,5.7e-06,0.03,0.03,0.0063,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
147 14490000,0.78,-0.017,0.0004,-0.63,-0.022,-0.018,-0.034,-0.00071,-0.0054,-3.7e+02,-0.001,-0.0059,-7.9e-05,0.0022,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.037,0.037,0.032,0.06,0.06,0.051,3.3e-06,3.7e-06,4.8e-06,0.031,0.031,0.0062,0.0012,6.2e-05,0.0012,0.00068,0.0012,0.0012,1,1 14490000,0.78,-0.017,0.00031,-0.63,-0.021,-0.016,-0.034,-0.00065,-0.0051,-3.7e+02,-0.0011,-0.006,4.8e-05,0.0016,-0.062,-0.12,-0.11,-0.024,0.5,-0.00098,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.037,0.037,0.032,0.06,0.06,0.051,2.8e-06,3.3e-06,5.7e-06,0.03,0.03,0.0062,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
148 14590000,0.78,-0.017,0.00048,-0.63,-0.023,-0.018,-0.034,-0.0013,-0.0052,-3.7e+02,-0.001,-0.0059,-8e-05,0.0021,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.032,0.032,0.031,0.051,0.051,0.051,3.2e-06,3.6e-06,4.8e-06,0.031,0.031,0.0058,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 14590000,0.78,-0.016,0.00038,-0.63,-0.022,-0.016,-0.034,-0.0013,-0.005,-3.7e+02,-0.0011,-0.006,4.8e-05,0.0016,-0.062,-0.12,-0.11,-0.024,0.5,-0.00097,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.032,0.032,0.031,0.051,0.051,0.051,2.7e-06,3.2e-06,5.7e-06,0.03,0.03,0.0058,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
149 14690000,0.78,-0.017,0.0005,-0.63,-0.026,-0.017,-0.031,-0.0038,-0.0071,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0024,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.00041,0.00042,0.046,0.035,0.035,0.032,0.056,0.056,0.051,3.1e-06,3.5e-06,4.8e-06,0.031,0.031,0.0057,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 14690000,0.78,-0.017,0.0004,-0.63,-0.025,-0.015,-0.031,-0.0037,-0.0067,-3.7e+02,-0.0011,-0.006,4.8e-05,0.0017,-0.062,-0.12,-0.11,-0.024,0.5,-0.00095,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.035,0.035,0.032,0.056,0.056,0.051,2.6e-06,3.1e-06,5.7e-06,0.03,0.03,0.0056,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1
150 14790000,0.78,-0.017,0.00051,-0.63,-0.025,-0.016,-0.027,-0.0038,-0.0066,-3.7e+02,-0.00099,-0.0059,-7.9e-05,0.0023,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.03,0.03,0.031,0.049,0.049,0.051,3e-06,3.3e-06,4.8e-06,0.031,0.031,0.0053,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 14790000,0.78,-0.016,0.00042,-0.63,-0.024,-0.014,-0.027,-0.0037,-0.0063,-3.7e+02,-0.0011,-0.006,4.8e-05,0.0017,-0.063,-0.12,-0.11,-0.024,0.5,-0.00094,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.03,0.03,0.031,0.048,0.049,0.051,2.6e-06,3e-06,5.7e-06,0.03,0.03,0.0053,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
151 14890000,0.78,-0.017,0.00052,-0.63,-0.028,-0.019,-0.03,-0.0065,-0.0085,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0025,-0.066,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.033,0.033,0.031,0.054,0.054,0.052,2.9e-06,3.3e-06,4.8e-06,0.031,0.031,0.0051,0.0012,6.2e-05,0.0012,0.00067,0.0012,0.0012,1,1 14890000,0.78,-0.016,0.00042,-0.63,-0.027,-0.017,-0.03,-0.0064,-0.008,-3.7e+02,-0.0011,-0.006,4.8e-05,0.0018,-0.063,-0.12,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.033,0.033,0.031,0.054,0.054,0.052,2.5e-06,2.9e-06,5.7e-06,0.03,0.03,0.0051,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
152 14990000,0.78,-0.017,0.00057,-0.63,-0.026,-0.016,-0.026,-0.0049,-0.0065,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.029,0.029,0.03,0.047,0.047,0.051,2.8e-06,3.2e-06,4.8e-06,0.031,0.031,0.0048,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 14990000,0.78,-0.016,0.00047,-0.63,-0.025,-0.014,-0.026,-0.0048,-0.0062,-3.7e+02,-0.001,-0.006,4.9e-05,0.0018,-0.063,-0.12,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.029,0.029,0.03,0.047,0.047,0.051,2.4e-06,2.8e-06,5.7e-06,0.03,0.03,0.0048,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
153 15090000,0.78,-0.017,0.00066,-0.63,-0.028,-0.017,-0.029,-0.0076,-0.0081,-3.7e+02,-0.00097,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0012,-0.091,-0.069,0,0,0.0004,0.00041,0.046,0.031,0.031,0.031,0.052,0.052,0.052,2.7e-06,3.1e-06,4.8e-06,0.031,0.031,0.0046,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15090000,0.78,-0.016,0.00056,-0.63,-0.027,-0.015,-0.029,-0.0074,-0.0076,-3.7e+02,-0.001,-0.006,4.8e-05,0.0017,-0.063,-0.12,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.031,0.031,0.031,0.052,0.052,0.052,2.3e-06,2.8e-06,5.7e-06,0.03,0.03,0.0046,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
154 15190000,0.78,-0.017,0.00069,-0.63,-0.026,-0.016,-0.026,-0.006,-0.0064,-3.7e+02,-0.00096,-0.0059,-7.9e-05,0.0022,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.00041,0.046,0.027,0.028,0.03,0.046,0.046,0.052,2.6e-06,3e-06,4.8e-06,0.031,0.031,0.0043,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15190000,0.78,-0.016,0.00059,-0.63,-0.025,-0.014,-0.026,-0.0059,-0.0061,-3.7e+02,-0.001,-0.006,4.9e-05,0.0017,-0.064,-0.12,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.027,0.028,0.03,0.046,0.046,0.052,2.3e-06,2.7e-06,5.7e-06,0.03,0.03,0.0043,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
155 15290000,0.78,-0.017,0.00069,-0.63,-0.028,-0.018,-0.024,-0.0086,-0.0082,-3.7e+02,-0.00097,-0.0059,-7.8e-05,0.0023,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.03,0.03,0.03,0.051,0.051,0.052,2.5e-06,2.9e-06,4.8e-06,0.031,0.031,0.0042,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15290000,0.78,-0.016,0.00059,-0.63,-0.026,-0.016,-0.024,-0.0083,-0.0076,-3.7e+02,-0.001,-0.006,5e-05,0.0018,-0.063,-0.12,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.03,0.03,0.03,0.051,0.051,0.052,2.2e-06,2.6e-06,5.7e-06,0.029,0.03,0.0042,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
156 15390000,0.78,-0.017,0.00064,-0.63,-0.027,-0.018,-0.022,-0.0082,-0.0083,-3.7e+02,-0.00099,-0.0059,-7.4e-05,0.0028,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.029,0.029,0.029,0.054,0.054,0.051,2.4e-06,2.8e-06,4.8e-06,0.031,0.031,0.0039,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15390000,0.78,-0.016,0.00055,-0.63,-0.026,-0.016,-0.022,-0.0079,-0.0078,-3.7e+02,-0.0011,-0.006,5.3e-05,0.0022,-0.063,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.028,0.029,0.029,0.054,0.054,0.051,2.1e-06,2.6e-06,5.7e-06,0.029,0.03,0.0039,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
157 15490000,0.78,-0.017,0.00066,-0.63,-0.03,-0.018,-0.022,-0.011,-0.0098,-3.7e+02,-0.00099,-0.0059,-7.6e-05,0.0024,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.09,-0.069,0,0,0.00039,0.00041,0.046,0.031,0.031,0.029,0.06,0.06,0.053,2.4e-06,2.7e-06,4.8e-06,0.031,0.031,0.0037,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15490000,0.78,-0.016,0.00057,-0.63,-0.028,-0.016,-0.022,-0.011,-0.009,-3.7e+02,-0.0011,-0.006,5.1e-05,0.0019,-0.063,-0.12,-0.11,-0.024,0.5,-0.00088,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.031,0.031,0.029,0.06,0.06,0.053,2.1e-06,2.5e-06,5.7e-06,0.029,0.03,0.0037,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1
158 15590000,0.78,-0.017,0.0007,-0.63,-0.028,-0.017,-0.021,-0.01,-0.0091,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0022,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.029,0.03,0.028,0.062,0.062,0.052,2.3e-06,2.7e-06,4.8e-06,0.031,0.031,0.0035,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15590000,0.78,-0.016,0.00061,-0.63,-0.026,-0.014,-0.021,-0.01,-0.0084,-3.7e+02,-0.0011,-0.006,5.1e-05,0.0017,-0.064,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.029,0.03,0.028,0.062,0.062,0.052,2e-06,2.4e-06,5.7e-06,0.029,0.03,0.0035,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
159 15690000,0.78,-0.017,0.00067,-0.63,-0.029,-0.017,-0.021,-0.013,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.0021,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.032,0.032,0.028,0.069,0.069,0.052,2.2e-06,2.6e-06,4.8e-06,0.03,0.031,0.0033,0.0012,6.1e-05,0.0012,0.00067,0.0012,0.0012,1,1 15690000,0.78,-0.016,0.00059,-0.63,-0.027,-0.015,-0.021,-0.012,-0.0097,-3.7e+02,-0.0011,-0.006,5.1e-05,0.0017,-0.063,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.031,0.032,0.028,0.069,0.069,0.052,2e-06,2.4e-06,5.7e-06,0.029,0.03,0.0033,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
160 15790000,0.78,-0.017,0.00067,-0.63,-0.026,-0.016,-0.024,-0.009,-0.009,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.026,0.027,0.027,0.056,0.057,0.051,2.2e-06,2.5e-06,4.8e-06,0.03,0.031,0.0031,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 15790000,0.78,-0.016,0.00058,-0.63,-0.025,-0.014,-0.024,-0.0088,-0.0084,-3.7e+02,-0.0011,-0.006,5.1e-05,0.0017,-0.064,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.026,0.027,0.027,0.056,0.057,0.051,1.9e-06,2.3e-06,5.7e-06,0.029,0.03,0.0031,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
161 15890000,0.78,-0.017,0.00068,-0.63,-0.028,-0.017,-0.022,-0.012,-0.011,-3.7e+02,-0.001,-0.006,-7.6e-05,0.002,-0.067,-0.12,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00039,0.0004,0.046,0.028,0.029,0.027,0.063,0.063,0.052,2.1e-06,2.5e-06,4.8e-06,0.03,0.031,0.003,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 15890000,0.78,-0.016,0.0006,-0.63,-0.027,-0.014,-0.022,-0.011,-0.0098,-3.7e+02,-0.0011,-0.006,5.1e-05,0.0016,-0.064,-0.12,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.028,0.029,0.027,0.063,0.063,0.052,1.9e-06,2.3e-06,5.7e-06,0.029,0.03,0.003,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
162 15990000,0.78,-0.017,0.00066,-0.63,-0.025,-0.017,-0.017,-0.0084,-0.0095,-3.7e+02,-0.001,-0.0059,-7.3e-05,0.0023,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.026,0.053,0.053,0.051,2e-06,2.4e-06,4.8e-06,0.03,0.031,0.0028,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 15990000,0.78,-0.016,0.00058,-0.63,-0.024,-0.014,-0.017,-0.0082,-0.0089,-3.7e+02,-0.0011,-0.006,5.3e-05,0.0019,-0.064,-0.13,-0.11,-0.024,0.5,-0.00085,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.024,0.025,0.026,0.052,0.053,0.051,1.8e-06,2.2e-06,5.7e-06,0.029,0.03,0.0028,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
163 16090000,0.78,-0.017,0.00058,-0.63,-0.027,-0.019,-0.014,-0.011,-0.012,-3.7e+02,-0.0011,-0.0059,-7.1e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.0011,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.026,0.026,0.025,0.058,0.058,0.052,2e-06,2.3e-06,4.8e-06,0.03,0.031,0.0027,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 16090000,0.78,-0.016,0.00051,-0.63,-0.026,-0.016,-0.014,-0.01,-0.011,-3.7e+02,-0.0011,-0.006,5.6e-05,0.0022,-0.064,-0.13,-0.11,-0.024,0.5,-0.00083,-0.091,-0.069,0,0,0.00037,0.00038,0.046,0.026,0.026,0.025,0.058,0.058,0.052,1.8e-06,2.2e-06,5.7e-06,0.029,0.03,0.0027,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1
164 16190000,0.78,-0.017,0.00056,-0.63,-0.025,-0.017,-0.013,-0.008,-0.009,-3.7e+02,-0.0011,-0.0059,-6.9e-05,0.0027,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.023,0.025,0.05,0.05,0.051,1.9e-06,2.3e-06,4.8e-06,0.03,0.031,0.0025,0.0012,6.1e-05,0.0012,0.00066,0.0012,0.0012,1,1 16190000,0.78,-0.016,0.00049,-0.63,-0.024,-0.015,-0.013,-0.0078,-0.0083,-3.7e+02,-0.0011,-0.006,5.8e-05,0.0022,-0.064,-0.13,-0.11,-0.024,0.5,-0.00081,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.023,0.023,0.025,0.05,0.05,0.051,1.7e-06,2.1e-06,5.7e-06,0.029,0.03,0.0025,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
165 16290000,0.78,-0.017,0.00049,-0.63,-0.028,-0.019,-0.014,-0.011,-0.011,-3.7e+02,-0.0011,-0.0059,-6.7e-05,0.0031,-0.067,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.024,0.025,0.024,0.055,0.055,0.052,1.9e-06,2.2e-06,4.8e-06,0.03,0.031,0.0024,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16290000,0.78,-0.016,0.00043,-0.63,-0.027,-0.016,-0.014,-0.01,-0.01,-3.7e+02,-0.0011,-0.006,6e-05,0.0025,-0.064,-0.13,-0.11,-0.024,0.5,-0.00079,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.024,0.025,0.024,0.055,0.055,0.052,1.7e-06,2.1e-06,5.7e-06,0.029,0.03,0.0024,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
166 16390000,0.78,-0.017,0.00051,-0.63,-0.024,-0.015,-0.013,-0.0081,-0.0086,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.022,0.022,0.023,0.047,0.047,0.051,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16390000,0.78,-0.016,0.00045,-0.63,-0.023,-0.013,-0.013,-0.0078,-0.008,-3.7e+02,-0.0012,-0.006,6.2e-05,0.0024,-0.063,-0.13,-0.11,-0.024,0.5,-0.00078,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.021,0.022,0.023,0.047,0.047,0.051,1.6e-06,2e-06,5.7e-06,0.029,0.03,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
167 16490000,0.78,-0.016,0.00047,-0.63,-0.024,-0.017,-0.016,-0.01,-0.01,-3.7e+02,-0.0011,-0.0059,-6.5e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.001,-0.091,-0.069,0,0,0.00038,0.0004,0.046,0.023,0.024,0.023,0.052,0.052,0.052,1.8e-06,2.1e-06,4.8e-06,0.03,0.031,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16490000,0.78,-0.016,0.00041,-0.63,-0.023,-0.014,-0.016,-0.0099,-0.0093,-3.7e+02,-0.0012,-0.006,6.2e-05,0.0024,-0.063,-0.13,-0.11,-0.024,0.5,-0.00079,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.023,0.023,0.023,0.052,0.052,0.052,1.6e-06,2e-06,5.7e-06,0.029,0.03,0.0022,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
168 16590000,0.78,-0.016,0.00043,-0.63,-0.024,-0.013,-0.017,-0.01,-0.0062,-3.7e+02,-0.0011,-0.0059,-5.9e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.00095,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.021,0.022,0.046,0.046,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.002,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16590000,0.78,-0.016,0.00038,-0.63,-0.023,-0.01,-0.017,-0.01,-0.0055,-3.7e+02,-0.0012,-0.006,6.8e-05,0.0026,-0.063,-0.13,-0.11,-0.024,0.5,-0.00073,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.021,0.022,0.046,0.046,0.051,1.5e-06,1.9e-06,5.6e-06,0.029,0.03,0.002,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
169 16690000,0.78,-0.016,0.00048,-0.63,-0.025,-0.014,-0.013,-0.013,-0.0073,-3.7e+02,-0.0011,-0.0059,-6.1e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.00096,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.022,0.023,0.022,0.05,0.051,0.051,1.7e-06,2e-06,4.8e-06,0.03,0.031,0.0019,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16690000,0.78,-0.016,0.00042,-0.63,-0.024,-0.011,-0.013,-0.013,-0.0064,-3.7e+02,-0.0012,-0.006,6.6e-05,0.0023,-0.063,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.022,0.022,0.022,0.05,0.051,0.051,1.5e-06,1.9e-06,5.6e-06,0.029,0.03,0.0019,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
170 16790000,0.78,-0.016,0.00052,-0.63,-0.024,-0.01,-0.012,-0.013,-0.004,-3.7e+02,-0.0011,-0.006,-5.6e-05,0.0028,-0.066,-0.13,-0.11,-0.024,0.5,-0.0009,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.02,0.021,0.044,0.044,0.05,1.6e-06,2e-06,4.8e-06,0.03,0.031,0.0018,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16790000,0.78,-0.016,0.00046,-0.63,-0.023,-0.0077,-0.012,-0.013,-0.0032,-3.7e+02,-0.0012,-0.006,7.2e-05,0.0024,-0.063,-0.13,-0.11,-0.024,0.5,-0.00068,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.02,0.021,0.044,0.044,0.05,1.5e-06,1.8e-06,5.6e-06,0.029,0.03,0.0018,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
171 16890000,0.78,-0.016,0.00051,-0.63,-0.025,-0.011,-0.0096,-0.015,-0.0049,-3.7e+02,-0.0011,-0.006,-5.7e-05,0.0027,-0.066,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.021,0.022,0.021,0.049,0.049,0.051,1.6e-06,1.9e-06,4.8e-06,0.03,0.031,0.0017,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16890000,0.78,-0.016,0.00045,-0.63,-0.024,-0.0087,-0.0097,-0.015,-0.0039,-3.7e+02,-0.0012,-0.006,7.1e-05,0.0023,-0.063,-0.13,-0.11,-0.024,0.5,-0.0007,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.021,0.022,0.021,0.049,0.049,0.051,1.4e-06,1.8e-06,5.6e-06,0.029,0.03,0.0017,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
172 16990000,0.78,-0.016,0.00055,-0.63,-0.024,-0.011,-0.0091,-0.014,-0.0048,-3.7e+02,-0.0012,-0.006,-5.9e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.019,0.02,0.02,0.043,0.043,0.05,1.5e-06,1.9e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 16990000,0.78,-0.016,0.0005,-0.63,-0.023,-0.0085,-0.0092,-0.013,-0.004,-3.7e+02,-0.0012,-0.006,6.8e-05,0.0021,-0.063,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.019,0.02,0.043,0.043,0.05,1.4e-06,1.7e-06,5.6e-06,0.029,0.029,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
173 17090000,0.78,-0.016,0.00054,-0.63,-0.025,-0.013,-0.009,-0.016,-0.0059,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0025,-0.066,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00038,0.00039,0.046,0.02,0.021,0.02,0.048,0.048,0.05,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17090000,0.78,-0.016,0.00049,-0.63,-0.024,-0.01,-0.0092,-0.016,-0.0049,-3.7e+02,-0.0012,-0.006,6.9e-05,0.0021,-0.063,-0.13,-0.11,-0.024,0.5,-0.00072,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.021,0.02,0.048,0.048,0.05,1.4e-06,1.7e-06,5.6e-06,0.029,0.029,0.0016,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
174 17190000,0.78,-0.016,0.00048,-0.63,-0.024,-0.015,-0.0099,-0.014,-0.0062,-3.7e+02,-0.0012,-0.006,-5.7e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.019,0.042,0.043,0.049,1.5e-06,1.8e-06,4.8e-06,0.03,0.031,0.0015,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17190000,0.78,-0.016,0.00043,-0.63,-0.023,-0.013,-0.01,-0.014,-0.0053,-3.7e+02,-0.0012,-0.006,7e-05,0.0022,-0.063,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.018,0.019,0.019,0.042,0.043,0.049,1.3e-06,1.7e-06,5.6e-06,0.029,0.029,0.0015,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
175 17290000,0.78,-0.016,0.00051,-0.63,-0.027,-0.017,-0.0054,-0.017,-0.0074,-3.7e+02,-0.0012,-0.006,-5.8e-05,0.0024,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.019,0.047,0.047,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0014,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17290000,0.78,-0.016,0.00047,-0.63,-0.026,-0.014,-0.0055,-0.016,-0.0063,-3.7e+02,-0.0012,-0.006,6.8e-05,0.0021,-0.063,-0.13,-0.11,-0.024,0.5,-0.00073,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.02,0.019,0.047,0.047,0.049,1.3e-06,1.7e-06,5.6e-06,0.029,0.029,0.0014,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
176 17390000,0.78,-0.016,0.00044,-0.63,-0.024,-0.018,-0.0035,-0.014,-0.0076,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00093,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.018,0.018,0.042,0.042,0.048,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17390000,0.78,-0.016,0.0004,-0.63,-0.023,-0.015,-0.0036,-0.014,-0.0066,-3.7e+02,-0.0012,-0.006,7e-05,0.0022,-0.063,-0.13,-0.11,-0.024,0.5,-0.00072,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.018,0.018,0.018,0.042,0.042,0.048,1.3e-06,1.6e-06,5.6e-06,0.029,0.029,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
177 17490000,0.78,-0.016,0.00046,-0.63,-0.026,-0.019,-0.0018,-0.017,-0.0095,-3.7e+02,-0.0012,-0.006,-5.6e-05,0.0026,-0.066,-0.13,-0.11,-0.024,0.5,-0.00092,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.018,0.046,0.046,0.049,1.4e-06,1.7e-06,4.8e-06,0.03,0.031,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17490000,0.78,-0.016,0.00042,-0.63,-0.025,-0.016,-0.0019,-0.016,-0.0083,-3.7e+02,-0.0012,-0.006,7e-05,0.0022,-0.063,-0.13,-0.11,-0.024,0.5,-0.00072,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.02,0.018,0.046,0.046,0.049,1.2e-06,1.6e-06,5.6e-06,0.029,0.029,0.0013,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1
178 17590000,0.78,-0.016,0.00047,-0.63,-0.024,-0.019,0.0036,-0.014,-0.0091,-3.7e+02,-0.0012,-0.006,-5.5e-05,0.0026,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.017,0.041,0.041,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17590000,0.78,-0.016,0.00043,-0.63,-0.024,-0.016,0.0035,-0.014,-0.0081,-3.7e+02,-0.0012,-0.006,7.1e-05,0.0022,-0.063,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.017,0.018,0.017,0.041,0.041,0.048,1.2e-06,1.5e-06,5.6e-06,0.029,0.029,0.0012,0.0012,6e-05,0.0012,0.00065,0.0012,0.0012,1,1
179 17690000,0.78,-0.016,0.00049,-0.63,-0.026,-0.021,0.003,-0.017,-0.011,-3.7e+02,-0.0012,-0.006,-5.4e-05,0.0027,-0.065,-0.13,-0.11,-0.024,0.5,-0.00091,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.019,0.017,0.045,0.045,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0012,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17690000,0.78,-0.016,0.00045,-0.63,-0.025,-0.018,0.0029,-0.016,-0.0099,-3.7e+02,-0.0012,-0.006,7.2e-05,0.0023,-0.063,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.018,0.019,0.017,0.045,0.045,0.048,1.2e-06,1.5e-06,5.6e-06,0.029,0.029,0.0012,0.0012,6e-05,0.0012,0.00065,0.0012,0.0012,1,1
180 17790000,0.78,-0.016,0.00043,-0.63,-0.024,-0.022,0.0016,-0.015,-0.012,-3.7e+02,-0.0012,-0.0059,-4.8e-05,0.0031,-0.065,-0.13,-0.11,-0.024,0.5,-0.00088,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.016,0.048,0.048,0.048,1.3e-06,1.6e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17790000,0.78,-0.016,0.00041,-0.63,-0.023,-0.019,0.0016,-0.014,-0.011,-3.7e+02,-0.0013,-0.006,7.9e-05,0.0026,-0.063,-0.13,-0.11,-0.024,0.5,-0.00067,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.018,0.019,0.016,0.048,0.048,0.048,1.2e-06,1.5e-06,5.6e-06,0.029,0.029,0.0011,0.0012,6e-05,0.0012,0.00065,0.0012,0.0012,1,1
181 17890000,0.78,-0.016,0.00042,-0.63,-0.027,-0.023,0.0017,-0.018,-0.015,-3.7e+02,-0.0012,-0.0059,-4.6e-05,0.0033,-0.065,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.02,0.02,0.016,0.053,0.053,0.048,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.0011,0.0012,6e-05,0.0012,0.00066,0.0012,0.0012,1,1 17890000,0.78,-0.016,0.00039,-0.63,-0.026,-0.02,0.0017,-0.017,-0.013,-3.7e+02,-0.0012,-0.006,8e-05,0.0028,-0.063,-0.13,-0.11,-0.024,0.5,-0.00066,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.02,0.016,0.052,0.053,0.048,1.1e-06,1.5e-06,5.6e-06,0.029,0.029,0.0011,0.0012,6e-05,0.0012,0.00065,0.0012,0.0012,1,1
182 17990000,0.78,-0.016,0.00045,-0.63,-0.026,-0.021,0.0029,-0.016,-0.015,-3.7e+02,-0.0012,-0.0059,-4.5e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00086,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.016,0.055,0.055,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.001,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1 17990000,0.78,-0.016,0.00042,-0.63,-0.025,-0.018,0.0029,-0.015,-0.013,-3.7e+02,-0.0013,-0.006,8.1e-05,0.0027,-0.063,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.019,0.02,0.016,0.055,0.055,0.047,1.1e-06,1.4e-06,5.6e-06,0.029,0.029,0.001,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
183 18090000,0.78,-0.016,0.00049,-0.63,-0.027,-0.021,0.0053,-0.019,-0.016,-3.7e+02,-0.0012,-0.006,-4.8e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00087,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.021,0.021,0.016,0.06,0.061,0.047,1.2e-06,1.5e-06,4.8e-06,0.03,0.031,0.00098,0.0012,5.9e-05,0.0012,0.00066,0.0012,0.0012,1,1 18090000,0.78,-0.016,0.00046,-0.63,-0.027,-0.018,0.0052,-0.018,-0.014,-3.7e+02,-0.0012,-0.006,7.8e-05,0.0025,-0.063,-0.13,-0.11,-0.024,0.5,-0.00066,-0.091,-0.069,0,0,0.00036,0.00038,0.046,0.02,0.021,0.016,0.06,0.061,0.047,1.1e-06,1.4e-06,5.6e-06,0.029,0.029,0.00098,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
184 18190000,0.78,-0.016,0.00049,-0.63,-0.024,-0.02,0.0066,-0.014,-0.013,-3.7e+02,-0.0012,-0.006,-4.2e-05,0.003,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.015,0.051,0.051,0.047,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00093,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18190000,0.78,-0.016,0.00047,-0.63,-0.023,-0.017,0.0065,-0.013,-0.011,-3.7e+02,-0.0013,-0.006,8.3e-05,0.0026,-0.063,-0.13,-0.11,-0.024,0.5,-0.00063,-0.091,-0.069,0,0,0.00035,0.00038,0.046,0.018,0.018,0.015,0.051,0.051,0.047,1.1e-06,1.4e-06,5.5e-06,0.029,0.029,0.00092,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
185 18290000,0.78,-0.016,0.00059,-0.63,-0.025,-0.02,0.0078,-0.016,-0.015,-3.7e+02,-0.0012,-0.006,-4.4e-05,0.0029,-0.066,-0.13,-0.11,-0.024,0.5,-0.00084,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.019,0.02,0.015,0.056,0.056,0.046,1.1e-06,1.4e-06,4.8e-06,0.03,0.03,0.00089,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18290000,0.78,-0.016,0.00056,-0.63,-0.024,-0.017,0.0077,-0.016,-0.013,-3.7e+02,-0.0013,-0.006,8.1e-05,0.0025,-0.063,-0.13,-0.11,-0.024,0.5,-0.00063,-0.091,-0.069,0,0,0.00035,0.00038,0.046,0.019,0.02,0.015,0.056,0.056,0.046,1e-06,1.3e-06,5.5e-06,0.029,0.029,0.00089,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
186 18390000,0.78,-0.016,0.00055,-0.63,-0.024,-0.021,0.009,-0.013,-0.012,-3.7e+02,-0.0012,-0.006,-3.8e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.014,0.048,0.048,0.046,1.1e-06,1.4e-06,4.7e-06,0.03,0.03,0.00085,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18390000,0.78,-0.016,0.00052,-0.63,-0.023,-0.018,0.0089,-0.012,-0.011,-3.7e+02,-0.0013,-0.006,8.8e-05,0.0026,-0.063,-0.13,-0.11,-0.024,0.5,-0.0006,-0.091,-0.069,0,0,0.00035,0.00038,0.046,0.017,0.017,0.014,0.048,0.048,0.046,1e-06,1.3e-06,5.5e-06,0.029,0.029,0.00085,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
187 18490000,0.78,-0.016,0.00051,-0.63,-0.024,-0.023,0.0086,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3.7e-05,0.0031,-0.066,-0.13,-0.11,-0.024,0.5,-0.0008,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.018,0.019,0.014,0.053,0.053,0.046,1.1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00082,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18490000,0.78,-0.016,0.00048,-0.63,-0.024,-0.02,0.0085,-0.014,-0.013,-3.7e+02,-0.0013,-0.006,8.9e-05,0.0027,-0.063,-0.13,-0.11,-0.024,0.5,-0.0006,-0.091,-0.069,0,0,0.00035,0.00038,0.046,0.018,0.019,0.014,0.052,0.053,0.046,9.9e-07,1.3e-06,5.5e-06,0.029,0.029,0.00082,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
188 18590000,0.78,-0.016,0.00049,-0.63,-0.022,-0.022,0.0067,-0.012,-0.013,-3.7e+02,-0.0013,-0.0059,-2.8e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.016,0.017,0.014,0.046,0.046,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00078,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18590000,0.78,-0.016,0.00047,-0.63,-0.022,-0.02,0.0066,-0.012,-0.011,-3.7e+02,-0.0013,-0.006,9.8e-05,0.0029,-0.063,-0.13,-0.11,-0.024,0.5,-0.00055,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.016,0.017,0.014,0.046,0.046,0.045,9.6e-07,1.3e-06,5.5e-06,0.029,0.029,0.00078,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
189 18690000,0.78,-0.016,0.00055,-0.63,-0.024,-0.023,0.0048,-0.015,-0.015,-3.7e+02,-0.0012,-0.006,-3e-05,0.0033,-0.066,-0.13,-0.11,-0.024,0.5,-0.00076,-0.091,-0.069,0,0,0.00037,0.00039,0.046,0.017,0.018,0.013,0.05,0.05,0.045,1e-06,1.3e-06,4.7e-06,0.03,0.03,0.00076,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18690000,0.78,-0.016,0.00053,-0.63,-0.024,-0.02,0.0047,-0.014,-0.013,-3.7e+02,-0.0013,-0.006,9.6e-05,0.0028,-0.063,-0.13,-0.11,-0.024,0.5,-0.00055,-0.091,-0.068,0,0,0.00035,0.00038,0.046,0.017,0.018,0.013,0.05,0.05,0.045,9.5e-07,1.2e-06,5.5e-06,0.029,0.029,0.00076,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
190 18790000,0.78,-0.016,0.00057,-0.63,-0.022,-0.021,0.0045,-0.012,-0.012,-3.7e+02,-0.0013,-0.006,-2.6e-05,0.0032,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.013,0.044,0.044,0.045,1e-06,1.2e-06,4.7e-06,0.03,0.03,0.00073,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18790000,0.78,-0.016,0.00055,-0.63,-0.022,-0.018,0.0044,-0.012,-0.011,-3.7e+02,-0.0013,-0.006,0.0001,0.0027,-0.063,-0.13,-0.11,-0.024,0.5,-0.00054,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.013,0.044,0.044,0.045,9.2e-07,1.2e-06,5.5e-06,0.029,0.029,0.00072,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
191 18890000,0.78,-0.016,0.00048,-0.63,-0.022,-0.024,0.0051,-0.014,-0.015,-3.7e+02,-0.0013,-0.0059,-2.2e-05,0.0034,-0.066,-0.13,-0.11,-0.024,0.5,-0.00074,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.013,0.048,0.048,0.045,9.8e-07,1.2e-06,4.7e-06,0.03,0.03,0.0007,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18890000,0.78,-0.016,0.00047,-0.63,-0.022,-0.021,0.005,-0.014,-0.013,-3.7e+02,-0.0013,-0.006,0.0001,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.00053,-0.091,-0.068,0,0,0.00035,0.00038,0.046,0.016,0.017,0.013,0.048,0.048,0.045,9.1e-07,1.2e-06,5.5e-06,0.029,0.029,0.0007,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
192 18990000,0.78,-0.016,0.00042,-0.63,-0.019,-0.024,0.0037,-0.0098,-0.013,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.015,0.016,0.012,0.043,0.043,0.044,9.5e-07,1.2e-06,4.7e-06,0.03,0.03,0.00067,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 18990000,0.78,-0.016,0.00041,-0.63,-0.018,-0.021,0.0036,-0.0097,-0.012,-3.7e+02,-0.0013,-0.006,0.00011,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.0005,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.012,0.042,0.043,0.044,8.8e-07,1.2e-06,5.5e-06,0.029,0.029,0.00067,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
193 19090000,0.78,-0.016,0.00041,-0.63,-0.019,-0.025,0.0067,-0.011,-0.015,-3.7e+02,-0.0013,-0.0059,-1.5e-05,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00071,-0.091,-0.068,0,0,0.00037,0.00039,0.046,0.016,0.017,0.012,0.046,0.047,0.044,9.4e-07,1.2e-06,4.7e-06,0.03,0.03,0.00065,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19090000,0.78,-0.016,0.0004,-0.63,-0.018,-0.022,0.0066,-0.011,-0.014,-3.7e+02,-0.0013,-0.006,0.00011,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.0005,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.016,0.017,0.012,0.046,0.047,0.044,8.7e-07,1.2e-06,5.5e-06,0.029,0.029,0.00065,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
194 19190000,0.78,-0.016,0.00036,-0.63,-0.015,-0.024,0.0067,-0.0077,-0.013,-3.7e+02,-0.0013,-0.0059,-8.2e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00068,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.015,0.012,0.041,0.042,0.044,9.1e-07,1.2e-06,4.7e-06,0.03,0.03,0.00063,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19190000,0.78,-0.015,0.00036,-0.63,-0.015,-0.021,0.0066,-0.0076,-0.012,-3.7e+02,-0.0013,-0.006,0.00012,0.0031,-0.063,-0.13,-0.11,-0.024,0.5,-0.00047,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.012,0.041,0.042,0.044,8.5e-07,1.1e-06,5.4e-06,0.029,0.029,0.00062,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
195 19290000,0.78,-0.016,0.00037,-0.63,-0.016,-0.024,0.0094,-0.0095,-0.016,-3.7e+02,-0.0013,-0.006,-1.1e-05,0.0034,-0.065,-0.13,-0.11,-0.024,0.5,-0.00069,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.012,0.045,0.046,0.044,9e-07,1.1e-06,4.7e-06,0.03,0.03,0.00061,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19290000,0.78,-0.015,0.00036,-0.63,-0.016,-0.021,0.0093,-0.0093,-0.014,-3.7e+02,-0.0013,-0.006,0.00012,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.00048,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.012,0.045,0.046,0.044,8.4e-07,1.1e-06,5.4e-06,0.029,0.029,0.00061,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
196 19390000,0.78,-0.016,0.0004,-0.63,-0.015,-0.022,0.013,-0.0084,-0.014,-3.7e+02,-0.0013,-0.006,-2.4e-06,0.0035,-0.065,-0.13,-0.11,-0.024,0.5,-0.00065,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.012,0.04,0.041,0.043,8.8e-07,1.1e-06,4.6e-06,0.03,0.03,0.00058,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19390000,0.78,-0.015,0.00039,-0.63,-0.015,-0.02,0.013,-0.0084,-0.012,-3.7e+02,-0.0013,-0.006,0.00012,0.003,-0.063,-0.13,-0.11,-0.024,0.5,-0.00044,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.012,0.04,0.041,0.043,8.2e-07,1.1e-06,5.4e-06,0.029,0.029,0.00058,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
197 19490000,0.78,-0.016,0.00035,-0.63,-0.015,-0.024,0.0096,-0.01,-0.017,-3.7e+02,-0.0013,-0.0059,1.4e-06,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00064,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.044,0.045,0.043,8.6e-07,1.1e-06,4.6e-06,0.03,0.03,0.00057,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19490000,0.78,-0.015,0.00034,-0.63,-0.015,-0.021,0.0095,-0.0099,-0.015,-3.7e+02,-0.0013,-0.006,0.00013,0.0032,-0.063,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.011,0.044,0.045,0.043,8.1e-07,1.1e-06,5.4e-06,0.029,0.029,0.00057,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
198 19590000,0.78,-0.015,0.0003,-0.63,-0.013,-0.022,0.0088,-0.0085,-0.015,-3.7e+02,-0.0013,-0.0059,1.4e-05,0.0039,-0.065,-0.13,-0.11,-0.024,0.5,-0.0006,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.04,0.04,0.042,8.4e-07,1.1e-06,4.6e-06,0.03,0.03,0.00055,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19590000,0.78,-0.015,0.0003,-0.63,-0.013,-0.019,0.0088,-0.0084,-0.013,-3.7e+02,-0.0013,-0.006,0.00014,0.0033,-0.063,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.011,0.04,0.04,0.042,7.8e-07,1e-06,5.4e-06,0.029,0.029,0.00054,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
199 19690000,0.78,-0.015,0.00028,-0.63,-0.014,-0.021,0.01,-0.0093,-0.017,-3.7e+02,-0.0013,-0.0059,1.1e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00061,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.044,0.042,8.3e-07,1.1e-06,4.6e-06,0.03,0.03,0.00053,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19690000,0.78,-0.015,0.00028,-0.63,-0.013,-0.018,0.01,-0.0093,-0.015,-3.7e+02,-0.0013,-0.006,0.00014,0.0032,-0.063,-0.13,-0.11,-0.024,0.5,-0.0004,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.011,0.043,0.044,0.042,7.7e-07,1e-06,5.4e-06,0.029,0.029,0.00053,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
200 19790000,0.78,-0.015,0.00024,-0.63,-0.012,-0.018,0.011,-0.0079,-0.015,-3.7e+02,-0.0013,-0.006,1.8e-05,0.0037,-0.065,-0.13,-0.11,-0.024,0.5,-0.00058,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.011,0.039,0.039,0.042,8.1e-07,1e-06,4.6e-06,0.03,0.03,0.00051,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19790000,0.78,-0.015,0.00024,-0.63,-0.012,-0.015,0.011,-0.0079,-0.013,-3.7e+02,-0.0013,-0.006,0.00014,0.0032,-0.063,-0.13,-0.11,-0.024,0.5,-0.00037,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.011,0.039,0.039,0.042,7.6e-07,1e-06,5.3e-06,0.029,0.029,0.00051,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
201 19890000,0.78,-0.015,0.00028,-0.63,-0.011,-0.02,0.012,-0.0096,-0.017,-3.7e+02,-0.0013,-0.0059,2.4e-05,0.004,-0.065,-0.13,-0.11,-0.024,0.5,-0.00056,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.011,0.043,0.043,0.042,8e-07,1e-06,4.6e-06,0.03,0.03,0.0005,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19890000,0.78,-0.015,0.00028,-0.63,-0.011,-0.017,0.012,-0.0095,-0.015,-3.7e+02,-0.0013,-0.006,0.00015,0.0034,-0.063,-0.13,-0.11,-0.024,0.5,-0.00035,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.011,0.043,0.043,0.042,7.5e-07,1e-06,5.3e-06,0.029,0.029,0.0005,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
202 19990000,0.78,-0.016,0.00028,-0.63,-0.0096,-0.02,0.015,-0.0084,-0.016,-3.7e+02,-0.0013,-0.0059,3.9e-05,0.0043,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.039,0.039,0.041,7.7e-07,9.9e-07,4.6e-06,0.03,0.03,0.00048,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 19990000,0.78,-0.015,0.00028,-0.63,-0.0095,-0.016,0.015,-0.0083,-0.014,-3.7e+02,-0.0013,-0.006,0.00017,0.0037,-0.063,-0.13,-0.11,-0.024,0.5,-0.00031,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.01,0.038,0.039,0.041,7.3e-07,9.7e-07,5.3e-06,0.029,0.029,0.00048,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
203 20090000,0.78,-0.016,0.00023,-0.63,-0.0096,-0.02,0.015,-0.0091,-0.019,-3.7e+02,-0.0013,-0.0059,4.7e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00051,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.01,0.042,0.043,0.042,7.7e-07,9.8e-07,4.6e-06,0.03,0.03,0.00047,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1 20090000,0.78,-0.015,0.00024,-0.63,-0.0095,-0.017,0.015,-0.009,-0.017,-3.7e+02,-0.0013,-0.0059,0.00018,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-0.0003,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.01,0.042,0.043,0.042,7.2e-07,9.7e-07,5.3e-06,0.029,0.029,0.00047,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
204 20190000,0.78,-0.016,0.00019,-0.63,-0.01,-0.019,0.017,-0.0092,-0.017,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00046,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.01,0.038,0.039,0.041,7.4e-07,9.5e-07,4.6e-06,0.03,0.03,0.00045,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20190000,0.78,-0.015,0.0002,-0.63,-0.01,-0.016,0.017,-0.0092,-0.015,-3.7e+02,-0.0013,-0.0059,0.00019,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-0.00026,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.01,0.038,0.039,0.041,7e-07,9.4e-07,5.3e-06,0.029,0.029,0.00045,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
205 20290000,0.78,-0.016,0.00019,-0.63,-0.0089,-0.019,0.015,-0.0096,-0.019,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00047,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0099,0.042,0.042,0.041,7.4e-07,9.4e-07,4.6e-06,0.03,0.03,0.00044,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20290000,0.78,-0.015,0.00021,-0.63,-0.0088,-0.015,0.015,-0.0097,-0.017,-3.7e+02,-0.0013,-0.0059,0.00019,0.0041,-0.063,-0.13,-0.11,-0.024,0.5,-0.00026,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.0099,0.042,0.042,0.041,6.9e-07,9.3e-07,5.3e-06,0.029,0.029,0.00044,0.0012,5.9e-05,0.0012,0.00065,0.0012,0.0012,1,1
206 20390000,0.78,-0.016,0.00024,-0.63,-0.0085,-0.016,0.017,-0.0095,-0.017,-3.7e+02,-0.0013,-0.0059,6.8e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0097,0.038,0.038,0.041,7.2e-07,9.2e-07,4.5e-06,0.03,0.03,0.00043,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20390000,0.78,-0.015,0.00025,-0.63,-0.0084,-0.013,0.017,-0.0095,-0.015,-3.7e+02,-0.0013,-0.0059,0.0002,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-0.00022,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0097,0.038,0.038,0.041,6.8e-07,9.1e-07,5.2e-06,0.029,0.029,0.00043,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
207 20490000,0.78,-0.016,0.0002,-0.63,-0.0087,-0.016,0.017,-0.01,-0.018,-3.7e+02,-0.0013,-0.0059,6.5e-05,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00043,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0096,0.041,0.042,0.041,7.1e-07,9.1e-07,4.5e-06,0.03,0.03,0.00042,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20490000,0.78,-0.015,0.00021,-0.63,-0.0086,-0.013,0.017,-0.01,-0.016,-3.7e+02,-0.0013,-0.006,0.00019,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-0.00023,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0096,0.041,0.042,0.041,6.7e-07,9e-07,5.2e-06,0.029,0.029,0.00042,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
208 20590000,0.78,-0.016,0.0002,-0.63,-0.0081,-0.014,0.014,-0.0089,-0.016,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0093,0.038,0.038,0.04,6.9e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20590000,0.78,-0.015,0.0002,-0.63,-0.0081,-0.011,0.014,-0.0089,-0.014,-3.7e+02,-0.0013,-0.006,0.0002,0.0038,-0.063,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0093,0.037,0.038,0.04,6.5e-07,8.7e-07,5.2e-06,0.029,0.029,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
209 20690000,0.78,-0.016,0.00015,-0.63,-0.0089,-0.014,0.015,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,7.2e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00041,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0093,0.041,0.042,0.04,6.8e-07,8.8e-07,4.5e-06,0.03,0.03,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20690000,0.78,-0.015,0.00017,-0.63,-0.0089,-0.011,0.015,-0.0098,-0.015,-3.7e+02,-0.0013,-0.006,0.0002,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0093,0.041,0.042,0.04,6.4e-07,8.7e-07,5.2e-06,0.029,0.029,0.0004,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
210 20790000,0.78,-0.016,0.00013,-0.63,-0.0065,-0.013,0.016,-0.0082,-0.015,-3.7e+02,-0.0013,-0.0059,7.9e-05,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0091,0.037,0.038,0.04,6.6e-07,8.5e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20790000,0.78,-0.015,0.00014,-0.63,-0.0065,-0.0099,0.015,-0.0082,-0.013,-3.7e+02,-0.0013,-0.006,0.00021,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0091,0.037,0.038,0.04,6.3e-07,8.4e-07,5.1e-06,0.029,0.029,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
211 20890000,0.78,-0.016,0.00011,-0.63,-0.0067,-0.013,0.015,-0.0088,-0.017,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00039,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.009,0.041,0.041,0.04,6.6e-07,8.4e-07,4.5e-06,0.03,0.03,0.00038,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20890000,0.78,-0.015,0.00013,-0.63,-0.0068,-0.0097,0.015,-0.0088,-0.015,-3.7e+02,-0.0013,-0.006,0.00021,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.009,0.041,0.041,0.04,6.2e-07,8.4e-07,5.1e-06,0.029,0.029,0.00037,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
212 20990000,0.78,-0.016,9.5e-05,-0.63,-0.0051,-0.011,0.015,-0.0084,-0.018,-3.7e+02,-0.0013,-0.0059,9e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00038,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0088,0.043,0.044,0.039,6.4e-07,8.3e-07,4.4e-06,0.03,0.03,0.00037,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 20990000,0.78,-0.015,0.00011,-0.63,-0.0052,-0.0078,0.015,-0.0085,-0.015,-3.7e+02,-0.0014,-0.006,0.00022,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0088,0.043,0.044,0.039,6.1e-07,8.2e-07,5.1e-06,0.029,0.029,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
213 21090000,0.78,-0.016,8.8e-05,-0.63,-0.0062,-0.011,0.016,-0.0094,-0.019,-3.7e+02,-0.0013,-0.0059,9.3e-05,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00037,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0088,0.047,0.048,0.039,6.4e-07,8.2e-07,4.4e-06,0.03,0.03,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21090000,0.78,-0.015,0.00011,-0.63,-0.0063,-0.0073,0.016,-0.0095,-0.016,-3.7e+02,-0.0013,-0.0059,0.00022,0.0041,-0.063,-0.13,-0.11,-0.024,0.5,-0.00017,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0088,0.047,0.048,0.039,6e-07,8.2e-07,5.1e-06,0.029,0.029,0.00036,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
214 21190000,0.78,-0.016,8.4e-05,-0.63,-0.0063,-0.011,0.015,-0.0099,-0.019,-3.7e+02,-0.0013,-0.0059,9.4e-05,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00036,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0086,0.049,0.05,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00035,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21190000,0.78,-0.015,0.0001,-0.63,-0.0064,-0.007,0.015,-0.01,-0.016,-3.7e+02,-0.0013,-0.006,0.00022,0.0041,-0.063,-0.13,-0.11,-0.024,0.5,-0.00016,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0086,0.049,0.05,0.039,5.9e-07,8e-07,5.1e-06,0.029,0.029,0.00035,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
215 21290000,0.78,-0.016,-6.5e-06,-0.63,-0.0059,-0.011,0.017,-0.0099,-0.021,-3.7e+02,-0.0013,-0.0059,0.0001,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00035,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0085,0.054,0.055,0.039,6.2e-07,8e-07,4.4e-06,0.03,0.03,0.00034,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21290000,0.78,-0.015,1.4e-05,-0.63,-0.006,-0.0072,0.017,-0.01,-0.018,-3.7e+02,-0.0013,-0.0059,0.00023,0.0042,-0.063,-0.13,-0.11,-0.024,0.5,-0.00016,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.016,0.017,0.0085,0.053,0.055,0.039,5.9e-07,7.9e-07,5.1e-06,0.029,0.029,0.00034,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
216 21390000,0.78,-0.016,4.3e-05,-0.63,-0.0052,-0.0064,0.016,-0.0087,-0.016,-3.7e+02,-0.0013,-0.0059,0.00011,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0084,0.046,0.047,0.039,6e-07,7.7e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21390000,0.78,-0.015,5.9e-05,-0.63,-0.0053,-0.003,0.016,-0.0088,-0.013,-3.7e+02,-0.0013,-0.006,0.00024,0.0041,-0.063,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.0084,0.046,0.047,0.039,5.7e-07,7.7e-07,5e-06,0.029,0.029,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
217 21490000,0.78,-0.016,3.3e-05,-0.63,-0.0059,-0.0073,0.016,-0.0098,-0.017,-3.7e+02,-0.0013,-0.0059,0.00011,0.0049,-0.065,-0.13,-0.11,-0.024,0.5,-0.00032,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.016,0.0083,0.05,0.052,0.038,5.9e-07,7.6e-07,4.4e-06,0.03,0.03,0.00033,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21490000,0.78,-0.015,5.1e-05,-0.63,-0.006,-0.0037,0.016,-0.0099,-0.014,-3.7e+02,-0.0013,-0.0059,0.00024,0.0042,-0.063,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.015,0.017,0.0083,0.05,0.052,0.038,5.6e-07,7.6e-07,5e-06,0.029,0.029,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
218 21590000,0.78,-0.016,7.2e-05,-0.63,-0.0045,-0.0056,0.016,-0.0082,-0.013,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.065,-0.13,-0.11,-0.024,0.5,-0.00029,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0081,0.044,0.045,0.038,5.8e-07,7.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21590000,0.78,-0.015,8.7e-05,-0.63,-0.0046,-0.0023,0.016,-0.0083,-0.011,-3.7e+02,-0.0013,-0.006,0.00025,0.0041,-0.063,-0.13,-0.11,-0.024,0.5,-0.00011,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.0081,0.044,0.045,0.038,5.5e-07,7.4e-07,5e-06,0.029,0.029,0.00032,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
219 21690000,0.78,-0.016,6.5e-05,-0.63,-0.0061,-0.0065,0.017,-0.0095,-0.015,-3.7e+02,-0.0013,-0.0059,0.00012,0.0048,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0081,0.048,0.049,0.038,5.7e-07,7.4e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21690000,0.78,-0.015,8.1e-05,-0.63,-0.0062,-0.003,0.017,-0.0096,-0.012,-3.7e+02,-0.0013,-0.0059,0.00025,0.0042,-0.063,-0.13,-0.11,-0.024,0.5,-0.0001,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.016,0.0081,0.048,0.049,0.038,5.5e-07,7.4e-07,5e-06,0.029,0.029,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1
220 21790000,0.78,-0.016,0.00016,-0.63,-0.0051,-0.0043,0.016,-0.0083,-0.0092,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.008,0.042,0.043,0.038,5.6e-07,7.1e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21790000,0.78,-0.015,0.00017,-0.63,-0.0053,-0.001,0.016,-0.0084,-0.0066,-3.7e+02,-0.0013,-0.006,0.00026,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-6.7e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.008,0.042,0.043,0.038,5.3e-07,7.1e-07,4.9e-06,0.029,0.029,0.0003,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
221 21890000,0.78,-0.015,0.00016,-0.63,-0.0058,-0.005,0.016,-0.009,-0.0097,-3.7e+02,-0.0013,-0.0059,0.00013,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0079,0.046,0.047,0.038,5.5e-07,7.1e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21890000,0.78,-0.015,0.00018,-0.63,-0.0059,-0.0016,0.016,-0.0091,-0.0069,-3.7e+02,-0.0013,-0.006,0.00026,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-6.4e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,7.1e-07,4.9e-06,0.029,0.029,0.0003,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
222 21990000,0.78,-0.015,0.00019,-0.63,-0.0057,-0.0022,0.017,-0.0084,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0078,0.041,0.042,0.038,5.4e-07,6.9e-07,4.3e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 21990000,0.78,-0.015,0.00021,-0.63,-0.0058,0.001,0.017,-0.0085,-0.0033,-3.7e+02,-0.0013,-0.006,0.00027,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-3.4e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.014,0.0078,0.041,0.042,0.038,5.2e-07,6.9e-07,4.8e-06,0.029,0.029,0.00029,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
223 22090000,0.78,-0.015,0.00018,-0.63,-0.0054,-0.0037,0.015,-0.0088,-0.006,-3.7e+02,-0.0013,-0.0059,0.00014,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00021,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.015,0.0078,0.045,0.046,0.037,5.4e-07,6.9e-07,4.2e-06,0.03,0.03,0.00029,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 22090000,0.78,-0.015,0.00019,-0.63,-0.0055,-0.00036,0.015,-0.0089,-0.0032,-3.7e+02,-0.0013,-0.006,0.00027,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-3.4e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.046,0.013,0.015,0.0078,0.044,0.046,0.037,5.1e-07,6.9e-07,4.8e-06,0.029,0.029,0.00029,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
224 22190000,0.78,-0.015,0.00019,-0.63,-0.004,-0.0043,0.016,-0.0073,-0.0054,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.014,0.0076,0.04,0.041,0.037,5.2e-07,6.7e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 22190000,0.78,-0.015,0.00021,-0.63,-0.0042,-0.0012,0.016,-0.0075,-0.003,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-2.8e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.046,0.012,0.014,0.0076,0.04,0.041,0.037,5e-07,6.7e-07,4.8e-06,0.029,0.029,0.00028,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
225 22290000,0.78,-0.015,0.00016,-0.63,-0.0036,-0.0039,0.016,-0.008,-0.0057,-3.7e+02,-0.0013,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0076,0.043,0.045,0.037,5.2e-07,6.6e-07,4.2e-06,0.03,0.03,0.00028,0.0011,5.8e-05,0.0012,0.00065,0.0012,0.0012,1,1 22290000,0.78,-0.015,0.00018,-0.63,-0.0038,-0.00059,0.016,-0.0082,-0.0029,-3.7e+02,-0.0013,-0.006,0.00027,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-2.8e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.047,0.013,0.015,0.0076,0.043,0.045,0.037,5e-07,6.7e-07,4.8e-06,0.029,0.029,0.00028,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
226 22390000,0.78,-0.015,0.00015,-0.63,-0.0011,-0.0039,0.017,-0.0062,-0.0051,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.012,0.014,0.0075,0.039,0.04,0.037,5.1e-07,6.5e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22390000,0.78,-0.015,0.00017,-0.63,-0.0013,-0.00078,0.017,-0.0064,-0.0026,-3.7e+02,-0.0014,-0.006,0.00028,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-3.2e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.012,0.014,0.0075,0.039,0.04,0.037,4.9e-07,6.5e-07,4.7e-06,0.029,0.029,0.00027,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
227 22490000,0.78,-0.015,0.00013,-0.63,7e-05,-0.0045,0.018,-0.0056,-0.0054,-3.7e+02,-0.0014,-0.0059,0.00015,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0074,0.042,0.044,0.037,5e-07,6.4e-07,4.2e-06,0.03,0.03,0.00027,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22490000,0.78,-0.015,0.00015,-0.63,-0.00017,-0.0012,0.018,-0.0058,-0.0026,-3.7e+02,-0.0014,-0.006,0.00028,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-3.3e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.013,0.015,0.0074,0.042,0.044,0.037,4.8e-07,6.5e-07,4.7e-06,0.029,0.029,0.00027,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
228 22590000,0.78,-0.015,0.00013,-0.63,0.0019,-0.0034,0.018,-0.0039,-0.0047,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.013,0.015,0.0073,0.045,0.046,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22590000,0.78,-0.015,0.00014,-0.63,0.0017,-0.0001,0.018,-0.0041,-0.0018,-3.7e+02,-0.0014,-0.006,0.00028,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-3.1e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.013,0.015,0.0073,0.045,0.046,0.036,4.8e-07,6.3e-07,4.7e-06,0.029,0.029,0.00026,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
229 22690000,0.78,-0.015,6.1e-05,-0.63,0.0035,-0.0046,0.019,-0.0032,-0.0056,-3.7e+02,-0.0014,-0.0059,0.00016,0.0047,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0073,0.048,0.05,0.036,4.9e-07,6.3e-07,4.1e-06,0.03,0.03,0.00026,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22690000,0.78,-0.015,8.2e-05,-0.63,0.0032,-0.0012,0.019,-0.0035,-0.0023,-3.7e+02,-0.0014,-0.006,0.00029,0.004,-0.063,-0.13,-0.11,-0.024,0.5,-3.1e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.047,0.014,0.016,0.0073,0.048,0.05,0.036,4.7e-07,6.3e-07,4.7e-06,0.029,0.029,0.00026,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
230 22790000,0.78,-0.015,0.0001,-0.63,0.0045,-0.004,0.02,-0.0026,-0.0042,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.0002,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.014,0.016,0.0072,0.051,0.052,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22790000,0.78,-0.015,0.00012,-0.63,0.0042,-0.00062,0.02,-0.0029,-0.001,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-4.1e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.014,0.016,0.0072,0.051,0.053,0.036,4.6e-07,6.2e-07,4.7e-06,0.029,0.029,0.00025,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
231 22890000,0.78,-0.015,0.00011,-0.63,0.0052,-0.0049,0.021,-0.0028,-0.0048,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0072,0.055,0.057,0.036,4.8e-07,6.2e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22890000,0.78,-0.015,0.00013,-0.63,0.0049,-0.0013,0.021,-0.0031,-0.0012,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-3.5e-05,-0.091,-0.068,0,0,0.00035,0.00037,0.047,0.015,0.017,0.0072,0.055,0.057,0.036,4.6e-07,6.2e-07,4.7e-06,0.029,0.029,0.00025,0.0012,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
232 22990000,0.78,-0.015,0.00012,-0.63,0.0049,-0.0049,0.022,-0.0029,-0.0055,-3.7e+02,-0.0014,-0.0059,0.00016,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.015,0.017,0.0071,0.058,0.06,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 22990000,0.78,-0.015,0.00014,-0.63,0.0046,-0.0014,0.022,-0.0033,-0.0019,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-2.9e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.015,0.017,0.0071,0.057,0.06,0.036,4.5e-07,6.1e-07,4.6e-06,0.029,0.029,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
233 23090000,0.78,-0.015,0.00018,-0.63,0.0051,-0.0046,0.023,-0.0027,-0.0052,-3.7e+02,-0.0014,-0.0059,0.00015,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00018,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.007,0.062,0.065,0.036,4.7e-07,6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 23090000,0.78,-0.015,0.0002,-0.63,0.0048,-0.00096,0.023,-0.003,-0.0012,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-2.7e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.016,0.018,0.007,0.062,0.065,0.036,4.5e-07,6e-07,4.6e-06,0.029,0.029,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
234 23190000,0.78,-0.015,0.00017,-0.63,0.0027,-0.0034,0.024,-0.0055,-0.005,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.017,0.0069,0.065,0.067,0.035,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 23190000,0.78,-0.015,0.00018,-0.63,0.0024,0.00015,0.024,-0.0058,-0.0011,-3.7e+02,-0.0014,-0.006,0.00028,0.0038,-0.063,-0.13,-0.11,-0.024,0.5,-1e-05,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.015,0.018,0.0069,0.064,0.067,0.035,4.4e-07,5.9e-07,4.6e-06,0.029,0.029,0.00024,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
235 23290000,0.78,-0.015,0.00023,-0.63,0.0023,-0.0031,0.025,-0.0058,-0.0057,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00015,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.017,0.019,0.0069,0.07,0.073,0.036,4.6e-07,5.9e-07,4e-06,0.03,0.03,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1 23290000,0.78,-0.015,0.00025,-0.63,0.002,0.00067,0.025,-0.0061,-0.0014,-3.7e+02,-0.0014,-0.006,0.00028,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,-6.5e-06,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.016,0.019,0.0069,0.07,0.073,0.036,4.4e-07,5.9e-07,4.6e-06,0.029,0.029,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
236 23390000,0.78,-0.015,0.00021,-0.63,-0.0011,-0.0028,0.022,-0.01,-0.0058,-3.7e+02,-0.0014,-0.0059,0.00016,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00013,-0.091,-0.068,0,0,0.00036,0.00038,0.046,0.016,0.018,0.0068,0.072,0.075,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23390000,0.78,-0.015,0.00022,-0.63,-0.0013,0.00086,0.022,-0.01,-0.0015,-3.7e+02,-0.0014,-0.006,0.00028,0.0038,-0.063,-0.13,-0.11,-0.024,0.5,7.1e-06,-0.091,-0.068,0,0,0.00034,0.00037,0.047,0.016,0.018,0.0068,0.072,0.075,0.035,4.3e-07,5.8e-07,4.5e-06,0.029,0.029,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
237 23490000,0.78,-0.013,-0.0019,-0.63,0.0044,-0.0021,-0.011,-0.011,-0.007,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00014,-0.091,-0.068,0,0,0.00036,0.00036,0.046,0.017,0.019,0.0068,0.078,0.081,0.035,4.5e-07,5.7e-07,4e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23490000,0.78,-0.012,-0.0019,-0.63,0.0041,0.0017,-0.011,-0.011,-0.0023,-3.7e+02,-0.0014,-0.006,0.00029,0.0039,-0.063,-0.13,-0.11,-0.024,0.5,1.3e-06,-0.091,-0.068,0,0,0.00034,0.00036,0.047,0.017,0.02,0.0068,0.078,0.082,0.035,4.3e-07,5.8e-07,4.5e-06,0.029,0.029,0.00023,0.0011,5.8e-05,0.0012,0.00064,0.0012,0.0012,1,1
238 23590000,0.78,-0.0042,-0.0062,-0.63,0.015,0.0017,-0.043,-0.0099,-0.0038,-3.7e+02,-0.0013,-0.0059,0.00017,0.0045,-0.066,-0.13,-0.11,-0.024,0.5,-0.00012,-0.091,-0.068,0,0,0.00035,0.00034,0.046,0.014,0.016,0.0067,0.062,0.064,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23590000,0.78,-0.0041,-0.0062,-0.63,0.015,0.0051,-0.043,-0.01,-0.00031,-3.7e+02,-0.0013,-0.006,0.00029,0.0039,-0.064,-0.13,-0.11,-0.024,0.5,5.1e-06,-0.091,-0.068,0,0,0.00034,0.00033,0.047,0.014,0.016,0.0067,0.062,0.064,0.035,4.2e-07,5.5e-07,4.4e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
239 23690000,0.78,0.0014,-0.0052,-0.63,0.042,0.016,-0.093,-0.0075,-0.0033,-3.7e+02,-0.0013,-0.0059,0.00018,0.0046,-0.066,-0.13,-0.11,-0.024,0.5,-0.00019,-0.091,-0.068,0,0,0.00034,0.00034,0.046,0.015,0.017,0.0067,0.067,0.069,0.035,4.3e-07,5.5e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23690000,0.78,0.0016,-0.0052,-0.63,0.042,0.019,-0.093,-0.0078,0.0005,-3.7e+02,-0.0013,-0.006,0.00029,0.004,-0.064,-0.13,-0.11,-0.024,0.5,-5.7e-05,-0.091,-0.068,0,0,0.00033,0.00033,0.047,0.015,0.017,0.0067,0.066,0.069,0.035,4.2e-07,5.5e-07,4.4e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
240 23790000,0.78,-0.0022,-0.0027,-0.63,0.063,0.033,-0.15,-0.0074,-0.0017,-3.7e+02,-0.0013,-0.0059,0.00018,0.0049,-0.066,-0.13,-0.11,-0.024,0.5,-0.00028,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.014,0.015,0.0066,0.055,0.056,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23790000,0.78,-0.0021,-0.0027,-0.63,0.063,0.036,-0.15,-0.0076,0.0013,-3.7e+02,-0.0013,-0.006,0.0003,0.0042,-0.064,-0.13,-0.11,-0.024,0.5,-0.00016,-0.09,-0.067,0,0,0.00033,0.00033,0.047,0.013,0.015,0.0066,0.055,0.057,0.035,4.1e-07,5.3e-07,4.4e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
241 23890000,0.78,-0.0085,-0.0007,-0.63,0.077,0.045,-0.2,2.8e-05,0.0023,-3.7e+02,-0.0013,-0.0059,0.00019,0.005,-0.066,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00034,0.00035,0.046,0.014,0.016,0.0066,0.059,0.061,0.035,4.2e-07,5.3e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23890000,0.78,-0.0084,-0.00069,-0.63,0.077,0.048,-0.2,-0.00014,0.0056,-3.7e+02,-0.0013,-0.006,0.0003,0.0043,-0.064,-0.13,-0.11,-0.024,0.5,-0.00021,-0.09,-0.067,0,0,0.00033,0.00034,0.047,0.014,0.016,0.0066,0.059,0.061,0.035,4.1e-07,5.3e-07,4.3e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
242 23990000,0.78,-0.013,0.00021,-0.63,0.072,0.045,-0.25,-0.0055,0.00083,-3.7e+02,-0.0013,-0.0059,0.00018,0.0052,-0.067,-0.13,-0.11,-0.024,0.5,-0.00029,-0.09,-0.067,0,0,0.00035,0.00037,0.046,0.015,0.016,0.0066,0.062,0.063,0.035,4.1e-07,5.2e-07,3.9e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 23990000,0.78,-0.013,0.00022,-0.63,0.072,0.048,-0.25,-0.0055,0.0042,-3.7e+02,-0.0013,-0.006,0.0003,0.0045,-0.065,-0.13,-0.11,-0.024,0.5,-0.00019,-0.09,-0.067,0,0,0.00034,0.00036,0.047,0.014,0.016,0.0066,0.061,0.064,0.035,4e-07,5.2e-07,4.3e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
243 24090000,0.78,-0.012,-0.00093,-0.63,0.072,0.044,-0.3,0.00081,0.0045,-3.7e+02,-0.0013,-0.0059,0.00019,0.0053,-0.067,-0.13,-0.11,-0.024,0.5,-0.00034,-0.09,-0.067,0,0,0.00035,0.00036,0.046,0.015,0.017,0.0065,0.066,0.069,0.035,4.1e-07,5.2e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1 24090000,0.78,-0.012,-0.00092,-0.63,0.072,0.047,-0.3,0.00074,0.0082,-3.7e+02,-0.0013,-0.006,0.0003,0.0046,-0.065,-0.13,-0.11,-0.024,0.5,-0.00024,-0.09,-0.067,0,0,0.00034,0.00035,0.047,0.015,0.017,0.0065,0.066,0.069,0.035,4e-07,5.2e-07,4.3e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.00064,0.0012,0.0012,1,1
244 24190000,0.78,-0.0097,-0.0017,-0.63,0.069,0.043,-0.35,-0.0065,0.0022,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00031,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.015,0.017,0.0065,0.069,0.071,0.034,4.1e-07,5.1e-07,3.8e-06,0.03,0.03,0.00021,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24190000,0.78,-0.0095,-0.0017,-0.63,0.069,0.046,-0.35,-0.0064,0.006,-3.7e+02,-0.0013,-0.0059,0.00029,0.0049,-0.066,-0.13,-0.11,-0.024,0.5,-0.00023,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.015,0.017,0.0065,0.068,0.071,0.034,3.9e-07,5.1e-07,4.3e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.00063,0.0012,0.0012,1,1
245 24290000,0.78,-0.0089,-0.0021,-0.63,0.077,0.048,-0.4,-0.00011,0.0069,-3.7e+02,-0.0013,-0.0059,0.00018,0.0056,-0.068,-0.13,-0.11,-0.024,0.5,-0.00033,-0.09,-0.067,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0065,0.074,0.077,0.034,4e-07,5.1e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24290000,0.78,-0.0087,-0.0021,-0.63,0.077,0.052,-0.4,-4.6e-05,0.011,-3.7e+02,-0.0013,-0.006,0.00029,0.005,-0.066,-0.13,-0.11,-0.024,0.5,-0.00024,-0.09,-0.067,0,0,0.00034,0.00034,0.046,0.016,0.019,0.0065,0.074,0.077,0.034,3.9e-07,5.1e-07,4.3e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.00063,0.0012,0.0012,1,1
246 24390000,0.78,-0.0093,-0.0022,-0.63,0.074,0.047,-0.46,-0.013,0.00027,-3.7e+02,-0.0012,-0.0059,0.00015,0.0062,-0.069,-0.13,-0.11,-0.024,0.5,-0.0003,-0.089,-0.068,0,0,0.00035,0.00035,0.046,0.016,0.018,0.0064,0.076,0.079,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24390000,0.78,-0.0091,-0.0022,-0.63,0.074,0.05,-0.46,-0.012,0.0043,-3.7e+02,-0.0013,-0.0059,0.00026,0.0056,-0.067,-0.13,-0.11,-0.024,0.5,-0.00024,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.016,0.018,0.0064,0.076,0.079,0.034,3.9e-07,5e-07,4.2e-06,0.029,0.029,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
247 24490000,0.78,-0.0051,-0.0026,-0.63,0.085,0.054,-0.51,-0.0046,0.0052,-3.7e+02,-0.0012,-0.0059,0.00015,0.0063,-0.069,-0.13,-0.11,-0.024,0.5,-0.00033,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.02,0.0064,0.082,0.085,0.034,4e-07,5e-07,3.8e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24490000,0.78,-0.0049,-0.0026,-0.63,0.085,0.057,-0.51,-0.0043,0.0096,-3.7e+02,-0.0013,-0.0059,0.00026,0.0057,-0.067,-0.13,-0.11,-0.024,0.5,-0.00026,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.017,0.02,0.0064,0.082,0.086,0.034,3.9e-07,5e-07,4.2e-06,0.029,0.029,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
248 24590000,0.78,-0.0016,-0.0027,-0.63,0.089,0.057,-0.56,-0.018,-0.0039,-3.7e+02,-0.0012,-0.0059,0.00014,0.0069,-0.071,-0.13,-0.11,-0.024,0.5,-0.00037,-0.089,-0.068,0,0,0.00034,0.00034,0.046,0.017,0.019,0.0063,0.084,0.088,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.0002,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24590000,0.78,-0.0014,-0.0027,-0.63,0.089,0.061,-0.56,-0.018,0.00042,-3.7e+02,-0.0012,-0.0059,0.00024,0.0063,-0.068,-0.13,-0.11,-0.024,0.5,-0.00033,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.017,0.019,0.0063,0.084,0.088,0.034,3.8e-07,4.9e-07,4.2e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
249 24690000,0.78,-0.00074,-0.0027,-0.63,0.11,0.073,-0.64,-0.0089,0.0014,-3.7e+02,-0.0012,-0.0059,0.00015,0.0072,-0.071,-0.13,-0.11,-0.024,0.5,-0.00055,-0.089,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0063,0.09,0.094,0.034,3.9e-07,4.9e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1 24690000,0.78,-0.00055,-0.0027,-0.63,0.11,0.077,-0.64,-0.0084,0.0062,-3.7e+02,-0.0012,-0.0059,0.00025,0.0065,-0.069,-0.13,-0.11,-0.024,0.5,-0.0005,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.018,0.021,0.0063,0.09,0.095,0.034,3.8e-07,4.9e-07,4.2e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00063,0.0012,0.0012,1,1
250 24790000,0.78,-0.0023,-0.0024,-0.63,0.11,0.082,-0.73,-0.028,-0.0034,-3.7e+02,-0.0012,-0.0059,0.00013,0.0079,-0.073,-0.13,-0.11,-0.025,0.5,-0.00036,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.018,0.021,0.0062,0.093,0.096,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1 24790000,0.78,-0.0021,-0.0024,-0.63,0.11,0.086,-0.73,-0.028,0.0011,-3.7e+02,-0.0012,-0.0059,0.00023,0.0072,-0.071,-0.13,-0.11,-0.025,0.5,-0.00035,-0.089,-0.068,0,0,0.00033,0.00033,0.046,0.018,0.021,0.0062,0.092,0.097,0.034,3.7e-07,4.8e-07,4.1e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1
251 24890000,0.78,-0.00046,-0.004,-0.63,0.13,0.097,-0.75,-0.017,0.0055,-3.7e+02,-0.0012,-0.0059,0.00012,0.0081,-0.074,-0.13,-0.11,-0.025,0.5,-0.00045,-0.088,-0.068,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.099,0.1,0.034,3.8e-07,4.8e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00062,0.0012,0.0012,1,1 24890000,0.78,-0.00027,-0.004,-0.63,0.13,0.1,-0.75,-0.016,0.01,-3.7e+02,-0.0012,-0.0059,0.00022,0.0075,-0.071,-0.13,-0.11,-0.025,0.5,-0.00043,-0.088,-0.068,0,0,0.00033,0.00033,0.046,0.019,0.022,0.0062,0.099,0.1,0.034,3.7e-07,4.8e-07,4.1e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.00062,0.0012,0.0012,1,1
252 24990000,0.78,0.0012,-0.0055,-0.63,0.13,0.1,-0.81,-0.039,-0.001,-3.7e+02,-0.0011,-0.0059,9e-05,0.0092,-0.076,-0.13,-0.11,-0.025,0.5,-0.00024,-0.087,-0.069,0,0,0.00034,0.00034,0.045,0.019,0.022,0.0062,0.1,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1 24990000,0.78,0.0014,-0.0056,-0.63,0.13,0.11,-0.81,-0.038,0.0037,-3.7e+02,-0.0012,-0.0059,0.00019,0.0086,-0.073,-0.13,-0.11,-0.025,0.5,-0.00026,-0.087,-0.069,0,0,0.00033,0.00033,0.045,0.019,0.022,0.0062,0.1,0.11,0.034,3.7e-07,4.7e-07,4.1e-06,0.029,0.029,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1
253 25090000,0.78,0.00063,-0.0059,-0.63,0.16,0.12,-0.86,-0.025,0.011,-3.7e+02,-0.0011,-0.0059,8.4e-05,0.0094,-0.076,-0.13,-0.11,-0.025,0.5,-0.00025,-0.087,-0.068,0,0,0.00034,0.00034,0.044,0.02,0.023,0.0062,0.11,0.11,0.034,3.8e-07,4.7e-07,3.7e-06,0.03,0.03,0.00019,0.0011,5.5e-05,0.0012,0.00061,0.0011,0.0012,1,1 25090000,0.78,0.00082,-0.0059,-0.63,0.16,0.12,-0.86,-0.024,0.016,-3.7e+02,-0.0012,-0.0059,0.00018,0.0087,-0.074,-0.13,-0.11,-0.025,0.5,-0.00026,-0.087,-0.068,0,0,0.00033,0.00033,0.045,0.02,0.023,0.0062,0.11,0.11,0.034,3.7e-07,4.7e-07,4.1e-06,0.029,0.029,0.00018,0.0011,5.5e-05,0.0012,0.00061,0.0012,0.0012,1,1
254 25190000,0.78,-0.0015,-0.0054,-0.62,0.15,0.11,-0.91,-0.069,-0.012,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00022,-0.086,-0.069,0,0,0.00034,0.00033,0.044,0.02,0.023,0.0061,0.11,0.11,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1 25190000,0.78,-0.0013,-0.0055,-0.63,0.15,0.12,-0.91,-0.067,-0.0074,-3.7e+02,-0.0011,-0.0059,0.00013,0.011,-0.078,-0.13,-0.11,-0.025,0.5,-0.00027,-0.086,-0.069,0,0,0.00033,0.00033,0.044,0.019,0.023,0.0061,0.11,0.12,0.033,3.6e-07,4.6e-07,4e-06,0.029,0.029,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1
255 25290000,0.78,0.0055,-0.0066,-0.62,0.17,0.13,-0.96,-0.053,-0.00075,-3.7e+02,-0.0011,-0.0059,4.8e-05,0.011,-0.081,-0.13,-0.11,-0.025,0.5,-0.00034,-0.086,-0.069,0,0,0.00033,0.00034,0.044,0.021,0.024,0.0061,0.12,0.12,0.033,3.7e-07,4.6e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.0006,0.0011,0.0012,1,1 25290000,0.78,0.0057,-0.0066,-0.63,0.18,0.13,-0.96,-0.051,0.0044,-3.7e+02,-0.0011,-0.0059,0.00013,0.011,-0.078,-0.13,-0.11,-0.025,0.5,-0.00038,-0.086,-0.069,0,0,0.00032,0.00033,0.044,0.021,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.6e-07,4e-06,0.029,0.029,0.00018,0.0011,5.5e-05,0.0012,0.0006,0.0011,0.0012,1,1
256 25390000,0.78,0.011,-0.0071,-0.62,0.18,0.13,-1,-0.1,-0.025,-3.7e+02,-0.001,-0.0058,8.1e-06,0.014,-0.086,-0.13,-0.11,-0.025,0.5,-0.00037,-0.085,-0.069,0,0,0.00033,0.00036,0.043,0.021,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.4e-05,0.0012,0.00059,0.0011,0.0012,1,1 25390000,0.78,0.012,-0.0071,-0.63,0.18,0.13,-1,-0.098,-0.02,-3.7e+02,-0.001,-0.0058,8.8e-05,0.013,-0.083,-0.13,-0.11,-0.025,0.5,-0.00046,-0.085,-0.069,0,0,0.00032,0.00035,0.043,0.02,0.024,0.0061,0.12,0.12,0.033,3.6e-07,4.5e-07,4e-06,0.029,0.029,0.00018,0.0011,5.4e-05,0.0012,0.00059,0.0011,0.0012,1,1
257 25490000,0.78,0.013,-0.0072,-0.63,0.22,0.16,-1.1,-0.082,-0.012,-3.7e+02,-0.001,-0.0058,2.3e-05,0.014,-0.087,-0.13,-0.11,-0.025,0.5,-0.00072,-0.084,-0.069,0,0,0.00033,0.00036,0.042,0.022,0.026,0.0061,0.13,0.13,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0012,0.00058,0.0011,0.0012,1,1 25490000,0.78,0.013,-0.0072,-0.63,0.22,0.16,-1.1,-0.079,-0.0069,-3.7e+02,-0.001,-0.0058,0.0001,0.013,-0.083,-0.13,-0.12,-0.025,0.5,-0.00079,-0.084,-0.069,0,0,0.00032,0.00035,0.043,0.022,0.026,0.0061,0.13,0.13,0.033,3.5e-07,4.5e-07,4e-06,0.029,0.029,0.00018,0.0011,5.3e-05,0.0012,0.00058,0.0011,0.0012,1,1
258 25590000,0.78,0.011,-0.007,-0.63,0.25,0.19,-1.1,-0.059,0.0041,-3.7e+02,-0.001,-0.0058,3.2e-05,0.014,-0.087,-0.13,-0.12,-0.025,0.5,-0.00098,-0.084,-0.068,0,0,0.00033,0.00035,0.042,0.024,0.028,0.0061,0.14,0.14,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00018,0.0011,5.3e-05,0.0011,0.00058,0.0011,0.0011,1,1 25590000,0.78,0.011,-0.0071,-0.63,0.25,0.19,-1.1,-0.057,0.0099,-3.7e+02,-0.001,-0.0058,0.00011,0.013,-0.084,-0.13,-0.12,-0.025,0.5,-0.001,-0.084,-0.068,0,0,0.00032,0.00034,0.043,0.023,0.028,0.0061,0.14,0.14,0.033,3.5e-07,4.5e-07,4e-06,0.029,0.029,0.00018,0.0011,5.3e-05,0.0011,0.00058,0.0011,0.0011,1,1
259 25690000,0.78,0.018,-0.0099,-0.63,0.29,0.21,-1.2,-0.032,0.022,-3.7e+02,-0.001,-0.0058,4.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0013,-0.082,-0.068,0,0,0.00034,0.00039,0.042,0.025,0.03,0.0061,0.14,0.15,0.033,3.6e-07,4.5e-07,3.6e-06,0.03,0.03,0.00017,0.001,5.2e-05,0.0011,0.00057,0.0011,0.0011,1,1 25690000,0.78,0.018,-0.0099,-0.63,0.3,0.22,-1.2,-0.03,0.029,-3.7e+02,-0.001,-0.0058,0.00012,0.014,-0.084,-0.13,-0.12,-0.026,0.5,-0.0014,-0.083,-0.067,0,0,0.00032,0.00038,0.042,0.025,0.03,0.0061,0.14,0.15,0.033,3.5e-07,4.5e-07,3.9e-06,0.029,0.029,0.00017,0.001,5.2e-05,0.0011,0.00058,0.0011,0.0011,1,1
260 25790000,0.78,0.024,-0.012,-0.63,0.35,0.25,-1.2,-0.00023,0.043,-3.7e+02,-0.00099,-0.0058,6.3e-05,0.015,-0.088,-0.13,-0.12,-0.026,0.5,-0.0019,-0.081,-0.067,0,0,0.00034,0.00043,0.041,0.027,0.033,0.0061,0.15,0.16,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5.1e-05,0.0011,0.00057,0.0011,0.0011,1,1 25790000,0.78,0.024,-0.012,-0.63,0.35,0.25,-1.2,0.0026,0.049,-3.7e+02,-0.001,-0.0058,0.00015,0.014,-0.085,-0.13,-0.12,-0.026,0.5,-0.0019,-0.081,-0.067,0,0,0.00033,0.00042,0.042,0.027,0.033,0.0061,0.15,0.16,0.033,3.5e-07,4.5e-07,3.9e-06,0.029,0.029,0.00017,0.001,5.1e-05,0.0011,0.00057,0.0011,0.0011,1,1
261 25890000,0.77,0.025,-0.012,-0.63,0.41,0.28,-1.3,0.039,0.066,-3.7e+02,-0.00099,-0.0058,8.6e-05,0.015,-0.089,-0.13,-0.12,-0.026,0.5,-0.0025,-0.079,-0.066,0,0,0.00034,0.00043,0.04,0.029,0.037,0.0061,0.17,0.17,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.001,5e-05,0.0011,0.00056,0.0011,0.0011,1,1 25890000,0.77,0.025,-0.012,-0.63,0.41,0.29,-1.3,0.042,0.073,-3.7e+02,-0.001,-0.0058,0.00017,0.014,-0.085,-0.13,-0.12,-0.026,0.5,-0.0026,-0.08,-0.066,0,0,0.00033,0.00043,0.041,0.029,0.037,0.0061,0.16,0.18,0.033,3.5e-07,4.6e-07,3.9e-06,0.029,0.029,0.00017,0.001,5.1e-05,0.0011,0.00056,0.0011,0.0011,1,1
262 25990000,0.77,0.021,-0.012,-0.63,0.47,0.31,-1.3,0.083,0.093,-3.7e+02,-0.00099,-0.0058,9.9e-05,0.015,-0.089,-0.13,-0.12,-0.027,0.5,-0.0029,-0.078,-0.065,0,0,0.00034,0.00041,0.04,0.032,0.04,0.0061,0.18,0.19,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00099,5e-05,0.0011,0.00055,0.001,0.0011,1,1 25990000,0.77,0.022,-0.012,-0.63,0.47,0.32,-1.3,0.086,0.1,-3.7e+02,-0.001,-0.0058,0.00019,0.014,-0.085,-0.13,-0.12,-0.027,0.5,-0.0029,-0.079,-0.065,0,0,0.00033,0.0004,0.04,0.031,0.04,0.0061,0.18,0.19,0.033,3.5e-07,4.6e-07,3.9e-06,0.029,0.029,0.00017,0.00099,5e-05,0.0011,0.00055,0.001,0.0011,1,1
263 26090000,0.78,0.032,-0.016,-0.63,0.52,0.35,-1.3,0.13,0.13,-3.7e+02,-0.00098,-0.0058,8.8e-05,0.016,-0.089,-0.13,-0.12,-0.027,0.5,-0.0028,-0.077,-0.065,0,0,0.00035,0.00049,0.039,0.034,0.043,0.0061,0.19,0.2,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00097,4.8e-05,0.0011,0.00054,0.001,0.0011,1,1 26090000,0.78,0.032,-0.016,-0.63,0.53,0.36,-1.3,0.13,0.14,-3.7e+02,-0.001,-0.0058,0.00017,0.015,-0.086,-0.13,-0.12,-0.027,0.5,-0.0028,-0.077,-0.065,0,0,0.00033,0.00049,0.039,0.033,0.043,0.0061,0.19,0.2,0.033,3.5e-07,4.6e-07,3.9e-06,0.029,0.029,0.00017,0.00097,4.9e-05,0.0011,0.00054,0.001,0.0011,1,1
264 26190000,0.78,0.041,-0.017,-0.63,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,9.6e-05,0.018,-0.09,-0.13,-0.13,-0.028,0.5,-0.0035,-0.074,-0.063,0,0,0.00036,0.00058,0.037,0.036,0.047,0.0061,0.2,0.22,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00093,4.7e-05,0.001,0.00053,0.00098,0.001,1,1 26190000,0.78,0.042,-0.017,-0.63,0.6,0.4,-1.3,0.19,0.17,-3.7e+02,-0.00099,-0.0058,0.00018,0.017,-0.087,-0.13,-0.13,-0.028,0.5,-0.0034,-0.074,-0.062,0,0,0.00035,0.00057,0.038,0.036,0.047,0.0061,0.2,0.22,0.033,3.5e-07,4.6e-07,3.8e-06,0.029,0.029,0.00017,0.00094,4.7e-05,0.001,0.00053,0.00098,0.001,1,1
265 26290000,0.78,0.044,-0.018,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,9.2e-05,0.019,-0.091,-0.13,-0.13,-0.028,0.49,-0.0037,-0.071,-0.061,0,0,0.00036,0.0006,0.036,0.039,0.052,0.0061,0.21,0.23,0.033,3.6e-07,4.5e-07,3.5e-06,0.03,0.03,0.00017,0.00091,4.6e-05,0.001,0.00052,0.00094,0.001,1,1 26290000,0.77,0.044,-0.018,-0.63,0.68,0.46,-1.3,0.25,0.21,-3.7e+02,-0.00098,-0.0058,0.00018,0.018,-0.087,-0.13,-0.13,-0.028,0.49,-0.0037,-0.071,-0.061,0,0,0.00035,0.00059,0.036,0.038,0.052,0.0061,0.21,0.23,0.033,3.5e-07,4.6e-07,3.8e-06,0.029,0.029,0.00016,0.00091,4.6e-05,0.001,0.00052,0.00095,0.001,1,1
266 26390000,0.77,0.04,-0.018,-0.63,0.76,0.5,-1.3,0.32,0.25,-3.7e+02,-0.00097,-0.0058,0.0001,0.02,-0.091,-0.13,-0.13,-0.028,0.49,-0.0042,-0.069,-0.06,0,0,0.00036,0.00055,0.034,0.042,0.056,0.0061,0.23,0.25,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00088,4.4e-05,0.00098,0.0005,0.00091,0.00097,1,1 26390000,0.77,0.04,-0.018,-0.63,0.76,0.51,-1.3,0.32,0.26,-3.7e+02,-0.00098,-0.0058,0.00018,0.018,-0.088,-0.13,-0.13,-0.028,0.49,-0.0041,-0.07,-0.06,0,0,0.00034,0.00054,0.035,0.041,0.056,0.0061,0.23,0.25,0.033,3.6e-07,4.6e-07,3.8e-06,0.029,0.029,0.00016,0.00088,4.4e-05,0.00098,0.0005,0.00091,0.00098,1,1
267 26490000,0.77,0.056,-0.024,-0.63,0.84,0.55,-1.3,0.4,0.3,-3.7e+02,-0.00096,-0.0058,0.0001,0.02,-0.092,-0.13,-0.13,-0.029,0.49,-0.0043,-0.067,-0.058,0,0,0.00038,0.00075,0.033,0.044,0.061,0.0061,0.24,0.27,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00084,4.2e-05,0.00094,0.00048,0.00088,0.00094,1,1 26490000,0.77,0.057,-0.024,-0.63,0.84,0.56,-1.3,0.4,0.31,-3.7e+02,-0.00098,-0.0058,0.00018,0.019,-0.088,-0.13,-0.13,-0.029,0.49,-0.0043,-0.068,-0.058,0,0,0.00037,0.00074,0.033,0.044,0.061,0.0061,0.24,0.27,0.033,3.6e-07,4.6e-07,3.8e-06,0.029,0.029,0.00016,0.00084,4.2e-05,0.00094,0.00048,0.00088,0.00094,1,1
268 26590000,0.77,0.073,-0.029,-0.63,0.95,0.63,-1.3,0.48,0.36,-3.7e+02,-0.00096,-0.0058,7.4e-05,0.023,-0.092,-0.13,-0.13,-0.03,0.49,-0.0039,-0.064,-0.057,0,0,0.00041,0.00098,0.031,0.048,0.067,0.0061,0.26,0.29,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0008,4e-05,0.00089,0.00046,0.00083,0.00089,1,1 26590000,0.77,0.074,-0.029,-0.63,0.96,0.64,-1.3,0.49,0.38,-3.7e+02,-0.00097,-0.0058,0.00015,0.021,-0.089,-0.13,-0.13,-0.03,0.49,-0.0038,-0.064,-0.056,0,0,0.0004,0.00097,0.031,0.047,0.067,0.0061,0.26,0.29,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.0008,4e-05,0.00089,0.00046,0.00083,0.00089,1,1
269 26690000,0.77,0.076,-0.03,-0.64,1.1,0.71,-1.3,0.59,0.42,-3.7e+02,-0.00096,-0.0058,8.5e-05,0.024,-0.093,-0.13,-0.14,-0.031,0.49,-0.0049,-0.059,-0.052,0,0,0.00041,0.00097,0.028,0.052,0.073,0.0061,0.28,0.31,0.033,3.6e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.00074,3.8e-05,0.00083,0.00044,0.00077,0.00083,1,1 26690000,0.77,0.076,-0.03,-0.64,1.1,0.71,-1.3,0.59,0.44,-3.7e+02,-0.00097,-0.0058,0.00016,0.023,-0.09,-0.13,-0.14,-0.031,0.49,-0.0048,-0.059,-0.052,0,0,0.0004,0.00097,0.029,0.051,0.074,0.0061,0.28,0.31,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.00074,3.8e-05,0.00083,0.00044,0.00077,0.00083,1,1
270 26790000,0.77,0.07,-0.029,-0.64,1.2,0.79,-1.3,0.7,0.5,-3.7e+02,-0.00095,-0.0058,6.9e-05,0.025,-0.093,-0.13,-0.14,-0.032,0.48,-0.0047,-0.055,-0.049,0,0,0.00039,0.00084,0.026,0.055,0.079,0.0061,0.3,0.33,0.033,3.7e-07,4.5e-07,3.4e-06,0.03,0.03,0.00016,0.0007,3.6e-05,0.00079,0.00041,0.00073,0.00078,1,1 26790000,0.77,0.071,-0.029,-0.64,1.2,0.8,-1.3,0.7,0.51,-3.7e+02,-0.00096,-0.0058,0.00014,0.024,-0.089,-0.13,-0.14,-0.032,0.48,-0.0046,-0.056,-0.049,0,0,0.00038,0.00084,0.026,0.054,0.079,0.0061,0.29,0.33,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.0007,3.6e-05,0.00079,0.00041,0.00073,0.00078,1,1
271 26890000,0.76,0.093,-0.036,-0.64,1.3,0.86,-1.3,0.83,0.58,-3.7e+02,-0.00095,-0.0058,7.2e-05,0.026,-0.093,-0.13,-0.15,-0.032,0.48,-0.0052,-0.052,-0.047,0,0,0.00044,0.0011,0.024,0.058,0.085,0.0061,0.32,0.35,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00066,3.4e-05,0.00074,0.00039,0.00068,0.00074,1,1 26890000,0.76,0.093,-0.036,-0.64,1.4,0.87,-1.3,0.83,0.59,-3.7e+02,-0.00096,-0.0058,0.00015,0.025,-0.089,-0.13,-0.15,-0.032,0.48,-0.0051,-0.052,-0.047,0,0,0.00043,0.0011,0.024,0.057,0.085,0.0061,0.31,0.35,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.00066,3.4e-05,0.00074,0.00039,0.00068,0.00074,1,1
272 26990000,0.76,0.12,-0.041,-0.64,1.5,0.97,-1.3,0.98,0.67,-3.7e+02,-0.00095,-0.0058,6.1e-05,0.029,-0.094,-0.13,-0.15,-0.034,0.48,-0.0055,-0.046,-0.043,0,0,0.00049,0.0014,0.021,0.061,0.091,0.0061,0.34,0.37,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.0006,3.1e-05,0.00067,0.00036,0.00062,0.00067,1,1 26990000,0.76,0.12,-0.041,-0.64,1.5,0.98,-1.3,0.98,0.69,-3.7e+02,-0.00096,-0.0059,0.00013,0.027,-0.09,-0.13,-0.15,-0.034,0.48,-0.0054,-0.046,-0.043,0,0,0.00048,0.0014,0.021,0.06,0.092,0.0061,0.33,0.38,0.033,3.6e-07,4.6e-07,3.7e-06,0.029,0.029,0.00016,0.0006,3.1e-05,0.00067,0.00036,0.00062,0.00067,1,1
273 27090000,0.76,0.12,-0.041,-0.64,1.7,1.1,-1.2,1.1,0.78,-3.7e+02,-0.00095,-0.0058,4.5e-05,0.03,-0.093,-0.13,-0.16,-0.035,0.47,-0.0055,-0.041,-0.038,0,0,0.00049,0.0013,0.018,0.065,0.098,0.0061,0.36,0.4,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00016,0.00055,2.8e-05,0.0006,0.00033,0.00056,0.0006,1,1 27090000,0.76,0.12,-0.042,-0.64,1.7,1.1,-1.2,1.1,0.79,-3.7e+02,-0.00096,-0.0059,0.00011,0.029,-0.09,-0.13,-0.16,-0.035,0.47,-0.0054,-0.041,-0.038,0,0,0.00048,0.0013,0.019,0.064,0.098,0.0061,0.36,0.4,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00055,2.8e-05,0.0006,0.00033,0.00056,0.0006,1,1
274 27190000,0.76,0.11,-0.039,-0.64,1.9,1.2,-1.2,1.3,0.9,-3.7e+02,-0.00096,-0.0058,2.8e-05,0.032,-0.092,-0.13,-0.16,-0.035,0.47,-0.0053,-0.038,-0.035,0,0,0.00045,0.0011,0.017,0.068,0.1,0.0062,0.38,0.43,0.034,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00051,2.6e-05,0.00056,0.00031,0.00052,0.00056,1,1 27190000,0.76,0.11,-0.039,-0.64,1.9,1.2,-1.2,1.3,0.92,-3.7e+02,-0.00097,-0.0059,9.3e-05,0.03,-0.089,-0.13,-0.16,-0.035,0.47,-0.0051,-0.038,-0.035,0,0,0.00044,0.0011,0.017,0.067,0.1,0.0062,0.38,0.43,0.034,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00051,2.6e-05,0.00056,0.00031,0.00052,0.00056,1,1
275 27290000,0.76,0.093,-0.035,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00096,-0.0058,2.2e-05,0.032,-0.091,-0.13,-0.16,-0.036,0.47,-0.0054,-0.035,-0.033,0,0,0.00041,0.00083,0.015,0.07,0.11,0.0062,0.4,0.46,0.033,3.7e-07,4.6e-07,3.3e-06,0.03,0.03,0.00015,0.00048,2.5e-05,0.00053,0.00029,0.00049,0.00052,1,1 27290000,0.76,0.093,-0.035,-0.64,2,1.3,-1.2,1.5,1,-3.7e+02,-0.00097,-0.0059,8.5e-05,0.031,-0.087,-0.13,-0.16,-0.036,0.47,-0.0053,-0.035,-0.033,0,0,0.0004,0.00083,0.015,0.069,0.11,0.0062,0.4,0.46,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00048,2.5e-05,0.00053,0.00029,0.00049,0.00052,1,1
276 27390000,0.76,0.077,-0.03,-0.64,2.1,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00095,-0.0058,1.7e-05,0.033,-0.089,-0.13,-0.17,-0.036,0.47,-0.0054,-0.033,-0.032,0,0,0.00038,0.00064,0.014,0.071,0.11,0.0062,0.43,0.49,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00046,2.4e-05,0.00051,0.00027,0.00047,0.00051,1,1 27390000,0.76,0.077,-0.03,-0.64,2.2,1.4,-1.2,1.7,1.2,-3.7e+02,-0.00097,-0.0059,7.9e-05,0.032,-0.085,-0.13,-0.17,-0.036,0.47,-0.0053,-0.033,-0.032,0,0,0.00037,0.00064,0.014,0.07,0.11,0.0062,0.43,0.49,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00046,2.4e-05,0.00051,0.00027,0.00047,0.00051,1,1
277 27490000,0.76,0.061,-0.025,-0.64,2.2,1.4,-1.2,1.9,1.3,-3.7e+02,-0.00095,-0.0058,9e-06,0.033,-0.087,-0.13,-0.17,-0.037,0.47,-0.0052,-0.032,-0.032,0,0,0.00036,0.00052,0.012,0.072,0.11,0.0062,0.46,0.52,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00044,2.3e-05,0.0005,0.00025,0.00046,0.0005,1,1 27490000,0.76,0.062,-0.025,-0.64,2.2,1.5,-1.2,1.9,1.3,-3.7e+02,-0.00097,-0.0059,7e-05,0.032,-0.083,-0.13,-0.17,-0.037,0.47,-0.005,-0.032,-0.031,0,0,0.00035,0.00051,0.013,0.071,0.11,0.0062,0.45,0.52,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00044,2.3e-05,0.0005,0.00025,0.00046,0.0005,1,1
278 27590000,0.77,0.049,-0.022,-0.64,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00095,-0.0058,-8.8e-07,0.034,-0.084,-0.13,-0.17,-0.037,0.47,-0.0048,-0.031,-0.031,0,0,0.00035,0.00045,0.012,0.073,0.11,0.0062,0.48,0.55,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.3e-05,0.00049,0.00024,0.00045,0.00049,1,1 27590000,0.77,0.049,-0.022,-0.64,2.3,1.5,-1.2,2.2,1.5,-3.7e+02,-0.00096,-0.0059,5.9e-05,0.032,-0.081,-0.13,-0.17,-0.037,0.47,-0.0046,-0.031,-0.031,0,0,0.00034,0.00044,0.012,0.072,0.11,0.0062,0.48,0.56,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00043,2.3e-05,0.00049,0.00024,0.00045,0.00049,1,1
279 27690000,0.77,0.047,-0.021,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,-9.9e-06,0.034,-0.083,-0.13,-0.17,-0.037,0.47,-0.0044,-0.031,-0.031,0,0,0.00035,0.00044,0.011,0.073,0.11,0.0063,0.51,0.59,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00043,2.2e-05,0.00049,0.00023,0.00045,0.00049,1,1 27690000,0.77,0.047,-0.021,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00096,-0.0059,4.8e-05,0.033,-0.079,-0.13,-0.17,-0.037,0.47,-0.0043,-0.031,-0.031,0,0,0.00034,0.00043,0.011,0.072,0.11,0.0063,0.51,0.59,0.033,3.6e-07,4.7e-07,3.6e-06,0.029,0.029,0.00015,0.00043,2.2e-05,0.00049,0.00023,0.00045,0.00049,1,1
280 27790000,0.77,0.049,-0.021,-0.64,2.3,1.5,-1.2,2.6,1.8,-3.7e+02,-0.00095,-0.0058,-2.3e-05,0.035,-0.081,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.031,0,0,0.00035,0.00044,0.0098,0.074,0.1,0.0063,0.54,0.62,0.033,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00042,2.2e-05,0.00049,0.00022,0.00044,0.00048,1,1 27790000,0.77,0.049,-0.021,-0.64,2.3,1.6,-1.2,2.6,1.8,-3.7e+02,-0.00097,-0.0059,3.3e-05,0.033,-0.078,-0.13,-0.17,-0.037,0.47,-0.0038,-0.03,-0.03,0,0,0.00034,0.00043,0.0099,0.073,0.11,0.0063,0.54,0.63,0.033,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00015,0.00042,2.2e-05,0.00048,0.00022,0.00044,0.00048,1,1
281 27890000,0.77,0.047,-0.021,-0.64,2.4,1.6,-1.2,2.8,1.9,-3.7e+02,-0.00095,-0.0058,-2.4e-05,0.034,-0.079,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00043,0.0093,0.075,0.1,0.0063,0.58,0.66,0.034,3.7e-07,4.6e-07,3.3e-06,0.029,0.03,0.00015,0.00041,2.2e-05,0.00048,0.00022,0.00044,0.00048,1,1 27890000,0.77,0.047,-0.021,-0.64,2.4,1.6,-1.2,2.8,2,-3.7e+02,-0.00096,-0.0059,3.2e-05,0.033,-0.076,-0.13,-0.17,-0.037,0.47,-0.0038,-0.03,-0.03,0,0,0.00034,0.00042,0.0093,0.074,0.11,0.0063,0.57,0.67,0.034,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.00041,2.2e-05,0.00048,0.00022,0.00043,0.00048,1,1
282 27990000,0.77,0.043,-0.02,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,-2.7e-05,0.034,-0.078,-0.13,-0.17,-0.037,0.47,-0.0039,-0.03,-0.03,0,0,0.00035,0.00041,0.0087,0.076,0.1,0.0064,0.61,0.7,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00041,2.1e-05,0.00048,0.00021,0.00043,0.00048,1,1 27990000,0.77,0.043,-0.02,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00097,-0.0059,2.9e-05,0.033,-0.075,-0.13,-0.17,-0.037,0.47,-0.0038,-0.03,-0.03,0,0,0.00034,0.0004,0.0087,0.075,0.11,0.0064,0.61,0.71,0.033,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.00041,2.1e-05,0.00048,0.00021,0.00043,0.00048,1,1
283 28090000,0.77,0.057,-0.025,-0.64,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00095,-0.0058,-3.8e-05,0.035,-0.076,-0.13,-0.17,-0.038,0.47,-0.0035,-0.029,-0.03,0,0,0.00035,0.00045,0.0081,0.077,0.1,0.0064,0.65,0.74,0.033,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.0004,2.1e-05,0.00048,0.00021,0.00042,0.00048,1,1 28090000,0.77,0.057,-0.025,-0.64,2.4,1.6,-1.2,3.3,2.3,-3.7e+02,-0.00096,-0.0059,1.6e-05,0.034,-0.073,-0.13,-0.17,-0.038,0.47,-0.0033,-0.029,-0.03,0,0,0.00034,0.00044,0.0082,0.076,0.11,0.0064,0.64,0.75,0.033,3.6e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.0004,2.1e-05,0.00048,0.0002,0.00042,0.00047,1,1
284 28190000,0.77,0.071,-0.028,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,-4e-05,0.035,-0.074,-0.13,-0.17,-0.038,0.46,-0.0035,-0.029,-0.03,0,0,0.00036,0.00049,0.0077,0.078,0.1,0.0065,0.68,0.79,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00039,2.1e-05,0.00047,0.0002,0.00042,0.00047,1,1 28190000,0.77,0.071,-0.028,-0.63,2.5,1.7,-0.93,3.6,2.5,-3.7e+02,-0.00096,-0.0059,1.4e-05,0.033,-0.071,-0.13,-0.17,-0.038,0.46,-0.0033,-0.029,-0.03,0,0,0.00035,0.00048,0.0077,0.077,0.11,0.0065,0.68,0.8,0.034,3.7e-07,4.7e-07,3.6e-06,0.028,0.029,0.00014,0.00039,2.1e-05,0.00047,0.0002,0.00042,0.00047,1,1
285 28290000,0.77,0.053,-0.022,-0.64,2.5,1.7,-0.065,3.8,2.6,-3.7e+02,-0.00095,-0.0058,-4.9e-05,0.035,-0.071,-0.13,-0.17,-0.038,0.46,-0.0033,-0.028,-0.029,0,0,0.00035,0.00043,0.0074,0.077,0.1,0.0066,0.72,0.83,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.0002,0.00041,0.00046,1,1 28290000,0.77,0.053,-0.022,-0.64,2.5,1.7,-0.065,3.8,2.6,-3.7e+02,-0.00096,-0.0059,3.6e-06,0.034,-0.068,-0.13,-0.17,-0.038,0.46,-0.0031,-0.028,-0.029,0,0,0.00034,0.00042,0.0074,0.076,0.1,0.0065,0.72,0.85,0.034,3.7e-07,4.8e-07,3.6e-06,0.028,0.029,0.00014,0.00038,2e-05,0.00046,0.0002,0.00041,0.00046,1,1
286 28390000,0.77,0.02,-0.0094,-0.64,2.5,1.7,0.79,4,2.8,-3.7e+02,-0.00095,-0.0058,-5.7e-05,0.035,-0.068,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00035,0.00037,0.0071,0.076,0.1,0.0066,0.76,0.88,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 28390000,0.77,0.021,-0.0094,-0.64,2.5,1.7,0.79,4,2.8,-3.7e+02,-0.00096,-0.0059,-5.4e-06,0.034,-0.065,-0.13,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00033,0.00036,0.0071,0.075,0.1,0.0066,0.75,0.89,0.033,3.7e-07,4.8e-07,3.6e-06,0.028,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.0004,0.00046,1,1
287 28490000,0.77,0.0014,-0.0026,-0.64,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00096,-0.0058,-6.3e-05,0.035,-0.065,-0.13,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0068,0.077,0.099,0.0067,0.8,0.93,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.03,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 28490000,0.77,0.0017,-0.0025,-0.64,2.4,1.7,1.1,4.3,3,-3.7e+02,-0.00097,-0.0059,-1.2e-05,0.034,-0.063,-0.13,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00033,0.00035,0.0068,0.076,0.1,0.0066,0.79,0.94,0.034,3.6e-07,4.8e-07,3.6e-06,0.028,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.0004,0.00046,1,1
288 28590000,0.77,-0.0022,-0.0011,-0.64,2.4,1.6,0.99,4.5,3.1,-3.7e+02,-0.00096,-0.0058,-6.4e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.0031,-0.027,-0.029,0,0,0.00034,0.00036,0.0065,0.077,0.098,0.0067,0.84,0.98,0.034,3.7e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00019,0.00041,0.00046,1,1 28590000,0.77,-0.002,-0.0011,-0.64,2.4,1.6,0.99,4.5,3.1,-3.7e+02,-0.00097,-0.0059,-1.3e-05,0.033,-0.061,-0.12,-0.17,-0.038,0.46,-0.003,-0.027,-0.029,0,0,0.00033,0.00036,0.0065,0.077,0.1,0.0067,0.83,0.99,0.034,3.6e-07,4.8e-07,3.6e-06,0.028,0.028,0.00014,0.00038,2e-05,0.00046,0.00019,0.0004,0.00046,1,1
289 28690000,0.77,-0.0032,-0.00057,-0.64,2.3,1.6,0.99,4.8,3.3,-3.7e+02,-0.00097,-0.0058,-7.1e-05,0.034,-0.064,-0.12,-0.17,-0.038,0.46,-0.003,-0.027,-0.029,0,0,0.00034,0.00036,0.0063,0.078,0.098,0.0067,0.88,1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00046,0.00018,0.0004,0.00046,1,1 28690000,0.77,-0.0029,-0.00054,-0.64,2.3,1.6,0.99,4.8,3.3,-3.7e+02,-0.00098,-0.0059,-2.1e-05,0.033,-0.061,-0.12,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00033,0.00036,0.0063,0.077,0.1,0.0067,0.87,1,0.034,3.6e-07,4.8e-07,3.6e-06,0.028,0.028,0.00014,0.00038,2e-05,0.00046,0.00018,0.0004,0.00046,1,1
290 28790000,0.77,-0.0034,-0.00035,-0.63,2.2,1.6,1,5,3.4,-3.7e+02,-0.00098,-0.0058,-7.9e-05,0.034,-0.061,-0.12,-0.17,-0.038,0.46,-0.0029,-0.027,-0.029,0,0,0.00034,0.00037,0.0061,0.079,0.098,0.0068,0.92,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00014,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 28790000,0.77,-0.0032,-0.00032,-0.63,2.2,1.6,1,5,3.5,-3.7e+02,-0.00099,-0.0059,-3e-05,0.033,-0.059,-0.12,-0.17,-0.038,0.46,-0.0027,-0.027,-0.029,0,0,0.00033,0.00036,0.0061,0.078,0.1,0.0067,0.91,1.1,0.034,3.6e-07,4.8e-07,3.6e-06,0.028,0.028,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
291 28890000,0.77,-0.0032,-0.00036,-0.63,2.2,1.5,0.99,5.2,3.6,-3.7e+02,-0.00099,-0.0058,-8.6e-05,0.033,-0.06,-0.12,-0.17,-0.038,0.46,-0.0028,-0.027,-0.029,0,0,0.00034,0.00037,0.0059,0.08,0.1,0.0068,0.97,1.1,0.034,3.6e-07,4.7e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 28890000,0.77,-0.0029,-0.00033,-0.63,2.2,1.6,0.99,5.2,3.6,-3.7e+02,-0.001,-0.0058,-3.7e-05,0.032,-0.057,-0.12,-0.17,-0.038,0.46,-0.0027,-0.027,-0.028,0,0,0.00033,0.00036,0.0059,0.079,0.1,0.0068,0.96,1.2,0.034,3.5e-07,4.8e-07,3.6e-06,0.028,0.028,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
292 28990000,0.77,-0.0027,-0.00054,-0.63,2.1,1.5,0.98,5.5,3.8,-3.7e+02,-0.001,-0.0058,-9.8e-05,0.033,-0.058,-0.12,-0.17,-0.038,0.46,-0.0026,-0.027,-0.028,0,0,0.00034,0.00037,0.0057,0.081,0.1,0.0069,1,1.2,0.034,3.6e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00038,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 28990000,0.77,-0.0024,-0.00051,-0.63,2.1,1.5,0.98,5.5,3.8,-3.7e+02,-0.001,-0.0058,-5e-05,0.032,-0.055,-0.12,-0.17,-0.038,0.46,-0.0025,-0.027,-0.028,0,0,0.00033,0.00036,0.0057,0.08,0.1,0.0068,1,1.2,0.034,3.5e-07,4.8e-07,3.6e-06,0.028,0.028,0.00013,0.00037,2e-05,0.00045,0.00018,0.0004,0.00045,1,1
293 29090000,0.78,-0.0022,-0.0007,-0.63,2.1,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.056,-0.12,-0.17,-0.038,0.46,-0.0025,-0.027,-0.028,0,0,0.00034,0.00037,0.0055,0.083,0.1,0.0069,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.029,0.00013,0.00037,2e-05,0.00045,0.00018,0.0004,0.00045,1,1 29090000,0.78,-0.0019,-0.00067,-0.63,2.1,1.5,0.97,5.7,4,-3.7e+02,-0.001,-0.0058,-5.8e-05,0.031,-0.054,-0.12,-0.17,-0.038,0.46,-0.0024,-0.027,-0.028,0,0,0.00033,0.00036,0.0055,0.082,0.11,0.0069,1,1.3,0.034,3.5e-07,4.8e-07,3.5e-06,0.028,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1
294 29190000,0.77,-0.0019,-0.00078,-0.63,2,1.5,0.97,5.9,4.1,-3.7e+02,-0.001,-0.0058,-0.0001,0.032,-0.055,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.028,0,0,0.00034,0.00037,0.0054,0.084,0.1,0.007,1.1,1.3,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1 29190000,0.77,-0.0016,-0.00075,-0.63,2,1.5,0.97,5.9,4.1,-3.7e+02,-0.001,-0.0058,-5.6e-05,0.031,-0.053,-0.12,-0.17,-0.038,0.46,-0.0024,-0.027,-0.028,0,0,0.00033,0.00036,0.0054,0.083,0.11,0.0069,1.1,1.3,0.034,3.5e-07,4.8e-07,3.5e-06,0.028,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00045,1,1
295 29290000,0.78,-0.00093,-0.0011,-0.63,1.9,1.4,1,6.1,4.2,-3.7e+02,-0.001,-0.0058,-0.00011,0.031,-0.053,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.028,0,0,0.00033,0.00037,0.0053,0.086,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00045,0.00017,0.0004,0.00044,1,1 29290000,0.78,-0.00068,-0.001,-0.63,1.9,1.4,1,6.1,4.3,-3.7e+02,-0.001,-0.0058,-6.5e-05,0.03,-0.051,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.028,0,0,0.00032,0.00036,0.0053,0.085,0.11,0.0069,1.1,1.4,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
296 29390000,0.78,0.00051,-0.0014,-0.63,1.9,1.4,1,6.3,4.4,-3.7e+02,-0.001,-0.0058,-0.00012,0.03,-0.051,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.0051,0.087,0.11,0.007,1.2,1.4,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 29390000,0.78,0.00075,-0.0014,-0.63,1.9,1.4,1,6.3,4.4,-3.7e+02,-0.001,-0.0058,-7.8e-05,0.029,-0.049,-0.12,-0.17,-0.038,0.46,-0.002,-0.027,-0.028,0,0,0.00032,0.00036,0.0051,0.086,0.11,0.007,1.2,1.5,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
297 29490000,0.78,0.0017,-0.0018,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,-0.00013,0.03,-0.05,-0.12,-0.17,-0.038,0.46,-0.0021,-0.027,-0.028,0,0,0.00033,0.00037,0.005,0.089,0.11,0.0071,1.3,1.5,0.034,3.5e-07,4.8e-07,3.3e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 29490000,0.78,0.002,-0.0018,-0.63,1.8,1.4,1,6.5,4.6,-3.7e+02,-0.001,-0.0058,-8.1e-05,0.029,-0.048,-0.12,-0.17,-0.038,0.46,-0.0019,-0.027,-0.028,0,0,0.00032,0.00036,0.005,0.088,0.12,0.007,1.3,1.5,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
298 29590000,0.78,0.0028,-0.002,-0.63,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,-0.00013,0.028,-0.048,-0.12,-0.17,-0.038,0.46,-0.002,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.091,0.12,0.0071,1.3,1.6,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00013,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 29590000,0.78,0.0031,-0.002,-0.63,1.8,1.4,1,6.6,4.7,-3.7e+02,-0.001,-0.0058,-8.6e-05,0.028,-0.046,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00032,0.00037,0.0049,0.09,0.12,0.007,1.3,1.6,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1
299 29690000,0.78,0.0036,-0.0023,-0.63,1.8,1.4,0.99,6.8,4.8,-3.7e+02,-0.001,-0.0058,-0.00014,0.028,-0.045,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0049,0.093,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 29690000,0.78,0.0038,-0.0023,-0.63,1.8,1.4,0.99,6.8,4.8,-3.7e+02,-0.001,-0.0058,-9.3e-05,0.027,-0.043,-0.12,-0.17,-0.038,0.46,-0.0018,-0.028,-0.028,0,0,0.00032,0.00037,0.0048,0.092,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1
300 29790000,0.78,0.0041,-0.0025,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0058,-0.00014,0.027,-0.042,-0.12,-0.17,-0.038,0.46,-0.0019,-0.028,-0.028,0,0,0.00033,0.00037,0.0048,0.095,0.12,0.0071,1.4,1.7,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.028,0.00012,0.00037,2e-05,0.00044,0.00017,0.0004,0.00044,1,1 29790000,0.78,0.0044,-0.0025,-0.63,1.7,1.4,0.98,7,5,-3.7e+02,-0.0011,-0.0058,-9.6e-05,0.026,-0.04,-0.12,-0.17,-0.038,0.46,-0.0018,-0.028,-0.028,0,0,0.00032,0.00037,0.0048,0.094,0.13,0.0071,1.4,1.8,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1
301 29890000,0.78,0.0045,-0.0026,-0.63,1.7,1.3,0.97,7.2,5.1,-3.7e+02,-0.001,-0.0058,-0.00015,0.026,-0.038,-0.12,-0.17,-0.038,0.46,-0.0017,-0.028,-0.028,0,0,0.00033,0.00038,0.0047,0.097,0.13,0.0072,1.5,1.8,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1 29890000,0.78,0.0047,-0.0026,-0.63,1.7,1.3,0.97,7.2,5.1,-3.7e+02,-0.0011,-0.0058,-0.0001,0.025,-0.036,-0.12,-0.17,-0.038,0.46,-0.0016,-0.028,-0.028,0,0,0.00032,0.00037,0.0047,0.096,0.13,0.0071,1.5,1.9,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00044,1,1
302 29990000,0.78,0.0046,-0.0027,-0.63,1.7,1.3,0.95,7.3,5.2,-3.7e+02,-0.001,-0.0058,-0.00015,0.025,-0.035,-0.12,-0.17,-0.038,0.46,-0.0016,-0.028,-0.028,0,0,0.00033,0.00038,0.0046,0.099,0.13,0.0072,1.6,1.9,0.034,3.4e-07,4.8e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00017,0.0004,0.00044,1,1 29990000,0.78,0.0049,-0.0027,-0.63,1.7,1.3,0.95,7.3,5.2,-3.7e+02,-0.0011,-0.0058,-0.00011,0.024,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.027,0,0,0.00032,0.00037,0.0046,0.098,0.14,0.0071,1.5,2,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00044,1,1
303 30090000,0.78,0.0046,-0.0027,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0058,-0.00016,0.024,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0046,0.1,0.14,0.0072,1.6,2,0.034,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 30090000,0.78,0.0048,-0.0026,-0.63,1.6,1.3,0.94,7.5,5.4,-3.7e+02,-0.0011,-0.0058,-0.00012,0.023,-0.031,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.028,0,0,0.00031,0.00037,0.0046,0.1,0.14,0.0071,1.6,2.1,0.034,3.3e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
304 30190000,0.78,0.0043,-0.0026,-0.63,1.6,1.3,0.93,7.7,5.5,-3.7e+02,-0.001,-0.0058,-0.00016,0.023,-0.033,-0.12,-0.17,-0.038,0.46,-0.0015,-0.028,-0.028,0,0,0.00032,0.00038,0.0045,0.1,0.14,0.0072,1.7,2.1,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 30190000,0.78,0.0046,-0.0026,-0.63,1.6,1.3,0.93,7.7,5.5,-3.7e+02,-0.0011,-0.0058,-0.00011,0.022,-0.031,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.028,0,0,0.00031,0.00037,0.0045,0.1,0.15,0.0072,1.7,2.2,0.035,3.3e-07,4.9e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
305 30290000,0.78,0.0042,-0.0026,-0.63,1.5,1.3,0.92,7.8,5.6,-3.7e+02,-0.0011,-0.0058,-0.00016,0.022,-0.031,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.028,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.2,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1 30290000,0.78,0.0044,-0.0025,-0.63,1.5,1.3,0.92,7.8,5.6,-3.7e+02,-0.0011,-0.0058,-0.00012,0.021,-0.029,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.028,0,0,0.00031,0.00037,0.0044,0.1,0.15,0.0072,1.8,2.3,0.035,3.3e-07,5e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00044,0.00016,0.0004,0.00043,1,1
306 30390000,0.78,0.0041,-0.0026,-0.63,1.5,1.2,0.9,8,5.7,-3.7e+02,-0.0011,-0.0058,-0.00017,0.021,-0.028,-0.12,-0.17,-0.038,0.46,-0.0014,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.15,0.0072,1.8,2.3,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.027,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30390000,0.78,0.0043,-0.0026,-0.63,1.5,1.3,0.9,8,5.8,-3.7e+02,-0.0011,-0.0058,-0.00012,0.02,-0.026,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00031,0.00037,0.0044,0.11,0.16,0.0072,1.8,2.4,0.034,3.2e-07,5e-07,3.5e-06,0.028,0.026,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
307 30490000,0.78,0.0039,-0.0025,-0.63,1.5,1.2,0.89,8.2,5.8,-3.7e+02,-0.0011,-0.0058,-0.00017,0.02,-0.026,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0044,0.11,0.16,0.0072,1.9,2.4,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00012,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30490000,0.78,0.0041,-0.0025,-0.63,1.5,1.2,0.89,8.2,5.9,-3.7e+02,-0.0011,-0.0058,-0.00012,0.02,-0.025,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00038,0.0043,0.11,0.16,0.0072,1.9,2.5,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.026,0.00011,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
308 30590000,0.78,0.0036,-0.0025,-0.63,1.5,1.2,0.85,8.3,6,-3.7e+02,-0.0011,-0.0058,-0.00017,0.019,-0.022,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00038,0.0043,0.11,0.16,0.0072,2,2.5,0.035,3.3e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00037,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30590000,0.78,0.0038,-0.0024,-0.63,1.5,1.2,0.85,8.3,6,-3.7e+02,-0.0011,-0.0058,-0.00012,0.019,-0.021,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00038,0.0043,0.11,0.17,0.0072,2,2.6,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
309 30690000,0.78,0.0034,-0.0024,-0.63,1.4,1.2,0.84,8.5,6.1,-3.7e+02,-0.0011,-0.0058,-0.00017,0.018,-0.019,-0.12,-0.17,-0.038,0.46,-0.0013,-0.028,-0.027,0,0,0.00032,0.00039,0.0043,0.11,0.17,0.0072,2.1,2.6,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30690000,0.78,0.0036,-0.0023,-0.63,1.4,1.2,0.84,8.5,6.1,-3.7e+02,-0.0011,-0.0058,-0.00013,0.018,-0.018,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00038,0.0043,0.11,0.18,0.0072,2.1,2.7,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
310 30790000,0.78,0.0031,-0.0023,-0.63,1.4,1.2,0.83,8.6,6.2,-3.7e+02,-0.0011,-0.0058,-0.00017,0.017,-0.018,-0.12,-0.17,-0.038,0.46,-0.0012,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.8,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30790000,0.78,0.0032,-0.0022,-0.63,1.4,1.2,0.83,8.6,6.3,-3.7e+02,-0.0011,-0.0058,-0.00013,0.017,-0.017,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00038,0.0042,0.12,0.18,0.0072,2.1,2.8,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
311 30890000,0.78,0.0027,-0.0022,-0.63,1.4,1.2,0.82,8.8,6.3,-3.7e+02,-0.0011,-0.0058,-0.00018,0.016,-0.016,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.18,0.0072,2.2,2.9,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30890000,0.78,0.0029,-0.0022,-0.63,1.4,1.2,0.82,8.8,6.4,-3.7e+02,-0.0011,-0.0058,-0.00013,0.016,-0.014,-0.12,-0.17,-0.038,0.46,-0.001,-0.028,-0.027,0,0,0.0003,0.00038,0.0042,0.12,0.19,0.0072,2.2,3,0.035,3.2e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1
312 30990000,0.78,0.0023,-0.0022,-0.63,1.3,1.2,0.81,8.9,6.4,-3.7e+02,-0.0011,-0.0058,-0.00018,0.015,-0.012,-0.12,-0.17,-0.038,0.46,-0.0011,-0.028,-0.027,0,0,0.00031,0.00039,0.0042,0.12,0.19,0.0072,2.3,3,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.026,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 30990000,0.78,0.0025,-0.0021,-0.63,1.3,1.2,0.81,8.9,6.5,-3.7e+02,-0.0011,-0.0058,-0.00014,0.015,-0.011,-0.12,-0.17,-0.038,0.46,-0.00097,-0.028,-0.027,0,0,0.0003,0.00038,0.0042,0.12,0.2,0.0071,2.3,3.1,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00043,1,1
313 31090000,0.78,0.0019,-0.0021,-0.63,1.3,1.1,0.8,9,6.6,-3.7e+02,-0.0011,-0.0058,-0.00018,0.014,-0.0094,-0.12,-0.17,-0.038,0.46,-0.00097,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.12,0.2,0.0072,2.4,3.2,0.035,3.2e-07,4.9e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 31090000,0.78,0.002,-0.002,-0.63,1.3,1.2,0.8,9,6.6,-3.7e+02,-0.0011,-0.0058,-0.00014,0.014,-0.0083,-0.12,-0.17,-0.038,0.46,-0.00088,-0.028,-0.027,0,0,0.0003,0.00038,0.0041,0.12,0.2,0.0072,2.4,3.3,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00043,1,1
314 31190000,0.78,0.0016,-0.002,-0.63,1.3,1.1,0.79,9.2,6.7,-3.7e+02,-0.0011,-0.0058,-0.00019,0.012,-0.0056,-0.12,-0.17,-0.038,0.46,-0.00088,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.2,0.0072,2.5,3.3,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 31190000,0.78,0.0018,-0.0019,-0.63,1.3,1.1,0.79,9.2,6.7,-3.7e+02,-0.0011,-0.0058,-0.00014,0.012,-0.0047,-0.12,-0.17,-0.038,0.46,-0.00079,-0.029,-0.027,0,0,0.0003,0.00039,0.0041,0.13,0.21,0.0071,2.5,3.4,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00043,1,1
315 31290000,0.78,0.0012,-0.0018,-0.63,1.2,1.1,0.79,9.3,6.8,-3.7e+02,-0.0011,-0.0058,-0.00019,0.011,-0.0028,-0.12,-0.17,-0.038,0.46,-0.00081,-0.029,-0.027,0,0,0.00031,0.00039,0.0041,0.13,0.21,0.0071,2.6,3.5,0.035,3.2e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00043,1,1 31290000,0.78,0.0013,-0.0017,-0.63,1.2,1.1,0.79,9.3,6.8,-3.7e+02,-0.0011,-0.0058,-0.00014,0.011,-0.0019,-0.12,-0.17,-0.038,0.46,-0.00072,-0.029,-0.027,0,0,0.0003,0.00039,0.0041,0.13,0.22,0.0071,2.6,3.6,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.024,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00043,1,1
316 31390000,0.78,0.00059,-0.0016,-0.63,1.2,1.1,0.79,9.4,6.9,-3.7e+02,-0.0011,-0.0058,-0.00019,0.0099,0.0002,-0.12,-0.17,-0.038,0.46,-0.00074,-0.029,-0.027,0,0,0.0003,0.0004,0.0041,0.13,0.22,0.0071,2.7,3.6,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 31390000,0.78,0.00075,-0.0015,-0.63,1.2,1.1,0.79,9.4,7,-3.7e+02,-0.0011,-0.0058,-0.00014,0.0096,0.001,-0.12,-0.17,-0.038,0.46,-0.00065,-0.029,-0.027,0,0,0.0003,0.00039,0.004,0.13,0.23,0.0071,2.7,3.7,0.035,3.1e-07,5e-07,3.5e-06,0.028,0.024,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00042,1,1
317 31490000,0.78,8.5e-05,-0.0015,-0.63,1.2,1.1,0.79,9.5,7,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0086,0.0029,-0.12,-0.17,-0.038,0.46,-0.00061,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.23,0.0071,2.8,3.8,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.00011,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 31490000,0.78,0.00024,-0.0014,-0.63,1.2,1.1,0.79,9.5,7.1,-3.7e+02,-0.0011,-0.0058,-0.00015,0.0084,0.0036,-0.12,-0.17,-0.038,0.46,-0.00052,-0.029,-0.027,0,0,0.00029,0.00039,0.004,0.13,0.23,0.0071,2.8,3.9,0.035,3.1e-07,5.1e-07,3.5e-06,0.028,0.024,0.0001,0.00036,1.9e-05,0.00043,0.00016,0.00039,0.00042,1,1
318 31590000,0.78,-0.00021,-0.0014,-0.63,1.1,1.1,0.78,9.7,7.1,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0073,0.005,-0.11,-0.17,-0.038,0.46,-0.00056,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.0071,2.9,3.9,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.025,0.0001,0.00036,1.9e-05,0.00043,0.00016,0.0004,0.00042,1,1 31590000,0.78,-6.9e-05,-0.0014,-0.63,1.1,1.1,0.78,9.7,7.2,-3.7e+02,-0.0011,-0.0058,-0.00015,0.0071,0.0057,-0.11,-0.17,-0.038,0.46,-0.00047,-0.029,-0.027,0,0,0.00029,0.00039,0.004,0.14,0.24,0.007,2.9,4.1,0.035,3.1e-07,5.1e-07,3.5e-06,0.028,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
319 31690000,0.78,-0.00082,-0.0013,-0.63,1.1,1.1,0.79,9.8,7.2,-3.7e+02,-0.0011,-0.0058,-0.0002,0.006,0.0077,-0.11,-0.17,-0.038,0.46,-0.00049,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.24,0.007,3,4.1,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 31690000,0.78,-0.00067,-0.0012,-0.63,1.1,1.1,0.79,9.8,7.3,-3.7e+02,-0.0011,-0.0058,-0.00015,0.0058,0.0083,-0.11,-0.17,-0.038,0.46,-0.0004,-0.029,-0.027,0,0,0.00029,0.00039,0.004,0.14,0.25,0.007,3,4.3,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
320 31790000,0.78,-0.0014,-0.0011,-0.63,1.1,1,0.79,9.9,7.3,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0047,0.011,-0.11,-0.17,-0.038,0.46,-0.00042,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.14,0.25,0.007,3.1,4.3,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 31790000,0.78,-0.0013,-0.001,-0.63,1.1,1.1,0.79,9.9,7.4,-3.7e+02,-0.0011,-0.0058,-0.00015,0.0045,0.011,-0.11,-0.17,-0.038,0.46,-0.00034,-0.029,-0.027,0,0,0.00029,0.0004,0.004,0.14,0.26,0.007,3.1,4.4,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
321 31890000,0.78,-0.002,-0.001,-0.63,1.1,1,0.78,10,7.4,-3.7e+02,-0.0011,-0.0058,-0.0002,0.0033,0.014,-0.11,-0.17,-0.038,0.46,-0.00033,-0.029,-0.027,0,0,0.0003,0.0004,0.004,0.15,0.26,0.007,3.2,4.5,0.035,3.1e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 31890000,0.78,-0.0019,-0.00091,-0.63,1.1,1,0.78,10,7.5,-3.7e+02,-0.0011,-0.0058,-0.00016,0.0032,0.014,-0.11,-0.17,-0.038,0.46,-0.00025,-0.029,-0.027,0,0,0.00029,0.0004,0.004,0.14,0.27,0.007,3.2,4.6,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
322 31990000,0.78,-0.0024,-0.0009,-0.63,1,1,0.78,10,7.6,-3.7e+02,-0.0011,-0.0058,-0.00021,0.0018,0.017,-0.11,-0.17,-0.038,0.46,-0.00022,-0.029,-0.027,0,0,0.00029,0.00041,0.004,0.15,0.27,0.007,3.3,4.7,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 31990000,0.78,-0.0022,-0.00081,-0.63,1,1,0.78,10,7.6,-3.7e+02,-0.0012,-0.0058,-0.00016,0.0017,0.018,-0.11,-0.17,-0.038,0.46,-0.00014,-0.029,-0.027,0,0,0.00029,0.0004,0.0039,0.15,0.28,0.0069,3.3,4.8,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
323 32090000,0.78,-0.003,-0.0007,-0.63,1,0.99,0.79,10,7.7,-3.7e+02,-0.0012,-0.0058,-0.00021,0.00019,0.02,-0.11,-0.17,-0.038,0.46,-0.00011,-0.029,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.28,0.007,3.5,4.9,0.035,3e-07,5e-07,3.2e-06,0.029,0.024,0.0001,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 32090000,0.78,-0.0029,-0.00061,-0.63,1,1,0.79,10,7.7,-3.7e+02,-0.0012,-0.0058,-0.00017,0.00018,0.02,-0.11,-0.18,-0.038,0.46,-3.6e-05,-0.029,-0.027,0,0,0.00028,0.0004,0.0039,0.15,0.29,0.0069,3.4,5.1,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,9.9e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
324 32190000,0.78,-0.0038,-0.00051,-0.63,0.97,0.98,0.78,10,7.8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0015,0.024,-0.11,-0.18,-0.038,0.46,3.2e-05,-0.03,-0.027,0,0,0.00029,0.00041,0.0039,0.15,0.29,0.0069,3.6,5.1,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.9e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 32190000,0.78,-0.0037,-0.00041,-0.63,0.97,1,0.78,10,7.8,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.0014,0.024,-0.11,-0.18,-0.038,0.46,0.00011,-0.029,-0.026,0,0,0.00028,0.0004,0.0039,0.15,0.3,0.0069,3.5,5.3,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,9.8e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
325 32290000,0.78,-0.0044,-0.00042,-0.63,0.94,0.96,0.78,11,7.9,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0032,0.028,-0.11,-0.18,-0.038,0.46,0.00014,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.3,0.0069,3.7,5.4,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.8e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 32290000,0.78,-0.0043,-0.00032,-0.63,0.94,0.98,0.78,11,7.9,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.0031,0.028,-0.11,-0.18,-0.038,0.46,0.00021,-0.03,-0.026,0,0,0.00028,0.0004,0.0039,0.16,0.31,0.0068,3.7,5.5,0.035,3e-07,5.1e-07,3.5e-06,0.028,0.023,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
326 32390000,0.78,-0.0049,-0.00032,-0.63,0.91,0.94,0.78,11,8,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0041,0.03,-0.11,-0.18,-0.038,0.46,0.00019,-0.03,-0.026,0,0,0.00029,0.00041,0.0039,0.16,0.31,0.0069,3.8,5.6,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1 32390000,0.78,-0.0048,-0.00023,-0.63,0.91,0.96,0.78,11,8,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.004,0.03,-0.11,-0.18,-0.038,0.46,0.00026,-0.03,-0.026,0,0,0.00028,0.00041,0.0039,0.16,0.32,0.0068,3.8,5.8,0.035,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.7e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00042,1,1
327 32490000,0.78,-0.0051,-0.00027,-0.63,0.88,0.92,0.78,11,8.1,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.0056,0.032,-0.11,-0.18,-0.038,0.46,0.00028,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.16,0.32,0.0068,4,5.8,0.035,3e-07,5e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1 32490000,0.78,-0.005,-0.00017,-0.63,0.88,0.94,0.78,11,8.1,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.0054,0.032,-0.11,-0.18,-0.038,0.46,0.00035,-0.03,-0.026,0,0,0.00028,0.00041,0.0039,0.16,0.33,0.0068,3.9,6,0.035,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1
328 32590000,0.78,-0.0053,-0.00021,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0064,0.033,-0.11,-0.18,-0.038,0.46,0.00034,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.56,0.25,0.25,0.037,3e-07,5.1e-07,3.2e-06,0.029,0.023,9.6e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1 32590000,0.78,-0.0052,-0.00011,-0.63,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0062,0.033,-0.11,-0.18,-0.039,0.46,0.00041,-0.03,-0.026,0,0,0.00028,0.00041,0.0039,0.25,0.25,0.56,0.25,0.25,0.037,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.5e-05,0.00036,1.9e-05,0.00042,0.00016,0.00039,0.00041,1,1
329 32690000,0.78,-0.0053,-0.00025,-0.63,-1.6,-0.85,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0073,0.035,-0.11,-0.18,-0.038,0.46,0.00041,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.25,0.25,0.55,0.26,0.26,0.048,2.9e-07,5.1e-07,3.2e-06,0.029,0.023,9.5e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 32690000,0.78,-0.0052,-0.00014,-0.63,-1.6,-0.85,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0071,0.035,-0.11,-0.18,-0.038,0.46,0.00048,-0.03,-0.026,0,0,0.00027,0.00041,0.0039,0.25,0.25,0.55,0.26,0.26,0.048,2.9e-07,5.1e-07,3.5e-06,0.028,0.022,9.5e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
330 32790000,0.78,-0.0052,-0.00026,-0.63,-1.5,-0.83,0.62,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0081,0.036,-0.11,-0.18,-0.038,0.46,0.00047,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.27,0.26,0.26,0.049,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 32790000,0.78,-0.0051,-0.00016,-0.63,-1.5,-0.83,0.62,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0079,0.036,-0.11,-0.18,-0.038,0.46,0.00053,-0.03,-0.026,0,0,0.00027,0.00041,0.0039,0.13,0.13,0.27,0.26,0.26,0.048,2.9e-07,5.2e-07,3.5e-06,0.028,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
331 32890000,0.78,-0.005,-0.00039,-0.63,-1.6,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00024,-0.0089,0.038,-0.11,-0.18,-0.038,0.46,0.00057,-0.03,-0.026,0,0,0.00028,0.00042,0.0039,0.13,0.13,0.26,0.27,0.27,0.059,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 32890000,0.78,-0.0049,-0.00028,-0.63,-1.6,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.0002,-0.0086,0.038,-0.11,-0.18,-0.039,0.46,0.00063,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.13,0.13,0.26,0.27,0.27,0.059,2.9e-07,5.2e-07,3.5e-06,0.028,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
332 32990000,0.78,-0.0049,-0.0005,-0.63,-1.5,-0.84,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.0098,0.04,-0.11,-0.18,-0.038,0.46,0.00059,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.085,0.17,0.27,0.27,0.057,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 32990000,0.78,-0.0048,-0.0004,-0.63,-1.5,-0.84,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0095,0.039,-0.11,-0.18,-0.038,0.46,0.00066,-0.03,-0.025,0,0,0.00027,0.00042,0.0038,0.084,0.085,0.17,0.27,0.27,0.057,2.9e-07,5.2e-07,3.5e-06,0.028,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
333 33090000,0.78,-0.005,-0.00048,-0.63,-1.6,-0.86,0.58,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.038,0.46,0.00061,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.084,0.086,0.16,0.28,0.28,0.065,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.4e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 33090000,0.78,-0.0049,-0.00037,-0.63,-1.6,-0.86,0.58,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0099,0.04,-0.11,-0.18,-0.038,0.46,0.00067,-0.03,-0.025,0,0,0.00027,0.00042,0.0038,0.084,0.086,0.16,0.28,0.28,0.065,2.9e-07,5.2e-07,3.5e-06,0.028,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
334 33190000,0.78,-0.0036,-0.0037,-0.62,-1.5,-0.84,0.53,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.01,0.041,-0.11,-0.18,-0.038,0.46,0.0006,-0.03,-0.025,0,0,0.00028,0.00042,0.0038,0.063,0.065,0.11,0.28,0.28,0.062,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 33190000,0.78,-0.0035,-0.0036,-0.62,-1.5,-0.84,0.53,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.01,0.04,-0.11,-0.18,-0.038,0.46,0.00067,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,5.1e-07,3.5e-06,0.028,0.022,9.3e-05,0.00036,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1
335 33290000,0.82,-0.0015,-0.016,-0.57,-1.5,-0.86,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.01,0.04,-0.11,-0.18,-0.039,0.46,0.00058,-0.03,-0.025,0,0,0.00027,0.00042,0.0038,0.064,0.066,0.11,0.29,0.29,0.067,2.9e-07,5.1e-07,3.2e-06,0.029,0.022,9.3e-05,0.00035,1.9e-05,0.00041,0.00016,0.00039,0.00041,1,1 33290000,0.82,-0.0014,-0.015,-0.57,-1.5,-0.86,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00019,-0.0098,0.04,-0.11,-0.18,-0.039,0.46,0.00065,-0.03,-0.025,0,0,0.00027,0.00041,0.0038,0.064,0.066,0.11,0.29,0.29,0.067,2.8e-07,5.2e-07,3.5e-06,0.028,0.021,9.3e-05,0.00035,1.9e-05,0.00041,0.00015,0.00039,0.00041,1,1
336 33390000,0.89,-0.0018,-0.013,-0.46,-1.5,-0.85,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.015,0.038,-0.11,-0.18,-0.039,0.46,0.0012,-0.028,-0.025,0,0,0.00028,0.0004,0.0037,0.051,0.053,0.083,0.29,0.29,0.065,2.9e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00033,1.7e-05,0.00041,0.00015,0.00035,0.00041,1,1 33390000,0.89,-0.0017,-0.013,-0.46,-1.5,-0.85,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00018,-0.015,0.037,-0.11,-0.18,-0.039,0.46,0.0012,-0.028,-0.025,0,0,0.00028,0.0004,0.0037,0.051,0.053,0.083,0.29,0.29,0.065,2.8e-07,5.1e-07,3.4e-06,0.027,0.021,9.3e-05,0.00033,1.7e-05,0.00041,0.00015,0.00035,0.00041,1,1
337 33490000,0.95,-0.00026,-0.0052,-0.31,-1.5,-0.86,0.72,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00023,-0.018,0.037,-0.11,-0.18,-0.04,0.46,0.0017,-0.02,-0.025,0,0,0.00031,0.00036,0.0034,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,5e-07,3.2e-06,0.028,0.022,9.3e-05,0.00025,1.4e-05,0.00041,0.00013,0.00026,0.00041,1,1 33490000,0.95,-0.00015,-0.0052,-0.31,-1.5,-0.86,0.72,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.017,0.037,-0.11,-0.18,-0.04,0.46,0.0018,-0.02,-0.025,0,0,0.00031,0.00036,0.0034,0.052,0.055,0.075,0.3,0.3,0.068,2.8e-07,5.1e-07,3.4e-06,0.027,0.021,9.3e-05,0.00025,1.4e-05,0.00041,0.00013,0.00026,0.00041,1,1
338 33590000,0.99,-0.003,0.0015,-0.14,-1.5,-0.84,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.0002,-0.018,0.037,-0.11,-0.19,-0.042,0.46,0.0025,-0.013,-0.026,0,0,0.00035,0.00031,0.003,0.044,0.047,0.061,0.3,0.3,0.065,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00017,1e-05,0.00041,9.5e-05,0.00016,0.0004,1,1 33590000,0.99,-0.0028,0.0015,-0.14,-1.5,-0.84,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.017,0.037,-0.11,-0.19,-0.042,0.46,0.0026,-0.013,-0.026,0,0,0.00034,0.00031,0.0029,0.044,0.047,0.061,0.3,0.3,0.065,2.8e-07,5.1e-07,3.4e-06,0.027,0.021,9.3e-05,0.00017,9.9e-06,0.00041,9.4e-05,0.00016,0.0004,1,1
339 33690000,1,-0.0064,0.005,0.024,-1.6,-0.86,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00022,-0.018,0.037,-0.11,-0.19,-0.043,0.46,0.0018,-0.0093,-0.026,0,0,0.00037,0.00028,0.0026,0.045,0.05,0.056,0.31,0.31,0.068,2.8e-07,5e-07,3.1e-06,0.028,0.022,9.3e-05,0.00013,7.8e-06,0.0004,6.9e-05,0.0001,0.0004,1,1 33690000,1,-0.0063,0.005,0.024,-1.6,-0.86,0.69,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00018,-0.017,0.037,-0.11,-0.19,-0.043,0.46,0.0018,-0.0093,-0.026,0,0,0.00037,0.00027,0.0026,0.045,0.05,0.056,0.31,0.31,0.068,2.8e-07,5.1e-07,3.3e-06,0.027,0.021,9.3e-05,0.00013,7.8e-06,0.0004,6.9e-05,0.0001,0.0004,1,1
340 33790000,0.98,-0.0073,0.0069,0.19,-1.6,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.002,-0.0068,-0.027,0,0,0.00037,0.00026,0.0023,0.04,0.045,0.047,0.31,0.31,0.064,2.8e-07,4.9e-07,3.1e-06,0.028,0.022,9.3e-05,9.7e-05,6.4e-06,0.0004,4.8e-05,6.3e-05,0.0004,1,1 33790000,0.98,-0.0072,0.0069,0.19,-1.6,-0.86,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.017,0.037,-0.11,-0.2,-0.043,0.46,0.002,-0.0067,-0.027,0,0,0.00037,0.00025,0.0023,0.04,0.045,0.047,0.31,0.31,0.064,2.8e-07,5e-07,3.3e-06,0.027,0.021,9.3e-05,9.6e-05,6.3e-06,0.0004,4.8e-05,6.3e-05,0.0004,1,1
341 33890000,0.94,-0.0075,0.0082,0.35,-1.7,-0.9,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.018,0.037,-0.11,-0.2,-0.043,0.46,0.0019,-0.0054,-0.027,0,0,0.00036,0.00026,0.0022,0.044,0.051,0.043,0.32,0.32,0.065,2.8e-07,4.9e-07,3e-06,0.028,0.022,9.3e-05,8.1e-05,5.6e-06,0.0004,3.4e-05,4.2e-05,0.0004,1,1 33890000,0.94,-0.0075,0.0081,0.35,-1.7,-0.9,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.017,0.037,-0.11,-0.2,-0.043,0.46,0.0019,-0.0054,-0.027,0,0,0.00036,0.00026,0.0022,0.044,0.051,0.043,0.32,0.32,0.065,2.8e-07,5e-07,3.3e-06,0.027,0.021,9.3e-05,8e-05,5.6e-06,0.0004,3.4e-05,4.2e-05,0.0004,1,1
342 33990000,0.87,-0.0095,0.0057,0.49,-1.7,-0.91,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.015,0.036,-0.11,-0.2,-0.044,0.46,0.0017,-0.004,-0.027,0,0,0.00032,0.00027,0.002,0.041,0.049,0.036,0.32,0.32,0.062,2.8e-07,4.8e-07,3e-06,0.028,0.022,9.3e-05,7.1e-05,5.1e-06,0.0004,2.6e-05,3e-05,0.0004,1,1 33990000,0.87,-0.0095,0.0056,0.49,-1.7,-0.91,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.015,0.036,-0.11,-0.2,-0.044,0.46,0.0017,-0.004,-0.027,0,0,0.00032,0.00026,0.002,0.041,0.049,0.036,0.32,0.32,0.062,2.8e-07,4.9e-07,3.3e-06,0.027,0.021,9.3e-05,7e-05,5.1e-06,0.0004,2.6e-05,3e-05,0.0004,1,1
343 34090000,0.81,-0.011,0.0044,0.59,-1.7,-0.97,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.01,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0034,-0.027,0,0,0.0003,0.00028,0.002,0.047,0.057,0.034,0.33,0.33,0.063,2.8e-07,4.9e-07,3e-06,0.027,0.022,9.3e-05,6.6e-05,4.9e-06,0.0004,2.1e-05,2.4e-05,0.0004,1,1 34090000,0.81,-0.011,0.0043,0.59,-1.7,-0.97,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00017,-0.0095,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0034,-0.027,0,0,0.0003,0.00028,0.002,0.047,0.057,0.033,0.33,0.33,0.063,2.8e-07,4.9e-07,3.2e-06,0.026,0.021,9.3e-05,6.5e-05,4.8e-06,0.0004,2.1e-05,2.4e-05,0.0004,1,1
344 34190000,0.76,-0.0081,0.0029,0.65,-1.7,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.039,0.052,-0.11,-0.2,-0.044,0.46,0.0012,-0.0028,-0.027,0,0,0.00026,0.00028,0.0018,0.045,0.054,0.029,0.33,0.33,0.06,2.8e-07,4.7e-07,3e-06,0.026,0.021,9.3e-05,6e-05,4.6e-06,0.0004,1.7e-05,1.9e-05,0.0004,1,1 34190000,0.76,-0.0081,0.0029,0.65,-1.7,-0.97,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00016,-0.038,0.052,-0.11,-0.2,-0.044,0.46,0.0012,-0.0028,-0.027,0,0,0.00026,0.00027,0.0018,0.045,0.054,0.029,0.33,0.33,0.06,2.8e-07,4.8e-07,3.2e-06,0.025,0.02,9.2e-05,5.9e-05,4.5e-06,0.0004,1.7e-05,1.9e-05,0.0004,1,1
345 34290000,0.72,-0.0052,0.0041,0.69,-1.7,-1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.038,0.051,-0.11,-0.2,-0.044,0.46,0.0011,-0.0024,-0.027,0,0,0.00025,0.00029,0.0018,0.053,0.064,0.027,0.34,0.34,0.06,2.8e-07,4.7e-07,3e-06,0.025,0.021,9.3e-05,5.7e-05,4.5e-06,0.0004,1.4e-05,1.6e-05,0.0004,1,1 34290000,0.72,-0.0052,0.0041,0.69,-1.7,-1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00016,-0.037,0.05,-0.11,-0.2,-0.044,0.46,0.0011,-0.0024,-0.027,0,0,0.00025,0.00028,0.0018,0.053,0.064,0.027,0.34,0.34,0.06,2.8e-07,4.8e-07,3.2e-06,0.025,0.02,9.2e-05,5.6e-05,4.4e-06,0.0004,1.5e-05,1.6e-05,0.0004,1,1
346 34390000,0.7,-0.0024,0.0054,0.71,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.036,0.05,-0.11,-0.2,-0.044,0.46,0.00092,-0.0022,-0.027,0,0,0.00025,0.00029,0.0018,0.062,0.075,0.025,0.35,0.35,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.5e-05,4.4e-06,0.0004,1.3e-05,1.4e-05,0.0004,1,1 34390000,0.7,-0.0024,0.0054,0.71,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.036,0.049,-0.11,-0.2,-0.044,0.46,0.00092,-0.0022,-0.027,0,0,0.00024,0.00029,0.0018,0.062,0.075,0.025,0.35,0.35,0.06,2.8e-07,4.8e-07,3.2e-06,0.024,0.02,9.2e-05,5.4e-05,4.3e-06,0.0004,1.3e-05,1.4e-05,0.0004,1,1
347 34490000,0.69,-0.00036,0.0066,0.73,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.049,-0.11,-0.2,-0.044,0.46,0.0008,-0.0021,-0.027,0,0,0.00024,0.0003,0.0017,0.073,0.088,0.023,0.36,0.36,0.06,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.4e-05,4.3e-06,0.0004,1.1e-05,1.2e-05,0.0004,1,1 34490000,0.69,-0.00035,0.0065,0.73,-1.8,-1.1,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.035,0.049,-0.11,-0.2,-0.044,0.46,0.0008,-0.0021,-0.027,0,0,0.00024,0.0003,0.0017,0.072,0.088,0.023,0.36,0.36,0.06,2.8e-07,4.8e-07,3.2e-06,0.024,0.02,9.3e-05,5.3e-05,4.2e-06,0.0004,1.1e-05,1.2e-05,0.0004,1,1
348 34590000,0.68,0.00092,0.0074,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.05,-0.11,-0.2,-0.044,0.46,0.00064,-0.002,-0.027,0,0,0.00024,0.0003,0.0017,0.085,0.1,0.021,0.38,0.38,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.2e-05,4.3e-06,0.0004,1e-05,1.1e-05,0.0004,1,1 34590000,0.68,0.00093,0.0074,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.033,0.049,-0.11,-0.2,-0.044,0.46,0.00064,-0.002,-0.027,0,0,0.00024,0.0003,0.0017,0.084,0.1,0.021,0.38,0.38,0.059,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,1e-05,1.1e-05,0.0004,1,1
349 34690000,0.67,0.0017,0.0079,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.034,0.049,-0.11,-0.2,-0.044,0.46,0.00068,-0.0018,-0.027,0,0,0.00024,0.0003,0.0017,0.098,0.12,0.019,0.39,0.4,0.059,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,9.6e-06,1e-05,0.0004,1,1 34690000,0.67,0.0018,0.0078,0.74,-1.9,-1.2,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.034,0.048,-0.11,-0.2,-0.044,0.46,0.00068,-0.0018,-0.027,0,0,0.00023,0.0003,0.0017,0.097,0.12,0.019,0.39,0.4,0.059,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,5.1e-05,4.1e-06,0.0004,9.7e-06,1e-05,0.0004,1,1
350 34790000,0.67,0.0024,0.0081,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.036,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00024,0.0003,0.0017,0.11,0.14,0.018,0.41,0.42,0.058,2.8e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5.1e-05,4.2e-06,0.0004,8.9e-06,9.2e-06,0.0004,1,1 34790000,0.67,0.0024,0.0081,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00014,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.11,0.14,0.018,0.41,0.42,0.058,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,5e-05,4.1e-06,0.0004,9e-06,9.2e-06,0.0004,1,1
351 34890000,0.66,0.0025,0.0082,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00069,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.13,0.16,0.017,0.43,0.44,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,5e-05,4.1e-06,0.0004,8.4e-06,8.5e-06,0.0004,1,1 34890000,0.66,0.0025,0.0081,0.75,-2,-1.3,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00014,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00069,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.13,0.16,0.017,0.43,0.44,0.056,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,8.4e-06,8.5e-06,0.0004,1,1
352 34990000,0.66,-0.00086,0.016,0.75,-3,-2.2,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00079,-0.0017,-0.027,0,0,0.00024,0.00031,0.0017,0.16,0.22,0.016,0.46,0.47,0.056,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.9e-06,8e-06,0.0004,1,1 34990000,0.66,-0.00085,0.015,0.75,-3,-2.2,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00014,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00079,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.16,0.22,0.016,0.46,0.47,0.056,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.8e-05,4e-06,0.0004,8e-06,8e-06,0.0004,1,1
353 35090000,0.66,-0.00092,0.016,0.75,-3.1,-2.3,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00078,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.18,0.25,0.015,0.49,0.51,0.055,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.9e-05,4.1e-06,0.0004,7.5e-06,7.5e-06,0.0004,1,1 35090000,0.66,-0.00091,0.016,0.75,-3.1,-2.3,-0.2,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00079,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.18,0.25,0.015,0.49,0.51,0.055,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.8e-05,4e-06,0.0004,7.6e-06,7.5e-06,0.0004,1,1
354 35190000,0.66,-0.001,0.015,0.75,-3.1,-2.3,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00081,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.2,0.28,0.014,0.52,0.55,0.054,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,7.2e-06,7.1e-06,0.0004,1,1 35190000,0.66,-0.001,0.015,0.75,-3.1,-2.3,-0.19,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.006,-0.00015,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00081,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.2,0.27,0.014,0.52,0.55,0.054,2.8e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.7e-05,4e-06,0.0004,7.2e-06,7.1e-06,0.0004,1,1
355 35290000,0.66,-0.0012,0.015,0.75,-3.2,-2.3,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00084,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.23,0.31,0.013,0.56,0.6,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.8e-05,4e-06,0.0004,6.9e-06,6.7e-06,0.0004,1,1 35290000,0.66,-0.0011,0.015,0.75,-3.2,-2.3,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00015,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00085,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.22,0.3,0.013,0.56,0.6,0.052,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.9e-06,6.7e-06,0.0004,1,1
356 35390000,0.66,-0.0011,0.015,0.75,-3.2,-2.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00091,-0.0017,-0.027,0,0,0.00023,0.00031,0.0017,0.25,0.34,0.013,0.61,0.66,0.052,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.6e-06,6.4e-06,0.0004,1,1 35390000,0.66,-0.0011,0.015,0.75,-3.2,-2.4,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00015,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00091,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.25,0.33,0.013,0.61,0.66,0.052,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.7e-06,6.4e-06,0.0004,1,1
357 35490000,0.66,-0.0012,0.016,0.75,-3.2,-2.4,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.28,0.37,0.012,0.66,0.73,0.051,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.7e-05,4e-06,0.0004,6.4e-06,6.2e-06,0.0004,1,1 35490000,0.66,-0.0012,0.015,0.75,-3.2,-2.4,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.27,0.37,0.012,0.66,0.73,0.051,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.5e-06,6.1e-06,0.0004,1,1
358 35590000,0.66,-0.0012,0.016,0.75,-3.3,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.047,-0.11,-0.2,-0.044,0.46,0.00092,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.31,0.4,0.011,0.72,0.81,0.05,2.9e-07,4.8e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,4e-06,0.0004,6.2e-06,5.9e-06,0.0004,1,1 35590000,0.66,-0.0012,0.015,0.75,-3.3,-2.5,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00015,-0.034,0.046,-0.11,-0.2,-0.044,0.46,0.00093,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.3,0.4,0.011,0.72,0.81,0.05,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,6.3e-06,5.9e-06,0.0004,1,1
359 35690000,0.66,-0.0011,0.016,0.75,-3.3,-2.5,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.046,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.33,0.44,0.011,0.79,0.9,0.049,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,6.1e-06,5.7e-06,0.0004,1,1 35690000,0.66,-0.0011,0.016,0.75,-3.3,-2.5,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.33,0.44,0.011,0.78,0.89,0.049,2.9e-07,4.9e-07,3.2e-06,0.024,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,6.1e-06,5.7e-06,0.0004,1,1
360 35790000,0.66,-0.0012,0.016,0.75,-3.3,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00023,0.0003,0.0017,0.36,0.48,0.01,0.86,1,0.048,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.6e-05,3.9e-06,0.0004,5.9e-06,5.5e-06,0.0004,1,1 35790000,0.66,-0.0012,0.016,0.75,-3.3,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.36,0.47,0.01,0.86,0.99,0.048,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.5e-05,3.9e-06,0.0004,5.9e-06,5.5e-06,0.0004,1,1
361 35890000,0.66,-0.0013,0.016,0.75,-3.4,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.035,0.045,-0.11,-0.2,-0.044,0.46,0.00098,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.4,0.52,0.01,0.95,1.1,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.3e-05,4.5e-05,3.9e-06,0.0004,5.7e-06,5.3e-06,0.0004,1,1 35890000,0.66,-0.0012,0.016,0.75,-3.4,-2.6,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.034,0.045,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.39,0.51,0.0099,0.94,1.1,0.047,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.8e-06,5.3e-06,0.0004,1,1
362 35990000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.045,-0.11,-0.2,-0.044,0.46,0.00094,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.43,0.56,0.0097,1,1.2,0.047,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.6e-06,5.1e-06,0.0004,1,1 35990000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.034,0.044,-0.11,-0.2,-0.044,0.46,0.00095,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.42,0.55,0.0096,1,1.2,0.047,2.9e-07,4.9e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.7e-06,5.1e-06,0.0004,1,1
363 36090000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.034,0.044,-0.11,-0.2,-0.044,0.46,0.00096,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.46,0.6,0.0093,1.2,1.4,0.046,2.9e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.5e-05,3.9e-06,0.0004,5.5e-06,5e-06,0.0004,1,1 36090000,0.66,-0.0013,0.016,0.75,-3.4,-2.7,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00016,-0.033,0.044,-0.11,-0.2,-0.044,0.46,0.00097,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.46,0.59,0.0093,1.1,1.4,0.046,2.9e-07,5e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.6e-06,5e-06,0.0004,1,1
364 36190000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.034,0.043,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.5,0.65,0.009,1.3,1.5,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.4e-06,4.8e-06,0.0004,1,1 36190000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00018,-0.034,0.043,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.49,0.64,0.009,1.3,1.5,0.045,2.9e-07,5e-07,3.2e-06,0.024,0.019,9.3e-05,4.4e-05,3.8e-06,0.0004,5.5e-06,4.8e-06,0.0004,1,1
365 36290000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.0003,0.0017,0.53,0.69,0.0088,1.4,1.7,0.045,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.3e-06,4.7e-06,0.0004,1,1 36290000,0.66,-0.0013,0.016,0.75,-3.5,-2.8,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00018,-0.033,0.041,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.53,0.68,0.0088,1.4,1.7,0.045,2.9e-07,5e-07,3.2e-06,0.024,0.019,9.3e-05,4.3e-05,3.8e-06,0.0004,5.4e-06,4.7e-06,0.0004,1,1
366 36390000,0.66,-0.0013,0.016,0.75,-3.5,-2.9,-0.097,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.033,0.042,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.57,0.74,0.0086,1.6,1.9,0.044,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.4e-05,3.8e-06,0.0004,5.2e-06,4.6e-06,0.0004,1,1 36390000,0.66,-0.0013,0.016,0.75,-3.5,-2.9,-0.097,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00018,-0.033,0.041,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.56,0.73,0.0085,1.5,1.9,0.044,2.9e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.3e-05,3.8e-06,0.00039,5.3e-06,4.6e-06,0.0004,1,1
367 36490000,0.66,-0.0014,0.016,0.75,-3.6,-2.9,-0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.032,0.041,-0.11,-0.2,-0.044,0.46,0.00099,-0.0017,-0.027,0,0,0.00022,0.00029,0.0017,0.61,0.79,0.0083,1.7,2.1,0.043,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.0004,5.2e-06,4.5e-06,0.0004,1,1 36490000,0.66,-0.0014,0.016,0.75,-3.6,-2.9,-0.09,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00017,-0.032,0.041,-0.11,-0.2,-0.044,0.46,0.001,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.6,0.78,0.0083,1.7,2.1,0.043,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.3e-05,3.7e-06,0.00039,5.2e-06,4.5e-06,0.0004,1,1
368 36590000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.08,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.032,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.65,0.84,0.0082,1.9,2.4,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5.1e-06,4.4e-06,0.0004,1,1 36590000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.08,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00018,-0.032,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.64,0.83,0.0081,1.9,2.4,0.042,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5.1e-06,4.3e-06,0.0004,1,1
369 36690000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.031,0.04,-0.11,-0.2,-0.044,0.46,0.001,-0.0016,-0.027,0,0,0.00022,0.00029,0.0017,0.69,0.89,0.0081,2.1,2.6,0.042,3e-07,4.9e-07,3e-06,0.025,0.02,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.3e-06,0.0004,1,1 36690000,0.66,-0.0014,0.016,0.75,-3.6,-3,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00019,-0.031,0.04,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.68,0.88,0.008,2.1,2.6,0.042,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5.1e-06,4.3e-06,0.0004,1,1
370 36790000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00024,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.74,0.94,0.0079,2.3,2.9,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.3e-05,3.8e-06,0.00039,5e-06,4.2e-06,0.0004,1,1 36790000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0002,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.72,0.93,0.0079,2.3,2.9,0.041,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5e-06,4.2e-06,0.0004,1,1
371 36890000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0017,-0.027,0,0,0.00021,0.00029,0.0017,0.78,1,0.0078,2.6,3.2,0.041,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4.1e-06,0.0004,1,1 36890000,0.66,-0.0014,0.016,0.75,-3.7,-3.1,-0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.031,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.77,0.98,0.0078,2.5,3.2,0.041,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,5e-06,4.1e-06,0.0004,1,1
372 36990000,0.66,-0.0014,0.016,0.75,-3.7,-3.2,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.038,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.82,1.1,0.0077,2.8,3.6,0.04,3e-07,4.9e-07,3e-06,0.025,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.9e-06,4e-06,0.0004,1,1 36990000,0.66,-0.0014,0.016,0.75,-3.7,-3.2,-0.049,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.03,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.81,1,0.0077,2.8,3.6,0.04,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.9e-06,4e-06,0.0004,1,1
373 37090000,0.66,-0.0014,0.016,0.75,-3.8,-3.2,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.03,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.87,1.1,0.0076,3.1,4,0.04,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1 37090000,0.66,-0.0014,0.016,0.75,-3.8,-3.2,-0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.03,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.86,1.1,0.0076,3.1,3.9,0.04,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.9e-06,3.9e-06,0.0004,1,1
374 37190000,0.66,-0.0014,0.016,0.75,-3.8,-3.3,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00029,0.0017,0.92,1.2,0.0076,3.4,4.4,0.039,3e-07,4.9e-07,3e-06,0.024,0.019,9.4e-05,4.2e-05,3.7e-06,0.00039,4.8e-06,3.9e-06,0.0004,1,1 37190000,0.66,-0.0015,0.016,0.75,-3.8,-3.3,-0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00021,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.9,1.2,0.0075,3.4,4.3,0.039,3e-07,5e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.8e-06,3.8e-06,0.0004,1,1
375 37290000,0.66,-0.0015,0.017,0.75,-3.8,-3.3,-0.026,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.97,1.2,0.0075,3.7,4.8,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.4e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.8e-06,0.0004,1,1 37290000,0.66,-0.0015,0.016,0.75,-3.8,-3.3,-0.026,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00022,-0.029,0.037,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,0.95,1.2,0.0075,3.7,4.8,0.039,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.6e-06,0.00039,4.8e-06,3.8e-06,0.0004,1,1
376 37390000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.029,0.036,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.00021,0.00028,0.0017,1,1.3,0.0075,4.1,5.3,0.039,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1 37390000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.019,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00023,-0.029,0.036,-0.11,-0.2,-0.044,0.46,0.0011,-0.0016,-0.027,0,0,0.0002,0.00028,0.0017,1,1.3,0.0074,4,5.2,0.039,3e-07,4.9e-07,3.2e-06,0.024,0.019,9.4e-05,4.1e-05,3.6e-06,0.00039,4.8e-06,3.7e-06,0.0004,1,1
377 37490000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.011,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.029,0.035,-0.11,-0.2,-0.044,0.46,0.0011,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.4,5.8,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1 37490000,0.66,-0.0014,0.017,0.75,-3.9,-3.4,-0.012,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00024,-0.029,0.035,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1,1.3,0.0074,4.4,5.7,0.038,3e-07,4.9e-07,3.1e-06,0.024,0.019,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.7e-06,0.0004,1,1
378 37590000,0.66,-0.0014,0.017,0.75,-3.9,-3.5,-0.0032,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.028,0.034,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.1,1.4,0.0074,4.9,6.3,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.7e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1 37590000,0.66,-0.0014,0.017,0.75,-3.9,-3.5,-0.0033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.028,0.034,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.1,1.4,0.0074,4.8,6.3,0.038,3e-07,4.9e-07,3.1e-06,0.024,0.018,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.6e-06,0.0004,1,1
379 37690000,0.66,-0.0015,0.017,0.75,-4,-3.5,0.0061,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.033,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00021,0.00028,0.0017,1.2,1.5,0.0074,5.3,6.9,0.038,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4.1e-05,3.6e-06,0.00039,4.6e-06,3.6e-06,0.0004,1,1 37690000,0.66,-0.0015,0.017,0.75,-4,-3.5,0.0059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00025,-0.027,0.033,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.1,1.5,0.0074,5.2,6.8,0.038,3.1e-07,4.9e-07,3.1e-06,0.024,0.018,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.5e-06,0.0004,1,1
380 37790000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.2,1.5,0.0074,5.8,7.5,0.037,3.1e-07,4.9e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.5e-06,0.0004,1,1 37790000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0017,1.2,1.5,0.0073,5.7,7.4,0.037,3.1e-07,4.9e-07,3.1e-06,0.024,0.018,9.4e-05,4e-05,3.6e-06,0.00039,4.7e-06,3.5e-06,0.0004,1,1
381 37890000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.022,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.6,0.0074,6.3,8.2,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 37890000,0.66,-0.0016,0.017,0.75,-4,-3.6,0.022,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.027,0.032,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0017,1.3,1.6,0.0073,6.2,8.1,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1
382 37990000,0.66,-0.0016,0.017,0.75,-4.1,-3.7,0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.026,0.031,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00028,0.0017,1.3,1.7,0.0074,6.8,8.9,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1 37990000,0.66,-0.0016,0.017,0.75,-4.1,-3.7,0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00026,-0.026,0.031,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0017,1.3,1.7,0.0074,6.7,8.8,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1
383 38090000,0.66,-0.0017,0.017,0.75,-4.1,-3.8,0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.7,0.0074,7.4,9.6,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,4e-05,3.6e-06,0.00039,4.5e-06,3.4e-06,0.0004,1,1 38090000,0.66,-0.0017,0.017,0.75,-4.1,-3.8,0.041,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0017,1.4,1.7,0.0073,7.3,9.5,0.037,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.6e-06,3.4e-06,0.0004,1,1
384 38190000,0.66,-0.0016,0.017,0.75,-4.2,-3.8,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.8,0.0074,8,10,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.5e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1 38190000,0.66,-0.0017,0.017,0.75,-4.2,-3.8,0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.025,0.03,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.4,1.8,0.0073,7.9,10,0.036,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.6e-06,3.3e-06,0.0004,1,1
385 38290000,0.66,-0.0017,0.017,0.75,-4.2,-3.9,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,8.6,11,0.037,3.1e-07,4.8e-07,2.9e-06,0.024,0.019,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.3e-06,0.0004,1,1 38290000,0.66,-0.0017,0.017,0.75,-4.2,-3.9,0.056,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,8.5,11,0.036,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.6e-06,3.3e-06,0.0004,1,1
386 38390000,0.66,-0.0016,0.017,0.75,-4.2,-3.9,0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,9.3,12,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.6e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 38390000,0.66,-0.0016,0.017,0.75,-4.2,-3.9,0.063,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.024,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.5,1.9,0.0074,9.2,12,0.036,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.6e-06,3.2e-06,0.0004,1,1
387 38490000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.07,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.6,2,0.0074,10,13,0.036,3.1e-07,4.8e-07,2.9e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 38490000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.069,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.6,2,0.0074,9.9,13,0.036,3.1e-07,4.9e-07,3.1e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.6e-06,3.2e-06,0.0004,1,1
388 38590000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.076,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.0003,-0.024,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.1,0.0075,11,14,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.9e-05,3.5e-06,0.00039,4.5e-06,3.2e-06,0.0004,1,1 38590000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.076,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00027,-0.024,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.7,2.1,0.0074,11,14,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.6e-06,3.2e-06,0.0004,1,1
389 38690000,0.66,-0.0016,0.017,0.75,-4.3,-4.1,0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.0002,0.00027,0.0016,1.7,2.2,0.0075,12,15,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1 38690000,0.66,-0.0016,0.017,0.75,-4.3,-4,0.082,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00028,-0.025,0.029,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.00019,0.00026,0.0016,1.7,2.1,0.0074,11,15,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1
390 38790000,0.66,-0.0016,0.017,0.75,-4.4,-4.1,0.089,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.0002,0.00026,0.0016,1.8,2.3,0.0075,12,16,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1 38790000,0.66,-0.0016,0.017,0.75,-4.4,-4.1,0.089,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0014,-0.027,0,0,0.00019,0.00026,0.0016,1.8,2.2,0.0075,12,16,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.7e-05,3.5e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1
391 38890000,0.66,-0.0017,0.017,0.75,-4.4,-4.1,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0058,-0.00031,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.9,2.3,0.0075,13,17,0.036,3.2e-07,4.8e-07,2.8e-06,0.024,0.018,9.4e-05,3.8e-05,3.5e-06,0.00039,4.4e-06,3.1e-06,0.0004,1,1 38890000,0.66,-0.0017,0.017,0.75,-4.4,-4.1,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0059,-0.00029,-0.025,0.028,-0.11,-0.2,-0.044,0.46,0.0012,-0.0015,-0.027,0,0,0.00019,0.00026,0.0016,1.8,2.3,0.0075,13,17,0.036,3.1e-07,4.8e-07,3e-06,0.023,0.018,9.4e-05,3.7e-05,3.4e-06,0.00039,4.5e-06,3.1e-06,0.0004,1,1

View File

@ -1,351 +1,351 @@
Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00094,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00054,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,5e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00066,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.9e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.7e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00056,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00049,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.3e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.3e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-7.7e-08,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3.3e-08,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00039,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-7e-09,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.1e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00035,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00039,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-7.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-7.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.3e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2490000,1,-0.011,-0.014,0.00047,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.3e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-1.9e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-1.8e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2790000,1,-0.01,-0.013,0.00037,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2990000,1,-0.01,-0.013,0.00031,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-2.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-2.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3190000,1,-0.01,-0.013,0.00056,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.2e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0088,0.0088,0.00021,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,3.4e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.2e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,3.4e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,2.9e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3490000,1,-0.0097,-0.013,0.00058,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,2.9e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.007,0.0071,0.00018,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,2.5e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3690000,1,-0.0095,-0.013,0.00052,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,2.5e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.3e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00017,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3890000,1,-0.0094,-0.013,0.00063,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,2.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4090000,1,-0.0093,-0.012,0.00076,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-4.8e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1.9e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-4.8e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00018,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1.9e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4290000,1,-0.0095,-0.012,0.00074,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.3e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,1.7e-05,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.2e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,1.7e-05,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4490000,1,-0.0094,-0.012,0.00076,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-5.7e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,1.5e-05,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-5.7e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00016,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,1.5e-05,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4690000,1,-0.0094,-0.012,0.00076,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.1e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,1.3e-05,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4790000,1,-0.0093,-0.012,0.00086,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.1e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,1.3e-05,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4890000,1,-0.0092,-0.012,0.0009,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-6.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-6.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5090000,1,-0.0091,-0.011,0.00096,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-6.8e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-6.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.3e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,9.3e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00013,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.4e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5590000,1,-0.0088,-0.012,0.00099,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.4e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5690000,1,-0.0089,-0.011,0.00089,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.6e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5790000,1,-0.0088,-0.011,0.00085,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.6e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5890000,1,-0.0088,-0.011,0.00088,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5990000,1,-0.0088,-0.012,0.00086,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6090000,1,-0.0088,-0.011,0.00067,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6190000,1,-0.0089,-0.011,0.00068,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6290000,1,-0.0089,-0.011,0.00071,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6390000,1,-0.0089,-0.011,0.00072,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,5.8e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,5.8e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6590000,1,-0.009,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6690000,1,-0.0089,-0.011,0.0005,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6790000,1,-0.009,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,0.00011,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6890000,1,-0.0088,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6990000,-0.29,0.024,-0.0065,0.96,-0.0055,0.0091,-0.037,0.0023,0.0053,-0.055,-0.0016,-0.0056,-8.7e-05,0,0,-0.13,-0.092,-0.02,0.51,0.069,-0.028,-0.058,0,0,0.0012,0.0012,0.072,0.16,0.16,0.031,0.11,0.11,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0026,0.0014,0.00048,0.0014,0.0014,0.0012,0.0014,1,1
7090000,-0.28,0.025,-0.0064,0.96,-0.026,-0.00083,-0.037,0.0022,0.0052,-0.056,-0.0015,-0.0055,-8.7e-05,0,0,-0.13,-0.099,-0.021,0.51,0.075,-0.029,-0.065,0,0,0.0012,0.0012,0.058,0.16,0.16,0.03,0.13,0.13,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00099,0.0013,1,1
7190000,-0.28,0.026,-0.0064,0.96,-0.047,-0.0082,-0.036,0.00063,0.0038,-0.058,-0.0015,-0.0055,-8.6e-05,3.9e-05,-1e-05,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.054,0.17,0.17,0.029,0.16,0.16,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.00094,0.0013,1,1
7290000,-0.28,0.026,-0.0064,0.96,-0.07,-0.017,-0.033,-0.0034,0.0023,-0.054,-0.0015,-0.0054,-8.5e-05,0.00011,-5e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.053,0.18,0.18,0.028,0.19,0.19,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00093,0.0013,1,1
7390000,-0.28,0.026,-0.0062,0.96,-0.091,-0.024,-0.031,-0.0098,-8.5e-05,-0.052,-0.0015,-0.0054,-8.4e-05,0.00016,-4e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.052,0.19,0.19,0.027,0.22,0.22,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.002,0.0013,0.00013,0.0013,0.0013,0.00092,0.0013,1,1
7490000,-0.28,0.026,-0.0062,0.96,-0.11,-0.032,-0.025,-0.015,-0.0034,-0.046,-0.0015,-0.0053,-8.1e-05,0.00033,7.2e-07,-0.13,-0.1,-0.022,0.5,0.077,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.2,0.2,0.026,0.26,0.26,0.063,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00091,0.0013,1,1
7590000,-0.28,0.026,-0.0063,0.96,-0.13,-0.041,-0.021,-0.024,-0.0083,-0.04,-0.0015,-0.0052,-8e-05,0.00045,-2.7e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.22,0.21,0.025,0.3,0.3,0.062,6.6e-05,6.5e-05,4.6e-06,0.04,0.04,0.0018,0.0013,0.00011,0.0013,0.0013,0.00091,0.0013,1,1
7690000,-0.28,0.026,-0.0063,0.96,-0.16,-0.051,-0.02,-0.034,-0.015,-0.036,-0.0014,-0.0051,-7.9e-05,0.00056,-6.8e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.23,0.23,0.025,0.34,0.34,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0017,0.0013,0.0001,0.0013,0.0013,0.0009,0.0013,1,1
7790000,-0.28,0.026,-0.0062,0.96,-0.18,-0.061,-0.022,-0.041,-0.025,-0.041,-0.0014,-0.005,-7.8e-05,0.00088,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.26,0.25,0.024,0.39,0.39,0.061,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0016,0.0013,9.8e-05,0.0013,0.0013,0.0009,0.0013,1,1
7890000,-0.28,0.026,-0.0062,0.96,-0.2,-0.071,-0.022,-0.057,-0.033,-0.044,-0.0013,-0.0049,-7.7e-05,0.00099,-0.00028,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.28,0.28,0.023,0.45,0.45,0.06,6.4e-05,6.4e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.4e-05,0.0013,0.0013,0.0009,0.0013,1,1
7990000,-0.28,0.026,-0.0061,0.96,-0.22,-0.078,-0.018,-0.08,-0.039,-0.04,-0.0013,-0.0049,-7.7e-05,0.00089,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.3,0.3,0.022,0.51,0.51,0.059,6.3e-05,6.3e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.1e-05,0.0013,0.0013,0.0009,0.0013,1,1
8090000,-0.28,0.026,-0.006,0.96,-0.25,-0.09,-0.019,-0.1,-0.053,-0.043,-0.0013,-0.0049,-8e-05,0.00093,-0.00038,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.33,0.33,0.022,0.57,0.57,0.059,6.2e-05,6.2e-05,4.6e-06,0.04,0.04,0.0014,0.0013,8.9e-05,0.0013,0.0013,0.0009,0.0013,1,1
8190000,-0.28,0.026,-0.0061,0.96,-0.27,-0.1,-0.014,-0.12,-0.069,-0.036,-0.0012,-0.0048,-8.2e-05,0.00096,-0.0005,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.36,0.36,0.021,0.64,0.64,0.058,6.1e-05,6.1e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.7e-05,0.0013,0.0013,0.0009,0.0013,1,1
8290000,-0.28,0.026,-0.0061,0.96,-0.3,-0.11,-0.013,-0.16,-0.077,-0.036,-0.0012,-0.005,-8.4e-05,0.0007,-0.00042,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.4,0.39,0.02,0.72,0.72,0.057,6e-05,6e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.5e-05,0.0013,0.0013,0.0009,0.0013,1,1
8390000,-0.28,0.026,-0.0061,0.96,-0.33,-0.12,-0.011,-0.2,-0.089,-0.034,-0.0012,-0.005,-8.5e-05,0.00063,-0.00041,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.43,0.43,0.02,0.81,0.8,0.057,5.9e-05,5.9e-05,4.6e-06,0.04,0.04,0.0012,0.0013,8.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
8490000,-0.28,0.026,-0.0059,0.96,-0.35,-0.12,-0.012,-0.23,-0.094,-0.039,-0.0013,-0.005,-8.2e-05,0.00062,-0.00029,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.47,0.46,0.019,0.9,0.9,0.056,5.8e-05,5.7e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
8590000,-0.28,0.027,-0.0059,0.96,-0.38,-0.14,-0.0073,-0.26,-0.12,-0.034,-0.0012,-0.0049,-8.2e-05,0.00079,-0.00042,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.51,0.51,0.019,1,1,0.055,5.6e-05,5.5e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
8690000,-0.28,0.027,-0.0059,0.96,-0.4,-0.14,-0.0089,-0.3,-0.13,-0.035,-0.0012,-0.0049,-8.2e-05,0.00071,-0.00035,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.56,0.55,0.018,1.1,1.1,0.055,5.5e-05,5.4e-05,4.6e-06,0.04,0.04,0.001,0.0013,8e-05,0.0013,0.0013,0.00089,0.0013,1,1
8790000,-0.28,0.027,-0.0059,0.96,-0.43,-0.15,-0.0084,-0.35,-0.14,-0.032,-0.0012,-0.005,-8.5e-05,0.00052,-0.0004,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.61,0.6,0.018,1.2,1.2,0.055,5.3e-05,5.2e-05,4.6e-06,0.04,0.04,0.00099,0.0013,7.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
8890000,-0.28,0.027,-0.0059,0.96,-0.46,-0.16,-0.0039,-0.38,-0.16,-0.026,-0.0012,-0.0049,-8.1e-05,0.00064,-0.00031,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.66,0.65,0.017,1.4,1.4,0.054,5.1e-05,5e-05,4.5e-06,0.04,0.04,0.00095,0.0013,7.8e-05,0.0013,0.0013,0.00089,0.0013,1,1
8990000,-0.28,0.027,-0.0058,0.96,-0.47,-0.17,-0.0028,-0.41,-0.17,-0.029,-0.0013,-0.0047,-7.5e-05,0.001,-0.0003,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.72,0.7,0.017,1.5,1.5,0.054,4.9e-05,4.8e-05,4.5e-06,0.04,0.04,0.00091,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1
9090000,-0.28,0.027,-0.0056,0.96,-0.5,-0.18,-0.0038,-0.47,-0.17,-0.029,-0.0014,-0.0048,-7.2e-05,0.00081,-2.1e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.77,0.76,0.016,1.7,1.7,0.053,4.7e-05,4.6e-05,4.5e-06,0.04,0.04,0.00087,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1
9190000,-0.28,0.027,-0.0055,0.96,-0.53,-0.18,-0.0029,-0.52,-0.18,-0.029,-0.0015,-0.0048,-6.9e-05,0.0008,0.00012,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.84,0.82,0.016,1.9,1.9,0.052,4.5e-05,4.4e-05,4.5e-06,0.04,0.04,0.00084,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1
9290000,-0.28,0.027,-0.0054,0.96,-0.56,-0.19,-0.0011,-0.56,-0.21,-0.026,-0.0014,-0.0047,-6.7e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.9,0.88,0.016,2.1,2.1,0.052,4.3e-05,4.2e-05,4.5e-06,0.04,0.04,0.0008,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1
9390000,-0.28,0.027,-0.0054,0.96,-0.023,-0.0084,0.0003,-0.57,-0.21,-0.026,-0.0013,-0.0047,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.052,4.2e-05,4e-05,4.5e-06,0.04,0.04,0.00077,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1
9490000,-0.28,0.027,-0.0053,0.96,-0.049,-0.017,0.0021,-0.58,-0.21,-0.023,-0.0014,-0.0048,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.051,4e-05,3.8e-05,4.5e-06,0.04,0.04,0.00074,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1
9590000,-0.28,0.027,-0.0056,0.96,-0.076,-0.023,0.0023,-0.58,-0.21,-0.024,-0.0012,-0.0048,-8e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,51,51,0.05,3.8e-05,3.7e-05,4.5e-06,0.04,0.04,0.00072,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
9690000,-0.28,0.027,-0.0057,0.96,-0.1,-0.031,0.0054,-0.59,-0.21,-0.023,-0.0012,-0.0048,-8.2e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,52,52,0.05,3.6e-05,3.5e-05,4.5e-06,0.04,0.04,0.00069,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
9790000,-0.28,0.027,-0.0059,0.96,-0.13,-0.038,0.0041,-0.59,-0.22,-0.023,-0.001,-0.005,-9.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,35,35,0.05,3.4e-05,3.3e-05,4.5e-06,0.04,0.04,0.00067,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
9890000,-0.28,0.027,-0.0058,0.96,-0.16,-0.047,0.0057,-0.61,-0.22,-0.023,-0.0011,-0.0049,-8.9e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,37,37,0.049,3.2e-05,3.1e-05,4.5e-06,0.04,0.04,0.00064,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
9990000,-0.28,0.027,-0.006,0.96,-0.18,-0.051,0.0065,-0.61,-0.22,-0.025,-0.00096,-0.005,-9.6e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.014,28,28,0.049,3.1e-05,3e-05,4.5e-06,0.04,0.04,0.00062,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
10090000,-0.28,0.027,-0.0061,0.96,-0.21,-0.054,0.0078,-0.63,-0.23,-0.023,-0.00084,-0.0051,-0.0001,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.013,30,30,0.049,2.9e-05,2.8e-05,4.5e-06,0.04,0.04,0.0006,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
10190000,-0.28,0.027,-0.0064,0.96,-0.23,-0.056,0.0087,-0.64,-0.23,-0.024,-0.00067,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,25,25,0.048,2.8e-05,2.7e-05,4.5e-06,0.04,0.04,0.00058,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
10290000,-0.28,0.027,-0.0064,0.96,-0.26,-0.065,0.0079,-0.66,-0.23,-0.023,-0.00072,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,27,27,0.048,2.6e-05,2.5e-05,4.5e-06,0.04,0.04,0.00057,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
10390000,-0.28,0.028,-0.0063,0.96,-0.012,-0.0081,-0.0025,-7.9e-05,-0.00028,-0.023,-0.00074,-0.0049,-0.0001,0.001,0.00015,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.25,0.25,0.56,0.25,0.25,0.049,2.5e-05,2.4e-05,4.5e-06,0.04,0.04,0.00055,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
10490000,-0.28,0.027,-0.0064,0.96,-0.041,-0.014,0.0066,-0.0027,-0.0013,-0.018,-0.00066,-0.005,-0.00011,0.00082,2.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.26,0.26,0.55,0.26,0.26,0.058,2.4e-05,2.3e-05,4.5e-06,0.04,0.04,0.00054,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
10590000,-0.28,0.027,-0.0063,0.96,-0.052,-0.013,0.012,-0.0032,-0.00096,-0.016,-0.00073,-0.005,-0.0001,0.0014,7.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.13,0.13,0.27,0.26,0.26,0.056,2.2e-05,2.1e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
10690000,-0.28,0.027,-0.0063,0.96,-0.081,-0.018,0.015,-0.0099,-0.0025,-0.013,-0.0007,-0.005,-0.00011,0.0014,2.4e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
10790000,-0.28,0.027,-0.0062,0.96,-0.079,-0.021,0.013,-7.5e-06,-0.0018,-0.012,-0.00072,-0.005,-0.00011,0.0035,-0.0011,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.095,0.095,0.17,0.13,0.13,0.062,2e-05,1.9e-05,4.5e-06,0.039,0.039,0.00051,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1
10890000,-0.28,0.027,-0.006,0.96,-0.11,-0.03,0.0093,-0.0092,-0.0044,-0.015,-0.00083,-0.005,-0.0001,0.0036,-0.00084,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.11,0.11,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1
10990000,-0.28,0.026,-0.006,0.96,-0.096,-0.031,0.016,-0.0034,-0.0023,-0.0093,-0.00085,-0.0052,-0.00011,0.0077,-0.0021,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.083,0.083,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1
11090000,-0.28,0.027,-0.0064,0.96,-0.12,-0.039,0.019,-0.014,-0.0055,-0.0055,-0.00072,-0.0052,-0.00011,0.0078,-0.0025,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.096,0.097,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,4.5e-06,0.039,0.039,0.00049,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1
11190000,-0.28,0.025,-0.0065,0.96,-0.1,-0.034,0.026,-0.0065,-0.0031,0.00085,-0.00071,-0.0053,-0.00011,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.079,0.079,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1
11290000,-0.28,0.025,-0.0066,0.96,-0.13,-0.038,0.025,-0.018,-0.0066,0.00091,-0.00071,-0.0054,-0.00012,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.094,0.094,0.077,0.078,0.078,0.069,1.5e-05,1.4e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1
11390000,-0.28,0.024,-0.0065,0.96,-0.11,-0.032,0.016,-0.01,-0.004,-0.008,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.078,0.078,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.8e-05,0.0013,0.0012,0.00085,0.0013,1,1
11490000,-0.28,0.024,-0.0064,0.96,-0.13,-0.036,0.021,-0.022,-0.0074,-0.002,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.093,0.093,0.057,0.069,0.069,0.067,1.3e-05,1.3e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1
11590000,-0.28,0.023,-0.0065,0.96,-0.11,-0.029,0.019,-0.013,-0.0046,-0.0033,-0.00079,-0.0056,-0.00012,0.027,-0.0085,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00098,0.048,0.077,0.077,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1
11690000,-0.28,0.022,-0.0065,0.96,-0.12,-0.035,0.019,-0.024,-0.0078,-0.0047,-0.00081,-0.0057,-0.00012,0.027,-0.0083,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00099,0.048,0.092,0.092,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1
11790000,-0.28,0.021,-0.0063,0.96,-0.097,-0.033,0.02,-0.014,-0.0064,-0.0019,-0.0009,-0.0057,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.069,0,0,0.00091,0.00087,0.048,0.076,0.076,0.037,0.053,0.053,0.063,1.1e-05,1.1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1
11890000,-0.28,0.021,-0.0065,0.96,-0.11,-0.037,0.018,-0.024,-0.0097,-0.0012,-0.00088,-0.0058,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00091,0.00087,0.048,0.089,0.089,0.034,0.06,0.06,0.063,1.1e-05,1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1
11990000,-0.28,0.02,-0.0066,0.96,-0.091,-0.028,0.015,-0.017,-0.0064,-0.005,-0.0009,-0.0059,-0.00012,0.039,-0.011,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.076,0.076,0.03,0.062,0.062,0.061,1e-05,9.8e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00082,0.0013,1,1
12090000,-0.28,0.02,-0.0066,0.96,-0.1,-0.03,0.019,-0.027,-0.0092,0.0011,-0.00086,-0.0058,-0.00012,0.039,-0.012,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.089,0.088,0.027,0.071,0.071,0.06,9.8e-06,9.3e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00081,0.0013,1,1
12190000,-0.28,0.019,-0.0067,0.96,-0.084,-0.018,0.018,-0.014,-0.0032,0.0029,-0.00082,-0.0059,-0.00012,0.045,-0.013,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.07,0.07,0.024,0.057,0.057,0.058,9.2e-06,8.8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1
12290000,-0.28,0.019,-0.0068,0.96,-0.09,-0.017,0.017,-0.023,-0.0048,0.004,-0.00079,-0.0059,-0.00012,0.045,-0.014,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.081,0.081,0.022,0.065,0.065,0.058,8.9e-06,8.5e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1
12390000,-0.28,0.019,-0.0068,0.96,-0.073,-0.012,0.015,-0.013,-0.0027,-0.002,-0.00078,-0.0059,-0.00012,0.048,-0.015,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00066,0.00063,0.047,0.066,0.065,0.02,0.054,0.054,0.056,8.4e-06,8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1
12490000,-0.28,0.019,-0.0069,0.96,-0.081,-0.013,0.019,-0.021,-0.004,9.6e-05,-0.00076,-0.0059,-0.00013,0.048,-0.016,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00066,0.00064,0.047,0.075,0.075,0.018,0.062,0.062,0.055,8.1e-06,7.7e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1
12590000,-0.28,0.018,-0.0068,0.96,-0.065,-0.011,0.021,-0.01,-0.0039,0.0019,-0.00076,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00058,0.047,0.061,0.061,0.017,0.052,0.052,0.054,7.7e-06,7.4e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1
12690000,-0.28,0.018,-0.0067,0.96,-0.072,-0.0098,0.02,-0.017,-0.0049,0.0035,-0.00075,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00059,0.047,0.069,0.069,0.015,0.059,0.059,0.053,7.4e-06,7e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1
12790000,-0.28,0.018,-0.0065,0.96,-0.056,-0.015,0.022,-0.01,-0.0078,0.0057,-0.00082,-0.0059,-0.00013,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.061,0.061,0.014,0.061,0.061,0.051,7.1e-06,6.7e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1
12890000,-0.28,0.018,-0.0065,0.96,-0.061,-0.016,0.023,-0.016,-0.0096,0.0088,-0.00084,-0.0059,-0.00012,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.069,0.069,0.013,0.07,0.07,0.051,6.8e-06,6.5e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1
12990000,-0.28,0.017,-0.0065,0.96,-0.05,-0.013,0.023,-0.008,-0.0066,0.01,-0.00088,-0.0059,-0.00012,0.056,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.047,0.055,0.055,0.012,0.056,0.056,0.05,6.5e-06,6.2e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1
13090000,-0.28,0.017,-0.0064,0.96,-0.054,-0.015,0.021,-0.013,-0.0083,0.0089,-0.00091,-0.0059,-0.00012,0.056,-0.018,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.046,0.062,0.062,0.011,0.065,0.065,0.049,6.3e-06,5.9e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1
13190000,-0.28,0.017,-0.0063,0.96,-0.046,-0.015,0.02,-0.0097,-0.0091,0.0096,-0.00094,-0.0059,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.055,0.055,0.011,0.066,0.066,0.047,6e-06,5.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13290000,-0.28,0.017,-0.0064,0.96,-0.049,-0.015,0.017,-0.015,-0.011,0.009,-0.00092,-0.0058,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.061,0.061,0.01,0.075,0.075,0.047,5.8e-06,5.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13390000,-0.28,0.017,-0.0064,0.96,-0.04,-0.011,0.017,-0.0074,-0.007,0.0097,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.049,0.049,0.0094,0.06,0.06,0.046,5.6e-06,5.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13490000,-0.28,0.017,-0.0064,0.96,-0.044,-0.014,0.017,-0.012,-0.0083,0.006,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.054,0.054,0.009,0.068,0.068,0.045,5.4e-06,5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13590000,-0.28,0.017,-0.0064,0.96,-0.035,-0.01,0.018,-0.0035,-0.0057,0.0045,-0.00088,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00045,0.046,0.045,0.045,0.0085,0.055,0.055,0.044,5.2e-06,4.9e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
13690000,-0.28,0.017,-0.0063,0.96,-0.037,-0.0095,0.019,-0.0071,-0.0067,0.0072,-0.00089,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00046,0.046,0.049,0.049,0.0082,0.063,0.063,0.044,5e-06,4.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
13790000,-0.28,0.016,-0.0064,0.96,-0.029,-0.0071,0.019,0.00061,-0.0035,0.0068,-0.00089,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.041,0.041,0.0078,0.052,0.052,0.042,4.8e-06,4.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
13890000,-0.28,0.016,-0.0063,0.96,-0.031,-0.0086,0.02,-0.0022,-0.0044,0.0091,-0.00092,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.045,0.045,0.0076,0.059,0.059,0.042,4.7e-06,4.4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00075,0.0012,1,1
13990000,-0.28,0.016,-0.0062,0.96,-0.03,-0.012,0.018,-0.00073,-0.0048,0.008,-0.00094,-0.0059,-0.00012,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.039,0.039,0.0073,0.05,0.05,0.041,4.5e-06,4.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14090000,-0.28,0.016,-0.0064,0.96,-0.031,-0.0062,0.02,-0.004,-0.0053,0.0046,-0.00087,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.042,0.042,0.0072,0.057,0.057,0.041,4.4e-06,4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14190000,-0.28,0.016,-0.0064,0.96,-0.025,-0.0047,0.02,-0.00094,-0.004,0.0049,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.036,0.036,0.007,0.049,0.049,0.04,4.2e-06,3.9e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14290000,-0.28,0.016,-0.0064,0.96,-0.028,-0.0051,0.018,-0.0036,-0.0044,0.0092,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.04,0.04,0.0069,0.055,0.055,0.039,4.1e-06,3.8e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14390000,-0.28,0.016,-0.0064,0.96,-0.026,-0.0045,0.019,-0.00096,-0.0049,0.014,-0.00083,-0.0059,-0.00012,0.064,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.034,0.034,0.0067,0.048,0.048,0.039,4e-06,3.6e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14490000,-0.28,0.016,-0.0066,0.96,-0.026,-0.0039,0.023,-0.0037,-0.005,0.016,-0.00079,-0.0059,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00042,0.046,0.037,0.037,0.0066,0.054,0.054,0.038,3.8e-06,3.5e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14590000,-0.28,0.016,-0.0067,0.96,-0.028,-0.0054,0.021,-0.0038,-0.0053,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.032,0.032,0.0065,0.047,0.047,0.038,3.7e-06,3.4e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14690000,-0.28,0.016,-0.0067,0.96,-0.029,-0.0058,0.021,-0.0067,-0.006,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.035,0.035,0.0065,0.053,0.053,0.037,3.6e-06,3.3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14790000,-0.28,0.016,-0.0068,0.96,-0.03,-0.003,0.021,-0.0052,-0.0014,0.015,-0.0008,-0.0058,-0.00012,0.065,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.031,0.031,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
14890000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0012,0.026,-0.0086,-0.002,0.016,-0.00081,-0.0057,-0.00012,0.066,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.00041,0.046,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
14990000,-0.28,0.016,-0.0067,0.96,-0.031,-0.003,0.028,-0.0069,-0.003,0.018,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15090000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0042,0.032,-0.01,-0.0033,0.021,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.032,0.032,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15190000,-0.28,0.016,-0.0068,0.96,-0.03,-0.0022,0.033,-0.008,-0.0026,0.023,-0.0008,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15290000,-0.28,0.016,-0.0069,0.96,-0.034,-0.0024,0.032,-0.012,-0.0032,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15390000,-0.28,0.016,-0.0069,0.96,-0.032,-0.0042,0.032,-0.0092,-0.0026,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.027,0.0064,0.044,0.044,0.034,2.9e-06,2.6e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15490000,-0.28,0.016,-0.007,0.96,-0.034,-0.0018,0.032,-0.012,-0.003,0.021,-0.00082,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.029,0.0065,0.05,0.05,0.034,2.8e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15590000,-0.28,0.016,-0.0069,0.96,-0.03,-0.006,0.032,-0.0077,-0.0061,0.02,-0.00085,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15690000,-0.28,0.016,-0.0068,0.96,-0.032,-0.0041,0.032,-0.01,-0.0067,0.021,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15790000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0028,0.032,-0.0077,-0.0057,0.023,-0.00092,-0.0057,-0.00012,0.068,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.024,0.024,0.0066,0.043,0.044,0.033,2.6e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15890000,-0.28,0.016,-0.0069,0.96,-0.029,-0.0041,0.033,-0.011,-0.0058,0.023,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15990000,-0.28,0.016,-0.0068,0.96,-0.027,-0.0035,0.03,-0.0091,-0.0049,0.022,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
16090000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0023,0.028,-0.012,-0.005,0.022,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.025,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16190000,-0.28,0.016,-0.0068,0.96,-0.026,-0.002,0.027,-0.011,-0.0041,0.019,-0.00086,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16290000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0011,0.027,-0.014,-0.0043,0.021,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.024,0.024,0.007,0.048,0.048,0.033,2.3e-06,2e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16390000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0015,0.027,-0.011,-0.0041,0.021,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16490000,-0.28,0.016,-0.0069,0.96,-0.033,-0.00051,0.029,-0.014,-0.0041,0.025,-0.00086,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.023,0.023,0.0072,0.047,0.047,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16590000,-0.28,0.016,-0.0069,0.96,-0.036,1.4e-05,0.033,-0.012,-0.0035,0.025,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.021,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16690000,-0.28,0.016,-0.0069,0.96,-0.039,0.0036,0.033,-0.016,-0.0035,0.026,-0.00089,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16790000,-0.28,0.016,-0.0068,0.96,-0.039,0.0034,0.032,-0.013,-0.0031,0.026,-0.00091,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0073,0.042,0.042,0.033,2e-06,1.7e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16890000,-0.28,0.016,-0.0067,0.96,-0.039,0.0029,0.033,-0.017,-0.0032,0.025,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16990000,-0.28,0.016,-0.0067,0.96,-0.036,0.0033,0.033,-0.015,-0.0034,0.024,-0.00094,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.049,0.049,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17090000,-0.28,0.016,-0.0068,0.96,-0.041,0.0053,0.033,-0.019,-0.0029,0.023,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0075,0.054,0.054,0.033,1.9e-06,1.6e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17190000,-0.28,0.016,-0.0069,0.96,-0.039,0.0071,0.034,-0.018,-0.0046,0.026,-0.00093,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0076,0.057,0.057,0.033,1.8e-06,1.6e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17290000,-0.28,0.016,-0.0069,0.96,-0.042,0.0077,0.034,-0.022,-0.0035,0.026,-0.00092,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.023,0.024,0.0077,0.062,0.063,0.033,1.8e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17390000,-0.28,0.016,-0.0069,0.96,-0.032,0.013,0.033,-0.014,-0.002,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17490000,-0.28,0.016,-0.0069,0.96,-0.032,0.014,0.033,-0.017,-0.00051,0.028,-0.00094,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.022,0.0078,0.058,0.058,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
17590000,-0.28,0.016,-0.0069,0.96,-0.032,0.012,0.032,-0.016,-0.00075,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
17690000,-0.28,0.016,-0.007,0.96,-0.033,0.012,0.033,-0.019,0.0003,0.028,-0.00096,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.02,0.02,0.0078,0.054,0.054,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
17790000,-0.28,0.016,-0.007,0.96,-0.033,0.013,0.033,-0.018,0.0011,0.033,-0.00097,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.019,0.02,0.0078,0.057,0.057,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1
17890000,-0.28,0.016,-0.0069,0.96,-0.037,0.014,0.033,-0.021,0.0022,0.038,-0.00098,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.021,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1
17990000,-0.28,0.016,-0.0069,0.96,-0.035,0.015,0.033,-0.017,0.0047,0.038,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.018,0.0079,0.052,0.052,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1
18090000,-0.28,0.016,-0.007,0.96,-0.037,0.016,0.032,-0.021,0.0061,0.037,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.019,0.02,0.008,0.057,0.057,0.034,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1
18190000,-0.28,0.016,-0.007,0.96,-0.034,0.013,0.033,-0.016,0.004,0.035,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18290000,-0.28,0.016,-0.007,0.96,-0.037,0.013,0.031,-0.02,0.005,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.019,0.008,0.053,0.054,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18390000,-0.28,0.016,-0.0069,0.96,-0.033,0.013,0.031,-0.014,0.0042,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0079,0.046,0.047,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18490000,-0.28,0.016,-0.0069,0.96,-0.037,0.012,0.03,-0.018,0.005,0.034,-0.001,-0.0057,-0.00013,0.072,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.018,0.008,0.051,0.051,0.034,1.3e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18590000,-0.28,0.016,-0.0068,0.96,-0.035,0.012,0.03,-0.015,0.0045,0.037,-0.001,-0.0057,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18690000,-0.28,0.016,-0.0067,0.96,-0.035,0.011,0.028,-0.017,0.0053,0.035,-0.0011,-0.0058,-0.00013,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.048,0.049,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18790000,-0.28,0.015,-0.0067,0.96,-0.031,0.011,0.028,-0.014,0.0046,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18890000,-0.28,0.015,-0.0067,0.96,-0.032,0.011,0.026,-0.017,0.0057,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.047,0.047,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
18990000,-0.28,0.015,-0.0066,0.96,-0.029,0.011,0.027,-0.015,0.005,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.015,0.0079,0.042,0.042,0.034,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19090000,-0.28,0.015,-0.0067,0.96,-0.029,0.012,0.027,-0.017,0.0056,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.016,0.0079,0.045,0.046,0.035,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19190000,-0.28,0.016,-0.0066,0.96,-0.026,0.013,0.027,-0.015,0.0056,0.028,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.8e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19290000,-0.28,0.016,-0.0066,0.96,-0.027,0.013,0.027,-0.018,0.0067,0.027,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.1e-06,9.7e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19390000,-0.28,0.015,-0.0067,0.96,-0.025,0.011,0.028,-0.016,0.0067,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0078,0.04,0.04,0.035,1.1e-06,9.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19490000,-0.28,0.015,-0.0068,0.96,-0.028,0.012,0.028,-0.019,0.008,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.044,0.035,1.1e-06,9.3e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19590000,-0.28,0.015,-0.0067,0.96,-0.024,0.013,0.03,-0.016,0.0063,0.026,-0.0011,-0.0058,-0.00016,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0077,0.039,0.04,0.035,1.1e-06,9e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19690000,-0.28,0.016,-0.0067,0.96,-0.024,0.011,0.028,-0.019,0.007,0.026,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.043,0.035,1e-06,8.9e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19790000,-0.28,0.015,-0.0068,0.96,-0.021,0.011,0.026,-0.019,0.0075,0.022,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0077,0.045,0.046,0.035,1e-06,8.7e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19890000,-0.28,0.016,-0.0068,0.96,-0.023,0.011,0.027,-0.021,0.0087,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0077,0.049,0.05,0.035,1e-06,8.6e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19990000,-0.28,0.016,-0.0068,0.96,-0.02,0.012,0.024,-0.016,0.0081,0.017,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0076,0.043,0.044,0.035,9.7e-07,8.3e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20090000,-0.28,0.016,-0.0068,0.96,-0.022,0.015,0.024,-0.018,0.0093,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0076,0.047,0.048,0.035,9.7e-07,8.2e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20190000,-0.28,0.016,-0.0068,0.96,-0.023,0.013,0.025,-0.019,0.0097,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0075,0.05,0.05,0.035,9.4e-07,8e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20290000,-0.28,0.016,-0.0068,0.96,-0.021,0.015,0.025,-0.022,0.011,0.021,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.054,0.055,0.035,9.3e-07,7.9e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20390000,-0.28,0.016,-0.0067,0.96,-0.019,0.013,0.025,-0.022,0.01,0.022,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.056,0.057,0.035,9.1e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20490000,-0.28,0.016,-0.0067,0.96,-0.017,0.015,0.025,-0.024,0.011,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0075,0.061,0.063,0.035,9e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
20590000,-0.28,0.016,-0.0066,0.96,-0.017,0.014,0.025,-0.024,0.01,0.018,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0074,0.064,0.065,0.035,8.8e-07,7.5e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20690000,-0.28,0.016,-0.0066,0.96,-0.016,0.014,0.026,-0.025,0.012,0.019,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.018,0.02,0.0074,0.069,0.071,0.035,8.7e-07,7.4e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20790000,-0.28,0.016,-0.006,0.96,-0.01,0.01,0.01,-0.019,0.0088,0.017,-0.0012,-0.0058,-0.00018,0.072,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.017,0.0073,0.057,0.057,0.035,8.4e-07,7.1e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20890000,-0.28,0.011,0.0027,0.96,-0.0058,-5.9e-05,-0.11,-0.021,0.0092,0.011,-0.0012,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00037,0.00034,0.046,0.017,0.018,0.0073,0.061,0.062,0.035,8.3e-07,7.1e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20990000,-0.28,0.0071,0.0057,0.96,0.0086,-0.017,-0.25,-0.017,0.007,-0.004,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.016,0.0072,0.052,0.052,0.034,8e-07,6.9e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
21090000,-0.28,0.0076,0.0042,0.96,0.022,-0.029,-0.37,-0.016,0.005,-0.035,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.017,0.0072,0.056,0.057,0.035,8e-07,6.8e-07,4.2e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
21190000,-0.28,0.0095,0.0015,0.96,0.028,-0.035,-0.49,-0.013,0.0038,-0.071,-0.0011,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.014,0.016,0.0071,0.048,0.049,0.035,7.7e-07,6.6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1
21290000,-0.28,0.011,-0.00054,0.96,0.026,-0.037,-0.62,-0.011,0.0011,-0.13,-0.0011,-0.0058,-0.00019,0.072,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.0071,0.052,0.053,0.035,7.7e-07,6.5e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1
21390000,-0.28,0.012,-0.002,0.96,0.019,-0.029,-0.75,-0.013,0.0046,-0.19,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.016,0.017,0.007,0.054,0.055,0.035,7.5e-07,6.4e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1
21490000,-0.28,0.012,-0.0028,0.96,0.013,-0.027,-0.88,-0.011,0.0015,-0.28,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.017,0.018,0.007,0.059,0.06,0.035,7.4e-07,6.3e-07,4.1e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21590000,-0.28,0.012,-0.0034,0.96,0.0009,-0.021,-1,-0.015,0.0065,-0.37,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.017,0.018,0.0069,0.061,0.063,0.034,7.3e-07,6.2e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21690000,-0.28,0.012,-0.0037,0.96,-0.0046,-0.017,-1.1,-0.015,0.004,-0.48,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0069,0.066,0.068,0.035,7.2e-07,6.1e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21790000,-0.28,0.012,-0.0041,0.96,-0.011,-0.0087,-1.3,-0.017,0.01,-0.6,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.019,0.0069,0.069,0.07,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21890000,-0.28,0.013,-0.0044,0.96,-0.017,-0.0041,-1.4,-0.018,0.01,-0.74,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.021,0.0068,0.074,0.076,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21990000,-0.28,0.013,-0.0052,0.96,-0.022,0.0043,-1.4,-0.024,0.018,-0.88,-0.0011,-0.0058,-8.8e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0068,0.077,0.079,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
22090000,-0.28,0.014,-0.0058,0.96,-0.025,0.0075,-1.4,-0.025,0.018,-1,-0.0011,-0.0058,-8.2e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0068,0.083,0.085,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
22190000,-0.28,0.014,-0.0063,0.96,-0.032,0.014,-1.4,-0.03,0.025,-1.2,-0.0011,-0.0058,-5.9e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0067,0.085,0.087,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22290000,-0.28,0.014,-0.007,0.96,-0.04,0.019,-1.4,-0.034,0.027,-1.3,-0.0011,-0.0058,-6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.022,0.0067,0.091,0.094,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22390000,-0.28,0.015,-0.0073,0.96,-0.047,0.026,-1.4,-0.04,0.031,-1.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0066,0.094,0.096,0.034,6.4e-07,5.5e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22490000,-0.28,0.015,-0.0074,0.96,-0.053,0.032,-1.4,-0.045,0.034,-1.6,-0.0011,-0.0058,-6.4e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0066,0.1,0.1,0.034,6.4e-07,5.4e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22590000,-0.28,0.016,-0.0073,0.96,-0.058,0.038,-1.4,-0.046,0.038,-1.7,-0.0011,-0.0058,-5.7e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.1,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22690000,-0.28,0.016,-0.0072,0.96,-0.062,0.042,-1.4,-0.053,0.042,-1.9,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.11,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22790000,-0.28,0.016,-0.0071,0.96,-0.069,0.047,-1.4,-0.059,0.045,-2,-0.0011,-0.0058,-6.6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.11,0.11,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22890000,-0.28,0.017,-0.0072,0.96,-0.074,0.051,-1.4,-0.065,0.048,-2.2,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.12,0.12,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22990000,-0.28,0.017,-0.007,0.96,-0.076,0.051,-1.4,-0.068,0.047,-2.3,-0.0011,-0.0058,-6.3e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.022,0.0064,0.12,0.12,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23090000,-0.28,0.017,-0.007,0.96,-0.082,0.055,-1.4,-0.075,0.053,-2.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0064,0.13,0.13,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23190000,-0.28,0.017,-0.0069,0.96,-0.084,0.05,-1.4,-0.074,0.049,-2.6,-0.0011,-0.0058,-8.4e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.13,0.13,0.033,5.7e-07,4.9e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23290000,-0.28,0.018,-0.0073,0.96,-0.09,0.054,-1.4,-0.083,0.053,-2.7,-0.0011,-0.0058,-8e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.14,0.14,0.034,5.6e-07,4.8e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23390000,-0.28,0.018,-0.0073,0.96,-0.089,0.056,-1.4,-0.077,0.055,-2.9,-0.0011,-0.0058,-9.8e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.14,0.14,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23490000,-0.28,0.018,-0.0073,0.96,-0.096,0.057,-1.4,-0.088,0.059,-3,-0.0011,-0.0058,-9e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.15,0.15,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23590000,-0.28,0.018,-0.0074,0.96,-0.094,0.051,-1.4,-0.083,0.049,-3.2,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0062,0.15,0.15,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23690000,-0.28,0.019,-0.008,0.96,-0.093,0.053,-1.3,-0.092,0.053,-3.3,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0062,0.16,0.16,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23790000,-0.28,0.021,-0.0095,0.96,-0.077,0.049,-0.95,-0.082,0.049,-3.4,-0.0012,-0.0058,-0.00012,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00039,0.00036,0.045,0.021,0.022,0.0061,0.16,0.16,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23890000,-0.28,0.026,-0.012,0.96,-0.071,0.05,-0.52,-0.089,0.053,-3.5,-0.0012,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00042,0.00038,0.045,0.021,0.023,0.0061,0.17,0.17,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
23990000,-0.28,0.028,-0.014,0.96,-0.061,0.048,-0.13,-0.077,0.048,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.02,0.022,0.0061,0.17,0.17,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
24090000,-0.28,0.027,-0.014,0.96,-0.067,0.055,0.1,-0.082,0.053,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.021,0.023,0.0061,0.18,0.18,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
24190000,-0.28,0.023,-0.011,0.96,-0.071,0.052,0.089,-0.069,0.04,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.0004,0.00037,0.045,0.02,0.022,0.006,0.18,0.18,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
24290000,-0.28,0.02,-0.0093,0.96,-0.076,0.055,0.068,-0.076,0.045,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.023,0.006,0.19,0.19,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
24390000,-0.28,0.018,-0.0085,0.96,-0.059,0.048,0.084,-0.058,0.036,-3.6,-0.0013,-0.0058,-0.00016,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.02,0.022,0.006,0.19,0.19,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
24490000,-0.28,0.019,-0.0087,0.96,-0.054,0.044,0.081,-0.063,0.039,-3.6,-0.0013,-0.0058,-0.00014,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.021,0.023,0.006,0.2,0.2,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
24590000,-0.28,0.019,-0.0094,0.96,-0.043,0.042,0.077,-0.045,0.033,-3.6,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.022,0.0059,0.2,0.2,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24690000,-0.28,0.019,-0.0099,0.96,-0.041,0.041,0.076,-0.049,0.037,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.024,0.0059,0.21,0.21,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24790000,-0.28,0.018,-0.01,0.96,-0.034,0.04,0.068,-0.037,0.029,-3.5,-0.0013,-0.0058,-0.00017,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0059,0.21,0.21,0.032,4.7e-07,4.1e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24890000,-0.28,0.017,-0.0099,0.96,-0.033,0.042,0.058,-0.04,0.032,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0059,0.22,0.22,0.032,4.7e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24990000,-0.28,0.017,-0.0097,0.96,-0.021,0.043,0.05,-0.026,0.027,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.22,0.22,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25090000,-0.28,0.017,-0.01,0.96,-0.016,0.043,0.048,-0.027,0.031,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.23,0.23,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25190000,-0.28,0.017,-0.01,0.96,-0.006,0.038,0.048,-0.011,0.021,-3.5,-0.0013,-0.0059,-0.0002,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.23,0.23,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25290000,-0.28,0.016,-0.01,0.96,-0.0013,0.041,0.043,-0.012,0.026,-3.5,-0.0013,-0.0059,-0.00021,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.24,0.24,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25390000,-0.28,0.016,-0.011,0.96,0.0076,0.039,0.041,-0.0022,0.02,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.24,0.24,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25490000,-0.28,0.016,-0.011,0.96,0.012,0.04,0.041,-0.0021,0.024,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.25,0.25,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25590000,-0.28,0.016,-0.011,0.96,0.017,0.035,0.042,0.0049,0.0094,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.25,0.25,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25690000,-0.28,0.015,-0.01,0.96,0.018,0.034,0.031,0.0066,0.013,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.26,0.26,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25790000,-0.28,0.015,-0.01,0.96,0.028,0.029,0.031,0.014,0.0031,-3.5,-0.0014,-0.0058,-0.00025,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.26,0.032,4.2e-07,3.7e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25890000,-0.28,0.015,-0.01,0.96,0.034,0.029,0.033,0.017,0.0067,-3.5,-0.0014,-0.0058,-0.00026,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.27,0.27,0.032,4.2e-07,3.7e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25990000,-0.28,0.015,-0.01,0.96,0.036,0.024,0.027,0.013,-0.004,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.27,0.27,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26090000,-0.28,0.015,-0.0099,0.96,0.041,0.024,0.025,0.017,-0.0023,-3.5,-0.0014,-0.0058,-0.00027,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.28,0.28,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26190000,-0.28,0.015,-0.0098,0.96,0.046,0.015,0.021,0.02,-0.018,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.27,0.28,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26290000,-0.28,0.016,-0.0098,0.96,0.046,0.014,0.015,0.024,-0.016,-3.5,-0.0014,-0.0058,-0.00029,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.29,0.29,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26390000,-0.28,0.016,-0.0092,0.96,0.043,0.0051,0.019,0.015,-0.03,-3.5,-0.0014,-0.0058,-0.0003,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0056,0.28,0.29,0.032,4e-07,3.5e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26490000,-0.28,0.016,-0.009,0.96,0.046,0.0028,0.028,0.02,-0.03,-3.5,-0.0014,-0.0058,-0.00031,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.3,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26590000,-0.28,0.016,-0.0084,0.96,0.045,-0.0071,0.029,0.019,-0.042,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0056,0.29,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26690000,-0.28,0.016,-0.0083,0.96,0.047,-0.011,0.027,0.023,-0.042,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.31,0.31,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26790000,-0.27,0.015,-0.0081,0.96,0.049,-0.017,0.027,0.02,-0.055,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.3,0.31,0.031,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26890000,-0.27,0.015,-0.0074,0.96,0.055,-0.02,0.022,0.026,-0.057,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.32,0.32,0.032,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26990000,-0.27,0.016,-0.0069,0.96,0.056,-0.026,0.021,0.018,-0.064,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.31,0.32,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27090000,-0.27,0.016,-0.0067,0.96,0.058,-0.033,0.025,0.024,-0.067,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0055,0.33,0.33,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27190000,-0.27,0.016,-0.0068,0.96,0.058,-0.036,0.027,0.014,-0.069,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.32,0.33,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27290000,-0.27,0.017,-0.0069,0.96,0.066,-0.041,0.14,0.02,-0.073,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.022,0.024,0.0055,0.33,0.34,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27390000,-0.27,0.019,-0.0081,0.96,0.07,-0.034,0.46,0.0048,-0.026,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27490000,-0.27,0.021,-0.0093,0.96,0.076,-0.037,0.78,0.012,-0.029,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.016,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27590000,-0.27,0.02,-0.0093,0.96,0.067,-0.039,0.87,0.0064,-0.02,-3.4,-0.0014,-0.0058,-0.00032,0.074,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.014,0.015,0.0055,0.096,0.097,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27690000,-0.27,0.017,-0.0084,0.96,0.061,-0.036,0.78,0.013,-0.024,-3.3,-0.0014,-0.0058,-0.00031,0.075,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0055,0.1,0.1,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
27790000,-0.27,0.016,-0.0072,0.96,0.058,-0.034,0.77,0.01,-0.019,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.013,0.015,0.0054,0.073,0.074,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
27890000,-0.27,0.016,-0.0068,0.96,0.064,-0.04,0.81,0.016,-0.023,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.014,0.016,0.0055,0.076,0.077,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
27990000,-0.27,0.016,-0.0072,0.96,0.064,-0.042,0.8,0.019,-0.026,-3.1,-0.0014,-0.0058,-0.00029,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0054,0.079,0.079,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28090000,-0.27,0.016,-0.0075,0.96,0.068,-0.043,0.8,0.026,-0.03,-3,-0.0014,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.082,0.083,0.031,3.6e-07,3.1e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28190000,-0.27,0.016,-0.0069,0.96,0.065,-0.041,0.81,0.027,-0.032,-2.9,-0.0013,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.085,0.085,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28290000,-0.27,0.017,-0.0064,0.96,0.069,-0.044,0.81,0.033,-0.037,-2.9,-0.0013,-0.0058,-0.00027,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.016,0.018,0.0054,0.089,0.09,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28390000,-0.27,0.017,-0.0063,0.96,0.07,-0.046,0.81,0.035,-0.038,-2.8,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0054,0.091,0.092,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28490000,-0.27,0.018,-0.0066,0.96,0.073,-0.049,0.81,0.043,-0.042,-2.7,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.095,0.097,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
28590000,-0.27,0.018,-0.0066,0.96,0.065,-0.049,0.81,0.043,-0.045,-2.6,-0.0013,-0.0058,-0.00023,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.098,0.099,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28690000,-0.27,0.017,-0.0064,0.96,0.064,-0.05,0.81,0.05,-0.05,-2.6,-0.0013,-0.0058,-0.00024,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.017,0.019,0.0054,0.1,0.1,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28790000,-0.27,0.017,-0.0058,0.96,0.062,-0.049,0.81,0.051,-0.049,-2.5,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.11,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28890000,-0.27,0.016,-0.0056,0.96,0.065,-0.051,0.81,0.057,-0.054,-2.4,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.02,0.0054,0.11,0.11,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28990000,-0.27,0.016,-0.0054,0.96,0.063,-0.048,0.81,0.058,-0.054,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.017,0.019,0.0053,0.11,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29090000,-0.27,0.017,-0.0052,0.96,0.067,-0.05,0.81,0.066,-0.059,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29190000,-0.27,0.017,-0.0051,0.96,0.067,-0.049,0.8,0.067,-0.058,-2.2,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29290000,-0.27,0.017,-0.0054,0.96,0.071,-0.054,0.81,0.076,-0.062,-2.1,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.021,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29390000,-0.27,0.016,-0.0059,0.96,0.067,-0.051,0.81,0.074,-0.059,-2,-0.0013,-0.0058,-0.00014,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29490000,-0.27,0.016,-0.0059,0.96,0.07,-0.052,0.81,0.081,-0.065,-2,-0.0013,-0.0058,-0.00013,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29590000,-0.27,0.016,-0.0058,0.96,0.068,-0.05,0.81,0.08,-0.063,-1.9,-0.0013,-0.0058,-0.00011,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.018,0.021,0.0053,0.14,0.14,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
29690000,-0.27,0.016,-0.0058,0.96,0.072,-0.049,0.81,0.087,-0.068,-1.8,-0.0013,-0.0058,-9.8e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.019,0.022,0.0053,0.15,0.15,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29790000,-0.27,0.016,-0.0056,0.96,0.069,-0.042,0.8,0.084,-0.064,-1.7,-0.0013,-0.0058,-6.9e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0053,0.15,0.15,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29890000,-0.27,0.016,-0.005,0.96,0.07,-0.044,0.8,0.092,-0.069,-1.7,-0.0013,-0.0058,-6.2e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0053,0.15,0.16,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29990000,-0.27,0.016,-0.0052,0.96,0.065,-0.041,0.8,0.087,-0.068,-1.6,-0.0013,-0.0058,-4.8e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.16,0.16,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30090000,-0.27,0.017,-0.0053,0.96,0.067,-0.041,0.8,0.094,-0.07,-1.5,-0.0013,-0.0058,-6.2e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.16,0.17,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30190000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.089,-0.061,-1.5,-0.0013,-0.0058,-5e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.17,0.17,0.031,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30290000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.096,-0.065,-1.4,-0.0013,-0.0058,-4.9e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.17,0.18,0.03,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30390000,-0.27,0.016,-0.0054,0.96,0.059,-0.029,0.8,0.095,-0.059,-1.3,-0.0013,-0.0058,-1.9e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.18,0.18,0.03,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30490000,-0.27,0.016,-0.0054,0.96,0.063,-0.028,0.8,0.1,-0.062,-1.2,-0.0013,-0.0058,-1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.18,0.19,0.031,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30590000,-0.27,0.017,-0.0056,0.96,0.061,-0.026,0.8,0.097,-0.058,-1.2,-0.0013,-0.0058,1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.18,0.19,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30690000,-0.27,0.017,-0.006,0.96,0.058,-0.026,0.8,0.1,-0.061,-1.1,-0.0013,-0.0058,1.1e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00035,0.044,0.02,0.023,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30790000,-0.27,0.016,-0.0058,0.96,0.052,-0.016,0.8,0.095,-0.049,-1,-0.0012,-0.0058,3.6e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30890000,-0.27,0.016,-0.0052,0.96,0.051,-0.012,0.79,0.099,-0.05,-0.95,-0.0012,-0.0058,2.6e-05,0.072,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30990000,-0.27,0.016,-0.0054,0.96,0.046,-0.01,0.79,0.095,-0.048,-0.88,-0.0012,-0.0058,3e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
31090000,-0.27,0.016,-0.0055,0.96,0.045,-0.0087,0.79,0.099,-0.049,-0.81,-0.0012,-0.0058,2.2e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.21,0.22,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
31190000,-0.27,0.017,-0.0057,0.96,0.042,-0.0051,0.8,0.093,-0.044,-0.74,-0.0012,-0.0058,4.6e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
31290000,-0.27,0.017,-0.0059,0.96,0.039,-0.0033,0.8,0.096,-0.045,-0.67,-0.0012,-0.0058,5.2e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
31390000,-0.27,0.016,-0.0057,0.96,0.035,0.0017,0.8,0.09,-0.042,-0.59,-0.0012,-0.0058,5.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
31490000,-0.27,0.017,-0.0054,0.96,0.036,0.0051,0.8,0.095,-0.041,-0.52,-0.0012,-0.0058,4.8e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
31590000,-0.27,0.017,-0.0052,0.96,0.036,0.007,0.8,0.092,-0.037,-0.45,-0.0012,-0.0058,6.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
31690000,-0.27,0.017,-0.0052,0.96,0.04,0.0082,0.8,0.097,-0.037,-0.38,-0.0012,-0.0058,7.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31790000,-0.27,0.018,-0.0054,0.96,0.034,0.014,0.8,0.093,-0.027,-0.3,-0.0012,-0.0058,9e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31890000,-0.27,0.018,-0.0052,0.96,0.032,0.016,0.8,0.097,-0.025,-0.23,-0.0012,-0.0058,9.4e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.25,0.26,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31990000,-0.27,0.017,-0.0055,0.96,0.029,0.017,0.79,0.094,-0.02,-0.17,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32090000,-0.27,0.017,-0.0059,0.96,0.03,0.021,0.8,0.098,-0.018,-0.096,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32190000,-0.27,0.017,-0.0061,0.96,0.027,0.029,0.8,0.093,-0.0092,-0.027,-0.0012,-0.0058,9.7e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32290000,-0.27,0.017,-0.006,0.96,0.027,0.031,0.8,0.096,-0.0063,0.042,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32390000,-0.27,0.017,-0.0062,0.96,0.023,0.033,0.79,0.092,-0.0029,0.12,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32490000,-0.27,0.016,-0.0092,0.96,-0.017,0.092,-0.077,0.091,0.0054,0.12,-0.0012,-0.0058,9.6e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.025,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32590000,-0.27,0.016,-0.0092,0.96,-0.014,0.09,-0.08,0.091,-0.0025,0.1,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.021,0.023,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32690000,-0.27,0.016,-0.0092,0.96,-0.01,0.097,-0.081,0.09,0.0069,0.088,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32790000,-0.27,0.016,-0.009,0.96,-0.0062,0.095,-0.082,0.092,-0.0016,0.073,-0.0012,-0.0058,7.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32890000,-0.27,0.016,-0.009,0.96,-0.0066,0.1,-0.084,0.09,0.0078,0.058,-0.0012,-0.0058,8.1e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32990000,-0.27,0.016,-0.0088,0.96,-0.0026,0.095,-0.083,0.091,-0.006,0.044,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33090000,-0.27,0.016,-0.0088,0.96,0.0013,0.1,-0.08,0.091,0.0037,0.037,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.31,0.32,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33190000,-0.27,0.016,-0.0086,0.96,0.0057,0.096,-0.079,0.092,-0.012,0.029,-0.0012,-0.0058,4e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33290000,-0.27,0.016,-0.0087,0.96,0.0098,0.099,-0.079,0.093,-0.0027,0.021,-0.0013,-0.0058,5.7e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33390000,-0.27,0.016,-0.0086,0.96,0.014,0.095,-0.077,0.092,-0.012,0.012,-0.0013,-0.0058,4.6e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33490000,-0.27,0.016,-0.0086,0.96,0.02,0.099,-0.076,0.095,-0.0019,0.0028,-0.0013,-0.0058,5.4e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.33,0.34,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33590000,-0.27,0.016,-0.0084,0.96,0.023,0.096,-0.073,0.094,-0.015,-0.0051,-0.0013,-0.0058,4.8e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.33,0.34,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33690000,-0.27,0.016,-0.0084,0.96,0.026,0.099,-0.074,0.095,-0.0061,-0.013,-0.0013,-0.0058,5.3e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.34,0.35,0.03,2.7e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33790000,-0.27,0.016,-0.0083,0.96,0.029,0.096,-0.068,0.092,-0.02,-0.02,-0.0013,-0.0058,3.3e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.34,0.35,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33890000,-0.27,0.016,-0.0083,0.96,0.033,0.097,-0.068,0.095,-0.01,-0.027,-0.0013,-0.0058,4.8e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
33990000,-0.27,0.016,-0.0082,0.96,0.036,0.095,-0.064,0.094,-0.019,-0.03,-0.0013,-0.0057,3.3e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
34090000,-0.27,0.016,-0.0081,0.96,0.039,0.1,-0.063,0.097,-0.0094,-0.035,-0.0013,-0.0057,3.6e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
34190000,-0.27,0.016,-0.0081,0.96,0.04,0.096,-0.06,0.092,-0.021,-0.038,-0.0013,-0.0057,3e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.022,0.005,0.36,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
34290000,-0.26,0.016,-0.0079,0.96,0.041,0.1,-0.059,0.096,-0.012,-0.044,-0.0013,-0.0057,4e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.005,0.37,0.38,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
34390000,-0.26,0.016,-0.0078,0.96,0.043,0.095,-0.054,0.091,-0.023,-0.048,-0.0013,-0.0057,3e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.02,0.022,0.005,0.37,0.37,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00062,0.0012,1,1
34490000,-0.26,0.016,-0.0079,0.96,0.046,0.099,-0.052,0.095,-0.014,-0.051,-0.0013,-0.0057,4.2e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.021,0.023,0.005,0.38,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34590000,-0.26,0.016,-0.0078,0.96,0.049,0.092,0.74,0.09,-0.028,-0.022,-0.0013,-0.0057,3e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.38,0.38,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34690000,-0.26,0.015,-0.0078,0.96,0.058,0.092,1.7,0.095,-0.019,0.097,-0.0013,-0.0057,3.5e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.0051,0.39,0.4,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34790000,-0.26,0.015,-0.0077,0.96,0.063,0.086,2.7,0.088,-0.032,0.28,-0.0013,-0.0057,2.6e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.021,0.005,0.39,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34890000,-0.26,0.015,-0.0077,0.96,0.071,0.086,3.7,0.094,-0.023,0.57,-0.0013,-0.0057,3.2e-05,0.079,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.021,0.023,0.005,0.4,0.41,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-1.5e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00094,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-4.7e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.011,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,-1.3e-09,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.5e-07,-1.7e-07,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.8e-07,-1.8e-07,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,-5.2e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00062,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,-5.1e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.00079,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1.2e-06,-7.4e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00052,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00067,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1.2e-06,-7.4e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00064,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00067,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,-1.8e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00045,0.93,0.92,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.7e-05,-1.3e-05,-2.2e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00053,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1290000,1,-0.012,-0.014,0.00041,0.019,-0.018,-0.11,0.002,-0.0024,-0.048,-0.00016,-9.4e-05,2.9e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.025,0.026,0.0004,0.88,0.88,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9e-05,2.8e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00046,1.2,1.1,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1490000,1,-0.012,-0.014,0.00037,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.1e-05,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00036,0.95,0.94,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00038,-0.00032,1.1e-05,0,0,-0.0015,0,0,0,0,0,0,0,0,0.029,0.029,0.00041,1.3,1.3,0.23,0.21,0.2,0.14,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1690000,1,-0.012,-0.014,0.00042,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00072,-0.00072,2.4e-05,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.00033,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1790000,1,-0.012,-0.014,0.00038,0.036,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00072,-0.00072,2.4e-05,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00037,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1890000,1,-0.012,-0.014,0.00037,0.043,-0.025,-0.14,0.012,-0.0084,-0.075,-0.00071,-0.00071,2.4e-05,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00041,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
1990000,1,-0.011,-0.014,0.00036,0.035,-0.018,-0.14,0.0082,-0.0054,-0.074,-0.0011,-0.0012,3.8e-05,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00033,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2090000,1,-0.011,-0.014,0.00039,0.042,-0.02,-0.14,0.012,-0.0074,-0.071,-0.0011,-0.0012,3.8e-05,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00037,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2190000,1,-0.011,-0.014,0.00032,0.033,-0.014,-0.14,0.0081,-0.0044,-0.077,-0.0014,-0.0018,5e-05,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.0003,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,8.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2290000,1,-0.011,-0.014,0.00031,0.038,-0.014,-0.14,0.012,-0.0058,-0.075,-0.0014,-0.0018,5e-05,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00033,1.5,1.5,0.11,0.29,0.29,0.1,0.0055,0.0055,8.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2390000,1,-0.011,-0.013,0.00031,0.03,-0.01,-0.14,0.0076,-0.0034,-0.072,-0.0017,-0.0023,5.9e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00027,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,7e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2490000,1,-0.011,-0.014,0.00039,0.033,-0.009,-0.14,0.011,-0.0044,-0.079,-0.0017,-0.0023,5.9e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.0003,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,7e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2590000,1,-0.01,-0.013,0.00028,0.023,-0.0061,-0.15,0.0066,-0.0024,-0.084,-0.0018,-0.0027,6.4e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00025,0.88,0.88,0.099,0.18,0.18,0.094,0.0038,0.0038,5.7e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2690000,1,-0.01,-0.013,0.00032,0.027,-0.0052,-0.15,0.0092,-0.003,-0.084,-0.0018,-0.0027,6.4e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00027,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,5.7e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2790000,1,-0.01,-0.013,0.00025,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,6.7e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.012,0.012,0.00023,0.75,0.75,0.095,0.16,0.16,0.089,0.0032,0.0032,4.7e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2890000,1,-0.01,-0.013,0.00017,0.026,-0.0046,-0.14,0.0083,-0.0021,-0.081,-0.0019,-0.003,6.7e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00025,0.93,0.93,0.096,0.23,0.23,0.089,0.0032,0.0032,4.7e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
2990000,1,-0.01,-0.013,0.00017,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,6.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.01,0.01,0.00022,0.66,0.66,0.095,0.15,0.15,0.088,0.0027,0.0027,3.9e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3090000,1,-0.01,-0.013,0.00037,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,6.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.81,0.81,0.095,0.22,0.22,0.086,0.0027,0.0027,3.9e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3190000,1,-0.01,-0.013,0.00041,0.02,-0.006,-0.15,0.0052,-0.0013,-0.097,-0.0021,-0.0036,6.8e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0089,0.0089,0.0002,0.58,0.58,0.096,0.14,0.14,0.087,0.0023,0.0023,3.3e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3290000,1,-0.01,-0.013,0.00042,0.023,-0.0061,-0.15,0.0074,-0.002,-0.11,-0.0021,-0.0036,6.8e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0097,0.0097,0.00022,0.71,0.71,0.095,0.2,0.2,0.086,0.0023,0.0023,3.3e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3390000,1,-0.0097,-0.013,0.00043,0.019,-0.0031,-0.15,0.005,-0.0013,-0.1,-0.0021,-0.0038,6.8e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0079,0.0079,0.00019,0.52,0.52,0.095,0.14,0.14,0.085,0.002,0.002,2.8e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3490000,1,-0.0097,-0.013,0.00041,0.025,-0.0017,-0.15,0.0072,-0.0015,-0.1,-0.0021,-0.0038,6.9e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.0002,0.64,0.64,0.095,0.19,0.19,0.086,0.002,0.002,2.8e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3590000,1,-0.0095,-0.012,0.00035,0.021,-0.0012,-0.15,0.0051,-0.00089,-0.11,-0.0022,-0.004,6.8e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.48,0.48,0.094,0.13,0.13,0.086,0.0017,0.0017,2.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3690000,1,-0.0095,-0.013,0.00033,0.024,-0.00046,-0.15,0.0074,-0.001,-0.11,-0.0022,-0.004,6.8e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.58,0.58,0.093,0.17,0.17,0.085,0.0017,0.0017,2.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3790000,1,-0.0094,-0.012,0.00034,0.02,0.0039,-0.15,0.0051,-0.00043,-0.11,-0.0022,-0.0043,6.6e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.44,0.44,0.093,0.12,0.12,0.086,0.0014,0.0014,2.1e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3890000,1,-0.0093,-0.012,0.00042,0.021,0.0052,-0.14,0.0072,4e-05,-0.11,-0.0022,-0.0043,6.6e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0068,0.0069,0.00018,0.53,0.53,0.091,0.16,0.16,0.086,0.0014,0.0014,2.1e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3990000,1,-0.0093,-0.013,0.00048,0.026,0.005,-0.14,0.0096,0.0005,-0.11,-0.0022,-0.0043,6.6e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0074,0.0074,0.00019,0.65,0.65,0.089,0.22,0.22,0.085,0.0014,0.0014,2.1e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4090000,1,-0.0093,-0.012,0.00054,0.022,0.0043,-0.12,0.0071,0.00068,-0.098,-0.0022,-0.0045,6.4e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0061,0.0061,0.00017,0.49,0.49,0.087,0.16,0.16,0.085,0.0012,0.0012,1.8e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4190000,1,-0.0094,-0.012,0.00049,0.024,0.0041,-0.12,0.0094,0.0011,-0.1,-0.0022,-0.0045,6.4e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0066,0.0066,0.00018,0.59,0.6,0.086,0.21,0.21,0.086,0.0012,0.0012,1.8e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4290000,1,-0.0095,-0.012,0.0005,0.021,0.0039,-0.12,0.0068,0.00091,-0.11,-0.0021,-0.0047,6.2e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00016,0.46,0.46,0.084,0.15,0.15,0.085,0.00094,0.00094,1.6e-05,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4390000,1,-0.0094,-0.012,0.00045,0.025,0.0025,-0.11,0.0091,0.0012,-0.094,-0.0021,-0.0047,6.2e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.0058,0.0058,0.00017,0.55,0.55,0.081,0.2,0.2,0.084,0.00094,0.00094,1.6e-05,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4490000,1,-0.0094,-0.012,0.0005,0.02,0.0041,-0.11,0.0067,0.00094,-0.095,-0.0021,-0.0048,5.9e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00015,0.42,0.42,0.08,0.14,0.14,0.085,0.00077,0.00077,1.4e-05,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4590000,1,-0.0094,-0.012,0.00056,0.023,0.003,-0.11,0.0089,0.0013,-0.098,-0.0021,-0.0048,5.9e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.51,0.51,0.077,0.19,0.19,0.084,0.00077,0.00077,1.4e-05,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4690000,1,-0.0094,-0.012,0.00049,0.017,0.0031,-0.1,0.0065,0.00095,-0.09,-0.0021,-0.005,5.7e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.004,0.004,0.00015,0.39,0.39,0.074,0.14,0.14,0.083,0.00062,0.00062,1.3e-05,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4790000,1,-0.0093,-0.012,0.00058,0.015,0.0053,-0.099,0.0081,0.0014,-0.092,-0.0021,-0.005,5.7e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0043,0.0043,0.00015,0.47,0.47,0.073,0.18,0.18,0.084,0.00062,0.00062,1.3e-05,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4890000,1,-0.0093,-0.012,0.00061,0.0099,0.0027,-0.093,0.0053,0.0011,-0.088,-0.0021,-0.0052,5.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0035,0.0035,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00049,0.00049,1.1e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4990000,1,-0.0092,-0.012,0.00059,0.013,0.0034,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0052,5.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00049,0.00049,1.1e-05,0.04,0.04,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5090000,1,-0.0091,-0.011,0.00066,0.01,0.0036,-0.082,0.0045,0.001,-0.081,-0.002,-0.0053,5.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.33,0.33,0.065,0.12,0.12,0.082,0.00039,0.00039,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5190000,1,-0.0089,-0.012,0.0007,0.0096,0.0072,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0053,5.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00039,0.00039,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5290000,1,-0.0089,-0.011,0.00075,0.0079,0.0072,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00013,0.31,0.31,0.06,0.12,0.12,0.08,0.00031,0.00031,9.1e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5390000,1,-0.0088,-0.011,0.00074,0.0074,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00014,0.36,0.36,0.057,0.15,0.15,0.079,0.00031,0.00031,9.1e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5490000,1,-0.0089,-0.011,0.00073,0.0069,0.012,-0.06,0.0031,0.002,-0.065,-0.002,-0.0054,5e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.28,0.28,0.056,0.11,0.11,0.079,0.00025,0.00025,8.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5590000,1,-0.0089,-0.011,0.00066,0.0081,0.015,-0.053,0.0039,0.0034,-0.058,-0.002,-0.0054,5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00025,0.00025,8.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5690000,1,-0.0089,-0.011,0.00055,0.0074,0.015,-0.052,0.0028,0.0029,-0.055,-0.0019,-0.0054,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.26,0.26,0.051,0.11,0.11,0.076,0.00019,0.00019,7.5e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5790000,1,-0.0088,-0.011,0.0005,0.0087,0.018,-0.049,0.0036,0.0046,-0.053,-0.0019,-0.0054,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00019,0.00019,7.5e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5890000,1,-0.0088,-0.011,0.00053,0.0092,0.015,-0.048,0.0027,0.0037,-0.056,-0.0018,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.24,0.24,0.047,0.1,0.1,0.075,0.00015,0.00015,6.8e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5990000,1,-0.0088,-0.011,0.00049,0.011,0.016,-0.041,0.0037,0.0053,-0.05,-0.0018,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00012,0.27,0.27,0.045,0.13,0.13,0.074,0.00015,0.00015,6.8e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6090000,1,-0.0088,-0.011,0.0003,0.011,0.018,-0.039,0.0048,0.007,-0.047,-0.0018,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00013,0.32,0.32,0.044,0.17,0.17,0.074,0.00015,0.00015,6.8e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6190000,1,-0.0089,-0.011,0.0003,0.0085,0.016,-0.038,0.0037,0.0056,-0.047,-0.0018,-0.0055,4.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.25,0.25,0.042,0.13,0.13,0.073,0.00012,0.00012,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6290000,1,-0.0089,-0.011,0.00032,0.0078,0.019,-0.041,0.0046,0.0073,-0.053,-0.0018,-0.0055,4.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.29,0.29,0.04,0.16,0.16,0.072,0.00012,0.00012,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6390000,-0.29,0.025,-0.0062,0.96,-0.0089,0.0093,-0.042,0.0041,0.0051,-0.056,-0.0017,-0.0055,4.3e-05,0,0,-0.12,-0.095,-0.021,0.51,0.072,-0.027,-0.063,0,0,0.0012,0.0012,0.066,0.2,0.2,0.039,0.12,0.12,0.072,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0038,0.0014,0.00037,0.0014,0.0014,0.0011,0.0014,1,1
6490000,-0.29,0.026,-0.0062,0.96,-0.027,0.0035,-0.039,0.0048,0.0045,-0.053,-0.0017,-0.0054,4.3e-05,0,0,-0.13,-0.1,-0.022,0.51,0.076,-0.028,-0.067,0,0,0.0012,0.0012,0.056,0.2,0.2,0.038,0.15,0.15,0.07,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0036,0.0013,0.00021,0.0013,0.0013,0.00096,0.0013,1,1
6590000,-0.29,0.026,-0.0062,0.96,-0.047,-0.0062,-0.041,0.004,0.003,-0.056,-0.0016,-0.0053,4.3e-05,-0.0003,0.00015,-0.13,-0.1,-0.022,0.5,0.077,-0.029,-0.068,0,0,0.0012,0.0012,0.054,0.21,0.21,0.036,0.18,0.18,0.069,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0033,0.0013,0.00016,0.0013,0.0013,0.00093,0.0013,1,1
6690000,-0.29,0.026,-0.0061,0.96,-0.066,-0.015,-0.043,0.0003,0.00035,-0.057,-0.0016,-0.0052,4.3e-05,-0.00055,0.00035,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0012,0.0012,0.052,0.21,0.21,0.035,0.22,0.22,0.068,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0031,0.0013,0.00014,0.0013,0.0013,0.00092,0.0013,1,1
6790000,-0.29,0.026,-0.0061,0.96,-0.087,-0.026,-0.041,-0.0024,-0.0041,-0.057,-0.0015,-0.0051,4.3e-05,-0.0011,0.00062,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0012,0.051,0.22,0.22,0.034,0.26,0.26,0.068,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.003,0.0013,0.00013,0.0013,0.0013,0.00091,0.0013,1,1
6890000,-0.29,0.026,-0.006,0.96,-0.11,-0.032,-0.037,-0.0093,-0.0084,-0.055,-0.0014,-0.005,4.3e-05,-0.0014,0.00078,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0012,0.051,0.23,0.23,0.032,0.3,0.3,0.067,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.0028,0.0013,0.00012,0.0013,0.0013,0.00091,0.0013,1,1
6990000,-0.29,0.026,-0.0059,0.96,-0.13,-0.04,-0.035,-0.018,-0.013,-0.054,-0.0014,-0.0049,4.4e-05,-0.0017,0.00089,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0013,0.05,0.24,0.24,0.031,0.35,0.35,0.066,9.7e-05,9.7e-05,5.8e-06,0.04,0.04,0.0026,0.0013,0.00011,0.0013,0.0013,0.0009,0.0013,1,1
7090000,-0.29,0.026,-0.0058,0.96,-0.15,-0.051,-0.035,-0.031,-0.018,-0.055,-0.0014,-0.0049,4.4e-05,-0.0018,0.00089,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0013,0.05,0.25,0.25,0.03,0.4,0.4,0.066,9.6e-05,9.6e-05,5.8e-06,0.04,0.04,0.0024,0.0013,0.0001,0.0013,0.0013,0.0009,0.0013,1,1
7190000,-0.29,0.026,-0.0058,0.96,-0.18,-0.061,-0.034,-0.045,-0.027,-0.058,-0.0014,-0.0048,4.3e-05,-0.0021,0.0011,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.27,0.27,0.029,0.46,0.46,0.065,9.5e-05,9.5e-05,5.8e-06,0.04,0.04,0.0023,0.0013,9.8e-05,0.0013,0.0013,0.0009,0.0013,1,1
7290000,-0.29,0.026,-0.0057,0.96,-0.2,-0.07,-0.031,-0.065,-0.032,-0.053,-0.0014,-0.0049,4.4e-05,-0.002,0.0011,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.29,0.29,0.028,0.51,0.51,0.064,9.4e-05,9.3e-05,5.8e-06,0.04,0.04,0.0022,0.0013,9.4e-05,0.0013,0.0013,0.0009,0.0013,1,1
7390000,-0.29,0.026,-0.0056,0.96,-0.23,-0.077,-0.029,-0.089,-0.037,-0.051,-0.0014,-0.0049,4.4e-05,-0.0019,0.00096,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0013,0.049,0.31,0.31,0.027,0.58,0.58,0.064,9.2e-05,9.1e-05,5.8e-06,0.04,0.04,0.002,0.0013,9.1e-05,0.0013,0.0013,0.0009,0.0013,1,1
7490000,-0.29,0.026,-0.0055,0.96,-0.25,-0.086,-0.023,-0.1,-0.044,-0.044,-0.0014,-0.0048,4.8e-05,-0.0026,0.0009,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0014,0.0013,0.049,0.34,0.33,0.026,0.64,0.64,0.063,9e-05,8.9e-05,5.7e-06,0.04,0.04,0.0019,0.0013,8.9e-05,0.0013,0.0013,0.0009,0.0013,1,1
7590000,-0.29,0.026,-0.0056,0.96,-0.27,-0.096,-0.019,-0.12,-0.055,-0.039,-0.0014,-0.0047,4.9e-05,-0.003,0.001,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0014,0.0013,0.049,0.37,0.36,0.025,0.71,0.71,0.062,8.8e-05,8.7e-05,5.7e-06,0.04,0.04,0.0018,0.0013,8.7e-05,0.0013,0.0013,0.0009,0.0013,1,1
7690000,-0.29,0.027,-0.0056,0.96,-0.3,-0.11,-0.018,-0.15,-0.069,-0.035,-0.0014,-0.0046,4.9e-05,-0.0033,0.0012,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.4,0.39,0.025,0.79,0.79,0.062,8.5e-05,8.5e-05,5.7e-06,0.04,0.04,0.0017,0.0013,8.5e-05,0.0013,0.0013,0.0009,0.0013,1,1
7790000,-0.29,0.027,-0.0056,0.96,-0.32,-0.12,-0.02,-0.16,-0.091,-0.039,-0.0012,-0.0043,4.9e-05,-0.0043,0.0018,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.43,0.43,0.024,0.88,0.87,0.061,8.3e-05,8.2e-05,5.7e-06,0.04,0.04,0.0016,0.0013,8.4e-05,0.0013,0.0013,0.00089,0.0013,1,1
7890000,-0.29,0.027,-0.0056,0.96,-0.34,-0.13,-0.021,-0.19,-0.11,-0.043,-0.0012,-0.0043,4.8e-05,-0.0043,0.0019,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.47,0.46,0.023,0.96,0.96,0.06,8e-05,7.9e-05,5.7e-06,0.04,0.04,0.0015,0.0013,8.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
7990000,-0.29,0.027,-0.0055,0.96,-0.37,-0.14,-0.017,-0.24,-0.11,-0.039,-0.0013,-0.0045,4.7e-05,-0.0037,0.0016,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.51,0.5,0.022,1.1,1.1,0.059,7.7e-05,7.5e-05,5.7e-06,0.04,0.04,0.0015,0.0013,8.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
8090000,-0.29,0.027,-0.0055,0.96,-0.4,-0.15,-0.017,-0.28,-0.14,-0.041,-0.0011,-0.0045,4.1e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.56,0.55,0.022,1.2,1.2,0.059,7.4e-05,7.2e-05,5.7e-06,0.04,0.04,0.0014,0.0013,8e-05,0.0013,0.0013,0.00089,0.0013,1,1
8190000,-0.29,0.027,-0.0057,0.96,-0.022,-0.0088,-0.012,-0.29,-0.14,-0.035,-0.001,-0.0045,3.7e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.021,1e+02,1e+02,0.058,7e-05,6.9e-05,5.7e-06,0.04,0.04,0.0013,0.0013,7.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
8290000,-0.29,0.027,-0.0057,0.96,-0.049,-0.019,-0.011,-0.3,-0.15,-0.035,-0.0011,-0.0048,3.4e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.02,1e+02,1e+02,0.057,6.7e-05,6.5e-05,5.7e-06,0.04,0.04,0.0013,0.0013,7.8e-05,0.0013,0.0013,0.00089,0.0013,1,1
8390000,-0.29,0.027,-0.0056,0.96,-0.073,-0.026,-0.01,-0.3,-0.15,-0.033,-0.0011,-0.0049,3.3e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.02,51,51,0.057,6.4e-05,6.2e-05,5.7e-06,0.04,0.04,0.0012,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1
8490000,-0.29,0.027,-0.0054,0.96,-0.097,-0.037,-0.011,-0.31,-0.15,-0.038,-0.0012,-0.005,3.6e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.019,52,52,0.056,6e-05,5.9e-05,5.7e-06,0.04,0.04,0.0011,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1
8590000,-0.29,0.027,-0.0054,0.96,-0.12,-0.045,-0.006,-0.31,-0.15,-0.032,-0.0011,-0.0049,3.4e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.019,35,35,0.055,5.7e-05,5.6e-05,5.7e-06,0.04,0.04,0.0011,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1
8690000,-0.29,0.027,-0.0054,0.96,-0.15,-0.054,-0.0078,-0.32,-0.16,-0.034,-0.0012,-0.005,3.5e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0016,0.0015,0.049,25,25,0.018,37,37,0.055,5.4e-05,5.3e-05,5.7e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1
8790000,-0.29,0.027,-0.0055,0.96,-0.17,-0.061,-0.0075,-0.33,-0.16,-0.031,-0.0012,-0.0051,3.1e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,24,24,0.018,28,28,0.055,5.1e-05,5e-05,5.7e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1
8890000,-0.29,0.027,-0.0054,0.96,-0.2,-0.072,-0.0029,-0.35,-0.16,-0.025,-0.0012,-0.005,3.4e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,24,24,0.017,30,30,0.054,4.8e-05,4.7e-05,5.7e-06,0.04,0.04,0.00095,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1
8990000,-0.29,0.027,-0.0053,0.96,-0.22,-0.083,-0.0018,-0.35,-0.17,-0.027,-0.0012,-0.0048,4e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,23,23,0.017,25,25,0.054,4.6e-05,4.4e-05,5.7e-06,0.04,0.04,0.00092,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1
9090000,-0.29,0.027,-0.0051,0.96,-0.24,-0.096,-0.003,-0.37,-0.18,-0.027,-0.0014,-0.005,4.3e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,23,23,0.017,27,27,0.053,4.3e-05,4.1e-05,5.7e-06,0.04,0.04,0.00088,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
9190000,-0.29,0.027,-0.0049,0.96,-0.26,-0.1,-0.0023,-0.38,-0.18,-0.028,-0.0015,-0.005,4.6e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0016,0.0015,0.049,21,21,0.016,23,23,0.053,4e-05,3.9e-05,5.7e-06,0.04,0.04,0.00084,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
9290000,-0.29,0.027,-0.0048,0.96,-0.29,-0.12,-0.00041,-0.41,-0.19,-0.025,-0.0015,-0.0049,4.7e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,21,21,0.016,26,26,0.052,3.8e-05,3.6e-05,5.7e-06,0.04,0.04,0.00081,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
9390000,-0.29,0.027,-0.0048,0.96,-0.3,-0.12,0.0009,-0.41,-0.19,-0.025,-0.0014,-0.0049,4.2e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,19,19,0.015,22,22,0.052,3.6e-05,3.4e-05,5.7e-06,0.04,0.04,0.00078,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
9490000,-0.29,0.027,-0.0048,0.96,-0.32,-0.12,0.0026,-0.44,-0.2,-0.022,-0.0014,-0.005,4.2e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,19,19,0.015,25,25,0.051,3.3e-05,3.2e-05,5.7e-06,0.04,0.04,0.00075,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
9590000,-0.29,0.027,-0.0051,0.96,-0.33,-0.12,0.0026,-0.43,-0.2,-0.023,-0.0013,-0.0051,3.4e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,17,17,0.015,22,22,0.051,3.1e-05,3e-05,5.7e-06,0.04,0.04,0.00072,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
9690000,-0.29,0.027,-0.0052,0.96,-0.36,-0.13,0.0057,-0.47,-0.21,-0.022,-0.0012,-0.0051,3.2e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,17,17,0.014,25,25,0.051,3e-05,2.8e-05,5.7e-06,0.04,0.04,0.0007,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
9790000,-0.29,0.027,-0.0055,0.96,-0.36,-0.12,0.0043,-0.46,-0.2,-0.023,-0.0011,-0.0053,2.5e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,15,15,0.014,22,22,0.05,2.8e-05,2.7e-05,5.7e-06,0.04,0.04,0.00068,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
9890000,-0.29,0.027,-0.0054,0.96,-0.39,-0.13,0.0058,-0.49,-0.21,-0.023,-0.0011,-0.0052,2.7e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,15,15,0.014,25,25,0.049,2.6e-05,2.5e-05,5.7e-06,0.04,0.04,0.00065,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
9990000,-0.29,0.027,-0.0056,0.96,-0.41,-0.13,0.0065,-0.53,-0.22,-0.025,-0.001,-0.0053,2.2e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,15,15,0.014,28,28,0.049,2.5e-05,2.4e-05,5.7e-06,0.04,0.04,0.00063,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
10090000,-0.29,0.027,-0.0058,0.96,-0.41,-0.12,0.0077,-0.52,-0.21,-0.023,-0.00089,-0.0054,1.6e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,13,14,0.013,24,24,0.049,2.3e-05,2.2e-05,5.7e-06,0.04,0.04,0.00061,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
10190000,-0.29,0.027,-0.0061,0.96,-0.44,-0.12,0.0086,-0.56,-0.22,-0.024,-0.00074,-0.0054,1.1e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,14,14,0.013,27,27,0.048,2.2e-05,2.1e-05,5.7e-06,0.04,0.04,0.00059,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
10290000,-0.29,0.027,-0.006,0.96,-0.43,-0.12,0.0077,-0.55,-0.22,-0.023,-0.00079,-0.0053,1.3e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,12,12,0.013,24,24,0.048,2.1e-05,2e-05,5.7e-06,0.04,0.04,0.00058,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
10390000,-0.29,0.027,-0.006,0.96,-0.011,-0.0086,-0.0026,-6e-05,-0.0003,-0.022,-0.00081,-0.0053,1.5e-05,-0.0038,0.0021,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,0.25,0.25,0.56,0.25,0.25,0.049,1.9e-05,1.8e-05,5.7e-06,0.04,0.04,0.00056,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
10490000,-0.29,0.027,-0.0061,0.96,-0.04,-0.015,0.0064,-0.0026,-0.0014,-0.018,-0.00073,-0.0053,1.2e-05,-0.0038,0.0025,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,0.26,0.26,0.55,0.26,0.26,0.058,1.8e-05,1.7e-05,5.7e-06,0.04,0.04,0.00055,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
10590000,-0.29,0.027,-0.0059,0.96,-0.051,-0.014,0.012,-0.0032,-0.001,-0.016,-0.0008,-0.0053,1.4e-05,-0.0032,0.0021,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0015,0.0015,0.049,0.13,0.13,0.27,0.26,0.26,0.056,1.7e-05,1.6e-05,5.7e-06,0.039,0.039,0.00054,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
10690000,-0.29,0.027,-0.0059,0.96,-0.08,-0.02,0.015,-0.0097,-0.0027,-0.013,-0.00077,-0.0053,1.3e-05,-0.0032,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0015,0.0015,0.049,0.14,0.14,0.26,0.27,0.27,0.065,1.6e-05,1.6e-05,5.7e-06,0.039,0.039,0.00053,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
10790000,-0.29,0.027,-0.0059,0.96,-0.078,-0.023,0.013,3.2e-06,-0.0018,-0.012,-0.00079,-0.0053,1.2e-05,-0.00092,0.0011,-0.14,-0.1,-0.022,0.5,0.079,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.096,0.096,0.17,0.13,0.13,0.062,1.5e-05,1.5e-05,5.7e-06,0.039,0.039,0.00052,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1
10890000,-0.29,0.027,-0.0056,0.96,-0.1,-0.032,0.009,-0.009,-0.0046,-0.015,-0.00088,-0.0053,1.6e-05,-0.00093,0.00078,-0.14,-0.1,-0.022,0.5,0.079,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.11,0.11,0.16,0.14,0.14,0.068,1.4e-05,1.4e-05,5.7e-06,0.039,0.039,0.00051,0.0013,6.8e-05,0.0013,0.0013,0.00088,0.0013,1,1
10990000,-0.29,0.026,-0.0057,0.96,-0.093,-0.033,0.015,-0.0033,-0.0023,-0.0093,-0.0009,-0.0055,1.3e-05,0.0039,-0.00053,-0.14,-0.1,-0.023,0.5,0.079,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.084,0.084,0.12,0.091,0.091,0.065,1.4e-05,1.3e-05,5.7e-06,0.038,0.038,0.00051,0.0013,6.8e-05,0.0013,0.0013,0.00087,0.0013,1,1
11090000,-0.29,0.026,-0.0061,0.96,-0.12,-0.041,0.019,-0.014,-0.0057,-0.0055,-0.00079,-0.0054,9.2e-06,0.0038,-0.00024,-0.14,-0.1,-0.023,0.5,0.079,-0.03,-0.069,0,0,0.0014,0.0013,0.048,0.097,0.098,0.11,0.097,0.097,0.069,1.3e-05,1.2e-05,5.7e-06,0.038,0.038,0.0005,0.0013,6.8e-05,0.0013,0.0013,0.00087,0.0013,1,1
11190000,-0.29,0.025,-0.0062,0.96,-0.1,-0.036,0.026,-0.0063,-0.0032,0.00088,-0.00078,-0.0056,5e-06,0.011,-0.0022,-0.14,-0.1,-0.023,0.5,0.079,-0.03,-0.069,0,0,0.0013,0.0012,0.048,0.08,0.08,0.083,0.072,0.072,0.066,1.2e-05,1.1e-05,5.7e-06,0.037,0.037,0.0005,0.0013,6.7e-05,0.0013,0.0012,0.00086,0.0013,1,1
11290000,-0.29,0.025,-0.0062,0.96,-0.12,-0.039,0.025,-0.017,-0.0068,0.00092,-0.00078,-0.0056,3.7e-06,0.011,-0.0022,-0.14,-0.1,-0.023,0.5,0.08,-0.03,-0.069,0,0,0.0013,0.0012,0.048,0.095,0.095,0.077,0.078,0.078,0.069,1.2e-05,1.1e-05,5.7e-06,0.037,0.037,0.0005,0.0013,6.7e-05,0.0013,0.0012,0.00086,0.0013,1,1
11390000,-0.29,0.023,-0.0062,0.96,-0.1,-0.033,0.016,-0.0096,-0.0041,-0.008,-0.00082,-0.0058,1.7e-06,0.018,-0.0041,-0.14,-0.1,-0.023,0.5,0.08,-0.03,-0.069,0,0,0.0011,0.0011,0.048,0.079,0.079,0.062,0.062,0.062,0.066,1.1e-05,1e-05,5.6e-06,0.036,0.036,0.00049,0.0012,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1
11490000,-0.29,0.023,-0.0061,0.96,-0.12,-0.037,0.021,-0.021,-0.0077,-0.002,-0.00082,-0.0057,2e-06,0.018,-0.0041,-0.14,-0.1,-0.023,0.5,0.08,-0.03,-0.069,0,0,0.0011,0.0011,0.048,0.094,0.094,0.057,0.069,0.069,0.067,1e-05,9.8e-06,5.6e-06,0.036,0.036,0.00049,0.0012,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1
11590000,-0.29,0.022,-0.0062,0.96,-0.1,-0.03,0.019,-0.012,-0.0047,-0.0033,-0.00084,-0.0059,-4.5e-07,0.025,-0.0061,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.069,0,0,0.001,0.00096,0.048,0.078,0.078,0.048,0.056,0.056,0.065,9.7e-06,9.2e-06,5.6e-06,0.035,0.035,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00084,0.0013,1,1
11690000,-0.29,0.022,-0.0062,0.96,-0.12,-0.037,0.019,-0.023,-0.008,-0.0047,-0.00086,-0.0059,-1.9e-07,0.025,-0.0061,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.069,0,0,0.001,0.00096,0.048,0.092,0.093,0.044,0.063,0.063,0.066,9.2e-06,8.8e-06,5.6e-06,0.035,0.035,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00084,0.0013,1,1
11790000,-0.29,0.021,-0.0061,0.96,-0.094,-0.035,0.02,-0.013,-0.0066,-0.0019,-0.00094,-0.0059,-2.5e-07,0.031,-0.0082,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.07,0,0,0.00088,0.00085,0.048,0.076,0.076,0.037,0.053,0.053,0.063,8.7e-06,8.3e-06,5.6e-06,0.034,0.034,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1
11890000,-0.29,0.021,-0.0062,0.96,-0.11,-0.038,0.018,-0.023,-0.01,-0.0012,-0.00092,-0.006,-1.7e-06,0.031,-0.0082,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.07,0,0,0.00088,0.00085,0.047,0.089,0.089,0.034,0.06,0.06,0.063,8.3e-06,7.9e-06,5.6e-06,0.034,0.034,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00082,0.0013,1,1
11990000,-0.29,0.02,-0.0064,0.96,-0.088,-0.029,0.015,-0.016,-0.0066,-0.0049,-0.00094,-0.006,-2.3e-06,0.037,-0.0094,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.00078,0.00076,0.047,0.077,0.077,0.03,0.062,0.062,0.061,7.9e-06,7.5e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0013,0.0012,0.00081,0.0013,1,1
12090000,-0.29,0.02,-0.0064,0.96,-0.1,-0.031,0.019,-0.026,-0.0095,0.0012,-0.00091,-0.006,-2.9e-06,0.037,-0.0095,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.00078,0.00076,0.047,0.089,0.089,0.027,0.071,0.071,0.06,7.6e-06,7.2e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00081,0.0013,1,1
12190000,-0.29,0.019,-0.0064,0.96,-0.081,-0.019,0.018,-0.014,-0.0034,0.0031,-0.00087,-0.006,-5.1e-06,0.042,-0.011,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.0007,0.00068,0.047,0.071,0.071,0.024,0.057,0.057,0.058,7.2e-06,6.8e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1
12290000,-0.29,0.019,-0.0066,0.96,-0.087,-0.018,0.017,-0.022,-0.005,0.0041,-0.00084,-0.006,-6.4e-06,0.042,-0.011,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.0007,0.00068,0.047,0.081,0.081,0.022,0.065,0.065,0.058,6.9e-06,6.5e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1
12390000,-0.29,0.018,-0.0066,0.96,-0.07,-0.013,0.015,-0.012,-0.0028,-0.0019,-0.00083,-0.0061,-8.2e-06,0.046,-0.013,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00063,0.00061,0.047,0.066,0.066,0.02,0.054,0.054,0.056,6.6e-06,6.2e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00079,0.0012,1,1
12490000,-0.29,0.019,-0.0066,0.96,-0.078,-0.014,0.02,-0.02,-0.0041,0.00028,-0.00081,-0.006,-8.8e-06,0.046,-0.013,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00063,0.00061,0.047,0.075,0.075,0.018,0.062,0.062,0.055,6.3e-06,6e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00079,0.0012,1,1
12590000,-0.29,0.018,-0.0065,0.96,-0.063,-0.012,0.021,-0.0099,-0.004,0.0021,-0.00081,-0.0061,-1.1e-05,0.049,-0.015,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00058,0.00056,0.047,0.061,0.061,0.017,0.052,0.052,0.054,6.1e-06,5.7e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1
12690000,-0.29,0.018,-0.0065,0.96,-0.069,-0.01,0.021,-0.017,-0.005,0.0038,-0.0008,-0.0061,-1.2e-05,0.049,-0.015,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00058,0.00057,0.047,0.07,0.07,0.015,0.059,0.059,0.053,5.9e-06,5.5e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1
12790000,-0.29,0.017,-0.0063,0.96,-0.054,-0.016,0.022,-0.0096,-0.008,0.006,-0.00086,-0.006,-1.2e-05,0.052,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00054,0.00053,0.047,0.061,0.061,0.014,0.061,0.061,0.051,5.6e-06,5.2e-06,5.6e-06,0.031,0.031,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1
12890000,-0.29,0.017,-0.0063,0.96,-0.058,-0.017,0.023,-0.015,-0.0098,0.0091,-0.00088,-0.006,-1e-05,0.052,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00054,0.00053,0.047,0.069,0.069,0.013,0.07,0.07,0.051,5.4e-06,5.1e-06,5.6e-06,0.031,0.031,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1
12990000,-0.29,0.017,-0.0063,0.96,-0.047,-0.014,0.024,-0.0076,-0.0067,0.01,-0.00091,-0.006,-9.3e-06,0.053,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00051,0.0005,0.046,0.055,0.055,0.012,0.057,0.056,0.05,5.2e-06,4.9e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13090000,-0.29,0.017,-0.0062,0.96,-0.052,-0.016,0.021,-0.013,-0.0085,0.0093,-0.00094,-0.006,-7.6e-06,0.054,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00051,0.0005,0.046,0.062,0.062,0.011,0.065,0.065,0.049,5e-06,4.7e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13190000,-0.29,0.017,-0.0062,0.96,-0.043,-0.015,0.021,-0.0093,-0.0093,0.01,-0.00096,-0.006,-7.5e-06,0.055,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00048,0.00048,0.046,0.055,0.055,0.011,0.066,0.066,0.047,4.9e-06,4.5e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13290000,-0.29,0.017,-0.0062,0.96,-0.047,-0.015,0.018,-0.014,-0.011,0.0094,-0.00094,-0.006,-7.7e-06,0.055,-0.017,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00049,0.00048,0.046,0.061,0.061,0.01,0.075,0.075,0.047,4.7e-06,4.3e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
13390000,-0.29,0.017,-0.0062,0.96,-0.038,-0.011,0.018,-0.0071,-0.0071,0.01,-0.00092,-0.006,-9e-06,0.056,-0.017,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00046,0.00045,0.046,0.049,0.049,0.0094,0.06,0.06,0.046,4.5e-06,4.2e-06,5.6e-06,0.031,0.03,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
13490000,-0.29,0.017,-0.0062,0.96,-0.041,-0.014,0.018,-0.011,-0.0085,0.0064,-0.00092,-0.006,-8.8e-06,0.057,-0.017,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00046,0.00045,0.046,0.054,0.054,0.009,0.068,0.068,0.045,4.4e-06,4e-06,5.6e-06,0.031,0.03,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
13590000,-0.29,0.017,-0.0062,0.96,-0.033,-0.01,0.019,-0.0033,-0.0058,0.005,-0.0009,-0.006,-9.9e-06,0.058,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00045,0.00044,0.046,0.044,0.044,0.0086,0.055,0.055,0.044,4.3e-06,3.9e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
13690000,-0.29,0.016,-0.0062,0.96,-0.035,-0.0095,0.019,-0.0067,-0.0069,0.0078,-0.00091,-0.006,-9e-06,0.058,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00045,0.00044,0.046,0.049,0.049,0.0082,0.063,0.063,0.044,4.1e-06,3.8e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00075,0.0012,1,1
13790000,-0.29,0.016,-0.0062,0.96,-0.027,-0.0071,0.019,0.00082,-0.0036,0.0074,-0.00091,-0.006,-9.9e-06,0.059,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00043,0.00042,0.046,0.041,0.041,0.0078,0.052,0.052,0.042,4e-06,3.6e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
13890000,-0.29,0.016,-0.0061,0.96,-0.029,-0.0085,0.02,-0.0018,-0.0045,0.0097,-0.00094,-0.006,-8.6e-06,0.059,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00043,0.00043,0.046,0.045,0.045,0.0076,0.059,0.059,0.042,3.9e-06,3.5e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
13990000,-0.29,0.016,-0.0061,0.96,-0.028,-0.012,0.019,-0.00051,-0.0049,0.0087,-0.00095,-0.006,-7.8e-06,0.06,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00042,0.00041,0.046,0.038,0.038,0.0073,0.05,0.05,0.041,3.8e-06,3.4e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14090000,-0.29,0.016,-0.0062,0.96,-0.029,-0.0061,0.021,-0.0036,-0.0054,0.0053,-0.00089,-0.006,-1.2e-05,0.059,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00042,0.00042,0.046,0.042,0.042,0.0072,0.057,0.057,0.041,3.6e-06,3.3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14190000,-0.29,0.016,-0.0063,0.96,-0.023,-0.0046,0.021,-0.0007,-0.0041,0.0056,-0.00085,-0.006,-1.4e-05,0.06,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.00041,0.046,0.036,0.036,0.007,0.049,0.049,0.04,3.5e-06,3.2e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14290000,-0.29,0.016,-0.0062,0.96,-0.026,-0.005,0.019,-0.0032,-0.0045,0.0099,-0.00085,-0.006,-1.4e-05,0.06,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.00041,0.046,0.039,0.04,0.0069,0.055,0.055,0.039,3.4e-06,3.1e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
14390000,-0.29,0.016,-0.0062,0.96,-0.024,-0.0044,0.02,-0.00068,-0.0049,0.014,-0.00086,-0.006,-1.4e-05,0.061,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.0004,0.046,0.034,0.034,0.0067,0.048,0.048,0.039,3.3e-06,3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00073,0.0012,1,1
14490000,-0.29,0.016,-0.0064,0.96,-0.024,-0.0038,0.024,-0.0032,-0.0051,0.017,-0.00082,-0.006,-1.6e-05,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.0004,0.046,0.037,0.037,0.0066,0.054,0.054,0.038,3.2e-06,2.9e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
14590000,-0.29,0.016,-0.0065,0.96,-0.026,-0.0053,0.022,-0.0035,-0.0054,0.013,-0.00081,-0.0059,-1.7e-05,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.0004,0.046,0.032,0.032,0.0065,0.047,0.047,0.038,3.1e-06,2.8e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
14690000,-0.29,0.016,-0.0065,0.96,-0.027,-0.0056,0.022,-0.0062,-0.0061,0.013,-0.00081,-0.0059,-1.7e-05,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.0004,0.046,0.035,0.035,0.0065,0.053,0.053,0.037,3.1e-06,2.7e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
14790000,-0.29,0.016,-0.0066,0.96,-0.028,-0.0027,0.022,-0.0048,-0.0015,0.016,-0.00082,-0.0059,-1.2e-05,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.00039,0.046,0.03,0.031,0.0064,0.046,0.046,0.036,3e-06,2.6e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
14890000,-0.29,0.016,-0.0065,0.96,-0.03,-0.00081,0.027,-0.008,-0.002,0.017,-0.00083,-0.0059,-1e-05,0.063,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.00039,0.046,0.033,0.033,0.0064,0.052,0.052,0.036,2.9e-06,2.6e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
14990000,-0.29,0.016,-0.0065,0.96,-0.028,-0.0026,0.029,-0.0064,-0.003,0.019,-0.00083,-0.0058,-1e-05,0.064,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.07,0,0,0.00039,0.00039,0.046,0.029,0.029,0.0064,0.045,0.045,0.036,2.8e-06,2.5e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15090000,-0.29,0.016,-0.0065,0.96,-0.03,-0.0037,0.033,-0.0094,-0.0033,0.022,-0.00083,-0.0058,-1e-05,0.064,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.07,0,0,0.00039,0.00039,0.046,0.031,0.032,0.0064,0.051,0.051,0.035,2.7e-06,2.4e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
15190000,-0.29,0.016,-0.0066,0.96,-0.028,-0.0017,0.034,-0.0075,-0.0026,0.024,-0.00082,-0.0058,-1.2e-05,0.064,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.027,0.028,0.0064,0.045,0.045,0.035,2.7e-06,2.3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
15290000,-0.29,0.016,-0.0067,0.96,-0.031,-0.0018,0.034,-0.011,-0.0031,0.021,-0.00083,-0.0058,-9.6e-06,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00039,0.046,0.03,0.03,0.0065,0.05,0.05,0.035,2.6e-06,2.3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
15390000,-0.29,0.016,-0.0068,0.96,-0.03,-0.0036,0.033,-0.0086,-0.0026,0.022,-0.00083,-0.0058,-1e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.026,0.026,0.0065,0.044,0.044,0.034,2.5e-06,2.2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
15490000,-0.29,0.016,-0.0068,0.96,-0.031,-0.0011,0.033,-0.012,-0.0029,0.023,-0.00083,-0.0058,-1e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.028,0.028,0.0065,0.05,0.05,0.034,2.5e-06,2.2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
15590000,-0.29,0.016,-0.0068,0.96,-0.028,-0.0053,0.033,-0.0071,-0.006,0.022,-0.00086,-0.0058,-1.4e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.025,0.025,0.0065,0.044,0.044,0.034,2.4e-06,2.1e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
15690000,-0.29,0.016,-0.0067,0.96,-0.03,-0.0034,0.034,-0.0093,-0.0065,0.023,-0.00089,-0.0058,-1.2e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.027,0.027,0.0066,0.049,0.049,0.034,2.4e-06,2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
15790000,-0.29,0.016,-0.0067,0.96,-0.026,-0.002,0.033,-0.0072,-0.0055,0.024,-0.00092,-0.0058,-1e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.024,0.024,0.0066,0.043,0.043,0.033,2.3e-06,2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
15890000,-0.29,0.016,-0.0068,0.96,-0.026,-0.0032,0.034,-0.01,-0.0056,0.024,-0.0009,-0.0058,-1.2e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.026,0.026,0.0068,0.049,0.049,0.034,2.2e-06,1.9e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
15990000,-0.29,0.016,-0.0066,0.96,-0.024,-0.0026,0.031,-0.0085,-0.0047,0.024,-0.00089,-0.0058,-1.2e-05,0.065,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.023,0.023,0.0068,0.043,0.043,0.033,2.2e-06,1.9e-06,5.6e-06,0.03,0.029,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16090000,-0.29,0.016,-0.0067,0.96,-0.026,-0.0013,0.029,-0.011,-0.0048,0.024,-0.00088,-0.0058,-1.4e-05,0.066,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.024,0.025,0.0069,0.048,0.048,0.033,2.1e-06,1.8e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16190000,-0.29,0.016,-0.0067,0.96,-0.024,-0.0011,0.028,-0.01,-0.0039,0.021,-0.00086,-0.0058,-1.5e-05,0.066,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.022,0.022,0.0069,0.043,0.043,0.033,2.1e-06,1.8e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16290000,-0.29,0.016,-0.0067,0.96,-0.026,-0.00014,0.028,-0.013,-0.0041,0.022,-0.00087,-0.0058,-1.5e-05,0.066,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.023,0.024,0.007,0.048,0.048,0.033,2e-06,1.7e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16390000,-0.29,0.016,-0.0066,0.96,-0.026,-0.00048,0.028,-0.01,-0.0038,0.022,-0.00088,-0.0058,-1.4e-05,0.066,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.021,0.007,0.042,0.042,0.033,2e-06,1.7e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16490000,-0.29,0.016,-0.0068,0.96,-0.03,0.00053,0.031,-0.013,-0.0038,0.027,-0.00087,-0.0058,-1.5e-05,0.067,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.022,0.023,0.0072,0.047,0.047,0.033,1.9e-06,1.7e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
16590000,-0.29,0.016,-0.0068,0.96,-0.033,0.00097,0.034,-0.011,-0.0032,0.027,-0.00087,-0.0058,-1.6e-05,0.067,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.02,0.02,0.0072,0.042,0.042,0.033,1.9e-06,1.6e-06,5.6e-06,0.03,0.029,0.00043,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
16690000,-0.29,0.016,-0.0068,0.96,-0.037,0.0046,0.034,-0.015,-0.0031,0.028,-0.00089,-0.0058,-1.4e-05,0.067,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.022,0.0073,0.047,0.047,0.033,1.9e-06,1.6e-06,5.6e-06,0.03,0.029,0.00043,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
16790000,-0.29,0.016,-0.0067,0.96,-0.037,0.0045,0.033,-0.012,-0.0028,0.028,-0.0009,-0.0058,-1.5e-05,0.067,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.019,0.02,0.0073,0.042,0.042,0.033,1.8e-06,1.5e-06,5.6e-06,0.03,0.029,0.00043,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
16890000,-0.29,0.016,-0.0066,0.96,-0.037,0.0041,0.034,-0.016,-0.0027,0.027,-0.00093,-0.0058,-1.2e-05,0.067,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.021,0.0074,0.046,0.046,0.033,1.8e-06,1.5e-06,5.6e-06,0.03,0.029,0.00042,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
16990000,-0.29,0.016,-0.0066,0.96,-0.034,0.0046,0.034,-0.014,-0.0029,0.025,-0.00094,-0.0058,-1.4e-05,0.067,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.02,0.021,0.0074,0.049,0.049,0.033,1.7e-06,1.5e-06,5.6e-06,0.03,0.029,0.00042,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
17090000,-0.29,0.016,-0.0067,0.96,-0.039,0.0066,0.034,-0.018,-0.0024,0.025,-0.00093,-0.0058,-1.5e-05,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.022,0.022,0.0075,0.054,0.054,0.033,1.7e-06,1.4e-06,5.6e-06,0.03,0.029,0.00042,0.0012,6e-05,0.0012,0.0011,0.00071,0.0012,1,1
17190000,-0.29,0.016,-0.0068,0.96,-0.037,0.0084,0.035,-0.017,-0.004,0.028,-0.00093,-0.0058,-2.4e-05,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.022,0.0076,0.056,0.057,0.033,1.7e-06,1.4e-06,5.6e-06,0.03,0.029,0.00041,0.0012,6e-05,0.0012,0.0011,0.00071,0.0012,1,1
17290000,-0.29,0.016,-0.0068,0.96,-0.04,0.009,0.035,-0.021,-0.0029,0.028,-0.00091,-0.0058,-2.6e-05,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.023,0.023,0.0077,0.062,0.063,0.033,1.6e-06,1.4e-06,5.6e-06,0.03,0.029,0.00041,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
17390000,-0.29,0.016,-0.0068,0.96,-0.03,0.014,0.034,-0.013,-0.0015,0.028,-0.00094,-0.0058,-2.6e-05,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.02,0.0076,0.052,0.052,0.033,1.6e-06,1.3e-06,5.6e-06,0.03,0.029,0.00041,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
17490000,-0.29,0.016,-0.0068,0.96,-0.03,0.015,0.034,-0.016,7.2e-05,0.03,-0.00094,-0.0058,-2.7e-05,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.3e-06,5.6e-06,0.03,0.029,0.0004,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
17590000,-0.29,0.016,-0.0068,0.96,-0.03,0.013,0.033,-0.015,-0.00029,0.027,-0.00094,-0.0058,-3e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.018,0.019,0.0077,0.049,0.049,0.033,1.5e-06,1.3e-06,5.6e-06,0.03,0.029,0.0004,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
17690000,-0.28,0.016,-0.0069,0.96,-0.031,0.014,0.034,-0.018,0.0009,0.03,-0.00095,-0.0058,-2.9e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.2e-06,5.6e-06,0.03,0.029,0.00039,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
17790000,-0.28,0.015,-0.0069,0.96,-0.031,0.014,0.035,-0.017,0.0017,0.035,-0.00096,-0.0058,-3e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.2e-06,5.6e-06,0.03,0.029,0.00039,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
17890000,-0.28,0.016,-0.0068,0.96,-0.035,0.016,0.034,-0.02,0.0029,0.039,-0.00097,-0.0058,-2.8e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.02,0.021,0.0079,0.062,0.062,0.033,1.4e-06,1.2e-06,5.6e-06,0.03,0.029,0.00039,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
17990000,-0.28,0.016,-0.0069,0.96,-0.034,0.016,0.034,-0.016,0.0053,0.04,-0.00097,-0.0058,-2.7e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.2e-06,5.5e-06,0.03,0.029,0.00038,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
18090000,-0.28,0.016,-0.0069,0.96,-0.035,0.017,0.033,-0.02,0.0068,0.038,-0.00097,-0.0058,-2.6e-05,0.068,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.1e-06,5.5e-06,0.03,0.029,0.00038,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
18190000,-0.28,0.016,-0.0069,0.96,-0.032,0.015,0.034,-0.015,0.0047,0.036,-0.001,-0.0058,-2.8e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.016,0.017,0.0079,0.049,0.049,0.034,1.3e-06,1.1e-06,5.5e-06,0.03,0.029,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
18290000,-0.28,0.016,-0.0069,0.96,-0.035,0.015,0.033,-0.019,0.0058,0.035,-0.001,-0.0058,-2.7e-05,0.069,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.018,0.018,0.008,0.053,0.054,0.034,1.3e-06,1.1e-06,5.5e-06,0.03,0.029,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
18390000,-0.28,0.016,-0.0068,0.96,-0.031,0.014,0.032,-0.014,0.0049,0.034,-0.001,-0.0058,-3.4e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.1e-06,5.5e-06,0.03,0.029,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
18490000,-0.28,0.016,-0.0069,0.96,-0.035,0.014,0.031,-0.017,0.0059,0.036,-0.001,-0.0058,-3.1e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.017,0.018,0.008,0.05,0.051,0.034,1.3e-06,1e-06,5.5e-06,0.03,0.029,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
18590000,-0.28,0.015,-0.0067,0.96,-0.033,0.014,0.031,-0.014,0.0052,0.038,-0.001,-0.0058,-3.8e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.2e-06,1e-06,5.5e-06,0.03,0.029,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
18690000,-0.28,0.015,-0.0067,0.96,-0.033,0.013,0.029,-0.017,0.0062,0.037,-0.001,-0.0058,-3.4e-05,0.069,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1e-06,5.5e-06,0.03,0.029,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
18790000,-0.28,0.015,-0.0066,0.96,-0.03,0.012,0.029,-0.013,0.0054,0.035,-0.0011,-0.0058,-4e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0079,0.043,0.043,0.034,1.2e-06,9.8e-07,5.5e-06,0.03,0.029,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
18890000,-0.28,0.015,-0.0066,0.96,-0.03,0.013,0.027,-0.017,0.0067,0.031,-0.0011,-0.0058,-4e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.017,0.008,0.047,0.047,0.034,1.2e-06,9.6e-07,5.5e-06,0.03,0.029,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
18990000,-0.28,0.015,-0.0066,0.96,-0.028,0.013,0.028,-0.014,0.0058,0.034,-0.0011,-0.0058,-4.5e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0079,0.042,0.042,0.034,1.1e-06,9.4e-07,5.4e-06,0.03,0.029,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19090000,-0.28,0.015,-0.0066,0.96,-0.027,0.014,0.028,-0.017,0.0067,0.031,-0.0011,-0.0058,-4.2e-05,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.008,0.045,0.046,0.035,1.1e-06,9.2e-07,5.4e-06,0.03,0.029,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19190000,-0.28,0.015,-0.0066,0.96,-0.025,0.015,0.028,-0.014,0.0065,0.03,-0.0011,-0.0058,-5.2e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9e-07,5.4e-06,0.03,0.029,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
19290000,-0.28,0.015,-0.0065,0.96,-0.026,0.015,0.028,-0.017,0.0078,0.029,-0.0011,-0.0058,-5.2e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.1e-06,8.9e-07,5.4e-06,0.03,0.029,0.00032,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
19390000,-0.28,0.015,-0.0067,0.96,-0.024,0.013,0.029,-0.015,0.0076,0.028,-0.0011,-0.0058,-5.6e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0078,0.04,0.04,0.035,1.1e-06,8.7e-07,5.4e-06,0.03,0.029,0.00031,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
19490000,-0.28,0.015,-0.0067,0.96,-0.026,0.014,0.029,-0.018,0.0092,0.027,-0.0011,-0.0058,-5.9e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,8.5e-07,5.4e-06,0.03,0.029,0.00031,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
19590000,-0.28,0.015,-0.0066,0.96,-0.023,0.015,0.031,-0.016,0.0073,0.028,-0.0011,-0.0058,-7e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0078,0.039,0.039,0.035,1e-06,8.3e-07,5.4e-06,0.03,0.029,0.00031,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
19690000,-0.28,0.015,-0.0066,0.96,-0.023,0.014,0.029,-0.018,0.0082,0.027,-0.0011,-0.0058,-6.6e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0078,0.043,0.043,0.035,1e-06,8.2e-07,5.4e-06,0.03,0.029,0.0003,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
19790000,-0.28,0.015,-0.0067,0.96,-0.02,0.013,0.027,-0.018,0.0088,0.023,-0.0011,-0.0058,-7.4e-05,0.069,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0077,0.045,0.046,0.035,9.9e-07,8e-07,5.3e-06,0.03,0.029,0.0003,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
19890000,-0.28,0.015,-0.0068,0.96,-0.021,0.014,0.028,-0.02,0.01,0.022,-0.0011,-0.0058,-7.4e-05,0.069,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.017,0.0077,0.049,0.05,0.035,9.8e-07,7.9e-07,5.3e-06,0.03,0.029,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
19990000,-0.28,0.016,-0.0067,0.96,-0.018,0.015,0.025,-0.016,0.0093,0.019,-0.0011,-0.0058,-7.7e-05,0.069,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0076,0.043,0.044,0.035,9.5e-07,7.7e-07,5.3e-06,0.03,0.029,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20090000,-0.28,0.016,-0.0068,0.96,-0.021,0.017,0.025,-0.018,0.011,0.022,-0.0011,-0.0058,-7.7e-05,0.069,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0076,0.047,0.048,0.035,9.4e-07,7.7e-07,5.3e-06,0.03,0.029,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20190000,-0.28,0.016,-0.0068,0.96,-0.022,0.015,0.026,-0.019,0.011,0.021,-0.0011,-0.0058,-8.6e-05,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.017,0.0075,0.049,0.05,0.035,9.2e-07,7.5e-07,5.3e-06,0.03,0.029,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20290000,-0.28,0.016,-0.0068,0.96,-0.02,0.017,0.026,-0.021,0.013,0.022,-0.0011,-0.0058,-8.6e-05,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.018,0.0075,0.054,0.055,0.035,9.1e-07,7.4e-07,5.3e-06,0.03,0.029,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20390000,-0.28,0.016,-0.0067,0.96,-0.018,0.015,0.026,-0.021,0.012,0.023,-0.0011,-0.0058,-8.8e-05,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.018,0.0075,0.056,0.057,0.035,8.9e-07,7.2e-07,5.3e-06,0.03,0.029,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20490000,-0.28,0.016,-0.0067,0.96,-0.016,0.017,0.026,-0.023,0.013,0.021,-0.0011,-0.0058,-8.7e-05,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.017,0.019,0.0075,0.061,0.063,0.035,8.8e-07,7.2e-07,5.2e-06,0.03,0.029,0.00027,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20590000,-0.28,0.016,-0.0066,0.96,-0.016,0.017,0.025,-0.023,0.012,0.019,-0.0011,-0.0058,-8.7e-05,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.017,0.018,0.0074,0.064,0.065,0.035,8.6e-07,7e-07,5.2e-06,0.03,0.029,0.00026,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20690000,-0.28,0.016,-0.0066,0.96,-0.015,0.017,0.026,-0.024,0.014,0.02,-0.0011,-0.0058,-9e-05,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.018,0.02,0.0074,0.069,0.071,0.035,8.6e-07,6.9e-07,5.2e-06,0.029,0.029,0.00026,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20790000,-0.28,0.015,-0.0059,0.96,-0.0091,0.013,0.011,-0.018,0.01,0.019,-0.0011,-0.0058,-9.8e-05,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.017,0.0073,0.056,0.057,0.035,8.2e-07,6.7e-07,5.2e-06,0.029,0.029,0.00026,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20890000,-0.28,0.011,0.0027,0.96,-0.0045,0.0026,-0.11,-0.02,0.011,0.012,-0.0011,-0.0058,-0.0001,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00036,0.00034,0.046,0.016,0.018,0.0073,0.061,0.062,0.035,8.2e-07,6.6e-07,5.2e-06,0.029,0.029,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
20990000,-0.28,0.0069,0.0057,0.96,0.01,-0.014,-0.25,-0.016,0.0086,-0.0029,-0.0011,-0.0058,-0.00011,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.068,0,0,0.00035,0.00034,0.046,0.014,0.016,0.0072,0.051,0.052,0.034,7.9e-07,6.5e-07,5.1e-06,0.029,0.029,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1
21090000,-0.28,0.0074,0.0042,0.96,0.023,-0.026,-0.37,-0.015,0.0068,-0.033,-0.0011,-0.0058,-0.00011,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.068,0,0,0.00035,0.00034,0.046,0.015,0.017,0.0072,0.056,0.057,0.035,7.9e-07,6.4e-07,5.1e-06,0.029,0.029,0.00025,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21190000,-0.28,0.0093,0.0016,0.96,0.029,-0.032,-0.49,-0.012,0.0052,-0.07,-0.0011,-0.0058,-0.00011,0.07,-0.021,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00035,0.00033,0.046,0.014,0.016,0.0071,0.048,0.049,0.035,7.6e-07,6.2e-07,5.1e-06,0.029,0.029,0.00024,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21290000,-0.28,0.011,-0.00052,0.96,0.028,-0.034,-0.62,-0.0099,0.0028,-0.13,-0.0011,-0.0058,-0.00012,0.07,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.0071,0.052,0.053,0.035,7.6e-07,6.2e-07,5.1e-06,0.029,0.029,0.00024,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
21390000,-0.28,0.012,-0.002,0.96,0.021,-0.027,-0.75,-0.012,0.0063,-0.19,-0.0011,-0.0058,-9.2e-05,0.07,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.007,0.054,0.055,0.035,7.4e-07,6.1e-07,5e-06,0.029,0.029,0.00024,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
21490000,-0.28,0.012,-0.0027,0.96,0.014,-0.025,-0.88,-0.0094,0.0035,-0.28,-0.0011,-0.0058,-8.9e-05,0.07,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.018,0.007,0.059,0.06,0.035,7.4e-07,6e-07,5e-06,0.029,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
21590000,-0.29,0.012,-0.0033,0.96,0.0027,-0.018,-1,-0.013,0.0085,-0.37,-0.0011,-0.0058,-5.8e-05,0.07,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.018,0.0069,0.061,0.063,0.034,7.2e-07,5.9e-07,5e-06,0.029,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
21690000,-0.29,0.012,-0.0037,0.96,-0.0027,-0.014,-1.1,-0.014,0.0063,-0.48,-0.0011,-0.0058,-5.3e-05,0.07,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.017,0.02,0.0069,0.066,0.068,0.035,7.2e-07,5.8e-07,5e-06,0.029,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
21790000,-0.29,0.012,-0.0041,0.96,-0.0088,-0.0058,-1.3,-0.015,0.013,-0.6,-0.0011,-0.0058,-1.9e-05,0.07,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.017,0.02,0.0069,0.068,0.07,0.034,7e-07,5.7e-07,5e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
21890000,-0.29,0.012,-0.0044,0.96,-0.015,-0.0012,-1.4,-0.016,0.013,-0.74,-0.0011,-0.0058,-2.3e-05,0.07,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.019,0.021,0.0068,0.074,0.076,0.034,7e-07,5.7e-07,5e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
21990000,-0.29,0.013,-0.0052,0.96,-0.021,0.0071,-1.4,-0.023,0.02,-0.88,-0.001,-0.0058,6.8e-06,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.046,0.018,0.02,0.0068,0.076,0.079,0.034,6.8e-07,5.5e-07,4.9e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22090000,-0.29,0.014,-0.0058,0.96,-0.024,0.011,-1.4,-0.024,0.021,-1,-0.0011,-0.0058,1.4e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.046,0.019,0.021,0.0068,0.082,0.085,0.034,6.8e-07,5.5e-07,4.9e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22190000,-0.29,0.014,-0.0063,0.96,-0.031,0.017,-1.4,-0.028,0.028,-1.2,-0.001,-0.0058,4.1e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.021,0.0067,0.085,0.087,0.034,6.6e-07,5.4e-07,4.9e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22290000,-0.29,0.014,-0.007,0.96,-0.039,0.022,-1.4,-0.032,0.03,-1.3,-0.001,-0.0058,4e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.022,0.0067,0.091,0.094,0.034,6.5e-07,5.3e-07,4.9e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22390000,-0.29,0.014,-0.0073,0.96,-0.045,0.028,-1.4,-0.039,0.034,-1.5,-0.001,-0.0058,3.8e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0066,0.093,0.096,0.034,6.4e-07,5.2e-07,4.8e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22490000,-0.29,0.015,-0.0074,0.96,-0.052,0.035,-1.4,-0.044,0.038,-1.6,-0.001,-0.0058,3.5e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.023,0.0066,0.1,0.1,0.034,6.4e-07,5.2e-07,4.8e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22590000,-0.29,0.015,-0.0072,0.96,-0.056,0.04,-1.4,-0.045,0.041,-1.7,-0.001,-0.0058,4.2e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.022,0.0065,0.1,0.11,0.034,6.2e-07,5.1e-07,4.8e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22690000,-0.29,0.016,-0.0071,0.96,-0.061,0.045,-1.4,-0.052,0.046,-1.9,-0.001,-0.0058,4e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.023,0.0065,0.11,0.11,0.034,6.2e-07,5.1e-07,4.8e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
22790000,-0.29,0.016,-0.007,0.96,-0.068,0.05,-1.4,-0.057,0.048,-2,-0.001,-0.0058,3e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.045,0.02,0.022,0.0065,0.11,0.11,0.034,6e-07,4.9e-07,4.7e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1
22890000,-0.29,0.016,-0.0071,0.96,-0.073,0.054,-1.4,-0.064,0.052,-2.2,-0.001,-0.0058,3.9e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.12,0.12,0.034,6e-07,4.9e-07,4.7e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1
22990000,-0.28,0.017,-0.007,0.96,-0.075,0.054,-1.4,-0.067,0.051,-2.3,-0.0011,-0.0058,3.2e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.022,0.0064,0.12,0.12,0.034,5.9e-07,4.8e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1
23090000,-0.28,0.017,-0.007,0.96,-0.081,0.058,-1.4,-0.074,0.056,-2.5,-0.0011,-0.0058,3.4e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.024,0.0064,0.13,0.13,0.034,5.8e-07,4.8e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1
23190000,-0.28,0.017,-0.0068,0.96,-0.083,0.053,-1.4,-0.073,0.052,-2.6,-0.0011,-0.0058,4.8e-06,0.07,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.023,0.0063,0.13,0.13,0.033,5.7e-07,4.7e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1
23290000,-0.28,0.018,-0.0073,0.96,-0.089,0.057,-1.4,-0.082,0.057,-2.7,-0.0011,-0.0058,9.4e-06,0.07,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.024,0.0063,0.14,0.14,0.034,5.7e-07,4.7e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
23390000,-0.28,0.018,-0.0072,0.96,-0.089,0.059,-1.4,-0.076,0.058,-2.9,-0.0011,-0.0058,-1.3e-05,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.14,0.14,0.033,5.5e-07,4.6e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
23490000,-0.28,0.018,-0.0072,0.96,-0.095,0.06,-1.4,-0.087,0.063,-3,-0.0011,-0.0058,-3.6e-06,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.024,0.0063,0.15,0.15,0.033,5.5e-07,4.5e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
23590000,-0.28,0.018,-0.0074,0.96,-0.094,0.053,-1.4,-0.082,0.053,-3.2,-0.0011,-0.0058,-3.5e-05,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0062,0.15,0.15,0.033,5.4e-07,4.5e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
23690000,-0.28,0.018,-0.0079,0.96,-0.092,0.055,-1.3,-0.091,0.057,-3.3,-0.0011,-0.0058,-2.6e-05,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.024,0.0062,0.16,0.16,0.033,5.4e-07,4.4e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
23790000,-0.28,0.021,-0.0094,0.96,-0.077,0.052,-0.95,-0.081,0.052,-3.4,-0.0012,-0.0058,-4e-05,0.069,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00039,0.00036,0.045,0.02,0.023,0.0061,0.16,0.16,0.033,5.3e-07,4.4e-07,4.4e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
23890000,-0.28,0.026,-0.012,0.96,-0.07,0.053,-0.52,-0.088,0.057,-3.5,-0.0012,-0.0058,-3.5e-05,0.069,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,0.00041,0.00038,0.045,0.021,0.023,0.0061,0.17,0.17,0.033,5.3e-07,4.3e-07,4.4e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
23990000,-0.28,0.028,-0.014,0.96,-0.061,0.051,-0.13,-0.076,0.051,-3.6,-0.0012,-0.0058,-5.7e-05,0.07,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,0.00043,0.0004,0.045,0.02,0.022,0.0061,0.17,0.17,0.033,5.1e-07,4.3e-07,4.4e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24090000,-0.28,0.027,-0.014,0.96,-0.067,0.058,0.1,-0.081,0.057,-3.6,-0.0012,-0.0058,-5.5e-05,0.07,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,0.00042,0.0004,0.045,0.021,0.023,0.0061,0.18,0.18,0.033,5.1e-07,4.2e-07,4.4e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24190000,-0.28,0.023,-0.011,0.96,-0.071,0.055,0.09,-0.069,0.044,-3.6,-0.0012,-0.0058,-8.4e-05,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.0004,0.00037,0.045,0.02,0.022,0.006,0.18,0.18,0.033,5e-07,4.2e-07,4.3e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24290000,-0.28,0.019,-0.0092,0.96,-0.076,0.057,0.068,-0.076,0.049,-3.6,-0.0012,-0.0058,-7.9e-05,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.023,0.006,0.19,0.19,0.033,5e-07,4.2e-07,4.3e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24390000,-0.28,0.018,-0.0085,0.96,-0.059,0.05,0.084,-0.057,0.039,-3.6,-0.0012,-0.0059,-9.7e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00035,0.045,0.02,0.023,0.006,0.19,0.19,0.033,4.9e-07,4.1e-07,4.3e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24490000,-0.28,0.018,-0.0087,0.96,-0.054,0.047,0.082,-0.063,0.043,-3.6,-0.0012,-0.0059,-8.1e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.024,0.006,0.2,0.2,0.033,4.9e-07,4.1e-07,4.3e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24590000,-0.28,0.019,-0.0094,0.96,-0.043,0.044,0.077,-0.044,0.037,-3.6,-0.0013,-0.0059,-0.0001,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.02,0.023,0.0059,0.2,0.2,0.033,4.8e-07,4e-07,4.2e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24690000,-0.28,0.018,-0.0099,0.96,-0.041,0.044,0.077,-0.049,0.041,-3.5,-0.0013,-0.0059,-9.9e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.024,0.0059,0.21,0.21,0.033,4.8e-07,4e-07,4.2e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24790000,-0.28,0.018,-0.01,0.96,-0.034,0.042,0.068,-0.037,0.032,-3.5,-0.0013,-0.0059,-0.00012,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.02,0.023,0.0059,0.21,0.21,0.032,4.7e-07,3.9e-07,4.2e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24890000,-0.28,0.017,-0.0098,0.96,-0.033,0.045,0.058,-0.04,0.036,-3.5,-0.0013,-0.0059,-0.00011,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.024,0.0059,0.22,0.22,0.032,4.7e-07,3.9e-07,4.1e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
24990000,-0.28,0.017,-0.0096,0.96,-0.021,0.045,0.051,-0.026,0.03,-3.5,-0.0013,-0.0059,-0.00013,0.073,-0.029,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.22,0.22,0.032,4.6e-07,3.9e-07,4.1e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25090000,-0.28,0.017,-0.01,0.96,-0.016,0.045,0.048,-0.026,0.035,-3.5,-0.0013,-0.0059,-0.00012,0.073,-0.029,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.024,0.0058,0.23,0.23,0.032,4.6e-07,3.9e-07,4.1e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25190000,-0.28,0.017,-0.01,0.96,-0.0064,0.041,0.048,-0.011,0.024,-3.5,-0.0013,-0.0059,-0.00016,0.073,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.23,0.23,0.032,4.5e-07,3.8e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25290000,-0.28,0.016,-0.01,0.96,-0.0016,0.043,0.043,-0.012,0.029,-3.5,-0.0013,-0.0059,-0.00016,0.073,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.24,0.24,0.032,4.5e-07,3.8e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25390000,-0.28,0.016,-0.011,0.96,0.0072,0.042,0.042,-0.0022,0.023,-3.5,-0.0013,-0.0059,-0.00017,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.24,0.24,0.032,4.5e-07,3.7e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25490000,-0.28,0.016,-0.011,0.96,0.012,0.042,0.041,-0.0021,0.027,-3.5,-0.0013,-0.0059,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.25,0.25,0.032,4.5e-07,3.7e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25590000,-0.28,0.016,-0.011,0.96,0.016,0.038,0.042,0.005,0.012,-3.5,-0.0013,-0.0059,-0.00021,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.25,0.25,0.032,4.4e-07,3.7e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25690000,-0.28,0.015,-0.01,0.96,0.017,0.037,0.031,0.0067,0.015,-3.5,-0.0013,-0.0059,-0.0002,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.26,0.26,0.032,4.4e-07,3.7e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25790000,-0.28,0.015,-0.01,0.96,0.028,0.032,0.031,0.014,0.0057,-3.5,-0.0014,-0.0059,-0.00022,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.26,0.032,4.3e-07,3.6e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25890000,-0.28,0.015,-0.01,0.96,0.034,0.031,0.033,0.017,0.0094,-3.5,-0.0013,-0.0059,-0.00023,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.27,0.27,0.032,4.3e-07,3.6e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
25990000,-0.28,0.015,-0.01,0.96,0.036,0.026,0.027,0.014,-0.0017,-3.5,-0.0014,-0.0058,-0.00025,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.27,0.032,4.2e-07,3.6e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26090000,-0.28,0.015,-0.0099,0.96,0.041,0.026,0.026,0.017,0.00025,-3.5,-0.0014,-0.0058,-0.00024,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.28,0.28,0.032,4.2e-07,3.6e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
26190000,-0.28,0.015,-0.0098,0.96,0.045,0.017,0.021,0.02,-0.016,-3.5,-0.0014,-0.0058,-0.00026,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.27,0.28,0.032,4.1e-07,3.5e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
26290000,-0.28,0.016,-0.0097,0.96,0.046,0.016,0.015,0.024,-0.014,-3.5,-0.0014,-0.0058,-0.00026,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0056,0.29,0.29,0.032,4.1e-07,3.5e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
26390000,-0.28,0.016,-0.0092,0.96,0.043,0.0073,0.019,0.016,-0.028,-3.5,-0.0014,-0.0058,-0.00028,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.28,0.29,0.032,4.1e-07,3.5e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
26490000,-0.28,0.016,-0.0089,0.96,0.046,0.0051,0.029,0.02,-0.028,-3.5,-0.0014,-0.0058,-0.00029,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00035,0.045,0.022,0.024,0.0056,0.3,0.3,0.032,4.1e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
26590000,-0.28,0.016,-0.0084,0.96,0.045,-0.005,0.029,0.019,-0.04,-3.5,-0.0014,-0.0058,-0.00031,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0056,0.29,0.3,0.032,4e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
26690000,-0.28,0.015,-0.0083,0.96,0.047,-0.0089,0.027,0.024,-0.041,-3.5,-0.0014,-0.0058,-0.00032,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.31,0.31,0.032,4e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
26790000,-0.28,0.015,-0.0081,0.96,0.049,-0.015,0.027,0.021,-0.054,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00035,0.045,0.021,0.023,0.0055,0.3,0.31,0.031,3.9e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
26890000,-0.28,0.015,-0.0074,0.96,0.055,-0.018,0.022,0.026,-0.055,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00035,0.045,0.022,0.024,0.0056,0.32,0.32,0.032,3.9e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
26990000,-0.28,0.015,-0.0068,0.96,0.056,-0.024,0.022,0.019,-0.062,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.31,0.32,0.031,3.9e-07,3.3e-07,3.6e-06,0.029,0.029,0.00014,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
27090000,-0.28,0.016,-0.0067,0.96,0.059,-0.03,0.025,0.025,-0.065,-3.5,-0.0014,-0.0058,-0.00034,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0055,0.32,0.33,0.031,3.9e-07,3.3e-07,3.6e-06,0.029,0.029,0.00014,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
27190000,-0.28,0.016,-0.0067,0.96,0.059,-0.034,0.027,0.014,-0.068,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.32,0.33,0.031,3.8e-07,3.3e-07,3.6e-06,0.029,0.029,0.00014,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
27290000,-0.28,0.017,-0.0068,0.96,0.066,-0.039,0.14,0.021,-0.072,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.022,0.024,0.0055,0.33,0.34,0.031,3.8e-07,3.3e-07,3.6e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
27390000,-0.28,0.019,-0.0081,0.96,0.07,-0.032,0.46,0.005,-0.026,-3.5,-0.0014,-0.0058,-0.00031,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
27490000,-0.28,0.021,-0.0093,0.96,0.076,-0.035,0.78,0.012,-0.029,-3.5,-0.0014,-0.0058,-0.00032,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.0004,0.00036,0.045,0.015,0.018,0.0055,0.15,0.15,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
27590000,-0.28,0.02,-0.0093,0.96,0.067,-0.037,0.87,0.0066,-0.02,-3.4,-0.0014,-0.0058,-0.0003,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00039,0.00036,0.045,0.014,0.015,0.0055,0.096,0.097,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
27690000,-0.28,0.017,-0.0083,0.96,0.062,-0.034,0.78,0.013,-0.023,-3.3,-0.0014,-0.0058,-0.0003,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0055,0.1,0.1,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
27790000,-0.28,0.016,-0.0072,0.96,0.058,-0.032,0.77,0.01,-0.019,-3.2,-0.0014,-0.0058,-0.00028,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.013,0.015,0.0054,0.073,0.074,0.031,3.7e-07,3.1e-07,3.4e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
27890000,-0.28,0.016,-0.0068,0.96,0.064,-0.038,0.81,0.016,-0.022,-3.2,-0.0013,-0.0058,-0.00028,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00034,0.045,0.014,0.016,0.0055,0.076,0.077,0.031,3.7e-07,3.1e-07,3.4e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
27990000,-0.28,0.016,-0.0072,0.96,0.065,-0.04,0.8,0.019,-0.025,-3.1,-0.0013,-0.0058,-0.00028,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.014,0.016,0.0054,0.079,0.079,0.031,3.6e-07,3.1e-07,3.4e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28090000,-0.28,0.016,-0.0075,0.96,0.068,-0.041,0.8,0.026,-0.029,-3,-0.0013,-0.0058,-0.00027,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.015,0.017,0.0054,0.082,0.083,0.031,3.6e-07,3.1e-07,3.4e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28190000,-0.28,0.016,-0.0069,0.96,0.065,-0.039,0.81,0.027,-0.031,-2.9,-0.0013,-0.0058,-0.00025,0.072,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.084,0.086,0.031,3.6e-07,3.1e-07,3.4e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28290000,-0.28,0.017,-0.0063,0.96,0.069,-0.042,0.81,0.033,-0.036,-2.9,-0.0013,-0.0058,-0.00025,0.072,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.015,0.018,0.0054,0.088,0.09,0.031,3.6e-07,3.1e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28390000,-0.28,0.017,-0.0063,0.96,0.07,-0.044,0.81,0.036,-0.036,-2.8,-0.0013,-0.0058,-0.00022,0.072,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.015,0.018,0.0054,0.091,0.092,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28490000,-0.28,0.018,-0.0065,0.96,0.073,-0.047,0.81,0.044,-0.041,-2.7,-0.0013,-0.0058,-0.00023,0.072,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.019,0.0054,0.095,0.097,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28590000,-0.28,0.017,-0.0065,0.96,0.065,-0.047,0.81,0.044,-0.044,-2.6,-0.0013,-0.0058,-0.00021,0.072,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.098,0.1,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28690000,-0.28,0.017,-0.0064,0.96,0.064,-0.048,0.81,0.05,-0.048,-2.6,-0.0013,-0.0058,-0.00021,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.017,0.019,0.0054,0.1,0.1,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
28790000,-0.28,0.017,-0.0057,0.96,0.062,-0.047,0.81,0.051,-0.047,-2.5,-0.0013,-0.0058,-0.00018,0.072,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.11,0.031,3.4e-07,3e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
28890000,-0.28,0.016,-0.0056,0.96,0.065,-0.048,0.81,0.057,-0.052,-2.4,-0.0013,-0.0058,-0.00018,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.02,0.0054,0.11,0.11,0.031,3.4e-07,3e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
28990000,-0.28,0.016,-0.0053,0.96,0.064,-0.046,0.81,0.059,-0.052,-2.3,-0.0013,-0.0058,-0.00016,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.12,0.031,3.4e-07,2.9e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29090000,-0.28,0.016,-0.0052,0.96,0.067,-0.048,0.81,0.066,-0.056,-2.3,-0.0013,-0.0058,-0.00016,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,2.9e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29190000,-0.28,0.017,-0.0051,0.96,0.067,-0.046,0.8,0.068,-0.055,-2.2,-0.0013,-0.0058,-0.00014,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29290000,-0.28,0.017,-0.0054,0.96,0.072,-0.051,0.81,0.077,-0.06,-2.1,-0.0013,-0.0058,-0.00014,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.021,0.0053,0.13,0.13,0.031,3.4e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29390000,-0.28,0.016,-0.0059,0.96,0.068,-0.048,0.81,0.075,-0.056,-2,-0.0013,-0.0058,-0.00011,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29490000,-0.27,0.016,-0.0059,0.96,0.071,-0.049,0.81,0.082,-0.062,-2,-0.0013,-0.0058,-9.8e-05,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29590000,-0.27,0.016,-0.0058,0.96,0.068,-0.047,0.81,0.08,-0.06,-1.9,-0.0013,-0.0058,-6.7e-05,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.8e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29690000,-0.27,0.016,-0.0058,0.96,0.072,-0.046,0.81,0.088,-0.065,-1.8,-0.0013,-0.0058,-5.9e-05,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.022,0.0053,0.15,0.15,0.031,3.3e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29790000,-0.27,0.016,-0.0056,0.96,0.069,-0.039,0.81,0.085,-0.061,-1.7,-0.0013,-0.0058,-2.7e-05,0.07,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.15,0.15,0.031,3.2e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29890000,-0.27,0.016,-0.005,0.96,0.071,-0.041,0.8,0.092,-0.065,-1.7,-0.0013,-0.0058,-1.9e-05,0.07,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.045,0.019,0.022,0.0053,0.15,0.16,0.031,3.2e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
29990000,-0.27,0.016,-0.0052,0.96,0.065,-0.039,0.8,0.087,-0.064,-1.6,-0.0013,-0.0058,-3.3e-06,0.07,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.045,0.019,0.021,0.0052,0.16,0.16,0.03,3.2e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30090000,-0.27,0.016,-0.0053,0.96,0.067,-0.038,0.8,0.095,-0.067,-1.5,-0.0013,-0.0058,-2e-05,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.16,0.17,0.03,3.2e-07,2.8e-07,3e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30190000,-0.27,0.016,-0.0054,0.96,0.062,-0.032,0.8,0.089,-0.058,-1.5,-0.0013,-0.0058,-5.8e-06,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.17,0.17,0.031,3.1e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30290000,-0.27,0.016,-0.0054,0.96,0.062,-0.032,0.8,0.096,-0.061,-1.4,-0.0013,-0.0058,-4.5e-06,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.17,0.18,0.031,3.2e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
30390000,-0.27,0.016,-0.0054,0.96,0.059,-0.026,0.8,0.095,-0.055,-1.3,-0.0012,-0.0058,2.8e-05,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.17,0.18,0.03,3.1e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
30490000,-0.27,0.016,-0.0054,0.96,0.063,-0.025,0.8,0.1,-0.058,-1.2,-0.0013,-0.0058,3.5e-05,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.18,0.19,0.031,3.1e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
30590000,-0.27,0.017,-0.0057,0.96,0.061,-0.023,0.8,0.097,-0.054,-1.2,-0.0012,-0.0058,6.1e-05,0.07,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.18,0.19,0.03,3.1e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
30690000,-0.27,0.017,-0.006,0.96,0.059,-0.023,0.8,0.1,-0.056,-1.1,-0.0012,-0.0058,6e-05,0.07,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.19,0.2,0.03,3.1e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
30790000,-0.27,0.016,-0.0058,0.96,0.052,-0.013,0.8,0.096,-0.044,-1,-0.0012,-0.0058,8.8e-05,0.07,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
30890000,-0.27,0.016,-0.0052,0.96,0.051,-0.0089,0.79,0.099,-0.045,-0.95,-0.0012,-0.0058,7.6e-05,0.071,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
30990000,-0.27,0.016,-0.0054,0.96,0.047,-0.0072,0.79,0.095,-0.044,-0.88,-0.0012,-0.0058,8e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.2,0.21,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31090000,-0.27,0.016,-0.0055,0.96,0.045,-0.0058,0.79,0.099,-0.044,-0.81,-0.0012,-0.0058,7.1e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.21,0.22,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31190000,-0.27,0.016,-0.0057,0.96,0.042,-0.0023,0.8,0.093,-0.04,-0.74,-0.0012,-0.0058,9.7e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.21,0.22,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31290000,-0.27,0.017,-0.0059,0.96,0.039,-0.0004,0.8,0.096,-0.041,-0.67,-0.0012,-0.0058,0.0001,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.22,0.23,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31390000,-0.27,0.016,-0.0057,0.96,0.035,0.0044,0.8,0.09,-0.037,-0.59,-0.0012,-0.0058,0.0001,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.22,0.23,0.03,2.9e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31490000,-0.27,0.017,-0.0054,0.96,0.036,0.0079,0.8,0.095,-0.036,-0.52,-0.0012,-0.0058,9.8e-05,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.23,0.24,0.03,3e-07,2.6e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31590000,-0.27,0.017,-0.0052,0.96,0.037,0.0097,0.8,0.093,-0.033,-0.45,-0.0012,-0.0058,0.00011,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.23,0.24,0.03,2.9e-07,2.6e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31690000,-0.27,0.017,-0.0052,0.96,0.04,0.011,0.8,0.097,-0.032,-0.38,-0.0012,-0.0058,0.00012,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.0004,0.00034,0.044,0.021,0.023,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31790000,-0.27,0.018,-0.0054,0.96,0.034,0.017,0.8,0.093,-0.023,-0.3,-0.0012,-0.0058,0.00014,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.0004,0.00034,0.044,0.02,0.022,0.0051,0.24,0.25,0.03,2.9e-07,2.5e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31890000,-0.27,0.018,-0.0052,0.96,0.032,0.019,0.8,0.098,-0.021,-0.23,-0.0012,-0.0058,0.00015,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.0004,0.00034,0.044,0.021,0.023,0.0051,0.25,0.26,0.03,2.9e-07,2.5e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
31990000,-0.27,0.017,-0.0055,0.96,0.029,0.02,0.79,0.094,-0.016,-0.17,-0.0012,-0.0058,0.00014,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.25,0.26,0.03,2.9e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32090000,-0.27,0.017,-0.0059,0.96,0.03,0.024,0.8,0.098,-0.013,-0.095,-0.0012,-0.0058,0.00014,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.26,0.27,0.03,2.9e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32190000,-0.27,0.017,-0.0062,0.96,0.027,0.031,0.8,0.093,-0.0048,-0.027,-0.0012,-0.0058,0.00015,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32290000,-0.27,0.017,-0.006,0.96,0.027,0.034,0.8,0.096,-0.0016,0.042,-0.0012,-0.0058,0.00015,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32390000,-0.27,0.017,-0.0062,0.96,0.023,0.036,0.8,0.092,0.0015,0.12,-0.0012,-0.0058,0.00015,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32490000,-0.27,0.016,-0.0092,0.96,-0.017,0.094,-0.077,0.091,0.01,0.12,-0.0012,-0.0058,0.00015,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.025,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32590000,-0.27,0.016,-0.0092,0.96,-0.015,0.093,-0.079,0.092,0.0017,0.1,-0.0012,-0.0058,0.00013,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
32690000,-0.27,0.015,-0.0092,0.96,-0.011,0.1,-0.081,0.09,0.011,0.088,-0.0012,-0.0058,0.00013,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00035,0.043,0.022,0.025,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
32790000,-0.27,0.016,-0.009,0.96,-0.0064,0.097,-0.082,0.092,0.0025,0.073,-0.0012,-0.0058,0.00012,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
32890000,-0.27,0.016,-0.009,0.96,-0.0068,0.1,-0.083,0.09,0.012,0.058,-0.0012,-0.0058,0.00013,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.3,0.31,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
32990000,-0.27,0.016,-0.0088,0.96,-0.0028,0.098,-0.083,0.091,-0.002,0.044,-0.0012,-0.0058,0.00011,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
33090000,-0.27,0.016,-0.0088,0.96,0.0011,0.1,-0.08,0.091,0.0079,0.037,-0.0012,-0.0058,0.00011,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
33190000,-0.27,0.016,-0.0087,0.96,0.0055,0.099,-0.079,0.092,-0.0081,0.029,-0.0012,-0.0058,8e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
33290000,-0.27,0.016,-0.0087,0.96,0.0096,0.1,-0.079,0.093,0.0015,0.021,-0.0012,-0.0058,9.7e-05,0.072,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
33390000,-0.27,0.016,-0.0086,0.96,0.014,0.097,-0.077,0.093,-0.0077,0.013,-0.0013,-0.0058,8.4e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
33490000,-0.27,0.016,-0.0086,0.96,0.019,0.1,-0.076,0.095,0.0022,0.0031,-0.0013,-0.0058,9.3e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.33,0.34,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
33590000,-0.27,0.016,-0.0084,0.96,0.023,0.098,-0.073,0.095,-0.012,-0.0048,-0.0013,-0.0058,8.5e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.33,0.34,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
33690000,-0.27,0.016,-0.0084,0.96,0.026,0.1,-0.074,0.096,-0.002,-0.013,-0.0013,-0.0058,9e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.34,0.35,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
33790000,-0.27,0.016,-0.0083,0.96,0.028,0.098,-0.068,0.092,-0.016,-0.02,-0.0013,-0.0058,6.7e-05,0.074,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.34,0.35,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
33890000,-0.27,0.016,-0.0083,0.96,0.033,0.1,-0.068,0.096,-0.0064,-0.026,-0.0013,-0.0058,8.3e-05,0.074,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.35,0.36,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
33990000,-0.27,0.016,-0.0082,0.96,0.035,0.097,-0.064,0.094,-0.015,-0.03,-0.0013,-0.0058,6.6e-05,0.075,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.043,0.02,0.023,0.005,0.35,0.36,0.03,2.6e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34090000,-0.27,0.016,-0.0081,0.96,0.039,0.1,-0.063,0.097,-0.0055,-0.034,-0.0013,-0.0058,7e-05,0.075,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34190000,-0.27,0.016,-0.0081,0.96,0.04,0.098,-0.06,0.092,-0.018,-0.038,-0.0013,-0.0057,6.1e-05,0.075,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.36,0.37,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34290000,-0.27,0.016,-0.0079,0.96,0.041,0.1,-0.059,0.096,-0.0076,-0.044,-0.0013,-0.0057,7.2e-05,0.075,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.042,0.021,0.023,0.005,0.37,0.38,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34390000,-0.27,0.016,-0.0078,0.96,0.042,0.097,-0.054,0.092,-0.02,-0.048,-0.0013,-0.0057,6e-05,0.076,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.37,0.37,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34490000,-0.27,0.016,-0.0079,0.96,0.045,0.1,-0.052,0.095,-0.0099,-0.05,-0.0013,-0.0057,7.3e-05,0.076,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.042,0.021,0.023,0.005,0.38,0.39,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34590000,-0.27,0.016,-0.0078,0.96,0.049,0.094,0.74,0.09,-0.024,-0.022,-0.0013,-0.0057,5.9e-05,0.076,-0.033,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.019,0.022,0.005,0.38,0.38,0.03,2.6e-07,2.3e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34690000,-0.27,0.015,-0.0078,0.96,0.058,0.095,1.7,0.096,-0.015,0.097,-0.0013,-0.0057,6.5e-05,0.076,-0.033,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.02,0.022,0.0051,0.39,0.4,0.03,2.6e-07,2.3e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34790000,-0.27,0.015,-0.0077,0.96,0.062,0.088,2.7,0.089,-0.028,0.28,-0.0013,-0.0057,5.4e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.02,0.021,0.005,0.39,0.39,0.03,2.6e-07,2.3e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
34890000,-0.27,0.015,-0.0077,0.96,0.071,0.089,3.7,0.095,-0.02,0.57,-0.0013,-0.0057,6e-05,0.077,-0.033,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.021,0.023,0.005,0.4,0.41,0.03,2.6e-07,2.3e-07,2.1e-06,0.028,0.028,0.0001,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1

1 Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23]
2 10000,1,-0.011,-0.01,0.00023,0.00033,-0.00013,-0.01,1e-05,-3.9e-06,-0.00042,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00018,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
3 90000,1,-0.011,-0.01,0.00033,-0.001,-0.0031,-0.024,-3.8e-05,-0.00013,-0.0021,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0.01,0.01,0.00046,25,25,10,1e+02,1e+02,1e+02,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
4 190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-2.1e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00094,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 190000,1,-0.012,-0.011,0.00044,-0.0023,-0.003,-0.037,-0.00017,-0.00043,-0.017,4.7e-10,-5e-10,-1.5e-11,0,0,-1.1e-06,0,0,0,0,0,0,0,0,0.011,0.011,0.00094,25,25,10,1e+02,1e+02,1,0.01,0.01,0.01,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
5 290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-2.1e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.012,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 290000,1,-0.012,-0.011,0.00044,-0.0033,-0.0044,-0.046,-0.00024,-0.00025,-0.018,3.8e-09,-5.9e-09,-4.7e-10,0,0,-1e-05,0,0,0,0,0,0,0,0,0.011,0.012,0.00077,25,25,9.6,0.37,0.37,0.41,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
6 390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,1.5e-11,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 390000,1,-0.012,-0.011,0.00049,-0.0025,-0.0059,-0.063,-0.00056,-0.00071,-0.013,-7.1e-09,-5.8e-09,-1.3e-09,0,0,2.2e-06,0,0,0,0,0,0,0,0,0.012,0.012,0.0012,25,25,8.1,0.97,0.97,0.32,0.01,0.01,0.0052,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
7 490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.4e-07,4.1e-08,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 490000,1,-0.012,-0.012,0.00055,-0.0007,-0.0062,-0.069,-0.00015,-0.00046,-0.011,-1.2e-06,7.5e-07,-1.7e-07,0,0,-1e-06,0,0,0,0,0,0,0,0,0.013,0.013,0.00073,7.8,7.8,5.9,0.34,0.34,0.31,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
8 590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.7e-07,4.5e-08,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 590000,1,-0.012,-0.012,0.00057,-0.002,-0.009,-0.12,-0.00028,-0.0012,-0.029,-1.3e-06,7.8e-07,-1.8e-07,0,0,7.8e-05,0,0,0,0,0,0,0,0,0.015,0.015,0.001,7.9,7.9,4.2,0.67,0.67,0.32,0.01,0.01,0.0024,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
9 690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,1.6e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00063,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 690000,1,-0.012,-0.012,0.0006,5.4e-05,-0.0088,-0.05,-8e-05,-0.00078,-0.0088,-5.6e-06,1.6e-06,-5.2e-07,0,0,-0.00016,0,0,0,0,0,0,0,0,0.016,0.016,0.00062,2.7,2.7,2.8,0.26,0.26,0.29,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
10 790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,1.5e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.0008,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 790000,1,-0.012,-0.012,0.0006,0.0022,-0.01,-0.054,-2.3e-05,-0.0017,-0.011,-5.4e-06,1.6e-06,-5.1e-07,0,0,-0.0002,0,0,0,0,0,0,0,0,0.018,0.018,0.00079,2.8,2.8,1.9,0.42,0.42,0.27,0.01,0.01,0.0012,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
11 890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1e-06,4.9e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00054,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 890000,1,-0.012,-0.013,0.00061,0.0031,-0.0084,-0.093,0.00015,-0.0011,-0.031,-2.1e-05,1.2e-06,-7.4e-07,0,0,-8.1e-05,0,0,0,0,0,0,0,0,0.019,0.019,0.00052,1.3,1.3,1.3,0.2,0.2,0.25,0.0099,0.0099,0.00067,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
12 990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1e-06,5e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00066,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00068,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 990000,1,-0.012,-0.013,0.00058,0.006,-0.0097,-0.12,0.00062,-0.002,-0.046,-2.2e-05,1.2e-06,-7.4e-07,0,0,-2.6e-05,0,0,0,0,0,0,0,0,0.021,0.021,0.00064,1.5,1.5,0.95,0.3,0.3,0.23,0.0099,0.0099,0.00067,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
13 1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,9.9e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00047,0.93,0.93,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1090000,1,-0.012,-0.013,0.00054,0.011,-0.013,-0.13,0.00077,-0.0014,-0.062,-6e-05,-1.5e-05,-1.8e-07,0,0,1.1e-05,0,0,0,0,0,0,0,0,0.023,0.023,0.00045,0.93,0.92,0.69,0.17,0.17,0.2,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
14 1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.8e-05,-1.3e-05,9.7e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00056,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00043,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1190000,1,-0.012,-0.013,0.00047,0.015,-0.018,-0.11,0.0021,-0.003,-0.047,-5.7e-05,-1.3e-05,-2.2e-07,0,0,-0.00056,0,0,0,0,0,0,0,0,0.025,0.025,0.00053,1.1,1.1,0.54,0.24,0.24,0.19,0.0098,0.0098,0.00042,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
15 1290000,1,-0.012,-0.014,0.00042,0.019,-0.018,-0.11,0.0019,-0.0024,-0.048,-0.00017,-9.7e-05,1.5e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.026,0.026,0.00042,0.89,0.89,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1290000,1,-0.012,-0.014,0.00041,0.019,-0.018,-0.11,0.002,-0.0024,-0.048,-0.00016,-9.4e-05,2.9e-06,0,0,-0.00083,0,0,0,0,0,0,0,0,0.025,0.026,0.0004,0.88,0.88,0.42,0.15,0.15,0.18,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
16 1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9.2e-05,1.5e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00049,1.2,1.2,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00029,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1390000,1,-0.012,-0.014,0.00038,0.026,-0.023,-0.097,0.0043,-0.0044,-0.038,-0.00016,-9e-05,2.8e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.028,0.028,0.00046,1.2,1.1,0.33,0.21,0.21,0.16,0.0095,0.0095,0.00028,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
17 1490000,1,-0.012,-0.014,0.00038,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.3e-06,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00038,0.96,0.96,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1490000,1,-0.012,-0.014,0.00037,0.024,-0.02,-0.12,0.0034,-0.0032,-0.053,-0.00039,-0.00033,1.1e-05,0,0,-0.0013,0,0,0,0,0,0,0,0,0.027,0.027,0.00036,0.95,0.94,0.27,0.14,0.14,0.15,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
18 1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00039,-0.00033,1.3e-06,0,0,-0.0015,0,0,0,0,0,0,0,0,0.03,0.03,0.00043,1.3,1.3,0.23,0.2,0.2,0.14,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1590000,1,-0.012,-0.014,0.00039,0.031,-0.024,-0.13,0.0061,-0.0055,-0.063,-0.00038,-0.00032,1.1e-05,0,0,-0.0015,0,0,0,0,0,0,0,0,0.029,0.029,0.00041,1.3,1.3,0.23,0.21,0.2,0.14,0.0088,0.0088,0.0002,0.04,0.04,0.04,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
19 1690000,1,-0.012,-0.014,0.00044,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00073,-0.00074,-7.7e-08,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.00034,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1690000,1,-0.012,-0.014,0.00042,0.028,-0.019,-0.13,0.0043,-0.0037,-0.068,-0.00072,-0.00072,2.4e-05,0,0,-0.0019,0,0,0,0,0,0,0,0,0.026,0.026,0.00033,1,1,0.19,0.14,0.14,0.13,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
20 1790000,1,-0.012,-0.014,0.0004,0.035,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00073,-0.00073,-3.3e-08,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00039,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1790000,1,-0.012,-0.014,0.00038,0.036,-0.024,-0.13,0.0076,-0.0059,-0.067,-0.00072,-0.00072,2.4e-05,0,0,-0.0029,0,0,0,0,0,0,0,0,0.028,0.028,0.00037,1.3,1.3,0.17,0.2,0.2,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
21 1890000,1,-0.012,-0.014,0.00039,0.043,-0.025,-0.14,0.011,-0.0083,-0.075,-0.00072,-0.00072,-7e-09,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00043,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1890000,1,-0.012,-0.014,0.00037,0.043,-0.025,-0.14,0.012,-0.0084,-0.075,-0.00071,-0.00071,2.4e-05,0,0,-0.0033,0,0,0,0,0,0,0,0,0.031,0.031,0.00041,1.7,1.7,0.15,0.31,0.31,0.12,0.0078,0.0078,0.00015,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
22 1990000,1,-0.011,-0.014,0.0004,0.035,-0.018,-0.14,0.0082,-0.0053,-0.074,-0.0011,-0.0013,-3.1e-06,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00035,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 1990000,1,-0.011,-0.014,0.00036,0.035,-0.018,-0.14,0.0082,-0.0054,-0.074,-0.0011,-0.0012,3.8e-05,0,0,-0.0047,0,0,0,0,0,0,0,0,0.025,0.025,0.00033,1.3,1.3,0.13,0.2,0.2,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
23 2090000,1,-0.011,-0.014,0.00043,0.042,-0.02,-0.14,0.012,-0.0073,-0.071,-0.0011,-0.0012,-3e-06,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00039,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2090000,1,-0.011,-0.014,0.00039,0.042,-0.02,-0.14,0.012,-0.0074,-0.071,-0.0011,-0.0012,3.8e-05,0,0,-0.0066,0,0,0,0,0,0,0,0,0.027,0.027,0.00037,1.7,1.7,0.12,0.31,0.31,0.11,0.0067,0.0067,0.00011,0.04,0.04,0.039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
24 2190000,1,-0.011,-0.014,0.00039,0.033,-0.013,-0.14,0.0081,-0.0043,-0.077,-0.0014,-0.0018,-7.8e-06,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.00031,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2190000,1,-0.011,-0.014,0.00032,0.033,-0.014,-0.14,0.0081,-0.0044,-0.077,-0.0014,-0.0018,5e-05,0,0,-0.0076,0,0,0,0,0,0,0,0,0.02,0.02,0.0003,1.2,1.2,0.11,0.2,0.2,0.11,0.0055,0.0055,8.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
25 2290000,1,-0.011,-0.014,0.00038,0.038,-0.014,-0.14,0.012,-0.0057,-0.075,-0.0014,-0.0018,-7.6e-06,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00034,1.5,1.5,0.11,0.3,0.3,0.1,0.0055,0.0055,9e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2290000,1,-0.011,-0.014,0.00031,0.038,-0.014,-0.14,0.012,-0.0058,-0.075,-0.0014,-0.0018,5e-05,0,0,-0.0099,0,0,0,0,0,0,0,0,0.022,0.022,0.00033,1.5,1.5,0.11,0.29,0.29,0.1,0.0055,0.0055,8.8e-05,0.04,0.04,0.038,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
26 2390000,1,-0.011,-0.013,0.0004,0.029,-0.0098,-0.14,0.0075,-0.0033,-0.072,-0.0017,-0.0023,-1.3e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00028,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2390000,1,-0.011,-0.013,0.00031,0.03,-0.01,-0.14,0.0076,-0.0034,-0.072,-0.0017,-0.0023,5.9e-05,0,0,-0.013,0,0,0,0,0,0,0,0,0.017,0.017,0.00027,1,1,0.1,0.19,0.19,0.098,0.0046,0.0046,7e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
27 2490000,1,-0.011,-0.014,0.00047,0.033,-0.0088,-0.14,0.011,-0.0042,-0.079,-0.0017,-0.0023,-1.3e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.00031,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,7.1e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2490000,1,-0.011,-0.014,0.00039,0.033,-0.009,-0.14,0.011,-0.0044,-0.079,-0.0017,-0.0023,5.9e-05,0,0,-0.014,0,0,0,0,0,0,0,0,0.018,0.018,0.0003,1.3,1.3,0.1,0.28,0.28,0.097,0.0046,0.0046,7e-05,0.04,0.04,0.037,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
28 2590000,1,-0.01,-0.013,0.00039,0.023,-0.0059,-0.15,0.0066,-0.0023,-0.084,-0.0018,-0.0027,-1.9e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00026,0.89,0.89,0.099,0.18,0.18,0.094,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2590000,1,-0.01,-0.013,0.00028,0.023,-0.0061,-0.15,0.0066,-0.0024,-0.084,-0.0018,-0.0027,6.4e-05,0,0,-0.015,0,0,0,0,0,0,0,0,0.014,0.014,0.00025,0.88,0.88,0.099,0.18,0.18,0.094,0.0038,0.0038,5.7e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
29 2690000,1,-0.01,-0.013,0.00043,0.027,-0.0051,-0.15,0.0091,-0.0029,-0.084,-0.0018,-0.0027,-1.8e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00028,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,5.8e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2690000,1,-0.01,-0.013,0.00032,0.027,-0.0052,-0.15,0.0092,-0.003,-0.084,-0.0018,-0.0027,6.4e-05,0,0,-0.018,0,0,0,0,0,0,0,0,0.015,0.015,0.00027,1.1,1.1,0.097,0.25,0.25,0.091,0.0038,0.0038,5.7e-05,0.04,0.04,0.036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
30 2790000,1,-0.01,-0.013,0.00037,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.77,0.77,0.095,0.16,0.16,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2790000,1,-0.01,-0.013,0.00025,0.022,-0.0029,-0.14,0.0059,-0.0016,-0.081,-0.0019,-0.003,6.7e-05,0,0,-0.022,0,0,0,0,0,0,0,0,0.012,0.012,0.00023,0.75,0.75,0.095,0.16,0.16,0.089,0.0032,0.0032,4.7e-05,0.04,0.04,0.035,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
31 2890000,1,-0.01,-0.013,0.0003,0.026,-0.0046,-0.14,0.0082,-0.002,-0.081,-0.0019,-0.003,-2.3e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00026,0.95,0.95,0.096,0.23,0.23,0.089,0.0032,0.0032,4.8e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2890000,1,-0.01,-0.013,0.00017,0.026,-0.0046,-0.14,0.0083,-0.0021,-0.081,-0.0019,-0.003,6.7e-05,0,0,-0.026,0,0,0,0,0,0,0,0,0.013,0.013,0.00025,0.93,0.93,0.096,0.23,0.23,0.089,0.0032,0.0032,4.7e-05,0.04,0.04,0.034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
32 2990000,1,-0.01,-0.013,0.00031,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,-2.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.0099,0.0099,0.00022,0.67,0.67,0.095,0.15,0.15,0.088,0.0027,0.0027,4e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 2990000,1,-0.01,-0.013,0.00017,0.02,-0.0035,-0.15,0.0054,-0.0012,-0.086,-0.002,-0.0033,6.8e-05,0,0,-0.028,0,0,0,0,0,0,0,0,0.01,0.01,0.00022,0.66,0.66,0.095,0.15,0.15,0.088,0.0027,0.0027,3.9e-05,0.04,0.04,0.033,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
33 3090000,1,-0.01,-0.013,0.00052,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,-2.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00024,0.83,0.83,0.095,0.22,0.22,0.086,0.0027,0.0027,4e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3090000,1,-0.01,-0.013,0.00037,0.025,-0.0063,-0.15,0.0077,-0.0018,-0.087,-0.002,-0.0033,6.8e-05,0,0,-0.031,0,0,0,0,0,0,0,0,0.011,0.011,0.00023,0.81,0.81,0.095,0.22,0.22,0.086,0.0027,0.0027,3.9e-05,0.04,0.04,0.032,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
34 3190000,1,-0.01,-0.013,0.00056,0.02,-0.0061,-0.15,0.0051,-0.0013,-0.097,-0.002,-0.0036,-3.2e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0088,0.0088,0.00021,0.59,0.59,0.096,0.14,0.14,0.087,0.0023,0.0023,3.4e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3190000,1,-0.01,-0.013,0.00041,0.02,-0.006,-0.15,0.0052,-0.0013,-0.097,-0.0021,-0.0036,6.8e-05,0,0,-0.033,0,0,0,0,0,0,0,0,0.0089,0.0089,0.0002,0.58,0.58,0.096,0.14,0.14,0.087,0.0023,0.0023,3.3e-05,0.04,0.04,0.031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
35 3290000,1,-0.01,-0.013,0.00059,0.023,-0.0062,-0.15,0.0073,-0.002,-0.11,-0.002,-0.0036,-3.2e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0096,0.0096,0.00022,0.73,0.73,0.095,0.2,0.2,0.086,0.0023,0.0023,3.4e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3290000,1,-0.01,-0.013,0.00042,0.023,-0.0061,-0.15,0.0074,-0.002,-0.11,-0.0021,-0.0036,6.8e-05,0,0,-0.035,0,0,0,0,0,0,0,0,0.0097,0.0097,0.00022,0.71,0.71,0.095,0.2,0.2,0.086,0.0023,0.0023,3.3e-05,0.04,0.04,0.03,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
36 3390000,1,-0.0098,-0.013,0.0006,0.019,-0.0032,-0.15,0.0049,-0.0013,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0078,0.0078,0.00019,0.53,0.53,0.095,0.14,0.14,0.085,0.002,0.002,2.9e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3390000,1,-0.0097,-0.013,0.00043,0.019,-0.0031,-0.15,0.005,-0.0013,-0.1,-0.0021,-0.0038,6.8e-05,0,0,-0.04,0,0,0,0,0,0,0,0,0.0079,0.0079,0.00019,0.52,0.52,0.095,0.14,0.14,0.085,0.002,0.002,2.8e-05,0.04,0.04,0.029,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
37 3490000,1,-0.0097,-0.013,0.00058,0.025,-0.0018,-0.15,0.0072,-0.0016,-0.1,-0.0021,-0.0038,-3.5e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.00021,0.66,0.66,0.095,0.19,0.19,0.086,0.002,0.002,2.9e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3490000,1,-0.0097,-0.013,0.00041,0.025,-0.0017,-0.15,0.0072,-0.0015,-0.1,-0.0021,-0.0038,6.9e-05,0,0,-0.044,0,0,0,0,0,0,0,0,0.0086,0.0086,0.0002,0.64,0.64,0.095,0.19,0.19,0.086,0.002,0.002,2.8e-05,0.04,0.04,0.027,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
38 3590000,1,-0.0095,-0.012,0.00054,0.021,-0.0014,-0.15,0.0051,-0.00091,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.007,0.0071,0.00018,0.49,0.49,0.094,0.13,0.13,0.086,0.0017,0.0017,2.5e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3590000,1,-0.0095,-0.012,0.00035,0.021,-0.0012,-0.15,0.0051,-0.00089,-0.11,-0.0022,-0.004,6.8e-05,0,0,-0.047,0,0,0,0,0,0,0,0,0.007,0.007,0.00018,0.48,0.48,0.094,0.13,0.13,0.086,0.0017,0.0017,2.4e-05,0.04,0.04,0.026,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
39 3690000,1,-0.0095,-0.013,0.00052,0.024,-0.00063,-0.15,0.0074,-0.0011,-0.11,-0.0022,-0.004,-3.9e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.6,0.6,0.093,0.18,0.18,0.085,0.0017,0.0017,2.5e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3690000,1,-0.0095,-0.013,0.00033,0.024,-0.00046,-0.15,0.0074,-0.001,-0.11,-0.0022,-0.004,6.8e-05,0,0,-0.052,0,0,0,0,0,0,0,0,0.0077,0.0077,0.00019,0.58,0.58,0.093,0.17,0.17,0.085,0.0017,0.0017,2.4e-05,0.04,0.04,0.025,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
40 3790000,1,-0.0094,-0.012,0.00055,0.019,0.0038,-0.15,0.0051,-0.00046,-0.11,-0.0022,-0.0043,-4.3e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0064,0.0064,0.00017,0.45,0.45,0.093,0.12,0.12,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3790000,1,-0.0094,-0.012,0.00034,0.02,0.0039,-0.15,0.0051,-0.00043,-0.11,-0.0022,-0.0043,6.6e-05,0,0,-0.055,0,0,0,0,0,0,0,0,0.0063,0.0063,0.00017,0.44,0.44,0.093,0.12,0.12,0.086,0.0014,0.0014,2.1e-05,0.04,0.04,0.024,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
41 3890000,1,-0.0094,-0.013,0.00063,0.021,0.005,-0.14,0.0072,-1.9e-05,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0069,0.0069,0.00018,0.55,0.55,0.091,0.17,0.17,0.086,0.0014,0.0014,2.2e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3890000,1,-0.0093,-0.012,0.00042,0.021,0.0052,-0.14,0.0072,4e-05,-0.11,-0.0022,-0.0043,6.6e-05,0,0,-0.059,0,0,0,0,0,0,0,0,0.0068,0.0069,0.00018,0.53,0.53,0.091,0.16,0.16,0.086,0.0014,0.0014,2.1e-05,0.04,0.04,0.022,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
42 3990000,1,-0.0094,-0.013,0.0007,0.026,0.0048,-0.14,0.0096,0.00041,-0.11,-0.0022,-0.0042,-4.3e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0075,0.0075,0.00019,0.66,0.66,0.089,0.23,0.23,0.085,0.0014,0.0014,2.2e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 3990000,1,-0.0093,-0.013,0.00048,0.026,0.005,-0.14,0.0096,0.0005,-0.11,-0.0022,-0.0043,6.6e-05,0,0,-0.064,0,0,0,0,0,0,0,0,0.0074,0.0074,0.00019,0.65,0.65,0.089,0.22,0.22,0.085,0.0014,0.0014,2.1e-05,0.04,0.04,0.021,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
43 4090000,1,-0.0093,-0.012,0.00076,0.022,0.0042,-0.12,0.0071,0.0006,-0.098,-0.0022,-0.0044,-4.8e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0062,0.0062,0.00017,0.5,0.5,0.087,0.16,0.16,0.085,0.0012,0.0012,1.9e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4090000,1,-0.0093,-0.012,0.00054,0.022,0.0043,-0.12,0.0071,0.00068,-0.098,-0.0022,-0.0045,6.4e-05,0,0,-0.072,0,0,0,0,0,0,0,0,0.0061,0.0061,0.00017,0.49,0.49,0.087,0.16,0.16,0.085,0.0012,0.0012,1.8e-05,0.04,0.04,0.02,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
44 4190000,1,-0.0094,-0.012,0.00073,0.024,0.0039,-0.12,0.0094,0.001,-0.1,-0.0022,-0.0044,-4.8e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0068,0.0068,0.00018,0.61,0.61,0.086,0.21,0.21,0.086,0.0012,0.0012,1.9e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4190000,1,-0.0094,-0.012,0.00049,0.024,0.0041,-0.12,0.0094,0.0011,-0.1,-0.0022,-0.0045,6.4e-05,0,0,-0.074,0,0,0,0,0,0,0,0,0.0066,0.0066,0.00018,0.59,0.6,0.086,0.21,0.21,0.086,0.0012,0.0012,1.8e-05,0.04,0.04,0.019,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
45 4290000,1,-0.0095,-0.012,0.00074,0.021,0.0037,-0.12,0.0068,0.00083,-0.11,-0.0021,-0.0046,-5.3e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0056,0.0056,0.00016,0.47,0.47,0.084,0.15,0.15,0.085,0.00097,0.00097,1.7e-05,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4290000,1,-0.0095,-0.012,0.0005,0.021,0.0039,-0.12,0.0068,0.00091,-0.11,-0.0021,-0.0047,6.2e-05,0,0,-0.077,0,0,0,0,0,0,0,0,0.0053,0.0053,0.00016,0.46,0.46,0.084,0.15,0.15,0.085,0.00094,0.00094,1.6e-05,0.04,0.04,0.017,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
46 4390000,1,-0.0094,-0.012,0.0007,0.025,0.0023,-0.11,0.0091,0.0011,-0.094,-0.0021,-0.0046,-5.2e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.006,0.006,0.00017,0.56,0.56,0.081,0.2,0.2,0.084,0.00097,0.00097,1.7e-05,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4390000,1,-0.0094,-0.012,0.00045,0.025,0.0025,-0.11,0.0091,0.0012,-0.094,-0.0021,-0.0047,6.2e-05,0,0,-0.083,0,0,0,0,0,0,0,0,0.0058,0.0058,0.00017,0.55,0.55,0.081,0.2,0.2,0.084,0.00094,0.00094,1.6e-05,0.04,0.04,0.016,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
47 4490000,1,-0.0094,-0.012,0.00076,0.021,0.004,-0.11,0.0067,0.00086,-0.095,-0.0021,-0.0048,-5.7e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.43,0.43,0.08,0.14,0.14,0.085,0.0008,0.0008,1.5e-05,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4490000,1,-0.0094,-0.012,0.0005,0.02,0.0041,-0.11,0.0067,0.00094,-0.095,-0.0021,-0.0048,5.9e-05,0,0,-0.086,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00015,0.42,0.42,0.08,0.14,0.14,0.085,0.00077,0.00077,1.4e-05,0.04,0.04,0.015,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
48 4590000,1,-0.0094,-0.012,0.00083,0.023,0.0029,-0.11,0.0089,0.0012,-0.098,-0.0021,-0.0048,-5.7e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.0054,0.0054,0.00016,0.52,0.52,0.077,0.19,0.19,0.084,0.0008,0.0008,1.5e-05,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4590000,1,-0.0094,-0.012,0.00056,0.023,0.003,-0.11,0.0089,0.0013,-0.098,-0.0021,-0.0048,5.9e-05,0,0,-0.088,0,0,0,0,0,0,0,0,0.005,0.005,0.00016,0.51,0.51,0.077,0.19,0.19,0.084,0.00077,0.00077,1.4e-05,0.04,0.04,0.014,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
49 4690000,1,-0.0094,-0.012,0.00076,0.017,0.0031,-0.1,0.0064,0.00089,-0.09,-0.0021,-0.005,-6.1e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.0044,0.0044,0.00015,0.4,0.4,0.074,0.14,0.14,0.083,0.00065,0.00065,1.3e-05,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4690000,1,-0.0094,-0.012,0.00049,0.017,0.0031,-0.1,0.0065,0.00095,-0.09,-0.0021,-0.005,5.7e-05,0,0,-0.093,0,0,0,0,0,0,0,0,0.004,0.004,0.00015,0.39,0.39,0.074,0.14,0.14,0.083,0.00062,0.00062,1.3e-05,0.04,0.04,0.013,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
50 4790000,1,-0.0093,-0.012,0.00086,0.015,0.0053,-0.099,0.008,0.0014,-0.092,-0.0021,-0.005,-6.1e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0047,0.0047,0.00016,0.47,0.47,0.073,0.18,0.18,0.084,0.00065,0.00065,1.3e-05,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4790000,1,-0.0093,-0.012,0.00058,0.015,0.0053,-0.099,0.0081,0.0014,-0.092,-0.0021,-0.005,5.7e-05,0,0,-0.095,0,0,0,0,0,0,0,0,0.0043,0.0043,0.00015,0.47,0.47,0.073,0.18,0.18,0.084,0.00062,0.00062,1.3e-05,0.04,0.04,0.012,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
51 4890000,1,-0.0092,-0.012,0.0009,0.01,0.0028,-0.093,0.0053,0.001,-0.088,-0.0021,-0.0051,-6.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0039,0.0039,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4890000,1,-0.0093,-0.012,0.00061,0.0099,0.0027,-0.093,0.0053,0.0011,-0.088,-0.0021,-0.0052,5.5e-05,0,0,-0.099,0,0,0,0,0,0,0,0,0.0035,0.0035,0.00014,0.36,0.36,0.07,0.13,0.13,0.083,0.00049,0.00049,1.1e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
52 4990000,1,-0.0092,-0.012,0.00089,0.013,0.0035,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0051,-6.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0042,0.0042,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00053,0.00053,1.2e-05,0.04,0.04,0.011,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 4990000,1,-0.0092,-0.012,0.00059,0.013,0.0034,-0.085,0.0065,0.0014,-0.083,-0.0021,-0.0052,5.5e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00015,0.43,0.43,0.067,0.17,0.17,0.082,0.00049,0.00049,1.1e-05,0.04,0.04,0.01,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
53 5090000,1,-0.0091,-0.011,0.00096,0.01,0.0038,-0.082,0.0045,0.001,-0.082,-0.002,-0.0052,-6.8e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.0034,0.0034,0.00014,0.33,0.33,0.065,0.12,0.12,0.082,0.00043,0.00043,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5090000,1,-0.0091,-0.011,0.00066,0.01,0.0036,-0.082,0.0045,0.001,-0.081,-0.002,-0.0053,5.3e-05,0,0,-0.1,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.33,0.33,0.065,0.12,0.12,0.082,0.00039,0.00039,1e-05,0.04,0.04,0.0098,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
54 5190000,1,-0.0089,-0.012,0.001,0.0099,0.0074,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0052,-6.8e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0037,0.0037,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00043,0.00043,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5190000,1,-0.0089,-0.012,0.0007,0.0096,0.0072,-0.08,0.0055,0.0015,-0.079,-0.002,-0.0053,5.3e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.39,0.39,0.063,0.16,0.16,0.081,0.00039,0.00039,1e-05,0.04,0.04,0.0091,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
55 5290000,1,-0.0089,-0.011,0.0011,0.0082,0.0074,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.003,0.003,0.00013,0.3,0.3,0.06,0.12,0.12,0.08,0.00035,0.00035,9.3e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5290000,1,-0.0089,-0.011,0.00075,0.0079,0.0072,-0.068,0.0038,0.0014,-0.072,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0026,0.0026,0.00013,0.31,0.31,0.06,0.12,0.12,0.08,0.00031,0.00031,9.1e-06,0.04,0.04,0.0084,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
56 5390000,1,-0.0088,-0.011,0.0011,0.0077,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,-7e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0032,0.0032,0.00014,0.36,0.36,0.057,0.16,0.16,0.079,0.00035,0.00035,9.3e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5390000,1,-0.0088,-0.011,0.00074,0.0074,0.011,-0.065,0.0046,0.0022,-0.067,-0.002,-0.0053,5.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00014,0.36,0.36,0.057,0.15,0.15,0.079,0.00031,0.00031,9.1e-06,0.04,0.04,0.0078,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
57 5490000,1,-0.0088,-0.011,0.0011,0.0072,0.012,-0.06,0.0031,0.0021,-0.065,-0.002,-0.0054,-7.2e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0027,0.0027,0.00013,0.28,0.28,0.056,0.11,0.11,0.079,0.00028,0.00028,8.4e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5490000,1,-0.0089,-0.011,0.00073,0.0069,0.012,-0.06,0.0031,0.002,-0.065,-0.002,-0.0054,5e-05,0,0,-0.11,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.28,0.28,0.056,0.11,0.11,0.079,0.00025,0.00025,8.3e-06,0.04,0.04,0.0073,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
58 5590000,1,-0.0088,-0.012,0.00099,0.0083,0.016,-0.053,0.004,0.0035,-0.058,-0.002,-0.0054,-7.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0028,0.0028,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00028,0.00028,8.4e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5590000,1,-0.0089,-0.011,0.00066,0.0081,0.015,-0.053,0.0039,0.0034,-0.058,-0.002,-0.0054,5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.33,0.33,0.053,0.15,0.15,0.078,0.00025,0.00025,8.3e-06,0.04,0.04,0.0067,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
59 5690000,1,-0.0089,-0.011,0.00089,0.0077,0.016,-0.052,0.0028,0.003,-0.055,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0024,0.0024,0.00012,0.25,0.25,0.051,0.11,0.11,0.076,0.00023,0.00023,7.6e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5690000,1,-0.0089,-0.011,0.00055,0.0074,0.015,-0.052,0.0028,0.0029,-0.055,-0.0019,-0.0054,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0019,0.0019,0.00012,0.26,0.26,0.051,0.11,0.11,0.076,0.00019,0.00019,7.5e-06,0.04,0.04,0.0063,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
60 5790000,1,-0.0088,-0.011,0.00085,0.0089,0.018,-0.049,0.0036,0.0047,-0.053,-0.0019,-0.0054,-7.5e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0025,0.0025,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00023,0.00023,7.6e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5790000,1,-0.0088,-0.011,0.0005,0.0087,0.018,-0.049,0.0036,0.0046,-0.053,-0.0019,-0.0054,4.8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00013,0.3,0.3,0.05,0.14,0.14,0.077,0.00019,0.00019,7.5e-06,0.04,0.04,0.0059,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
61 5890000,1,-0.0088,-0.011,0.00088,0.0095,0.015,-0.048,0.0027,0.0038,-0.056,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.23,0.23,0.047,0.1,0.1,0.075,0.00018,0.00018,6.9e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5890000,1,-0.0088,-0.011,0.00053,0.0092,0.015,-0.048,0.0027,0.0037,-0.056,-0.0018,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.24,0.24,0.047,0.1,0.1,0.075,0.00015,0.00015,6.8e-06,0.04,0.04,0.0054,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
62 5990000,1,-0.0088,-0.012,0.00086,0.011,0.017,-0.041,0.0038,0.0054,-0.05,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0022,0.0022,0.00012,0.27,0.27,0.045,0.13,0.13,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 5990000,1,-0.0088,-0.011,0.00049,0.011,0.016,-0.041,0.0037,0.0053,-0.05,-0.0018,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00012,0.27,0.27,0.045,0.13,0.13,0.074,0.00015,0.00015,6.8e-06,0.04,0.04,0.005,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
63 6090000,1,-0.0088,-0.011,0.00067,0.011,0.018,-0.039,0.0049,0.0072,-0.047,-0.0019,-0.0055,-7.7e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0023,0.0023,0.00013,0.31,0.31,0.044,0.17,0.17,0.074,0.00018,0.00018,6.9e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6090000,1,-0.0088,-0.011,0.0003,0.011,0.018,-0.039,0.0048,0.007,-0.047,-0.0018,-0.0055,4.6e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00013,0.32,0.32,0.044,0.17,0.17,0.074,0.00015,0.00015,6.8e-06,0.04,0.04,0.0047,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
64 6190000,1,-0.0089,-0.011,0.00068,0.0087,0.017,-0.038,0.0038,0.0057,-0.047,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.002,0.002,0.00012,0.24,0.24,0.042,0.13,0.13,0.073,0.00015,0.00015,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6190000,1,-0.0089,-0.011,0.0003,0.0085,0.016,-0.038,0.0037,0.0056,-0.047,-0.0018,-0.0055,4.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00012,0.25,0.25,0.042,0.13,0.13,0.073,0.00012,0.00012,6.3e-06,0.04,0.04,0.0044,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
65 6290000,1,-0.0089,-0.011,0.00071,0.008,0.019,-0.041,0.0046,0.0075,-0.053,-0.0018,-0.0055,-8e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0021,0.0021,0.00012,0.28,0.28,0.04,0.16,0.16,0.072,0.00015,0.00015,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6290000,1,-0.0089,-0.011,0.00032,0.0078,0.019,-0.041,0.0046,0.0073,-0.053,-0.0018,-0.0055,4.4e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00012,0.29,0.29,0.04,0.16,0.16,0.072,0.00012,0.00012,6.3e-06,0.04,0.04,0.0041,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1
66 6390000,1,-0.0089,-0.011,0.00072,0.0082,0.016,-0.042,0.0034,0.006,-0.056,-0.0017,-0.0056,-8.2e-05,0,0,-0.12,0,0,0,0,0,0,0,0,0.0017,0.0017,0.00011,0.22,0.22,0.039,0.12,0.12,0.072,0.00012,0.00012,5.8e-06,0.04,0.04,0.0039,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6390000,-0.29,0.025,-0.0062,0.96,-0.0089,0.0093,-0.042,0.0041,0.0051,-0.056,-0.0017,-0.0055,4.3e-05,0,0,-0.12,-0.095,-0.021,0.51,0.072,-0.027,-0.063,0,0,0.0012,0.0012,0.066,0.2,0.2,0.039,0.12,0.12,0.072,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0038,0.0014,0.00037,0.0014,0.0014,0.0011,0.0014,1,1
67 6490000,1,-0.0089,-0.011,0.00062,0.0057,0.016,-0.039,0.0041,0.0076,-0.053,-0.0017,-0.0056,-8.2e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0018,0.0018,0.00012,0.25,0.25,0.038,0.15,0.15,0.07,0.00012,0.00012,5.8e-06,0.04,0.04,0.0036,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6490000,-0.29,0.026,-0.0062,0.96,-0.027,0.0035,-0.039,0.0048,0.0045,-0.053,-0.0017,-0.0054,4.3e-05,0,0,-0.13,-0.1,-0.022,0.51,0.076,-0.028,-0.067,0,0,0.0012,0.0012,0.056,0.2,0.2,0.038,0.15,0.15,0.07,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0036,0.0013,0.00021,0.0013,0.0013,0.00096,0.0013,1,1
68 6590000,1,-0.009,-0.011,0.00055,0.0039,0.015,-0.042,0.0029,0.0058,-0.056,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.2,0.2,0.036,0.12,0.12,0.069,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0034,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6590000,-0.29,0.026,-0.0062,0.96,-0.047,-0.0062,-0.041,0.004,0.003,-0.056,-0.0016,-0.0053,4.3e-05,-0.0003,0.00015,-0.13,-0.1,-0.022,0.5,0.077,-0.029,-0.068,0,0,0.0012,0.0012,0.054,0.21,0.21,0.036,0.18,0.18,0.069,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0033,0.0013,0.00016,0.0013,0.0013,0.00093,0.0013,1,1
69 6690000,1,-0.0089,-0.011,0.0005,0.0022,0.018,-0.044,0.0032,0.0075,-0.057,-0.0017,-0.0056,-8.5e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0016,0.0016,0.00011,0.23,0.23,0.035,0.14,0.14,0.068,9.8e-05,9.8e-05,5.3e-06,0.04,0.04,0.0031,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6690000,-0.29,0.026,-0.0061,0.96,-0.066,-0.015,-0.043,0.0003,0.00035,-0.057,-0.0016,-0.0052,4.3e-05,-0.00055,0.00035,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0012,0.0012,0.052,0.21,0.21,0.035,0.22,0.22,0.068,9.9e-05,9.9e-05,5.8e-06,0.04,0.04,0.0031,0.0013,0.00014,0.0013,0.0013,0.00092,0.0013,1,1
70 6790000,1,-0.009,-0.011,0.00047,0.003,0.015,-0.042,0.0021,0.0059,-0.058,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0014,0.0014,0.00011,0.18,0.18,0.034,0.11,0.11,0.068,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.003,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6790000,-0.29,0.026,-0.0061,0.96,-0.087,-0.026,-0.041,-0.0024,-0.0041,-0.057,-0.0015,-0.0051,4.3e-05,-0.0011,0.00062,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0012,0.051,0.22,0.22,0.034,0.26,0.26,0.068,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.003,0.0013,0.00013,0.0013,0.0013,0.00091,0.0013,1,1
71 6890000,1,-0.0088,-0.011,0.00039,0.0023,0.015,-0.039,0.0024,0.0074,-0.055,-0.0016,-0.0056,-8.6e-05,0,0,-0.13,0,0,0,0,0,0,0,0,0.0015,0.0015,0.00011,0.21,0.21,0.032,0.14,0.14,0.067,8e-05,8.1e-05,4.9e-06,0.04,0.04,0.0028,0.0025,0.0025,0.0025,0.0025,0.0025,0.0025,1,1 6890000,-0.29,0.026,-0.006,0.96,-0.11,-0.032,-0.037,-0.0093,-0.0084,-0.055,-0.0014,-0.005,4.3e-05,-0.0014,0.00078,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0012,0.051,0.23,0.23,0.032,0.3,0.3,0.067,9.8e-05,9.8e-05,5.8e-06,0.04,0.04,0.0028,0.0013,0.00012,0.0013,0.0013,0.00091,0.0013,1,1
72 6990000,-0.29,0.024,-0.0065,0.96,-0.0055,0.0091,-0.037,0.0023,0.0053,-0.055,-0.0016,-0.0056,-8.7e-05,0,0,-0.13,-0.092,-0.02,0.51,0.069,-0.028,-0.058,0,0,0.0012,0.0012,0.072,0.16,0.16,0.031,0.11,0.11,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0026,0.0014,0.00048,0.0014,0.0014,0.0012,0.0014,1,1 6990000,-0.29,0.026,-0.0059,0.96,-0.13,-0.04,-0.035,-0.018,-0.013,-0.054,-0.0014,-0.0049,4.4e-05,-0.0017,0.00089,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0013,0.05,0.24,0.24,0.031,0.35,0.35,0.066,9.7e-05,9.7e-05,5.8e-06,0.04,0.04,0.0026,0.0013,0.00011,0.0013,0.0013,0.0009,0.0013,1,1
73 7090000,-0.28,0.025,-0.0064,0.96,-0.026,-0.00083,-0.037,0.0022,0.0052,-0.056,-0.0015,-0.0055,-8.7e-05,0,0,-0.13,-0.099,-0.021,0.51,0.075,-0.029,-0.065,0,0,0.0012,0.0012,0.058,0.16,0.16,0.03,0.13,0.13,0.066,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0024,0.0013,0.00025,0.0013,0.0013,0.00099,0.0013,1,1 7090000,-0.29,0.026,-0.0058,0.96,-0.15,-0.051,-0.035,-0.031,-0.018,-0.055,-0.0014,-0.0049,4.4e-05,-0.0018,0.00089,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0013,0.05,0.25,0.25,0.03,0.4,0.4,0.066,9.6e-05,9.6e-05,5.8e-06,0.04,0.04,0.0024,0.0013,0.0001,0.0013,0.0013,0.0009,0.0013,1,1
74 7190000,-0.28,0.026,-0.0064,0.96,-0.047,-0.0082,-0.036,0.00063,0.0038,-0.058,-0.0015,-0.0055,-8.6e-05,3.9e-05,-1e-05,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.054,0.17,0.17,0.029,0.16,0.16,0.065,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0023,0.0013,0.00018,0.0013,0.0013,0.00094,0.0013,1,1 7190000,-0.29,0.026,-0.0058,0.96,-0.18,-0.061,-0.034,-0.045,-0.027,-0.058,-0.0014,-0.0048,4.3e-05,-0.0021,0.0011,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.27,0.27,0.029,0.46,0.46,0.065,9.5e-05,9.5e-05,5.8e-06,0.04,0.04,0.0023,0.0013,9.8e-05,0.0013,0.0013,0.0009,0.0013,1,1
75 7290000,-0.28,0.026,-0.0064,0.96,-0.07,-0.017,-0.033,-0.0034,0.0023,-0.054,-0.0015,-0.0054,-8.5e-05,0.00011,-5e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.053,0.18,0.18,0.028,0.19,0.19,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0022,0.0013,0.00015,0.0013,0.0013,0.00093,0.0013,1,1 7290000,-0.29,0.026,-0.0057,0.96,-0.2,-0.07,-0.031,-0.065,-0.032,-0.053,-0.0014,-0.0049,4.4e-05,-0.002,0.0011,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.29,0.29,0.028,0.51,0.51,0.064,9.4e-05,9.3e-05,5.8e-06,0.04,0.04,0.0022,0.0013,9.4e-05,0.0013,0.0013,0.0009,0.0013,1,1
76 7390000,-0.28,0.026,-0.0062,0.96,-0.091,-0.024,-0.031,-0.0098,-8.5e-05,-0.052,-0.0015,-0.0054,-8.4e-05,0.00016,-4e-06,-0.13,-0.1,-0.022,0.51,0.077,-0.03,-0.067,0,0,0.0012,0.0012,0.052,0.19,0.19,0.027,0.22,0.22,0.064,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.002,0.0013,0.00013,0.0013,0.0013,0.00092,0.0013,1,1 7390000,-0.29,0.026,-0.0056,0.96,-0.23,-0.077,-0.029,-0.089,-0.037,-0.051,-0.0014,-0.0049,4.4e-05,-0.0019,0.00096,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0013,0.0013,0.049,0.31,0.31,0.027,0.58,0.58,0.064,9.2e-05,9.1e-05,5.8e-06,0.04,0.04,0.002,0.0013,9.1e-05,0.0013,0.0013,0.0009,0.0013,1,1
77 7490000,-0.28,0.026,-0.0062,0.96,-0.11,-0.032,-0.025,-0.015,-0.0034,-0.046,-0.0015,-0.0053,-8.1e-05,0.00033,7.2e-07,-0.13,-0.1,-0.022,0.5,0.077,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.2,0.2,0.026,0.26,0.26,0.063,6.6e-05,6.6e-05,4.6e-06,0.04,0.04,0.0019,0.0013,0.00012,0.0013,0.0013,0.00091,0.0013,1,1 7490000,-0.29,0.026,-0.0055,0.96,-0.25,-0.086,-0.023,-0.1,-0.044,-0.044,-0.0014,-0.0048,4.8e-05,-0.0026,0.0009,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0014,0.0013,0.049,0.34,0.33,0.026,0.64,0.64,0.063,9e-05,8.9e-05,5.7e-06,0.04,0.04,0.0019,0.0013,8.9e-05,0.0013,0.0013,0.0009,0.0013,1,1
78 7590000,-0.28,0.026,-0.0063,0.96,-0.13,-0.041,-0.021,-0.024,-0.0083,-0.04,-0.0015,-0.0052,-8e-05,0.00045,-2.7e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0012,0.0012,0.051,0.22,0.21,0.025,0.3,0.3,0.062,6.6e-05,6.5e-05,4.6e-06,0.04,0.04,0.0018,0.0013,0.00011,0.0013,0.0013,0.00091,0.0013,1,1 7590000,-0.29,0.026,-0.0056,0.96,-0.27,-0.096,-0.019,-0.12,-0.055,-0.039,-0.0014,-0.0047,4.9e-05,-0.003,0.001,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0014,0.0013,0.049,0.37,0.36,0.025,0.71,0.71,0.062,8.8e-05,8.7e-05,5.7e-06,0.04,0.04,0.0018,0.0013,8.7e-05,0.0013,0.0013,0.0009,0.0013,1,1
79 7690000,-0.28,0.026,-0.0063,0.96,-0.16,-0.051,-0.02,-0.034,-0.015,-0.036,-0.0014,-0.0051,-7.9e-05,0.00056,-6.8e-05,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.23,0.23,0.025,0.34,0.34,0.062,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0017,0.0013,0.0001,0.0013,0.0013,0.0009,0.0013,1,1 7690000,-0.29,0.027,-0.0056,0.96,-0.3,-0.11,-0.018,-0.15,-0.069,-0.035,-0.0014,-0.0046,4.9e-05,-0.0033,0.0012,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.4,0.39,0.025,0.79,0.79,0.062,8.5e-05,8.5e-05,5.7e-06,0.04,0.04,0.0017,0.0013,8.5e-05,0.0013,0.0013,0.0009,0.0013,1,1
80 7790000,-0.28,0.026,-0.0062,0.96,-0.18,-0.061,-0.022,-0.041,-0.025,-0.041,-0.0014,-0.005,-7.8e-05,0.00088,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0012,0.05,0.26,0.25,0.024,0.39,0.39,0.061,6.5e-05,6.5e-05,4.6e-06,0.04,0.04,0.0016,0.0013,9.8e-05,0.0013,0.0013,0.0009,0.0013,1,1 7790000,-0.29,0.027,-0.0056,0.96,-0.32,-0.12,-0.02,-0.16,-0.091,-0.039,-0.0012,-0.0043,4.9e-05,-0.0043,0.0018,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.43,0.43,0.024,0.88,0.87,0.061,8.3e-05,8.2e-05,5.7e-06,0.04,0.04,0.0016,0.0013,8.4e-05,0.0013,0.0013,0.00089,0.0013,1,1
81 7890000,-0.28,0.026,-0.0062,0.96,-0.2,-0.071,-0.022,-0.057,-0.033,-0.044,-0.0013,-0.0049,-7.7e-05,0.00099,-0.00028,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.28,0.28,0.023,0.45,0.45,0.06,6.4e-05,6.4e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.4e-05,0.0013,0.0013,0.0009,0.0013,1,1 7890000,-0.29,0.027,-0.0056,0.96,-0.34,-0.13,-0.021,-0.19,-0.11,-0.043,-0.0012,-0.0043,4.8e-05,-0.0043,0.0019,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.47,0.46,0.023,0.96,0.96,0.06,8e-05,7.9e-05,5.7e-06,0.04,0.04,0.0015,0.0013,8.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
82 7990000,-0.28,0.026,-0.0061,0.96,-0.22,-0.078,-0.018,-0.08,-0.039,-0.04,-0.0013,-0.0049,-7.7e-05,0.00089,-0.00023,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.3,0.3,0.022,0.51,0.51,0.059,6.3e-05,6.3e-05,4.6e-06,0.04,0.04,0.0015,0.0013,9.1e-05,0.0013,0.0013,0.0009,0.0013,1,1 7990000,-0.29,0.027,-0.0055,0.96,-0.37,-0.14,-0.017,-0.24,-0.11,-0.039,-0.0013,-0.0045,4.7e-05,-0.0037,0.0016,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.51,0.5,0.022,1.1,1.1,0.059,7.7e-05,7.5e-05,5.7e-06,0.04,0.04,0.0015,0.0013,8.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
83 8090000,-0.28,0.026,-0.006,0.96,-0.25,-0.09,-0.019,-0.1,-0.053,-0.043,-0.0013,-0.0049,-8e-05,0.00093,-0.00038,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.05,0.33,0.33,0.022,0.57,0.57,0.059,6.2e-05,6.2e-05,4.6e-06,0.04,0.04,0.0014,0.0013,8.9e-05,0.0013,0.0013,0.0009,0.0013,1,1 8090000,-0.29,0.027,-0.0055,0.96,-0.4,-0.15,-0.017,-0.28,-0.14,-0.041,-0.0011,-0.0045,4.1e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.56,0.55,0.022,1.2,1.2,0.059,7.4e-05,7.2e-05,5.7e-06,0.04,0.04,0.0014,0.0013,8e-05,0.0013,0.0013,0.00089,0.0013,1,1
84 8190000,-0.28,0.026,-0.0061,0.96,-0.27,-0.1,-0.014,-0.12,-0.069,-0.036,-0.0012,-0.0048,-8.2e-05,0.00096,-0.0005,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.36,0.36,0.021,0.64,0.64,0.058,6.1e-05,6.1e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.7e-05,0.0013,0.0013,0.0009,0.0013,1,1 8190000,-0.29,0.027,-0.0057,0.96,-0.022,-0.0088,-0.012,-0.29,-0.14,-0.035,-0.001,-0.0045,3.7e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.021,1e+02,1e+02,0.058,7e-05,6.9e-05,5.7e-06,0.04,0.04,0.0013,0.0013,7.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
85 8290000,-0.28,0.026,-0.0061,0.96,-0.3,-0.11,-0.013,-0.16,-0.077,-0.036,-0.0012,-0.005,-8.4e-05,0.0007,-0.00042,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0013,0.0013,0.049,0.4,0.39,0.02,0.72,0.72,0.057,6e-05,6e-05,4.6e-06,0.04,0.04,0.0013,0.0013,8.5e-05,0.0013,0.0013,0.0009,0.0013,1,1 8290000,-0.29,0.027,-0.0057,0.96,-0.049,-0.019,-0.011,-0.3,-0.15,-0.035,-0.0011,-0.0048,3.4e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.02,1e+02,1e+02,0.057,6.7e-05,6.5e-05,5.7e-06,0.04,0.04,0.0013,0.0013,7.8e-05,0.0013,0.0013,0.00089,0.0013,1,1
86 8390000,-0.28,0.026,-0.0061,0.96,-0.33,-0.12,-0.011,-0.2,-0.089,-0.034,-0.0012,-0.005,-8.5e-05,0.00063,-0.00041,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.43,0.43,0.02,0.81,0.8,0.057,5.9e-05,5.9e-05,4.6e-06,0.04,0.04,0.0012,0.0013,8.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 8390000,-0.29,0.027,-0.0056,0.96,-0.073,-0.026,-0.01,-0.3,-0.15,-0.033,-0.0011,-0.0049,3.3e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.02,51,51,0.057,6.4e-05,6.2e-05,5.7e-06,0.04,0.04,0.0012,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1
87 8490000,-0.28,0.026,-0.0059,0.96,-0.35,-0.12,-0.012,-0.23,-0.094,-0.039,-0.0013,-0.005,-8.2e-05,0.00062,-0.00029,-0.13,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.47,0.46,0.019,0.9,0.9,0.056,5.8e-05,5.7e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 8490000,-0.29,0.027,-0.0054,0.96,-0.097,-0.037,-0.011,-0.31,-0.15,-0.038,-0.0012,-0.005,3.6e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.019,52,52,0.056,6e-05,5.9e-05,5.7e-06,0.04,0.04,0.0011,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1
88 8590000,-0.28,0.027,-0.0059,0.96,-0.38,-0.14,-0.0073,-0.26,-0.12,-0.034,-0.0012,-0.0049,-8.2e-05,0.00079,-0.00042,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0013,0.049,0.51,0.51,0.019,1,1,0.055,5.6e-05,5.5e-05,4.6e-06,0.04,0.04,0.0011,0.0013,8.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 8590000,-0.29,0.027,-0.0054,0.96,-0.12,-0.045,-0.006,-0.31,-0.15,-0.032,-0.0011,-0.0049,3.4e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.019,35,35,0.055,5.7e-05,5.6e-05,5.7e-06,0.04,0.04,0.0011,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1
89 8690000,-0.28,0.027,-0.0059,0.96,-0.4,-0.14,-0.0089,-0.3,-0.13,-0.035,-0.0012,-0.0049,-8.2e-05,0.00071,-0.00035,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.56,0.55,0.018,1.1,1.1,0.055,5.5e-05,5.4e-05,4.6e-06,0.04,0.04,0.001,0.0013,8e-05,0.0013,0.0013,0.00089,0.0013,1,1 8690000,-0.29,0.027,-0.0054,0.96,-0.15,-0.054,-0.0078,-0.32,-0.16,-0.034,-0.0012,-0.005,3.5e-05,-0.0036,0.0022,-0.13,-0.1,-0.022,0.5,0.078,-0.029,-0.068,0,0,0.0016,0.0015,0.049,25,25,0.018,37,37,0.055,5.4e-05,5.3e-05,5.7e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1
90 8790000,-0.28,0.027,-0.0059,0.96,-0.43,-0.15,-0.0084,-0.35,-0.14,-0.032,-0.0012,-0.005,-8.5e-05,0.00052,-0.0004,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.61,0.6,0.018,1.2,1.2,0.055,5.3e-05,5.2e-05,4.6e-06,0.04,0.04,0.00099,0.0013,7.9e-05,0.0013,0.0013,0.00089,0.0013,1,1 8790000,-0.29,0.027,-0.0055,0.96,-0.17,-0.061,-0.0075,-0.33,-0.16,-0.031,-0.0012,-0.0051,3.1e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,24,24,0.018,28,28,0.055,5.1e-05,5e-05,5.7e-06,0.04,0.04,0.001,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1
91 8890000,-0.28,0.027,-0.0059,0.96,-0.46,-0.16,-0.0039,-0.38,-0.16,-0.026,-0.0012,-0.0049,-8.1e-05,0.00064,-0.00031,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.66,0.65,0.017,1.4,1.4,0.054,5.1e-05,5e-05,4.5e-06,0.04,0.04,0.00095,0.0013,7.8e-05,0.0013,0.0013,0.00089,0.0013,1,1 8890000,-0.29,0.027,-0.0054,0.96,-0.2,-0.072,-0.0029,-0.35,-0.16,-0.025,-0.0012,-0.005,3.4e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,24,24,0.017,30,30,0.054,4.8e-05,4.7e-05,5.7e-06,0.04,0.04,0.00095,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1
92 8990000,-0.28,0.027,-0.0058,0.96,-0.47,-0.17,-0.0028,-0.41,-0.17,-0.029,-0.0013,-0.0047,-7.5e-05,0.001,-0.0003,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0014,0.0014,0.049,0.72,0.7,0.017,1.5,1.5,0.054,4.9e-05,4.8e-05,4.5e-06,0.04,0.04,0.00091,0.0013,7.7e-05,0.0013,0.0013,0.00089,0.0013,1,1 8990000,-0.29,0.027,-0.0053,0.96,-0.22,-0.083,-0.0018,-0.35,-0.17,-0.027,-0.0012,-0.0048,4e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,23,23,0.017,25,25,0.054,4.6e-05,4.4e-05,5.7e-06,0.04,0.04,0.00092,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1
93 9090000,-0.28,0.027,-0.0056,0.96,-0.5,-0.18,-0.0038,-0.47,-0.17,-0.029,-0.0014,-0.0048,-7.2e-05,0.00081,-2.1e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.77,0.76,0.016,1.7,1.7,0.053,4.7e-05,4.6e-05,4.5e-06,0.04,0.04,0.00087,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1 9090000,-0.29,0.027,-0.0051,0.96,-0.24,-0.096,-0.003,-0.37,-0.18,-0.027,-0.0014,-0.005,4.3e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,23,23,0.017,27,27,0.053,4.3e-05,4.1e-05,5.7e-06,0.04,0.04,0.00088,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
94 9190000,-0.28,0.027,-0.0055,0.96,-0.53,-0.18,-0.0029,-0.52,-0.18,-0.029,-0.0015,-0.0048,-6.9e-05,0.0008,0.00012,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.84,0.82,0.016,1.9,1.9,0.052,4.5e-05,4.4e-05,4.5e-06,0.04,0.04,0.00084,0.0013,7.6e-05,0.0013,0.0013,0.00089,0.0013,1,1 9190000,-0.29,0.027,-0.0049,0.96,-0.26,-0.1,-0.0023,-0.38,-0.18,-0.028,-0.0015,-0.005,4.6e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0016,0.0015,0.049,21,21,0.016,23,23,0.053,4e-05,3.9e-05,5.7e-06,0.04,0.04,0.00084,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
95 9290000,-0.28,0.027,-0.0054,0.96,-0.56,-0.19,-0.0011,-0.56,-0.21,-0.026,-0.0014,-0.0047,-6.7e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,0.9,0.88,0.016,2.1,2.1,0.052,4.3e-05,4.2e-05,4.5e-06,0.04,0.04,0.0008,0.0013,7.5e-05,0.0013,0.0013,0.00089,0.0013,1,1 9290000,-0.29,0.027,-0.0048,0.96,-0.29,-0.12,-0.00041,-0.41,-0.19,-0.025,-0.0015,-0.0049,4.7e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,21,21,0.016,26,26,0.052,3.8e-05,3.6e-05,5.7e-06,0.04,0.04,0.00081,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1
96 9390000,-0.28,0.027,-0.0054,0.96,-0.023,-0.0084,0.0003,-0.57,-0.21,-0.026,-0.0013,-0.0047,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.052,4.2e-05,4e-05,4.5e-06,0.04,0.04,0.00077,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 9390000,-0.29,0.027,-0.0048,0.96,-0.3,-0.12,0.0009,-0.41,-0.19,-0.025,-0.0014,-0.0049,4.2e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,19,19,0.015,22,22,0.052,3.6e-05,3.4e-05,5.7e-06,0.04,0.04,0.00078,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
97 9490000,-0.28,0.027,-0.0053,0.96,-0.049,-0.017,0.0021,-0.58,-0.21,-0.023,-0.0014,-0.0048,-7.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,1e+02,1e+02,0.051,4e-05,3.8e-05,4.5e-06,0.04,0.04,0.00074,0.0013,7.4e-05,0.0013,0.0013,0.00089,0.0013,1,1 9490000,-0.29,0.027,-0.0048,0.96,-0.32,-0.12,0.0026,-0.44,-0.2,-0.022,-0.0014,-0.005,4.2e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,19,19,0.015,25,25,0.051,3.3e-05,3.2e-05,5.7e-06,0.04,0.04,0.00075,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1
98 9590000,-0.28,0.027,-0.0056,0.96,-0.076,-0.023,0.0023,-0.58,-0.21,-0.024,-0.0012,-0.0048,-8e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0014,0.049,25,25,0.015,51,51,0.05,3.8e-05,3.7e-05,4.5e-06,0.04,0.04,0.00072,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 9590000,-0.29,0.027,-0.0051,0.96,-0.33,-0.12,0.0026,-0.43,-0.2,-0.023,-0.0013,-0.0051,3.4e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,17,17,0.015,22,22,0.051,3.1e-05,3e-05,5.7e-06,0.04,0.04,0.00072,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
99 9690000,-0.28,0.027,-0.0057,0.96,-0.1,-0.031,0.0054,-0.59,-0.21,-0.023,-0.0012,-0.0048,-8.2e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,52,52,0.05,3.6e-05,3.5e-05,4.5e-06,0.04,0.04,0.00069,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 9690000,-0.29,0.027,-0.0052,0.96,-0.36,-0.13,0.0057,-0.47,-0.21,-0.022,-0.0012,-0.0051,3.2e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,17,17,0.014,25,25,0.051,3e-05,2.8e-05,5.7e-06,0.04,0.04,0.0007,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
100 9790000,-0.28,0.027,-0.0059,0.96,-0.13,-0.038,0.0041,-0.59,-0.22,-0.023,-0.001,-0.005,-9.1e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,35,35,0.05,3.4e-05,3.3e-05,4.5e-06,0.04,0.04,0.00067,0.0013,7.3e-05,0.0013,0.0013,0.00089,0.0013,1,1 9790000,-0.29,0.027,-0.0055,0.96,-0.36,-0.12,0.0043,-0.46,-0.2,-0.023,-0.0011,-0.0053,2.5e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,15,15,0.014,22,22,0.05,2.8e-05,2.7e-05,5.7e-06,0.04,0.04,0.00068,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
101 9890000,-0.28,0.027,-0.0058,0.96,-0.16,-0.047,0.0057,-0.61,-0.22,-0.023,-0.0011,-0.0049,-8.9e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,25,25,0.014,37,37,0.049,3.2e-05,3.1e-05,4.5e-06,0.04,0.04,0.00064,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 9890000,-0.29,0.027,-0.0054,0.96,-0.39,-0.13,0.0058,-0.49,-0.21,-0.023,-0.0011,-0.0052,2.7e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,15,15,0.014,25,25,0.049,2.6e-05,2.5e-05,5.7e-06,0.04,0.04,0.00065,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1
102 9990000,-0.28,0.027,-0.006,0.96,-0.18,-0.051,0.0065,-0.61,-0.22,-0.025,-0.00096,-0.005,-9.6e-05,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.014,28,28,0.049,3.1e-05,3e-05,4.5e-06,0.04,0.04,0.00062,0.0013,7.2e-05,0.0013,0.0013,0.00089,0.0013,1,1 9990000,-0.29,0.027,-0.0056,0.96,-0.41,-0.13,0.0065,-0.53,-0.22,-0.025,-0.001,-0.0053,2.2e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,15,15,0.014,28,28,0.049,2.5e-05,2.4e-05,5.7e-06,0.04,0.04,0.00063,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
103 10090000,-0.28,0.027,-0.0061,0.96,-0.21,-0.054,0.0078,-0.63,-0.23,-0.023,-0.00084,-0.0051,-0.0001,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,24,24,0.013,30,30,0.049,2.9e-05,2.8e-05,4.5e-06,0.04,0.04,0.0006,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 10090000,-0.29,0.027,-0.0058,0.96,-0.41,-0.12,0.0077,-0.52,-0.21,-0.023,-0.00089,-0.0054,1.6e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,13,14,0.013,24,24,0.049,2.3e-05,2.2e-05,5.7e-06,0.04,0.04,0.00061,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
104 10190000,-0.28,0.027,-0.0064,0.96,-0.23,-0.056,0.0087,-0.64,-0.23,-0.024,-0.00067,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,25,25,0.048,2.8e-05,2.7e-05,4.5e-06,0.04,0.04,0.00058,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 10190000,-0.29,0.027,-0.0061,0.96,-0.44,-0.12,0.0086,-0.56,-0.22,-0.024,-0.00074,-0.0054,1.1e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,14,14,0.013,27,27,0.048,2.2e-05,2.1e-05,5.7e-06,0.04,0.04,0.00059,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
105 10290000,-0.28,0.027,-0.0064,0.96,-0.26,-0.065,0.0079,-0.66,-0.23,-0.023,-0.00072,-0.005,-0.00011,0.00094,9e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,23,23,0.013,27,27,0.048,2.6e-05,2.5e-05,4.5e-06,0.04,0.04,0.00057,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 10290000,-0.29,0.027,-0.006,0.96,-0.43,-0.12,0.0077,-0.55,-0.22,-0.023,-0.00079,-0.0053,1.3e-05,-0.0036,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,12,12,0.013,24,24,0.048,2.1e-05,2e-05,5.7e-06,0.04,0.04,0.00058,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1
106 10390000,-0.28,0.028,-0.0063,0.96,-0.012,-0.0081,-0.0025,-7.9e-05,-0.00028,-0.023,-0.00074,-0.0049,-0.0001,0.001,0.00015,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.25,0.25,0.56,0.25,0.25,0.049,2.5e-05,2.4e-05,4.5e-06,0.04,0.04,0.00055,0.0013,7.1e-05,0.0013,0.0013,0.00089,0.0013,1,1 10390000,-0.29,0.027,-0.006,0.96,-0.011,-0.0086,-0.0026,-6e-05,-0.0003,-0.022,-0.00081,-0.0053,1.5e-05,-0.0038,0.0021,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,0.25,0.25,0.56,0.25,0.25,0.049,1.9e-05,1.8e-05,5.7e-06,0.04,0.04,0.00056,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
107 10490000,-0.28,0.027,-0.0064,0.96,-0.041,-0.014,0.0066,-0.0027,-0.0013,-0.018,-0.00066,-0.005,-0.00011,0.00082,2.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.26,0.26,0.55,0.26,0.26,0.058,2.4e-05,2.3e-05,4.5e-06,0.04,0.04,0.00054,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 10490000,-0.29,0.027,-0.0061,0.96,-0.04,-0.015,0.0064,-0.0026,-0.0014,-0.018,-0.00073,-0.0053,1.2e-05,-0.0038,0.0025,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0016,0.0015,0.049,0.26,0.26,0.55,0.26,0.26,0.058,1.8e-05,1.7e-05,5.7e-06,0.04,0.04,0.00055,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
108 10590000,-0.28,0.027,-0.0063,0.96,-0.052,-0.013,0.012,-0.0032,-0.00096,-0.016,-0.00073,-0.005,-0.0001,0.0014,7.7e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.13,0.13,0.27,0.26,0.26,0.056,2.2e-05,2.1e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 10590000,-0.29,0.027,-0.0059,0.96,-0.051,-0.014,0.012,-0.0032,-0.001,-0.016,-0.0008,-0.0053,1.4e-05,-0.0032,0.0021,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0015,0.0015,0.049,0.13,0.13,0.27,0.26,0.26,0.056,1.7e-05,1.6e-05,5.7e-06,0.039,0.039,0.00054,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
109 10690000,-0.28,0.027,-0.0063,0.96,-0.081,-0.018,0.015,-0.0099,-0.0025,-0.013,-0.0007,-0.005,-0.00011,0.0014,2.4e-05,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.068,0,0,0.0015,0.0015,0.049,0.14,0.14,0.26,0.27,0.27,0.065,2.1e-05,2e-05,4.5e-06,0.04,0.04,0.00052,0.0013,7e-05,0.0013,0.0013,0.00089,0.0013,1,1 10690000,-0.29,0.027,-0.0059,0.96,-0.08,-0.02,0.015,-0.0097,-0.0027,-0.013,-0.00077,-0.0053,1.3e-05,-0.0032,0.0022,-0.14,-0.1,-0.022,0.5,0.078,-0.029,-0.069,0,0,0.0015,0.0015,0.049,0.14,0.14,0.26,0.27,0.27,0.065,1.6e-05,1.6e-05,5.7e-06,0.039,0.039,0.00053,0.0013,6.9e-05,0.0013,0.0013,0.00089,0.0013,1,1
110 10790000,-0.28,0.027,-0.0062,0.96,-0.079,-0.021,0.013,-7.5e-06,-0.0018,-0.012,-0.00072,-0.005,-0.00011,0.0035,-0.0011,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.095,0.095,0.17,0.13,0.13,0.062,2e-05,1.9e-05,4.5e-06,0.039,0.039,0.00051,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 10790000,-0.29,0.027,-0.0059,0.96,-0.078,-0.023,0.013,3.2e-06,-0.0018,-0.012,-0.00079,-0.0053,1.2e-05,-0.00092,0.0011,-0.14,-0.1,-0.022,0.5,0.079,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.096,0.096,0.17,0.13,0.13,0.062,1.5e-05,1.5e-05,5.7e-06,0.039,0.039,0.00052,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1
111 10890000,-0.28,0.027,-0.006,0.96,-0.11,-0.03,0.0093,-0.0092,-0.0044,-0.015,-0.00083,-0.005,-0.0001,0.0036,-0.00084,-0.14,-0.1,-0.022,0.5,0.078,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.11,0.11,0.16,0.14,0.14,0.068,1.9e-05,1.8e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 10890000,-0.29,0.027,-0.0056,0.96,-0.1,-0.032,0.009,-0.009,-0.0046,-0.015,-0.00088,-0.0053,1.6e-05,-0.00093,0.00078,-0.14,-0.1,-0.022,0.5,0.079,-0.03,-0.069,0,0,0.0015,0.0014,0.049,0.11,0.11,0.16,0.14,0.14,0.068,1.4e-05,1.4e-05,5.7e-06,0.039,0.039,0.00051,0.0013,6.8e-05,0.0013,0.0013,0.00088,0.0013,1,1
112 10990000,-0.28,0.026,-0.006,0.96,-0.096,-0.031,0.016,-0.0034,-0.0023,-0.0093,-0.00085,-0.0052,-0.00011,0.0077,-0.0021,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.083,0.083,0.12,0.091,0.091,0.065,1.8e-05,1.7e-05,4.5e-06,0.039,0.039,0.0005,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 10990000,-0.29,0.026,-0.0057,0.96,-0.093,-0.033,0.015,-0.0033,-0.0023,-0.0093,-0.0009,-0.0055,1.3e-05,0.0039,-0.00053,-0.14,-0.1,-0.023,0.5,0.079,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.084,0.084,0.12,0.091,0.091,0.065,1.4e-05,1.3e-05,5.7e-06,0.038,0.038,0.00051,0.0013,6.8e-05,0.0013,0.0013,0.00087,0.0013,1,1
113 11090000,-0.28,0.027,-0.0064,0.96,-0.12,-0.039,0.019,-0.014,-0.0055,-0.0055,-0.00072,-0.0052,-0.00011,0.0078,-0.0025,-0.14,-0.1,-0.023,0.5,0.078,-0.03,-0.069,0,0,0.0014,0.0013,0.049,0.096,0.097,0.11,0.097,0.097,0.069,1.7e-05,1.6e-05,4.5e-06,0.039,0.039,0.00049,0.0013,6.9e-05,0.0013,0.0013,0.00088,0.0013,1,1 11090000,-0.29,0.026,-0.0061,0.96,-0.12,-0.041,0.019,-0.014,-0.0057,-0.0055,-0.00079,-0.0054,9.2e-06,0.0038,-0.00024,-0.14,-0.1,-0.023,0.5,0.079,-0.03,-0.069,0,0,0.0014,0.0013,0.048,0.097,0.098,0.11,0.097,0.097,0.069,1.3e-05,1.2e-05,5.7e-06,0.038,0.038,0.0005,0.0013,6.8e-05,0.0013,0.0013,0.00087,0.0013,1,1
114 11190000,-0.28,0.025,-0.0065,0.96,-0.1,-0.034,0.026,-0.0065,-0.0031,0.00085,-0.00071,-0.0053,-0.00011,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.079,0.079,0.083,0.072,0.072,0.066,1.6e-05,1.5e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1 11190000,-0.29,0.025,-0.0062,0.96,-0.1,-0.036,0.026,-0.0063,-0.0032,0.00088,-0.00078,-0.0056,5e-06,0.011,-0.0022,-0.14,-0.1,-0.023,0.5,0.079,-0.03,-0.069,0,0,0.0013,0.0012,0.048,0.08,0.08,0.083,0.072,0.072,0.066,1.2e-05,1.1e-05,5.7e-06,0.037,0.037,0.0005,0.0013,6.7e-05,0.0013,0.0012,0.00086,0.0013,1,1
115 11290000,-0.28,0.025,-0.0066,0.96,-0.13,-0.038,0.025,-0.018,-0.0066,0.00091,-0.00071,-0.0054,-0.00012,0.014,-0.0046,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0013,0.0012,0.049,0.094,0.094,0.077,0.078,0.078,0.069,1.5e-05,1.4e-05,4.5e-06,0.038,0.038,0.00049,0.0013,6.8e-05,0.0013,0.0012,0.00087,0.0013,1,1 11290000,-0.29,0.025,-0.0062,0.96,-0.12,-0.039,0.025,-0.017,-0.0068,0.00092,-0.00078,-0.0056,3.7e-06,0.011,-0.0022,-0.14,-0.1,-0.023,0.5,0.08,-0.03,-0.069,0,0,0.0013,0.0012,0.048,0.095,0.095,0.077,0.078,0.078,0.069,1.2e-05,1.1e-05,5.7e-06,0.037,0.037,0.0005,0.0013,6.7e-05,0.0013,0.0012,0.00086,0.0013,1,1
116 11390000,-0.28,0.024,-0.0065,0.96,-0.11,-0.032,0.016,-0.01,-0.004,-0.008,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.078,0.078,0.062,0.062,0.062,0.066,1.4e-05,1.4e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.8e-05,0.0013,0.0012,0.00085,0.0013,1,1 11390000,-0.29,0.023,-0.0062,0.96,-0.1,-0.033,0.016,-0.0096,-0.0041,-0.008,-0.00082,-0.0058,1.7e-06,0.018,-0.0041,-0.14,-0.1,-0.023,0.5,0.08,-0.03,-0.069,0,0,0.0011,0.0011,0.048,0.079,0.079,0.062,0.062,0.062,0.066,1.1e-05,1e-05,5.6e-06,0.036,0.036,0.00049,0.0012,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1
117 11490000,-0.28,0.024,-0.0064,0.96,-0.13,-0.036,0.021,-0.022,-0.0074,-0.002,-0.00075,-0.0055,-0.00012,0.021,-0.0065,-0.14,-0.1,-0.023,0.5,0.079,-0.031,-0.069,0,0,0.0012,0.0011,0.048,0.093,0.093,0.057,0.069,0.069,0.067,1.3e-05,1.3e-05,4.5e-06,0.037,0.037,0.00048,0.0013,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1 11490000,-0.29,0.023,-0.0061,0.96,-0.12,-0.037,0.021,-0.021,-0.0077,-0.002,-0.00082,-0.0057,2e-06,0.018,-0.0041,-0.14,-0.1,-0.023,0.5,0.08,-0.03,-0.069,0,0,0.0011,0.0011,0.048,0.094,0.094,0.057,0.069,0.069,0.067,1e-05,9.8e-06,5.6e-06,0.036,0.036,0.00049,0.0012,6.7e-05,0.0013,0.0012,0.00085,0.0013,1,1
118 11590000,-0.28,0.023,-0.0065,0.96,-0.11,-0.029,0.019,-0.013,-0.0046,-0.0033,-0.00079,-0.0056,-0.00012,0.027,-0.0085,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00098,0.048,0.077,0.077,0.048,0.056,0.056,0.065,1.3e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1 11590000,-0.29,0.022,-0.0062,0.96,-0.1,-0.03,0.019,-0.012,-0.0047,-0.0033,-0.00084,-0.0059,-4.5e-07,0.025,-0.0061,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.069,0,0,0.001,0.00096,0.048,0.078,0.078,0.048,0.056,0.056,0.065,9.7e-06,9.2e-06,5.6e-06,0.035,0.035,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00084,0.0013,1,1
119 11690000,-0.28,0.022,-0.0065,0.96,-0.12,-0.035,0.019,-0.024,-0.0078,-0.0047,-0.00081,-0.0057,-0.00012,0.027,-0.0083,-0.14,-0.1,-0.023,0.5,0.08,-0.031,-0.069,0,0,0.001,0.00099,0.048,0.092,0.092,0.044,0.063,0.063,0.066,1.2e-05,1.2e-05,4.5e-06,0.036,0.036,0.00048,0.0012,6.7e-05,0.0013,0.0012,0.00084,0.0013,1,1 11690000,-0.29,0.022,-0.0062,0.96,-0.12,-0.037,0.019,-0.023,-0.008,-0.0047,-0.00086,-0.0059,-1.9e-07,0.025,-0.0061,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.069,0,0,0.001,0.00096,0.048,0.092,0.093,0.044,0.063,0.063,0.066,9.2e-06,8.8e-06,5.6e-06,0.035,0.035,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00084,0.0013,1,1
120 11790000,-0.28,0.021,-0.0063,0.96,-0.097,-0.033,0.02,-0.014,-0.0064,-0.0019,-0.0009,-0.0057,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.069,0,0,0.00091,0.00087,0.048,0.076,0.076,0.037,0.053,0.053,0.063,1.1e-05,1.1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 11790000,-0.29,0.021,-0.0061,0.96,-0.094,-0.035,0.02,-0.013,-0.0066,-0.0019,-0.00094,-0.0059,-2.5e-07,0.031,-0.0082,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.07,0,0,0.00088,0.00085,0.048,0.076,0.076,0.037,0.053,0.053,0.063,8.7e-06,8.3e-06,5.6e-06,0.034,0.034,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1
121 11890000,-0.28,0.021,-0.0065,0.96,-0.11,-0.037,0.018,-0.024,-0.0097,-0.0012,-0.00088,-0.0058,-0.00012,0.033,-0.01,-0.14,-0.1,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00091,0.00087,0.048,0.089,0.089,0.034,0.06,0.06,0.063,1.1e-05,1e-05,4.5e-06,0.035,0.035,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00083,0.0013,1,1 11890000,-0.29,0.021,-0.0062,0.96,-0.11,-0.038,0.018,-0.023,-0.01,-0.0012,-0.00092,-0.006,-1.7e-06,0.031,-0.0082,-0.14,-0.1,-0.023,0.5,0.081,-0.03,-0.07,0,0,0.00088,0.00085,0.047,0.089,0.089,0.034,0.06,0.06,0.063,8.3e-06,7.9e-06,5.6e-06,0.034,0.034,0.00048,0.0012,6.6e-05,0.0013,0.0012,0.00082,0.0013,1,1
122 11990000,-0.28,0.02,-0.0066,0.96,-0.091,-0.028,0.015,-0.017,-0.0064,-0.005,-0.0009,-0.0059,-0.00012,0.039,-0.011,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.076,0.076,0.03,0.062,0.062,0.061,1e-05,9.8e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00082,0.0013,1,1 11990000,-0.29,0.02,-0.0064,0.96,-0.088,-0.029,0.015,-0.016,-0.0066,-0.0049,-0.00094,-0.006,-2.3e-06,0.037,-0.0094,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.00078,0.00076,0.047,0.077,0.077,0.03,0.062,0.062,0.061,7.9e-06,7.5e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0013,0.0012,0.00081,0.0013,1,1
123 12090000,-0.28,0.02,-0.0066,0.96,-0.1,-0.03,0.019,-0.027,-0.0092,0.0011,-0.00086,-0.0058,-0.00012,0.039,-0.012,-0.14,-0.11,-0.023,0.5,0.081,-0.031,-0.07,0,0,0.00081,0.00078,0.047,0.089,0.088,0.027,0.071,0.071,0.06,9.8e-06,9.3e-06,4.5e-06,0.034,0.034,0.00047,0.0012,6.6e-05,0.0013,0.0012,0.00081,0.0013,1,1 12090000,-0.29,0.02,-0.0064,0.96,-0.1,-0.031,0.019,-0.026,-0.0095,0.0012,-0.00091,-0.006,-2.9e-06,0.037,-0.0095,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.00078,0.00076,0.047,0.089,0.089,0.027,0.071,0.071,0.06,7.6e-06,7.2e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00081,0.0013,1,1
124 12190000,-0.28,0.019,-0.0067,0.96,-0.084,-0.018,0.018,-0.014,-0.0032,0.0029,-0.00082,-0.0059,-0.00012,0.045,-0.013,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.07,0.07,0.024,0.057,0.057,0.058,9.2e-06,8.8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1 12190000,-0.29,0.019,-0.0064,0.96,-0.081,-0.019,0.018,-0.014,-0.0034,0.0031,-0.00087,-0.006,-5.1e-06,0.042,-0.011,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.0007,0.00068,0.047,0.071,0.071,0.024,0.057,0.057,0.058,7.2e-06,6.8e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1
125 12290000,-0.28,0.019,-0.0068,0.96,-0.09,-0.017,0.017,-0.023,-0.0048,0.004,-0.00079,-0.0059,-0.00012,0.045,-0.014,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00072,0.0007,0.047,0.081,0.081,0.022,0.065,0.065,0.058,8.9e-06,8.5e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1 12290000,-0.29,0.019,-0.0066,0.96,-0.087,-0.018,0.017,-0.022,-0.005,0.0041,-0.00084,-0.006,-6.4e-06,0.042,-0.011,-0.14,-0.11,-0.023,0.5,0.082,-0.03,-0.07,0,0,0.0007,0.00068,0.047,0.081,0.081,0.022,0.065,0.065,0.058,6.9e-06,6.5e-06,5.6e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.0008,0.0012,1,1
126 12390000,-0.28,0.019,-0.0068,0.96,-0.073,-0.012,0.015,-0.013,-0.0027,-0.002,-0.00078,-0.0059,-0.00012,0.048,-0.015,-0.14,-0.11,-0.023,0.5,0.082,-0.031,-0.07,0,0,0.00066,0.00063,0.047,0.066,0.065,0.02,0.054,0.054,0.056,8.4e-06,8e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1 12390000,-0.29,0.018,-0.0066,0.96,-0.07,-0.013,0.015,-0.012,-0.0028,-0.0019,-0.00083,-0.0061,-8.2e-06,0.046,-0.013,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00063,0.00061,0.047,0.066,0.066,0.02,0.054,0.054,0.056,6.6e-06,6.2e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00079,0.0012,1,1
127 12490000,-0.28,0.019,-0.0069,0.96,-0.081,-0.013,0.019,-0.021,-0.004,9.6e-05,-0.00076,-0.0059,-0.00013,0.048,-0.016,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00066,0.00064,0.047,0.075,0.075,0.018,0.062,0.062,0.055,8.1e-06,7.7e-06,4.5e-06,0.033,0.033,0.00047,0.0012,6.5e-05,0.0012,0.0012,0.00079,0.0012,1,1 12490000,-0.29,0.019,-0.0066,0.96,-0.078,-0.014,0.02,-0.02,-0.0041,0.00028,-0.00081,-0.006,-8.8e-06,0.046,-0.013,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00063,0.00061,0.047,0.075,0.075,0.018,0.062,0.062,0.055,6.3e-06,6e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00079,0.0012,1,1
128 12590000,-0.28,0.018,-0.0068,0.96,-0.065,-0.011,0.021,-0.01,-0.0039,0.0019,-0.00076,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00058,0.047,0.061,0.061,0.017,0.052,0.052,0.054,7.7e-06,7.4e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 12590000,-0.29,0.018,-0.0065,0.96,-0.063,-0.012,0.021,-0.0099,-0.004,0.0021,-0.00081,-0.0061,-1.1e-05,0.049,-0.015,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00058,0.00056,0.047,0.061,0.061,0.017,0.052,0.052,0.054,6.1e-06,5.7e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1
129 12690000,-0.28,0.018,-0.0067,0.96,-0.072,-0.0098,0.02,-0.017,-0.0049,0.0035,-0.00075,-0.0059,-0.00013,0.051,-0.018,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.0006,0.00059,0.047,0.069,0.069,0.015,0.059,0.059,0.053,7.4e-06,7e-06,4.5e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 12690000,-0.29,0.018,-0.0065,0.96,-0.069,-0.01,0.021,-0.017,-0.005,0.0038,-0.0008,-0.0061,-1.2e-05,0.049,-0.015,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00058,0.00057,0.047,0.07,0.07,0.015,0.059,0.059,0.053,5.9e-06,5.5e-06,5.6e-06,0.032,0.032,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1
130 12790000,-0.28,0.018,-0.0065,0.96,-0.056,-0.015,0.022,-0.01,-0.0078,0.0057,-0.00082,-0.0059,-0.00013,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.061,0.061,0.014,0.061,0.061,0.051,7.1e-06,6.7e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00078,0.0012,1,1 12790000,-0.29,0.017,-0.0063,0.96,-0.054,-0.016,0.022,-0.0096,-0.008,0.006,-0.00086,-0.006,-1.2e-05,0.052,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00054,0.00053,0.047,0.061,0.061,0.014,0.061,0.061,0.051,5.6e-06,5.2e-06,5.6e-06,0.031,0.031,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1
131 12890000,-0.28,0.018,-0.0065,0.96,-0.061,-0.016,0.023,-0.016,-0.0096,0.0088,-0.00084,-0.0059,-0.00012,0.054,-0.019,-0.14,-0.11,-0.023,0.5,0.082,-0.032,-0.07,0,0,0.00056,0.00055,0.047,0.069,0.069,0.013,0.07,0.07,0.051,6.8e-06,6.5e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 12890000,-0.29,0.017,-0.0063,0.96,-0.058,-0.017,0.023,-0.015,-0.0098,0.0091,-0.00088,-0.006,-1e-05,0.052,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00054,0.00053,0.047,0.069,0.069,0.013,0.07,0.07,0.051,5.4e-06,5.1e-06,5.6e-06,0.031,0.031,0.00047,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1
132 12990000,-0.28,0.017,-0.0065,0.96,-0.05,-0.013,0.023,-0.008,-0.0066,0.01,-0.00088,-0.0059,-0.00012,0.056,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.047,0.055,0.055,0.012,0.056,0.056,0.05,6.5e-06,6.2e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 12990000,-0.29,0.017,-0.0063,0.96,-0.047,-0.014,0.024,-0.0076,-0.0067,0.01,-0.00091,-0.006,-9.3e-06,0.053,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00051,0.0005,0.046,0.055,0.055,0.012,0.057,0.056,0.05,5.2e-06,4.9e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
133 13090000,-0.28,0.017,-0.0064,0.96,-0.054,-0.015,0.021,-0.013,-0.0083,0.0089,-0.00091,-0.0059,-0.00012,0.056,-0.018,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00053,0.00052,0.046,0.062,0.062,0.011,0.065,0.065,0.049,6.3e-06,5.9e-06,4.5e-06,0.032,0.032,0.00046,0.0012,6.4e-05,0.0012,0.0012,0.00077,0.0012,1,1 13090000,-0.29,0.017,-0.0062,0.96,-0.052,-0.016,0.021,-0.013,-0.0085,0.0093,-0.00094,-0.006,-7.6e-06,0.054,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00051,0.0005,0.046,0.062,0.062,0.011,0.065,0.065,0.049,5e-06,4.7e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
134 13190000,-0.28,0.017,-0.0063,0.96,-0.046,-0.015,0.02,-0.0097,-0.0091,0.0096,-0.00094,-0.0059,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.055,0.055,0.011,0.066,0.066,0.047,6e-06,5.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 13190000,-0.29,0.017,-0.0062,0.96,-0.043,-0.015,0.021,-0.0093,-0.0093,0.01,-0.00096,-0.006,-7.5e-06,0.055,-0.016,-0.14,-0.11,-0.023,0.5,0.083,-0.031,-0.07,0,0,0.00048,0.00048,0.046,0.055,0.055,0.011,0.066,0.066,0.047,4.9e-06,4.5e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
135 13290000,-0.28,0.017,-0.0064,0.96,-0.049,-0.015,0.017,-0.015,-0.011,0.009,-0.00092,-0.0058,-0.00012,0.058,-0.019,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00051,0.00049,0.046,0.061,0.061,0.01,0.075,0.075,0.047,5.8e-06,5.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 13290000,-0.29,0.017,-0.0062,0.96,-0.047,-0.015,0.018,-0.014,-0.011,0.0094,-0.00094,-0.006,-7.7e-06,0.055,-0.017,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00049,0.00048,0.046,0.061,0.061,0.01,0.075,0.075,0.047,4.7e-06,4.3e-06,5.6e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1
136 13390000,-0.28,0.017,-0.0064,0.96,-0.04,-0.011,0.017,-0.0074,-0.007,0.0097,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.049,0.049,0.0094,0.06,0.06,0.046,5.6e-06,5.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 13390000,-0.29,0.017,-0.0062,0.96,-0.038,-0.011,0.018,-0.0071,-0.0071,0.01,-0.00092,-0.006,-9e-06,0.056,-0.017,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00046,0.00045,0.046,0.049,0.049,0.0094,0.06,0.06,0.046,4.5e-06,4.2e-06,5.6e-06,0.031,0.03,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
137 13490000,-0.28,0.017,-0.0064,0.96,-0.044,-0.014,0.017,-0.012,-0.0083,0.006,-0.0009,-0.0059,-0.00012,0.059,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00048,0.00047,0.046,0.054,0.054,0.009,0.068,0.068,0.045,5.4e-06,5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00076,0.0012,1,1 13490000,-0.29,0.017,-0.0062,0.96,-0.041,-0.014,0.018,-0.011,-0.0085,0.0064,-0.00092,-0.006,-8.8e-06,0.057,-0.017,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00046,0.00045,0.046,0.054,0.054,0.009,0.068,0.068,0.045,4.4e-06,4e-06,5.6e-06,0.031,0.03,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
138 13590000,-0.28,0.017,-0.0064,0.96,-0.035,-0.01,0.018,-0.0035,-0.0057,0.0045,-0.00088,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00045,0.046,0.045,0.045,0.0085,0.055,0.055,0.044,5.2e-06,4.9e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 13590000,-0.29,0.017,-0.0062,0.96,-0.033,-0.01,0.019,-0.0033,-0.0058,0.005,-0.0009,-0.006,-9.9e-06,0.058,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00045,0.00044,0.046,0.044,0.044,0.0086,0.055,0.055,0.044,4.3e-06,3.9e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1
139 13690000,-0.28,0.017,-0.0063,0.96,-0.037,-0.0095,0.019,-0.0071,-0.0067,0.0072,-0.00089,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00047,0.00046,0.046,0.049,0.049,0.0082,0.063,0.063,0.044,5e-06,4.7e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 13690000,-0.29,0.016,-0.0062,0.96,-0.035,-0.0095,0.019,-0.0067,-0.0069,0.0078,-0.00091,-0.006,-9e-06,0.058,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00045,0.00044,0.046,0.049,0.049,0.0082,0.063,0.063,0.044,4.1e-06,3.8e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00075,0.0012,1,1
140 13790000,-0.28,0.016,-0.0064,0.96,-0.029,-0.0071,0.019,0.00061,-0.0035,0.0068,-0.00089,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.041,0.041,0.0078,0.052,0.052,0.042,4.8e-06,4.5e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.3e-05,0.0012,0.0012,0.00075,0.0012,1,1 13790000,-0.29,0.016,-0.0062,0.96,-0.027,-0.0071,0.019,0.00082,-0.0036,0.0074,-0.00091,-0.006,-9.9e-06,0.059,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00043,0.00042,0.046,0.041,0.041,0.0078,0.052,0.052,0.042,4e-06,3.6e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
141 13890000,-0.28,0.016,-0.0063,0.96,-0.031,-0.0086,0.02,-0.0022,-0.0044,0.0091,-0.00092,-0.0059,-0.00012,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00045,0.00044,0.046,0.045,0.045,0.0076,0.059,0.059,0.042,4.7e-06,4.4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00075,0.0012,1,1 13890000,-0.29,0.016,-0.0061,0.96,-0.029,-0.0085,0.02,-0.0018,-0.0045,0.0097,-0.00094,-0.006,-8.6e-06,0.059,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00043,0.00043,0.046,0.045,0.045,0.0076,0.059,0.059,0.042,3.9e-06,3.5e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
142 13990000,-0.28,0.016,-0.0062,0.96,-0.03,-0.012,0.018,-0.00073,-0.0048,0.008,-0.00094,-0.0059,-0.00012,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.039,0.039,0.0073,0.05,0.05,0.041,4.5e-06,4.2e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 13990000,-0.29,0.016,-0.0061,0.96,-0.028,-0.012,0.019,-0.00051,-0.0049,0.0087,-0.00095,-0.006,-7.8e-06,0.06,-0.018,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00042,0.00041,0.046,0.038,0.038,0.0073,0.05,0.05,0.041,3.8e-06,3.4e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
143 14090000,-0.28,0.016,-0.0064,0.96,-0.031,-0.0062,0.02,-0.004,-0.0053,0.0046,-0.00087,-0.0059,-0.00012,0.062,-0.021,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00044,0.00043,0.046,0.042,0.042,0.0072,0.057,0.057,0.041,4.4e-06,4e-06,4.5e-06,0.031,0.031,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14090000,-0.29,0.016,-0.0062,0.96,-0.029,-0.0061,0.021,-0.0036,-0.0054,0.0053,-0.00089,-0.006,-1.2e-05,0.059,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00042,0.00042,0.046,0.042,0.042,0.0072,0.057,0.057,0.041,3.6e-06,3.3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
144 14190000,-0.28,0.016,-0.0064,0.96,-0.025,-0.0047,0.02,-0.00094,-0.004,0.0049,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.036,0.036,0.007,0.049,0.049,0.04,4.2e-06,3.9e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14190000,-0.29,0.016,-0.0063,0.96,-0.023,-0.0046,0.021,-0.0007,-0.0041,0.0056,-0.00085,-0.006,-1.4e-05,0.06,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.00041,0.046,0.036,0.036,0.007,0.049,0.049,0.04,3.5e-06,3.2e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
145 14290000,-0.28,0.016,-0.0064,0.96,-0.028,-0.0051,0.018,-0.0036,-0.0044,0.0092,-0.00082,-0.0059,-0.00013,0.063,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00043,0.00042,0.046,0.04,0.04,0.0069,0.055,0.055,0.039,4.1e-06,3.8e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14290000,-0.29,0.016,-0.0062,0.96,-0.026,-0.005,0.019,-0.0032,-0.0045,0.0099,-0.00085,-0.006,-1.4e-05,0.06,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.00041,0.046,0.039,0.04,0.0069,0.055,0.055,0.039,3.4e-06,3.1e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1
146 14390000,-0.28,0.016,-0.0064,0.96,-0.026,-0.0045,0.019,-0.00096,-0.0049,0.014,-0.00083,-0.0059,-0.00012,0.064,-0.022,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.034,0.034,0.0067,0.048,0.048,0.039,4e-06,3.6e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14390000,-0.29,0.016,-0.0062,0.96,-0.024,-0.0044,0.02,-0.00068,-0.0049,0.014,-0.00086,-0.006,-1.4e-05,0.061,-0.019,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.0004,0.046,0.034,0.034,0.0067,0.048,0.048,0.039,3.3e-06,3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00073,0.0012,1,1
147 14490000,-0.28,0.016,-0.0066,0.96,-0.026,-0.0039,0.023,-0.0037,-0.005,0.016,-0.00079,-0.0059,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00042,0.046,0.037,0.037,0.0066,0.054,0.054,0.038,3.8e-06,3.5e-06,4.5e-06,0.031,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14490000,-0.29,0.016,-0.0064,0.96,-0.024,-0.0038,0.024,-0.0032,-0.0051,0.017,-0.00082,-0.006,-1.6e-05,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.00041,0.0004,0.046,0.037,0.037,0.0066,0.054,0.054,0.038,3.2e-06,2.9e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
148 14590000,-0.28,0.016,-0.0067,0.96,-0.028,-0.0054,0.021,-0.0038,-0.0053,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.032,0.032,0.0065,0.047,0.047,0.038,3.7e-06,3.4e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14590000,-0.29,0.016,-0.0065,0.96,-0.026,-0.0053,0.022,-0.0035,-0.0054,0.013,-0.00081,-0.0059,-1.7e-05,0.061,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.0004,0.046,0.032,0.032,0.0065,0.047,0.047,0.038,3.1e-06,2.8e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
149 14690000,-0.28,0.016,-0.0067,0.96,-0.029,-0.0058,0.021,-0.0067,-0.006,0.012,-0.00078,-0.0058,-0.00013,0.064,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00042,0.00041,0.046,0.035,0.035,0.0065,0.053,0.053,0.037,3.6e-06,3.3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.2e-05,0.0012,0.0012,0.00074,0.0012,1,1 14690000,-0.29,0.016,-0.0065,0.96,-0.027,-0.0056,0.022,-0.0062,-0.0061,0.013,-0.00081,-0.0059,-1.7e-05,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.0004,0.046,0.035,0.035,0.0065,0.053,0.053,0.037,3.1e-06,2.7e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
150 14790000,-0.28,0.016,-0.0068,0.96,-0.03,-0.003,0.021,-0.0052,-0.0014,0.015,-0.0008,-0.0058,-0.00012,0.065,-0.023,-0.14,-0.11,-0.023,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.031,0.031,0.0064,0.046,0.046,0.036,3.5e-06,3.2e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 14790000,-0.29,0.016,-0.0066,0.96,-0.028,-0.0027,0.022,-0.0048,-0.0015,0.016,-0.00082,-0.0059,-1.2e-05,0.062,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.00039,0.046,0.03,0.031,0.0064,0.046,0.046,0.036,3e-06,2.6e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
151 14890000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0012,0.026,-0.0086,-0.002,0.016,-0.00081,-0.0057,-0.00012,0.066,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.00041,0.046,0.033,0.033,0.0064,0.052,0.052,0.036,3.4e-06,3.1e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 14890000,-0.29,0.016,-0.0065,0.96,-0.03,-0.00081,0.027,-0.008,-0.002,0.017,-0.00083,-0.0059,-1e-05,0.063,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.07,0,0,0.0004,0.00039,0.046,0.033,0.033,0.0064,0.052,0.052,0.036,2.9e-06,2.6e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
152 14990000,-0.28,0.016,-0.0067,0.96,-0.031,-0.003,0.028,-0.0069,-0.003,0.018,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.029,0.029,0.0064,0.045,0.045,0.036,3.3e-06,3e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 14990000,-0.29,0.016,-0.0065,0.96,-0.028,-0.0026,0.029,-0.0064,-0.003,0.019,-0.00083,-0.0058,-1e-05,0.064,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.07,0,0,0.00039,0.00039,0.046,0.029,0.029,0.0064,0.045,0.045,0.036,2.8e-06,2.5e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
153 15090000,-0.28,0.016,-0.0067,0.96,-0.032,-0.0042,0.032,-0.01,-0.0033,0.021,-0.00081,-0.0057,-0.00012,0.067,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.00041,0.0004,0.046,0.032,0.032,0.0064,0.051,0.051,0.035,3.2e-06,2.9e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15090000,-0.29,0.016,-0.0065,0.96,-0.03,-0.0037,0.033,-0.0094,-0.0033,0.022,-0.00083,-0.0058,-1e-05,0.064,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.07,0,0,0.00039,0.00039,0.046,0.031,0.032,0.0064,0.051,0.051,0.035,2.7e-06,2.4e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1
154 15190000,-0.28,0.016,-0.0068,0.96,-0.03,-0.0022,0.033,-0.008,-0.0026,0.023,-0.0008,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.028,0.0064,0.045,0.045,0.035,3.1e-06,2.8e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15190000,-0.29,0.016,-0.0066,0.96,-0.028,-0.0017,0.034,-0.0075,-0.0026,0.024,-0.00082,-0.0058,-1.2e-05,0.064,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.027,0.028,0.0064,0.045,0.045,0.035,2.7e-06,2.3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
155 15290000,-0.28,0.016,-0.0069,0.96,-0.034,-0.0024,0.032,-0.012,-0.0032,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.03,0.03,0.0065,0.05,0.05,0.035,3e-06,2.7e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15290000,-0.29,0.016,-0.0067,0.96,-0.031,-0.0018,0.034,-0.011,-0.0031,0.021,-0.00083,-0.0058,-9.6e-06,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00039,0.046,0.03,0.03,0.0065,0.05,0.05,0.035,2.6e-06,2.3e-06,5.6e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
156 15390000,-0.28,0.016,-0.0069,0.96,-0.032,-0.0042,0.032,-0.0092,-0.0026,0.02,-0.00081,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.027,0.0064,0.044,0.044,0.034,2.9e-06,2.6e-06,4.5e-06,0.03,0.03,0.00046,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15390000,-0.29,0.016,-0.0068,0.96,-0.03,-0.0036,0.033,-0.0086,-0.0026,0.022,-0.00083,-0.0058,-1e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.026,0.026,0.0065,0.044,0.044,0.034,2.5e-06,2.2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
157 15490000,-0.28,0.016,-0.007,0.96,-0.034,-0.0018,0.032,-0.012,-0.003,0.021,-0.00082,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.0004,0.046,0.028,0.029,0.0065,0.05,0.05,0.034,2.8e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15490000,-0.29,0.016,-0.0068,0.96,-0.031,-0.0011,0.033,-0.012,-0.0029,0.023,-0.00083,-0.0058,-1e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.028,0.028,0.0065,0.05,0.05,0.034,2.5e-06,2.2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
158 15590000,-0.28,0.016,-0.0069,0.96,-0.03,-0.006,0.032,-0.0077,-0.0061,0.02,-0.00085,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.025,0.025,0.0065,0.044,0.044,0.034,2.7e-06,2.5e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15590000,-0.29,0.016,-0.0068,0.96,-0.028,-0.0053,0.033,-0.0071,-0.006,0.022,-0.00086,-0.0058,-1.4e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.025,0.025,0.0065,0.044,0.044,0.034,2.4e-06,2.1e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1
159 15690000,-0.28,0.016,-0.0068,0.96,-0.032,-0.0041,0.032,-0.01,-0.0067,0.021,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.027,0.027,0.0066,0.049,0.049,0.034,2.7e-06,2.4e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15690000,-0.29,0.016,-0.0067,0.96,-0.03,-0.0034,0.034,-0.0093,-0.0065,0.023,-0.00089,-0.0058,-1.2e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00039,0.00038,0.046,0.027,0.027,0.0066,0.049,0.049,0.034,2.4e-06,2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
160 15790000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0028,0.032,-0.0077,-0.0057,0.023,-0.00092,-0.0057,-0.00012,0.068,-0.022,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.024,0.024,0.0066,0.043,0.044,0.033,2.6e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15790000,-0.29,0.016,-0.0067,0.96,-0.026,-0.002,0.033,-0.0072,-0.0055,0.024,-0.00092,-0.0058,-1e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.024,0.024,0.0066,0.043,0.043,0.033,2.3e-06,2e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
161 15890000,-0.28,0.016,-0.0069,0.96,-0.029,-0.0041,0.033,-0.011,-0.0058,0.023,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.083,-0.032,-0.07,0,0,0.0004,0.00039,0.046,0.026,0.026,0.0067,0.049,0.049,0.034,2.5e-06,2.3e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00073,0.0012,1,1 15890000,-0.29,0.016,-0.0068,0.96,-0.026,-0.0032,0.034,-0.01,-0.0056,0.024,-0.0009,-0.0058,-1.2e-05,0.065,-0.02,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.026,0.026,0.0068,0.049,0.049,0.034,2.2e-06,1.9e-06,5.6e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
162 15990000,-0.28,0.016,-0.0068,0.96,-0.027,-0.0035,0.03,-0.0091,-0.0049,0.022,-0.00089,-0.0057,-0.00012,0.068,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.023,0.023,0.0068,0.043,0.043,0.033,2.4e-06,2.2e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6.1e-05,0.0012,0.0012,0.00072,0.0012,1,1 15990000,-0.29,0.016,-0.0066,0.96,-0.024,-0.0026,0.031,-0.0085,-0.0047,0.024,-0.00089,-0.0058,-1.2e-05,0.065,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.023,0.023,0.0068,0.043,0.043,0.033,2.2e-06,1.9e-06,5.6e-06,0.03,0.029,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
163 16090000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0023,0.028,-0.012,-0.005,0.022,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.025,0.025,0.0069,0.048,0.048,0.033,2.4e-06,2.1e-06,4.5e-06,0.03,0.03,0.00045,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16090000,-0.29,0.016,-0.0067,0.96,-0.026,-0.0013,0.029,-0.011,-0.0048,0.024,-0.00088,-0.0058,-1.4e-05,0.066,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00038,0.046,0.024,0.025,0.0069,0.048,0.048,0.033,2.1e-06,1.8e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
164 16190000,-0.28,0.016,-0.0068,0.96,-0.026,-0.002,0.027,-0.011,-0.0041,0.019,-0.00086,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0069,0.043,0.043,0.033,2.3e-06,2.1e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16190000,-0.29,0.016,-0.0067,0.96,-0.024,-0.0011,0.028,-0.01,-0.0039,0.021,-0.00086,-0.0058,-1.5e-05,0.066,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.022,0.022,0.0069,0.043,0.043,0.033,2.1e-06,1.8e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
165 16290000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0011,0.027,-0.014,-0.0043,0.021,-0.00087,-0.0057,-0.00012,0.069,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00039,0.046,0.024,0.024,0.007,0.048,0.048,0.033,2.3e-06,2e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16290000,-0.29,0.016,-0.0067,0.96,-0.026,-0.00014,0.028,-0.013,-0.0041,0.022,-0.00087,-0.0058,-1.5e-05,0.066,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.023,0.024,0.007,0.048,0.048,0.033,2e-06,1.7e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
166 16390000,-0.28,0.016,-0.0068,0.96,-0.028,-0.0015,0.027,-0.011,-0.0041,0.021,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.021,0.021,0.007,0.042,0.042,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16390000,-0.29,0.016,-0.0066,0.96,-0.026,-0.00048,0.028,-0.01,-0.0038,0.022,-0.00088,-0.0058,-1.4e-05,0.066,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.021,0.007,0.042,0.042,0.033,2e-06,1.7e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
167 16490000,-0.28,0.016,-0.0069,0.96,-0.033,-0.00051,0.029,-0.014,-0.0041,0.025,-0.00086,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.07,0,0,0.00039,0.00038,0.046,0.023,0.023,0.0072,0.047,0.047,0.033,2.2e-06,1.9e-06,4.5e-06,0.03,0.03,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16490000,-0.29,0.016,-0.0068,0.96,-0.03,0.00053,0.031,-0.013,-0.0038,0.027,-0.00087,-0.0058,-1.5e-05,0.067,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.022,0.023,0.0072,0.047,0.047,0.033,1.9e-06,1.7e-06,5.6e-06,0.03,0.029,0.00044,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1
168 16590000,-0.28,0.016,-0.0069,0.96,-0.036,1.4e-05,0.033,-0.012,-0.0035,0.025,-0.00087,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.021,0.0072,0.042,0.042,0.033,2.1e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16590000,-0.29,0.016,-0.0068,0.96,-0.033,0.00097,0.034,-0.011,-0.0032,0.027,-0.00087,-0.0058,-1.6e-05,0.067,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.02,0.02,0.0072,0.042,0.042,0.033,1.9e-06,1.6e-06,5.6e-06,0.03,0.029,0.00043,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
169 16690000,-0.28,0.016,-0.0069,0.96,-0.039,0.0036,0.033,-0.016,-0.0035,0.026,-0.00089,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0073,0.047,0.047,0.033,2e-06,1.8e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16690000,-0.29,0.016,-0.0068,0.96,-0.037,0.0046,0.034,-0.015,-0.0031,0.028,-0.00089,-0.0058,-1.4e-05,0.067,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.022,0.0073,0.047,0.047,0.033,1.9e-06,1.6e-06,5.6e-06,0.03,0.029,0.00043,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
170 16790000,-0.28,0.016,-0.0068,0.96,-0.039,0.0034,0.032,-0.013,-0.0031,0.026,-0.00091,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0073,0.042,0.042,0.033,2e-06,1.7e-06,4.5e-06,0.03,0.03,0.00043,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16790000,-0.29,0.016,-0.0067,0.96,-0.037,0.0045,0.033,-0.012,-0.0028,0.028,-0.0009,-0.0058,-1.5e-05,0.067,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.019,0.02,0.0073,0.042,0.042,0.033,1.8e-06,1.5e-06,5.6e-06,0.03,0.029,0.00043,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
171 16890000,-0.28,0.016,-0.0067,0.96,-0.039,0.0029,0.033,-0.017,-0.0032,0.025,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.046,0.046,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16890000,-0.29,0.016,-0.0066,0.96,-0.037,0.0041,0.034,-0.016,-0.0027,0.027,-0.00093,-0.0058,-1.2e-05,0.067,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.031,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.021,0.0074,0.046,0.046,0.033,1.8e-06,1.5e-06,5.6e-06,0.03,0.029,0.00042,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
172 16990000,-0.28,0.016,-0.0067,0.96,-0.036,0.0033,0.033,-0.015,-0.0034,0.024,-0.00094,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.021,0.0074,0.049,0.049,0.033,1.9e-06,1.7e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 16990000,-0.29,0.016,-0.0066,0.96,-0.034,0.0046,0.034,-0.014,-0.0029,0.025,-0.00094,-0.0058,-1.4e-05,0.067,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.02,0.021,0.0074,0.049,0.049,0.033,1.7e-06,1.5e-06,5.6e-06,0.03,0.029,0.00042,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1
173 17090000,-0.28,0.016,-0.0068,0.96,-0.041,0.0053,0.033,-0.019,-0.0029,0.023,-0.00093,-0.0057,-0.00012,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0075,0.054,0.054,0.033,1.9e-06,1.6e-06,4.5e-06,0.03,0.03,0.00042,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 17090000,-0.29,0.016,-0.0067,0.96,-0.039,0.0066,0.034,-0.018,-0.0024,0.025,-0.00093,-0.0058,-1.5e-05,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.022,0.022,0.0075,0.054,0.054,0.033,1.7e-06,1.4e-06,5.6e-06,0.03,0.029,0.00042,0.0012,6e-05,0.0012,0.0011,0.00071,0.0012,1,1
174 17190000,-0.28,0.016,-0.0069,0.96,-0.039,0.0071,0.034,-0.018,-0.0046,0.026,-0.00093,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.022,0.022,0.0076,0.057,0.057,0.033,1.8e-06,1.6e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 17190000,-0.29,0.016,-0.0068,0.96,-0.037,0.0084,0.035,-0.017,-0.004,0.028,-0.00093,-0.0058,-2.4e-05,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.022,0.0076,0.056,0.057,0.033,1.7e-06,1.4e-06,5.6e-06,0.03,0.029,0.00041,0.0012,6e-05,0.0012,0.0011,0.00071,0.0012,1,1
175 17290000,-0.28,0.016,-0.0069,0.96,-0.042,0.0077,0.034,-0.022,-0.0035,0.026,-0.00092,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.023,0.024,0.0077,0.062,0.063,0.033,1.8e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 17290000,-0.29,0.016,-0.0068,0.96,-0.04,0.009,0.035,-0.021,-0.0029,0.028,-0.00091,-0.0058,-2.6e-05,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.023,0.023,0.0077,0.062,0.063,0.033,1.6e-06,1.4e-06,5.6e-06,0.03,0.029,0.00041,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
176 17390000,-0.28,0.016,-0.0069,0.96,-0.032,0.013,0.033,-0.014,-0.002,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.02,0.02,0.0076,0.052,0.052,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.00041,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 17390000,-0.29,0.016,-0.0068,0.96,-0.03,0.014,0.034,-0.013,-0.0015,0.028,-0.00094,-0.0058,-2.6e-05,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.02,0.0076,0.052,0.052,0.033,1.6e-06,1.3e-06,5.6e-06,0.03,0.029,0.00041,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
177 17490000,-0.28,0.016,-0.0069,0.96,-0.032,0.014,0.033,-0.017,-0.00051,0.028,-0.00094,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00039,0.00038,0.046,0.021,0.022,0.0078,0.058,0.058,0.033,1.7e-06,1.5e-06,4.5e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00072,0.0012,1,1 17490000,-0.29,0.016,-0.0068,0.96,-0.03,0.015,0.034,-0.016,7.2e-05,0.03,-0.00094,-0.0058,-2.7e-05,0.067,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00038,0.00037,0.046,0.021,0.021,0.0078,0.058,0.058,0.033,1.6e-06,1.3e-06,5.6e-06,0.03,0.029,0.0004,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
178 17590000,-0.28,0.016,-0.0069,0.96,-0.032,0.012,0.032,-0.016,-0.00075,0.026,-0.00095,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.018,0.019,0.0077,0.049,0.049,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.0004,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 17590000,-0.29,0.016,-0.0068,0.96,-0.03,0.013,0.033,-0.015,-0.00029,0.027,-0.00094,-0.0058,-3e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.018,0.019,0.0077,0.049,0.049,0.033,1.5e-06,1.3e-06,5.6e-06,0.03,0.029,0.0004,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
179 17690000,-0.28,0.016,-0.007,0.96,-0.033,0.012,0.033,-0.019,0.0003,0.028,-0.00096,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.02,0.02,0.0078,0.054,0.054,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,6e-05,0.0012,0.0012,0.00071,0.0012,1,1 17690000,-0.28,0.016,-0.0069,0.96,-0.031,0.014,0.034,-0.018,0.0009,0.03,-0.00095,-0.0058,-2.9e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.085,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.02,0.0078,0.054,0.054,0.033,1.5e-06,1.2e-06,5.6e-06,0.03,0.029,0.00039,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
180 17790000,-0.28,0.016,-0.007,0.96,-0.033,0.013,0.033,-0.018,0.0011,0.033,-0.00097,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.019,0.02,0.0078,0.057,0.057,0.033,1.6e-06,1.4e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 17790000,-0.28,0.015,-0.0069,0.96,-0.031,0.014,0.035,-0.017,0.0017,0.035,-0.00096,-0.0058,-3e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.02,0.0078,0.057,0.057,0.033,1.5e-06,1.2e-06,5.6e-06,0.03,0.029,0.00039,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
181 17890000,-0.28,0.016,-0.0069,0.96,-0.037,0.014,0.033,-0.021,0.0022,0.038,-0.00098,-0.0057,-0.00013,0.07,-0.023,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00038,0.046,0.021,0.021,0.0079,0.062,0.062,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00039,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 17890000,-0.28,0.016,-0.0068,0.96,-0.035,0.016,0.034,-0.02,0.0029,0.039,-0.00097,-0.0058,-2.8e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.02,0.021,0.0079,0.062,0.062,0.033,1.4e-06,1.2e-06,5.6e-06,0.03,0.029,0.00039,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1
182 17990000,-0.28,0.016,-0.0069,0.96,-0.035,0.015,0.033,-0.017,0.0047,0.038,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.018,0.0079,0.052,0.052,0.033,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 17990000,-0.28,0.016,-0.0069,0.96,-0.034,0.016,0.034,-0.016,0.0053,0.04,-0.00097,-0.0058,-2.7e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.018,0.018,0.0079,0.052,0.052,0.033,1.4e-06,1.2e-06,5.5e-06,0.03,0.029,0.00038,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
183 18090000,-0.28,0.016,-0.007,0.96,-0.037,0.016,0.032,-0.021,0.0061,0.037,-0.00098,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.019,0.02,0.008,0.057,0.057,0.034,1.5e-06,1.3e-06,4.4e-06,0.03,0.03,0.00038,0.0012,5.9e-05,0.0012,0.0012,0.00071,0.0012,1,1 18090000,-0.28,0.016,-0.0069,0.96,-0.035,0.017,0.033,-0.02,0.0068,0.038,-0.00097,-0.0058,-2.6e-05,0.068,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.019,0.019,0.008,0.057,0.057,0.034,1.4e-06,1.1e-06,5.5e-06,0.03,0.029,0.00038,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
184 18190000,-0.28,0.016,-0.007,0.96,-0.034,0.013,0.033,-0.016,0.004,0.035,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.017,0.0079,0.049,0.049,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18190000,-0.28,0.016,-0.0069,0.96,-0.032,0.015,0.034,-0.015,0.0047,0.036,-0.001,-0.0058,-2.8e-05,0.068,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.016,0.017,0.0079,0.049,0.049,0.034,1.3e-06,1.1e-06,5.5e-06,0.03,0.029,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
185 18290000,-0.28,0.016,-0.007,0.96,-0.037,0.013,0.031,-0.02,0.005,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.018,0.019,0.008,0.053,0.054,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18290000,-0.28,0.016,-0.0069,0.96,-0.035,0.015,0.033,-0.019,0.0058,0.035,-0.001,-0.0058,-2.7e-05,0.069,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.018,0.018,0.008,0.053,0.054,0.034,1.3e-06,1.1e-06,5.5e-06,0.03,0.029,0.00037,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
186 18390000,-0.28,0.016,-0.0069,0.96,-0.033,0.013,0.031,-0.014,0.0042,0.033,-0.001,-0.0057,-0.00013,0.071,-0.023,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0079,0.046,0.047,0.034,1.4e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18390000,-0.28,0.016,-0.0068,0.96,-0.031,0.014,0.032,-0.014,0.0049,0.034,-0.001,-0.0058,-3.4e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.016,0.0079,0.046,0.046,0.034,1.3e-06,1.1e-06,5.5e-06,0.03,0.029,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
187 18490000,-0.28,0.016,-0.0069,0.96,-0.037,0.012,0.03,-0.018,0.005,0.034,-0.001,-0.0057,-0.00013,0.072,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.017,0.018,0.008,0.051,0.051,0.034,1.3e-06,1.2e-06,4.4e-06,0.03,0.03,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18490000,-0.28,0.016,-0.0069,0.96,-0.035,0.014,0.031,-0.017,0.0059,0.036,-0.001,-0.0058,-3.1e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00037,0.046,0.017,0.018,0.008,0.05,0.051,0.034,1.3e-06,1e-06,5.5e-06,0.03,0.029,0.00036,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
188 18590000,-0.28,0.016,-0.0068,0.96,-0.035,0.012,0.03,-0.015,0.0045,0.037,-0.001,-0.0057,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18590000,-0.28,0.015,-0.0067,0.96,-0.033,0.014,0.031,-0.014,0.0052,0.038,-0.001,-0.0058,-3.8e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.2e-06,1e-06,5.5e-06,0.03,0.029,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
189 18690000,-0.28,0.016,-0.0067,0.96,-0.035,0.011,0.028,-0.017,0.0053,0.035,-0.0011,-0.0058,-0.00013,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.048,0.049,0.034,1.3e-06,1.1e-06,4.4e-06,0.03,0.03,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18690000,-0.28,0.015,-0.0067,0.96,-0.033,0.013,0.029,-0.017,0.0062,0.037,-0.001,-0.0058,-3.4e-05,0.069,-0.021,-0.14,-0.11,-0.024,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.017,0.008,0.048,0.049,0.034,1.2e-06,1e-06,5.5e-06,0.03,0.029,0.00035,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
190 18790000,-0.28,0.015,-0.0067,0.96,-0.031,0.011,0.028,-0.014,0.0046,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.043,0.043,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18790000,-0.28,0.015,-0.0066,0.96,-0.03,0.012,0.029,-0.013,0.0054,0.035,-0.0011,-0.0058,-4e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0079,0.043,0.043,0.034,1.2e-06,9.8e-07,5.5e-06,0.03,0.029,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
191 18890000,-0.28,0.015,-0.0067,0.96,-0.032,0.011,0.026,-0.017,0.0057,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.008,0.047,0.047,0.034,1.2e-06,1.1e-06,4.4e-06,0.03,0.03,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.00071,0.0012,1,1 18890000,-0.28,0.015,-0.0066,0.96,-0.03,0.013,0.027,-0.017,0.0067,0.031,-0.0011,-0.0058,-4e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.017,0.008,0.047,0.047,0.034,1.2e-06,9.6e-07,5.5e-06,0.03,0.029,0.00034,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
192 18990000,-0.28,0.015,-0.0066,0.96,-0.029,0.011,0.027,-0.015,0.005,0.033,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.015,0.0079,0.042,0.042,0.034,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 18990000,-0.28,0.015,-0.0066,0.96,-0.028,0.013,0.028,-0.014,0.0058,0.034,-0.0011,-0.0058,-4.5e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0079,0.042,0.042,0.034,1.1e-06,9.4e-07,5.4e-06,0.03,0.029,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
193 19090000,-0.28,0.015,-0.0067,0.96,-0.029,0.012,0.027,-0.017,0.0056,0.029,-0.0011,-0.0058,-0.00014,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.016,0.0079,0.045,0.046,0.035,1.2e-06,1e-06,4.4e-06,0.03,0.03,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19090000,-0.28,0.015,-0.0066,0.96,-0.027,0.014,0.028,-0.017,0.0067,0.031,-0.0011,-0.0058,-4.2e-05,0.069,-0.02,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.008,0.045,0.046,0.035,1.1e-06,9.2e-07,5.4e-06,0.03,0.029,0.00033,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
194 19190000,-0.28,0.016,-0.0066,0.96,-0.026,0.013,0.027,-0.015,0.0056,0.028,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9.8e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19190000,-0.28,0.015,-0.0066,0.96,-0.025,0.015,0.028,-0.014,0.0065,0.03,-0.0011,-0.0058,-5.2e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0079,0.041,0.041,0.034,1.1e-06,9e-07,5.4e-06,0.03,0.029,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1
195 19290000,-0.28,0.016,-0.0066,0.96,-0.027,0.013,0.027,-0.018,0.0067,0.027,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.1e-06,9.7e-07,4.4e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19290000,-0.28,0.015,-0.0065,0.96,-0.026,0.015,0.028,-0.017,0.0078,0.029,-0.0011,-0.0058,-5.2e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0079,0.044,0.045,0.034,1.1e-06,8.9e-07,5.4e-06,0.03,0.029,0.00032,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
196 19390000,-0.28,0.015,-0.0067,0.96,-0.025,0.011,0.028,-0.016,0.0067,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.014,0.015,0.0078,0.04,0.04,0.035,1.1e-06,9.4e-07,4.3e-06,0.03,0.03,0.00032,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19390000,-0.28,0.015,-0.0067,0.96,-0.024,0.013,0.029,-0.015,0.0076,0.028,-0.0011,-0.0058,-5.6e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0078,0.04,0.04,0.035,1.1e-06,8.7e-07,5.4e-06,0.03,0.029,0.00031,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
197 19490000,-0.28,0.015,-0.0068,0.96,-0.028,0.012,0.028,-0.019,0.008,0.026,-0.0011,-0.0058,-0.00015,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.044,0.035,1.1e-06,9.3e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19490000,-0.28,0.015,-0.0067,0.96,-0.026,0.014,0.029,-0.018,0.0092,0.027,-0.0011,-0.0058,-5.9e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0078,0.043,0.044,0.035,1e-06,8.5e-07,5.4e-06,0.03,0.029,0.00031,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1
198 19590000,-0.28,0.015,-0.0067,0.96,-0.024,0.013,0.03,-0.016,0.0063,0.026,-0.0011,-0.0058,-0.00016,0.071,-0.022,-0.14,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0077,0.039,0.04,0.035,1.1e-06,9e-07,4.3e-06,0.03,0.03,0.00031,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19590000,-0.28,0.015,-0.0066,0.96,-0.023,0.015,0.031,-0.016,0.0073,0.028,-0.0011,-0.0058,-7e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0078,0.039,0.039,0.035,1e-06,8.3e-07,5.4e-06,0.03,0.029,0.00031,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
199 19690000,-0.28,0.016,-0.0067,0.96,-0.024,0.011,0.028,-0.019,0.007,0.026,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0078,0.043,0.043,0.035,1e-06,8.9e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19690000,-0.28,0.015,-0.0066,0.96,-0.023,0.014,0.029,-0.018,0.0082,0.027,-0.0011,-0.0058,-6.6e-05,0.069,-0.021,-0.14,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0078,0.043,0.043,0.035,1e-06,8.2e-07,5.4e-06,0.03,0.029,0.0003,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
200 19790000,-0.28,0.015,-0.0068,0.96,-0.021,0.011,0.026,-0.019,0.0075,0.022,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.015,0.016,0.0077,0.045,0.046,0.035,1e-06,8.7e-07,4.3e-06,0.03,0.03,0.0003,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19790000,-0.28,0.015,-0.0067,0.96,-0.02,0.013,0.027,-0.018,0.0088,0.023,-0.0011,-0.0058,-7.4e-05,0.069,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0077,0.045,0.046,0.035,9.9e-07,8e-07,5.3e-06,0.03,0.029,0.0003,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
201 19890000,-0.28,0.016,-0.0068,0.96,-0.023,0.011,0.027,-0.021,0.0087,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00037,0.046,0.016,0.017,0.0077,0.049,0.05,0.035,1e-06,8.6e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.9e-05,0.0012,0.0011,0.0007,0.0012,1,1 19890000,-0.28,0.015,-0.0068,0.96,-0.021,0.014,0.028,-0.02,0.01,0.022,-0.0011,-0.0058,-7.4e-05,0.069,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.017,0.0077,0.049,0.05,0.035,9.8e-07,7.9e-07,5.3e-06,0.03,0.029,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
202 19990000,-0.28,0.016,-0.0068,0.96,-0.02,0.012,0.024,-0.016,0.0081,0.017,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.014,0.015,0.0076,0.043,0.044,0.035,9.7e-07,8.3e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 19990000,-0.28,0.016,-0.0067,0.96,-0.018,0.015,0.025,-0.016,0.0093,0.019,-0.0011,-0.0058,-7.7e-05,0.069,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.014,0.015,0.0076,0.043,0.044,0.035,9.5e-07,7.7e-07,5.3e-06,0.03,0.029,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
203 20090000,-0.28,0.016,-0.0068,0.96,-0.022,0.015,0.024,-0.018,0.0093,0.02,-0.0011,-0.0058,-0.00016,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0076,0.047,0.048,0.035,9.7e-07,8.2e-07,4.3e-06,0.03,0.03,0.00029,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 20090000,-0.28,0.016,-0.0068,0.96,-0.021,0.017,0.025,-0.018,0.011,0.022,-0.0011,-0.0058,-7.7e-05,0.069,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.016,0.0076,0.047,0.048,0.035,9.4e-07,7.7e-07,5.3e-06,0.03,0.029,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
204 20190000,-0.28,0.016,-0.0068,0.96,-0.023,0.013,0.025,-0.019,0.0097,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.015,0.017,0.0075,0.05,0.05,0.035,9.4e-07,8e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 20190000,-0.28,0.016,-0.0068,0.96,-0.022,0.015,0.026,-0.019,0.011,0.021,-0.0011,-0.0058,-8.6e-05,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.017,0.0075,0.049,0.05,0.035,9.2e-07,7.5e-07,5.3e-06,0.03,0.029,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
205 20290000,-0.28,0.016,-0.0068,0.96,-0.021,0.015,0.025,-0.022,0.011,0.021,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.054,0.055,0.035,9.3e-07,7.9e-07,4.3e-06,0.03,0.03,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 20290000,-0.28,0.016,-0.0068,0.96,-0.02,0.017,0.026,-0.021,0.013,0.022,-0.0011,-0.0058,-8.6e-05,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.018,0.0075,0.054,0.055,0.035,9.1e-07,7.4e-07,5.3e-06,0.03,0.029,0.00028,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
206 20390000,-0.28,0.016,-0.0067,0.96,-0.019,0.013,0.025,-0.022,0.01,0.022,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.018,0.0075,0.056,0.057,0.035,9.1e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 20390000,-0.28,0.016,-0.0067,0.96,-0.018,0.015,0.026,-0.021,0.012,0.023,-0.0011,-0.0058,-8.8e-05,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.016,0.018,0.0075,0.056,0.057,0.035,8.9e-07,7.2e-07,5.3e-06,0.03,0.029,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
207 20490000,-0.28,0.016,-0.0067,0.96,-0.017,0.015,0.025,-0.024,0.011,0.02,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0075,0.061,0.063,0.035,9e-07,7.7e-07,4.3e-06,0.03,0.03,0.00027,0.0012,5.8e-05,0.0012,0.0011,0.0007,0.0012,1,1 20490000,-0.28,0.016,-0.0067,0.96,-0.016,0.017,0.026,-0.023,0.013,0.021,-0.0011,-0.0058,-8.7e-05,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.017,0.019,0.0075,0.061,0.063,0.035,8.8e-07,7.2e-07,5.2e-06,0.03,0.029,0.00027,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
208 20590000,-0.28,0.016,-0.0066,0.96,-0.017,0.014,0.025,-0.024,0.01,0.018,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.017,0.019,0.0074,0.064,0.065,0.035,8.8e-07,7.5e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 20590000,-0.28,0.016,-0.0066,0.96,-0.016,0.017,0.025,-0.023,0.012,0.019,-0.0011,-0.0058,-8.7e-05,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.017,0.018,0.0074,0.064,0.065,0.035,8.6e-07,7e-07,5.2e-06,0.03,0.029,0.00026,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
209 20690000,-0.28,0.016,-0.0066,0.96,-0.016,0.014,0.026,-0.025,0.012,0.019,-0.0011,-0.0058,-0.00017,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.018,0.02,0.0074,0.069,0.071,0.035,8.7e-07,7.4e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 20690000,-0.28,0.016,-0.0066,0.96,-0.015,0.017,0.026,-0.024,0.014,0.02,-0.0011,-0.0058,-9e-05,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00038,0.00036,0.046,0.018,0.02,0.0074,0.069,0.071,0.035,8.6e-07,6.9e-07,5.2e-06,0.029,0.029,0.00026,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
210 20790000,-0.28,0.016,-0.006,0.96,-0.01,0.01,0.01,-0.019,0.0088,0.017,-0.0012,-0.0058,-0.00018,0.072,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,0.00038,0.00036,0.046,0.016,0.017,0.0073,0.057,0.057,0.035,8.4e-07,7.1e-07,4.2e-06,0.03,0.03,0.00026,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 20790000,-0.28,0.015,-0.0059,0.96,-0.0091,0.013,0.011,-0.018,0.01,0.019,-0.0011,-0.0058,-9.8e-05,0.07,-0.02,-0.13,-0.11,-0.023,0.5,0.085,-0.033,-0.069,0,0,0.00037,0.00036,0.046,0.015,0.017,0.0073,0.056,0.057,0.035,8.2e-07,6.7e-07,5.2e-06,0.029,0.029,0.00026,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
211 20890000,-0.28,0.011,0.0027,0.96,-0.0058,-5.9e-05,-0.11,-0.021,0.0092,0.011,-0.0012,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00037,0.00034,0.046,0.017,0.018,0.0073,0.061,0.062,0.035,8.3e-07,7.1e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 20890000,-0.28,0.011,0.0027,0.96,-0.0045,0.0026,-0.11,-0.02,0.011,0.012,-0.0011,-0.0058,-0.0001,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.033,-0.069,0,0,0.00036,0.00034,0.046,0.016,0.018,0.0073,0.061,0.062,0.035,8.2e-07,6.6e-07,5.2e-06,0.029,0.029,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1
212 20990000,-0.28,0.0071,0.0057,0.96,0.0086,-0.017,-0.25,-0.017,0.007,-0.004,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.016,0.0072,0.052,0.052,0.034,8e-07,6.9e-07,4.2e-06,0.03,0.03,0.00025,0.0012,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 20990000,-0.28,0.0069,0.0057,0.96,0.01,-0.014,-0.25,-0.016,0.0086,-0.0029,-0.0011,-0.0058,-0.00011,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.068,0,0,0.00035,0.00034,0.046,0.014,0.016,0.0072,0.051,0.052,0.034,7.9e-07,6.5e-07,5.1e-06,0.029,0.029,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1
213 21090000,-0.28,0.0076,0.0042,0.96,0.022,-0.029,-0.37,-0.016,0.005,-0.035,-0.0011,-0.0058,-0.00019,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.017,0.0072,0.056,0.057,0.035,8e-07,6.8e-07,4.2e-06,0.03,0.03,0.00025,0.0011,5.8e-05,0.0012,0.0011,0.00069,0.0012,1,1 21090000,-0.28,0.0074,0.0042,0.96,0.023,-0.026,-0.37,-0.015,0.0068,-0.033,-0.0011,-0.0058,-0.00011,0.07,-0.021,-0.13,-0.11,-0.023,0.5,0.084,-0.032,-0.068,0,0,0.00035,0.00034,0.046,0.015,0.017,0.0072,0.056,0.057,0.035,7.9e-07,6.4e-07,5.1e-06,0.029,0.029,0.00025,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
214 21190000,-0.28,0.0095,0.0015,0.96,0.028,-0.035,-0.49,-0.013,0.0038,-0.071,-0.0011,-0.0058,-0.00018,0.072,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.014,0.016,0.0071,0.048,0.049,0.035,7.7e-07,6.6e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 21190000,-0.28,0.0093,0.0016,0.96,0.029,-0.032,-0.49,-0.012,0.0052,-0.07,-0.0011,-0.0058,-0.00011,0.07,-0.021,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00035,0.00033,0.046,0.014,0.016,0.0071,0.048,0.049,0.035,7.6e-07,6.2e-07,5.1e-06,0.029,0.029,0.00024,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
215 21290000,-0.28,0.011,-0.00054,0.96,0.026,-0.037,-0.62,-0.011,0.0011,-0.13,-0.0011,-0.0058,-0.00019,0.072,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.0071,0.052,0.053,0.035,7.7e-07,6.5e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 21290000,-0.28,0.011,-0.00052,0.96,0.028,-0.034,-0.62,-0.0099,0.0028,-0.13,-0.0011,-0.0058,-0.00012,0.07,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.0071,0.052,0.053,0.035,7.6e-07,6.2e-07,5.1e-06,0.029,0.029,0.00024,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
216 21390000,-0.28,0.012,-0.002,0.96,0.019,-0.029,-0.75,-0.013,0.0046,-0.19,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.016,0.017,0.007,0.054,0.055,0.035,7.5e-07,6.4e-07,4.1e-06,0.03,0.03,0.00024,0.0011,5.8e-05,0.0012,0.0011,0.00068,0.0012,1,1 21390000,-0.28,0.012,-0.002,0.96,0.021,-0.027,-0.75,-0.012,0.0063,-0.19,-0.0011,-0.0058,-9.2e-05,0.07,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.015,0.017,0.007,0.054,0.055,0.035,7.4e-07,6.1e-07,5e-06,0.029,0.029,0.00024,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
217 21490000,-0.28,0.012,-0.0028,0.96,0.013,-0.027,-0.88,-0.011,0.0015,-0.28,-0.0011,-0.0058,-0.00017,0.072,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.046,0.017,0.018,0.007,0.059,0.06,0.035,7.4e-07,6.3e-07,4.1e-06,0.03,0.03,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21490000,-0.28,0.012,-0.0027,0.96,0.014,-0.025,-0.88,-0.0094,0.0035,-0.28,-0.0011,-0.0058,-8.9e-05,0.07,-0.022,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.018,0.007,0.059,0.06,0.035,7.4e-07,6e-07,5e-06,0.029,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
218 21590000,-0.28,0.012,-0.0034,0.96,0.0009,-0.021,-1,-0.015,0.0065,-0.37,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.017,0.018,0.0069,0.061,0.063,0.034,7.3e-07,6.2e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21590000,-0.29,0.012,-0.0033,0.96,0.0027,-0.018,-1,-0.013,0.0085,-0.37,-0.0011,-0.0058,-5.8e-05,0.07,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.016,0.018,0.0069,0.061,0.063,0.034,7.2e-07,5.9e-07,5e-06,0.029,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
219 21690000,-0.28,0.012,-0.0037,0.96,-0.0046,-0.017,-1.1,-0.015,0.004,-0.48,-0.0011,-0.0058,-0.00014,0.072,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0069,0.066,0.068,0.035,7.2e-07,6.1e-07,4.1e-06,0.03,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21690000,-0.29,0.012,-0.0037,0.96,-0.0027,-0.014,-1.1,-0.014,0.0063,-0.48,-0.0011,-0.0058,-5.3e-05,0.07,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.017,0.02,0.0069,0.066,0.068,0.035,7.2e-07,5.8e-07,5e-06,0.029,0.029,0.00023,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
220 21790000,-0.28,0.012,-0.0041,0.96,-0.011,-0.0087,-1.3,-0.017,0.01,-0.6,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.019,0.0069,0.069,0.07,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21790000,-0.29,0.012,-0.0041,0.96,-0.0088,-0.0058,-1.3,-0.015,0.013,-0.6,-0.0011,-0.0058,-1.9e-05,0.07,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.017,0.02,0.0069,0.068,0.07,0.034,7e-07,5.7e-07,5e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
221 21890000,-0.28,0.013,-0.0044,0.96,-0.017,-0.0041,-1.4,-0.018,0.01,-0.74,-0.0011,-0.0058,-0.00011,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.021,0.0068,0.074,0.076,0.034,7e-07,6e-07,4.1e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21890000,-0.29,0.012,-0.0044,0.96,-0.015,-0.0012,-1.4,-0.016,0.013,-0.74,-0.0011,-0.0058,-2.3e-05,0.07,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00036,0.00034,0.046,0.019,0.021,0.0068,0.074,0.076,0.034,7e-07,5.7e-07,5e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
222 21990000,-0.28,0.013,-0.0052,0.96,-0.022,0.0043,-1.4,-0.024,0.018,-0.88,-0.0011,-0.0058,-8.8e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00034,0.045,0.018,0.02,0.0068,0.077,0.079,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 21990000,-0.29,0.013,-0.0052,0.96,-0.021,0.0071,-1.4,-0.023,0.02,-0.88,-0.001,-0.0058,6.8e-06,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.046,0.018,0.02,0.0068,0.076,0.079,0.034,6.8e-07,5.5e-07,4.9e-06,0.029,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
223 22090000,-0.28,0.014,-0.0058,0.96,-0.025,0.0075,-1.4,-0.025,0.018,-1,-0.0011,-0.0058,-8.2e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0068,0.083,0.085,0.034,6.8e-07,5.8e-07,4e-06,0.03,0.029,0.00022,0.0011,5.7e-05,0.0012,0.0011,0.00068,0.0012,1,1 22090000,-0.29,0.014,-0.0058,0.96,-0.024,0.011,-1.4,-0.024,0.021,-1,-0.0011,-0.0058,1.4e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.046,0.019,0.021,0.0068,0.082,0.085,0.034,6.8e-07,5.5e-07,4.9e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
224 22190000,-0.28,0.014,-0.0063,0.96,-0.032,0.014,-1.4,-0.03,0.025,-1.2,-0.0011,-0.0058,-5.9e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0067,0.085,0.087,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22190000,-0.29,0.014,-0.0063,0.96,-0.031,0.017,-1.4,-0.028,0.028,-1.2,-0.001,-0.0058,4.1e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.045,0.019,0.021,0.0067,0.085,0.087,0.034,6.6e-07,5.4e-07,4.9e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
225 22290000,-0.28,0.014,-0.007,0.96,-0.04,0.019,-1.4,-0.034,0.027,-1.3,-0.0011,-0.0058,-6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.022,0.0067,0.091,0.094,0.034,6.6e-07,5.6e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22290000,-0.29,0.014,-0.007,0.96,-0.039,0.022,-1.4,-0.032,0.03,-1.3,-0.001,-0.0058,4e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.022,0.0067,0.091,0.094,0.034,6.5e-07,5.3e-07,4.9e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
226 22390000,-0.28,0.015,-0.0073,0.96,-0.047,0.026,-1.4,-0.04,0.031,-1.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0066,0.094,0.096,0.034,6.4e-07,5.5e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22390000,-0.29,0.014,-0.0073,0.96,-0.045,0.028,-1.4,-0.039,0.034,-1.5,-0.001,-0.0058,3.8e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.021,0.0066,0.093,0.096,0.034,6.4e-07,5.2e-07,4.8e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
227 22490000,-0.28,0.015,-0.0074,0.96,-0.053,0.032,-1.4,-0.045,0.034,-1.6,-0.0011,-0.0058,-6.4e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0066,0.1,0.1,0.034,6.4e-07,5.4e-07,4e-06,0.029,0.029,0.00021,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22490000,-0.29,0.015,-0.0074,0.96,-0.052,0.035,-1.4,-0.044,0.038,-1.6,-0.001,-0.0058,3.5e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.023,0.0066,0.1,0.1,0.034,6.4e-07,5.2e-07,4.8e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
228 22590000,-0.28,0.016,-0.0073,0.96,-0.058,0.038,-1.4,-0.046,0.038,-1.7,-0.0011,-0.0058,-5.7e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.1,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22590000,-0.29,0.015,-0.0072,0.96,-0.056,0.04,-1.4,-0.045,0.041,-1.7,-0.001,-0.0058,4.2e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.019,0.022,0.0065,0.1,0.11,0.034,6.2e-07,5.1e-07,4.8e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
229 22690000,-0.28,0.016,-0.0072,0.96,-0.062,0.042,-1.4,-0.053,0.042,-1.9,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.11,0.11,0.034,6.2e-07,5.3e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22690000,-0.29,0.016,-0.0071,0.96,-0.061,0.045,-1.4,-0.052,0.046,-1.9,-0.001,-0.0058,4e-05,0.07,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00035,0.045,0.02,0.023,0.0065,0.11,0.11,0.034,6.2e-07,5.1e-07,4.8e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
230 22790000,-0.28,0.016,-0.0071,0.96,-0.069,0.047,-1.4,-0.059,0.045,-2,-0.0011,-0.0058,-6.6e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.02,0.022,0.0065,0.11,0.11,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22790000,-0.29,0.016,-0.007,0.96,-0.068,0.05,-1.4,-0.057,0.048,-2,-0.001,-0.0058,3e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00036,0.00034,0.045,0.02,0.022,0.0065,0.11,0.11,0.034,6e-07,4.9e-07,4.7e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1
231 22890000,-0.28,0.017,-0.0072,0.96,-0.074,0.051,-1.4,-0.065,0.048,-2.2,-0.0011,-0.0058,-5.8e-05,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.12,0.12,0.034,6e-07,5.1e-07,3.9e-06,0.029,0.029,0.0002,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22890000,-0.29,0.016,-0.0071,0.96,-0.073,0.054,-1.4,-0.064,0.052,-2.2,-0.001,-0.0058,3.9e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0065,0.12,0.12,0.034,6e-07,4.9e-07,4.7e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1
232 22990000,-0.28,0.017,-0.007,0.96,-0.076,0.051,-1.4,-0.068,0.047,-2.3,-0.0011,-0.0058,-6.3e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.022,0.0064,0.12,0.12,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 22990000,-0.28,0.017,-0.007,0.96,-0.075,0.054,-1.4,-0.067,0.051,-2.3,-0.0011,-0.0058,3.2e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.022,0.0064,0.12,0.12,0.034,5.9e-07,4.8e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1
233 23090000,-0.28,0.017,-0.007,0.96,-0.082,0.055,-1.4,-0.075,0.053,-2.5,-0.0011,-0.0058,-6.1e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0064,0.13,0.13,0.034,5.8e-07,5e-07,3.9e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23090000,-0.28,0.017,-0.007,0.96,-0.081,0.058,-1.4,-0.074,0.056,-2.5,-0.0011,-0.0058,3.4e-05,0.07,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.031,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.024,0.0064,0.13,0.13,0.034,5.8e-07,4.8e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1
234 23190000,-0.28,0.017,-0.0069,0.96,-0.084,0.05,-1.4,-0.074,0.049,-2.6,-0.0011,-0.0058,-8.4e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.13,0.13,0.033,5.7e-07,4.9e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23190000,-0.28,0.017,-0.0068,0.96,-0.083,0.053,-1.4,-0.073,0.052,-2.6,-0.0011,-0.0058,4.8e-06,0.07,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.02,0.023,0.0063,0.13,0.13,0.033,5.7e-07,4.7e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00066,0.0012,1,1
235 23290000,-0.28,0.018,-0.0073,0.96,-0.09,0.054,-1.4,-0.083,0.053,-2.7,-0.0011,-0.0058,-8e-05,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.14,0.14,0.034,5.6e-07,4.8e-07,3.8e-06,0.029,0.029,0.00019,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23290000,-0.28,0.018,-0.0073,0.96,-0.089,0.057,-1.4,-0.082,0.057,-2.7,-0.0011,-0.0058,9.4e-06,0.07,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.024,0.0063,0.14,0.14,0.034,5.7e-07,4.7e-07,4.6e-06,0.029,0.029,0.00019,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
236 23390000,-0.28,0.018,-0.0073,0.96,-0.089,0.056,-1.4,-0.077,0.055,-2.9,-0.0011,-0.0058,-9.8e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.14,0.14,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23390000,-0.28,0.018,-0.0072,0.96,-0.089,0.059,-1.4,-0.076,0.058,-2.9,-0.0011,-0.0058,-1.3e-05,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0063,0.14,0.14,0.033,5.5e-07,4.6e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
237 23490000,-0.28,0.018,-0.0073,0.96,-0.096,0.057,-1.4,-0.088,0.059,-3,-0.0011,-0.0058,-9e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0063,0.15,0.15,0.033,5.5e-07,4.7e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23490000,-0.28,0.018,-0.0072,0.96,-0.095,0.06,-1.4,-0.087,0.063,-3,-0.0011,-0.0058,-3.6e-06,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.024,0.0063,0.15,0.15,0.033,5.5e-07,4.5e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
238 23590000,-0.28,0.018,-0.0074,0.96,-0.094,0.051,-1.4,-0.083,0.049,-3.2,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0062,0.15,0.15,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23590000,-0.28,0.018,-0.0074,0.96,-0.094,0.053,-1.4,-0.082,0.053,-3.2,-0.0011,-0.0058,-3.5e-05,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00034,0.045,0.021,0.023,0.0062,0.15,0.15,0.033,5.4e-07,4.5e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
239 23690000,-0.28,0.019,-0.008,0.96,-0.093,0.053,-1.3,-0.092,0.053,-3.3,-0.0011,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0062,0.16,0.16,0.033,5.4e-07,4.6e-07,3.8e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23690000,-0.28,0.018,-0.0079,0.96,-0.092,0.055,-1.3,-0.091,0.057,-3.3,-0.0011,-0.0058,-2.6e-05,0.069,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00037,0.00035,0.045,0.021,0.024,0.0062,0.16,0.16,0.033,5.4e-07,4.4e-07,4.5e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
240 23790000,-0.28,0.021,-0.0095,0.96,-0.077,0.049,-0.95,-0.082,0.049,-3.4,-0.0012,-0.0058,-0.00012,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,0.00039,0.00036,0.045,0.021,0.022,0.0061,0.16,0.16,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23790000,-0.28,0.021,-0.0094,0.96,-0.077,0.052,-0.95,-0.081,0.052,-3.4,-0.0012,-0.0058,-4e-05,0.069,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.068,0,0,0.00039,0.00036,0.045,0.02,0.023,0.0061,0.16,0.16,0.033,5.3e-07,4.4e-07,4.4e-06,0.029,0.029,0.00018,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
241 23890000,-0.28,0.026,-0.012,0.96,-0.071,0.05,-0.52,-0.089,0.053,-3.5,-0.0012,-0.0058,-0.00011,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00042,0.00038,0.045,0.021,0.023,0.0061,0.17,0.17,0.033,5.2e-07,4.5e-07,3.7e-06,0.029,0.029,0.00018,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23890000,-0.28,0.026,-0.012,0.96,-0.07,0.053,-0.52,-0.088,0.057,-3.5,-0.0012,-0.0058,-3.5e-05,0.069,-0.023,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,0.00041,0.00038,0.045,0.021,0.023,0.0061,0.17,0.17,0.033,5.3e-07,4.3e-07,4.4e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
242 23990000,-0.28,0.028,-0.014,0.96,-0.061,0.048,-0.13,-0.077,0.048,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.02,0.022,0.0061,0.17,0.17,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 23990000,-0.28,0.028,-0.014,0.96,-0.061,0.051,-0.13,-0.076,0.051,-3.6,-0.0012,-0.0058,-5.7e-05,0.07,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,0.00043,0.0004,0.045,0.02,0.022,0.0061,0.17,0.17,0.033,5.1e-07,4.3e-07,4.4e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
243 24090000,-0.28,0.027,-0.014,0.96,-0.067,0.055,0.1,-0.082,0.053,-3.6,-0.0012,-0.0058,-0.00013,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.067,0,0,0.00043,0.0004,0.045,0.021,0.023,0.0061,0.18,0.18,0.033,5.1e-07,4.4e-07,3.7e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 24090000,-0.28,0.027,-0.014,0.96,-0.067,0.058,0.1,-0.081,0.057,-3.6,-0.0012,-0.0058,-5.5e-05,0.07,-0.024,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,0.00042,0.0004,0.045,0.021,0.023,0.0061,0.18,0.18,0.033,5.1e-07,4.2e-07,4.4e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
244 24190000,-0.28,0.023,-0.011,0.96,-0.071,0.052,0.089,-0.069,0.04,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.0004,0.00037,0.045,0.02,0.022,0.006,0.18,0.18,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 24190000,-0.28,0.023,-0.011,0.96,-0.071,0.055,0.09,-0.069,0.044,-3.6,-0.0012,-0.0058,-8.4e-05,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.0004,0.00037,0.045,0.02,0.022,0.006,0.18,0.18,0.033,5e-07,4.2e-07,4.3e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
245 24290000,-0.28,0.02,-0.0093,0.96,-0.076,0.055,0.068,-0.076,0.045,-3.6,-0.0012,-0.0058,-0.00015,0.072,-0.026,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.023,0.006,0.19,0.19,0.033,5e-07,4.3e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.7e-05,0.0012,0.0011,0.00067,0.0012,1,1 24290000,-0.28,0.019,-0.0092,0.96,-0.076,0.057,0.068,-0.076,0.049,-3.6,-0.0012,-0.0058,-7.9e-05,0.071,-0.025,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.023,0.006,0.19,0.19,0.033,5e-07,4.2e-07,4.3e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
246 24390000,-0.28,0.018,-0.0085,0.96,-0.059,0.048,0.084,-0.058,0.036,-3.6,-0.0013,-0.0058,-0.00016,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.02,0.022,0.006,0.19,0.19,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 24390000,-0.28,0.018,-0.0085,0.96,-0.059,0.05,0.084,-0.057,0.039,-3.6,-0.0012,-0.0059,-9.7e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00035,0.045,0.02,0.023,0.006,0.19,0.19,0.033,4.9e-07,4.1e-07,4.3e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
247 24490000,-0.28,0.019,-0.0087,0.96,-0.054,0.044,0.081,-0.063,0.039,-3.6,-0.0013,-0.0058,-0.00014,0.073,-0.027,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.021,0.023,0.006,0.2,0.2,0.033,4.9e-07,4.2e-07,3.6e-06,0.029,0.029,0.00017,0.0011,5.6e-05,0.0012,0.0011,0.00067,0.0012,1,1 24490000,-0.28,0.018,-0.0087,0.96,-0.054,0.047,0.082,-0.063,0.043,-3.6,-0.0012,-0.0059,-8.1e-05,0.071,-0.026,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.024,0.006,0.2,0.2,0.033,4.9e-07,4.1e-07,4.3e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
248 24590000,-0.28,0.019,-0.0094,0.96,-0.043,0.042,0.077,-0.045,0.033,-3.6,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.022,0.0059,0.2,0.2,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 24590000,-0.28,0.019,-0.0094,0.96,-0.043,0.044,0.077,-0.044,0.037,-3.6,-0.0013,-0.0059,-0.0001,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.02,0.023,0.0059,0.2,0.2,0.033,4.8e-07,4e-07,4.2e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
249 24690000,-0.28,0.019,-0.0099,0.96,-0.041,0.041,0.076,-0.049,0.037,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.028,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00036,0.045,0.021,0.024,0.0059,0.21,0.21,0.033,4.8e-07,4.1e-07,3.6e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 24690000,-0.28,0.018,-0.0099,0.96,-0.041,0.044,0.077,-0.049,0.041,-3.5,-0.0013,-0.0059,-9.9e-05,0.072,-0.027,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.024,0.0059,0.21,0.21,0.033,4.8e-07,4e-07,4.2e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
250 24790000,-0.28,0.018,-0.01,0.96,-0.034,0.04,0.068,-0.037,0.029,-3.5,-0.0013,-0.0058,-0.00017,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0059,0.21,0.21,0.032,4.7e-07,4.1e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 24790000,-0.28,0.018,-0.01,0.96,-0.034,0.042,0.068,-0.037,0.032,-3.5,-0.0013,-0.0059,-0.00012,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.02,0.023,0.0059,0.21,0.21,0.032,4.7e-07,3.9e-07,4.2e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
251 24890000,-0.28,0.017,-0.0099,0.96,-0.033,0.042,0.058,-0.04,0.032,-3.5,-0.0013,-0.0058,-0.00016,0.074,-0.029,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0059,0.22,0.22,0.032,4.7e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 24890000,-0.28,0.017,-0.0098,0.96,-0.033,0.045,0.058,-0.04,0.036,-3.5,-0.0013,-0.0059,-0.00011,0.072,-0.028,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.024,0.0059,0.22,0.22,0.032,4.7e-07,3.9e-07,4.1e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
252 24990000,-0.28,0.017,-0.0097,0.96,-0.021,0.043,0.05,-0.026,0.027,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.22,0.22,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 24990000,-0.28,0.017,-0.0096,0.96,-0.021,0.045,0.051,-0.026,0.03,-3.5,-0.0013,-0.0059,-0.00013,0.073,-0.029,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.22,0.22,0.032,4.6e-07,3.9e-07,4.1e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
253 25090000,-0.28,0.017,-0.01,0.96,-0.016,0.043,0.048,-0.027,0.031,-3.5,-0.0013,-0.0058,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.23,0.23,0.032,4.6e-07,4e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25090000,-0.28,0.017,-0.01,0.96,-0.016,0.045,0.048,-0.026,0.035,-3.5,-0.0013,-0.0059,-0.00012,0.073,-0.029,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.024,0.0058,0.23,0.23,0.032,4.6e-07,3.9e-07,4.1e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
254 25190000,-0.28,0.017,-0.01,0.96,-0.006,0.038,0.048,-0.011,0.021,-3.5,-0.0013,-0.0059,-0.0002,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0058,0.23,0.23,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00016,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25190000,-0.28,0.017,-0.01,0.96,-0.0064,0.041,0.048,-0.011,0.024,-3.5,-0.0013,-0.0059,-0.00016,0.073,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.23,0.23,0.032,4.5e-07,3.8e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
255 25290000,-0.28,0.016,-0.01,0.96,-0.0013,0.041,0.043,-0.012,0.026,-3.5,-0.0013,-0.0059,-0.00021,0.075,-0.03,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0058,0.24,0.24,0.032,4.5e-07,3.9e-07,3.5e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25290000,-0.28,0.016,-0.01,0.96,-0.0016,0.043,0.043,-0.012,0.029,-3.5,-0.0013,-0.0059,-0.00016,0.073,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.24,0.24,0.032,4.5e-07,3.8e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
256 25390000,-0.28,0.016,-0.011,0.96,0.0076,0.039,0.041,-0.0022,0.02,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.24,0.24,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25390000,-0.28,0.016,-0.011,0.96,0.0072,0.042,0.042,-0.0022,0.023,-3.5,-0.0013,-0.0059,-0.00017,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0058,0.24,0.24,0.032,4.5e-07,3.7e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
257 25490000,-0.28,0.016,-0.011,0.96,0.012,0.04,0.041,-0.0021,0.024,-3.5,-0.0013,-0.0059,-0.00022,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.25,0.25,0.032,4.4e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25490000,-0.28,0.016,-0.011,0.96,0.012,0.042,0.041,-0.0021,0.027,-3.5,-0.0013,-0.0059,-0.00018,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0058,0.25,0.25,0.032,4.5e-07,3.7e-07,4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
258 25590000,-0.28,0.016,-0.011,0.96,0.017,0.035,0.042,0.0049,0.0094,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.25,0.25,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25590000,-0.28,0.016,-0.011,0.96,0.016,0.038,0.042,0.005,0.012,-3.5,-0.0013,-0.0059,-0.00021,0.074,-0.03,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.25,0.25,0.032,4.4e-07,3.7e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
259 25690000,-0.28,0.015,-0.01,0.96,0.018,0.034,0.031,0.0066,0.013,-3.5,-0.0014,-0.0058,-0.00024,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.26,0.26,0.032,4.3e-07,3.8e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25690000,-0.28,0.015,-0.01,0.96,0.017,0.037,0.031,0.0067,0.015,-3.5,-0.0013,-0.0059,-0.0002,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.26,0.26,0.032,4.4e-07,3.7e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
260 25790000,-0.28,0.015,-0.01,0.96,0.028,0.029,0.031,0.014,0.0031,-3.5,-0.0014,-0.0058,-0.00025,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.26,0.032,4.2e-07,3.7e-07,3.4e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25790000,-0.28,0.015,-0.01,0.96,0.028,0.032,0.031,0.014,0.0057,-3.5,-0.0014,-0.0059,-0.00022,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.26,0.032,4.3e-07,3.6e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
261 25890000,-0.28,0.015,-0.01,0.96,0.034,0.029,0.033,0.017,0.0067,-3.5,-0.0014,-0.0058,-0.00026,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.27,0.27,0.032,4.2e-07,3.7e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25890000,-0.28,0.015,-0.01,0.96,0.034,0.031,0.033,0.017,0.0094,-3.5,-0.0013,-0.0059,-0.00023,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.27,0.27,0.032,4.3e-07,3.6e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
262 25990000,-0.28,0.015,-0.01,0.96,0.036,0.024,0.027,0.013,-0.004,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.27,0.27,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 25990000,-0.28,0.015,-0.01,0.96,0.036,0.026,0.027,0.014,-0.0017,-3.5,-0.0014,-0.0058,-0.00025,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0057,0.26,0.27,0.032,4.2e-07,3.6e-07,3.9e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
263 26090000,-0.28,0.015,-0.0099,0.96,0.041,0.024,0.025,0.017,-0.0023,-3.5,-0.0014,-0.0058,-0.00027,0.075,-0.031,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.28,0.28,0.032,4.2e-07,3.6e-07,3.3e-06,0.029,0.029,0.00015,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26090000,-0.28,0.015,-0.0099,0.96,0.041,0.026,0.026,0.017,0.00025,-3.5,-0.0014,-0.0058,-0.00024,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0057,0.28,0.28,0.032,4.2e-07,3.6e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
264 26190000,-0.28,0.015,-0.0098,0.96,0.046,0.015,0.021,0.02,-0.018,-3.5,-0.0014,-0.0058,-0.00028,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.27,0.28,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26190000,-0.28,0.015,-0.0098,0.96,0.045,0.017,0.021,0.02,-0.016,-3.5,-0.0014,-0.0058,-0.00026,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.27,0.28,0.032,4.1e-07,3.5e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
265 26290000,-0.28,0.016,-0.0098,0.96,0.046,0.014,0.015,0.024,-0.016,-3.5,-0.0014,-0.0058,-0.00029,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.29,0.29,0.032,4.1e-07,3.6e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26290000,-0.28,0.016,-0.0097,0.96,0.046,0.016,0.015,0.024,-0.014,-3.5,-0.0014,-0.0058,-0.00026,0.074,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.022,0.024,0.0056,0.29,0.29,0.032,4.1e-07,3.5e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
266 26390000,-0.28,0.016,-0.0092,0.96,0.043,0.0051,0.019,0.015,-0.03,-3.5,-0.0014,-0.0058,-0.0003,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.021,0.023,0.0056,0.28,0.29,0.032,4e-07,3.5e-07,3.3e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26390000,-0.28,0.016,-0.0092,0.96,0.043,0.0073,0.019,0.016,-0.028,-3.5,-0.0014,-0.0058,-0.00028,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00036,0.045,0.021,0.023,0.0056,0.28,0.29,0.032,4.1e-07,3.5e-07,3.8e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
267 26490000,-0.28,0.016,-0.009,0.96,0.046,0.0028,0.028,0.02,-0.03,-3.5,-0.0014,-0.0058,-0.00031,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00036,0.045,0.022,0.024,0.0056,0.3,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26490000,-0.28,0.016,-0.0089,0.96,0.046,0.0051,0.029,0.02,-0.028,-3.5,-0.0014,-0.0058,-0.00029,0.073,-0.031,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00035,0.045,0.022,0.024,0.0056,0.3,0.3,0.032,4.1e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
268 26590000,-0.28,0.016,-0.0084,0.96,0.045,-0.0071,0.029,0.019,-0.042,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0056,0.29,0.3,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26590000,-0.28,0.016,-0.0084,0.96,0.045,-0.005,0.029,0.019,-0.04,-3.5,-0.0014,-0.0058,-0.00031,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0056,0.29,0.3,0.032,4e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
269 26690000,-0.28,0.016,-0.0083,0.96,0.047,-0.011,0.027,0.023,-0.042,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.31,0.31,0.032,4e-07,3.5e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26690000,-0.28,0.015,-0.0083,0.96,0.047,-0.0089,0.027,0.024,-0.041,-3.5,-0.0014,-0.0058,-0.00032,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.31,0.31,0.032,4e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
270 26790000,-0.27,0.015,-0.0081,0.96,0.049,-0.017,0.027,0.02,-0.055,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.3,0.31,0.031,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26790000,-0.28,0.015,-0.0081,0.96,0.049,-0.015,0.027,0.021,-0.054,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00035,0.045,0.021,0.023,0.0055,0.3,0.31,0.031,3.9e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
271 26890000,-0.27,0.015,-0.0074,0.96,0.055,-0.02,0.022,0.026,-0.057,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0056,0.32,0.32,0.032,3.9e-07,3.4e-07,3.2e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26890000,-0.28,0.015,-0.0074,0.96,0.055,-0.018,0.022,0.026,-0.055,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00036,0.00035,0.045,0.022,0.024,0.0056,0.32,0.32,0.032,3.9e-07,3.4e-07,3.7e-06,0.029,0.029,0.00014,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
272 26990000,-0.27,0.016,-0.0069,0.96,0.056,-0.026,0.021,0.018,-0.064,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.31,0.32,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 26990000,-0.28,0.015,-0.0068,0.96,0.056,-0.024,0.022,0.019,-0.062,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.31,0.32,0.031,3.9e-07,3.3e-07,3.6e-06,0.029,0.029,0.00014,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
273 27090000,-0.27,0.016,-0.0067,0.96,0.058,-0.033,0.025,0.024,-0.067,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0055,0.33,0.33,0.031,3.8e-07,3.4e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27090000,-0.28,0.016,-0.0067,0.96,0.059,-0.03,0.025,0.025,-0.065,-3.5,-0.0014,-0.0058,-0.00034,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.022,0.024,0.0055,0.32,0.33,0.031,3.9e-07,3.3e-07,3.6e-06,0.029,0.029,0.00014,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
274 27190000,-0.27,0.016,-0.0068,0.96,0.058,-0.036,0.027,0.014,-0.069,-3.5,-0.0014,-0.0058,-0.00034,0.075,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.32,0.33,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27190000,-0.28,0.016,-0.0067,0.96,0.059,-0.034,0.027,0.014,-0.068,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.021,0.023,0.0055,0.32,0.33,0.031,3.8e-07,3.3e-07,3.6e-06,0.029,0.029,0.00014,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
275 27290000,-0.27,0.017,-0.0069,0.96,0.066,-0.041,0.14,0.02,-0.073,-3.5,-0.0014,-0.0058,-0.00035,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.022,0.024,0.0055,0.33,0.34,0.031,3.8e-07,3.3e-07,3.1e-06,0.029,0.029,0.00014,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27290000,-0.28,0.017,-0.0068,0.96,0.066,-0.039,0.14,0.021,-0.072,-3.5,-0.0014,-0.0058,-0.00033,0.073,-0.032,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.022,0.024,0.0055,0.33,0.34,0.031,3.8e-07,3.3e-07,3.6e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
276 27390000,-0.27,0.019,-0.0081,0.96,0.07,-0.034,0.46,0.0048,-0.026,-3.5,-0.0014,-0.0058,-0.00032,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27390000,-0.28,0.019,-0.0081,0.96,0.07,-0.032,0.46,0.005,-0.026,-3.5,-0.0014,-0.0058,-0.00031,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
277 27490000,-0.27,0.021,-0.0093,0.96,0.076,-0.037,0.78,0.012,-0.029,-3.5,-0.0014,-0.0058,-0.00033,0.075,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.016,0.017,0.0055,0.15,0.15,0.031,3.7e-07,3.3e-07,3.1e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27490000,-0.28,0.021,-0.0093,0.96,0.076,-0.035,0.78,0.012,-0.029,-3.5,-0.0014,-0.0058,-0.00032,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.0004,0.00036,0.045,0.015,0.018,0.0055,0.15,0.15,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
278 27590000,-0.27,0.02,-0.0093,0.96,0.067,-0.039,0.87,0.0064,-0.02,-3.4,-0.0014,-0.0058,-0.00032,0.074,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.0004,0.00036,0.045,0.014,0.015,0.0055,0.096,0.097,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27590000,-0.28,0.02,-0.0093,0.96,0.067,-0.037,0.87,0.0066,-0.02,-3.4,-0.0014,-0.0058,-0.0003,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00039,0.00036,0.045,0.014,0.015,0.0055,0.096,0.097,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
279 27690000,-0.27,0.017,-0.0084,0.96,0.061,-0.036,0.78,0.013,-0.024,-3.3,-0.0014,-0.0058,-0.00031,0.075,-0.034,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0055,0.1,0.1,0.031,3.7e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00066,0.0012,1,1 27690000,-0.28,0.017,-0.0083,0.96,0.062,-0.034,0.78,0.013,-0.023,-3.3,-0.0014,-0.0058,-0.0003,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0055,0.1,0.1,0.031,3.7e-07,3.2e-07,3.5e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
280 27790000,-0.27,0.016,-0.0072,0.96,0.058,-0.034,0.77,0.01,-0.019,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.013,0.015,0.0054,0.073,0.074,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 27790000,-0.28,0.016,-0.0072,0.96,0.058,-0.032,0.77,0.01,-0.019,-3.2,-0.0014,-0.0058,-0.00028,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.013,0.015,0.0054,0.073,0.074,0.031,3.7e-07,3.1e-07,3.4e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
281 27890000,-0.27,0.016,-0.0068,0.96,0.064,-0.04,0.81,0.016,-0.023,-3.2,-0.0014,-0.0058,-0.0003,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00037,0.00035,0.045,0.014,0.016,0.0055,0.076,0.077,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 27890000,-0.28,0.016,-0.0068,0.96,0.064,-0.038,0.81,0.016,-0.022,-3.2,-0.0013,-0.0058,-0.00028,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.066,0,0,0.00037,0.00034,0.045,0.014,0.016,0.0055,0.076,0.077,0.031,3.7e-07,3.1e-07,3.4e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
282 27990000,-0.27,0.016,-0.0072,0.96,0.064,-0.042,0.8,0.019,-0.026,-3.1,-0.0014,-0.0058,-0.00029,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.014,0.016,0.0054,0.079,0.079,0.031,3.6e-07,3.2e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 27990000,-0.28,0.016,-0.0072,0.96,0.065,-0.04,0.8,0.019,-0.025,-3.1,-0.0013,-0.0058,-0.00028,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.014,0.016,0.0054,0.079,0.079,0.031,3.6e-07,3.1e-07,3.4e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
283 28090000,-0.27,0.016,-0.0075,0.96,0.068,-0.043,0.8,0.026,-0.03,-3,-0.0014,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.082,0.083,0.031,3.6e-07,3.1e-07,3e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 28090000,-0.28,0.016,-0.0075,0.96,0.068,-0.041,0.8,0.026,-0.029,-3,-0.0013,-0.0058,-0.00027,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00037,0.00035,0.045,0.015,0.017,0.0054,0.082,0.083,0.031,3.6e-07,3.1e-07,3.4e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
284 28190000,-0.27,0.016,-0.0069,0.96,0.065,-0.041,0.81,0.027,-0.032,-2.9,-0.0013,-0.0058,-0.00028,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.085,0.085,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 28190000,-0.28,0.016,-0.0069,0.96,0.065,-0.039,0.81,0.027,-0.031,-2.9,-0.0013,-0.0058,-0.00025,0.072,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.015,0.017,0.0054,0.084,0.086,0.031,3.6e-07,3.1e-07,3.4e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
285 28290000,-0.27,0.017,-0.0064,0.96,0.069,-0.044,0.81,0.033,-0.037,-2.9,-0.0013,-0.0058,-0.00027,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00035,0.045,0.016,0.018,0.0054,0.089,0.09,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 28290000,-0.28,0.017,-0.0063,0.96,0.069,-0.042,0.81,0.033,-0.036,-2.9,-0.0013,-0.0058,-0.00025,0.072,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.015,0.018,0.0054,0.088,0.09,0.031,3.6e-07,3.1e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
286 28390000,-0.27,0.017,-0.0063,0.96,0.07,-0.046,0.81,0.035,-0.038,-2.8,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.015,0.017,0.0054,0.091,0.092,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 28390000,-0.28,0.017,-0.0063,0.96,0.07,-0.044,0.81,0.036,-0.036,-2.8,-0.0013,-0.0058,-0.00022,0.072,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.015,0.018,0.0054,0.091,0.092,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
287 28490000,-0.27,0.018,-0.0066,0.96,0.073,-0.049,0.81,0.043,-0.042,-2.7,-0.0013,-0.0058,-0.00025,0.074,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.095,0.097,0.031,3.5e-07,3.1e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.6e-05,0.0012,0.0011,0.00065,0.0012,1,1 28490000,-0.28,0.018,-0.0065,0.96,0.073,-0.047,0.81,0.044,-0.041,-2.7,-0.0013,-0.0058,-0.00023,0.072,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.019,0.0054,0.095,0.097,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
288 28590000,-0.27,0.018,-0.0066,0.96,0.065,-0.049,0.81,0.043,-0.045,-2.6,-0.0013,-0.0058,-0.00023,0.073,-0.033,-0.13,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.098,0.099,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 28590000,-0.28,0.017,-0.0065,0.96,0.065,-0.047,0.81,0.044,-0.044,-2.6,-0.0013,-0.0058,-0.00021,0.072,-0.032,-0.13,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00035,0.045,0.016,0.018,0.0054,0.098,0.1,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
289 28690000,-0.27,0.017,-0.0064,0.96,0.064,-0.05,0.81,0.05,-0.05,-2.6,-0.0013,-0.0058,-0.00024,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00039,0.00035,0.045,0.017,0.019,0.0054,0.1,0.1,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 28690000,-0.28,0.017,-0.0064,0.96,0.064,-0.048,0.81,0.05,-0.048,-2.6,-0.0013,-0.0058,-0.00021,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00035,0.045,0.017,0.019,0.0054,0.1,0.1,0.031,3.5e-07,3e-07,3.3e-06,0.029,0.028,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
290 28790000,-0.27,0.017,-0.0058,0.96,0.062,-0.049,0.81,0.051,-0.049,-2.5,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.11,0.031,3.4e-07,3e-07,2.9e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 28790000,-0.28,0.017,-0.0057,0.96,0.062,-0.047,0.81,0.051,-0.047,-2.5,-0.0013,-0.0058,-0.00018,0.072,-0.032,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.11,0.031,3.4e-07,3e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
291 28890000,-0.27,0.016,-0.0056,0.96,0.065,-0.051,0.81,0.057,-0.054,-2.4,-0.0013,-0.0058,-0.00021,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.02,0.0054,0.11,0.11,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00013,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 28890000,-0.28,0.016,-0.0056,0.96,0.065,-0.048,0.81,0.057,-0.052,-2.4,-0.0013,-0.0058,-0.00018,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.02,0.0054,0.11,0.11,0.031,3.4e-07,3e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
292 28990000,-0.27,0.016,-0.0054,0.96,0.063,-0.048,0.81,0.058,-0.054,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.017,0.019,0.0053,0.11,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 28990000,-0.28,0.016,-0.0053,0.96,0.064,-0.046,0.81,0.059,-0.052,-2.3,-0.0013,-0.0058,-0.00016,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.017,0.019,0.0053,0.11,0.12,0.031,3.4e-07,2.9e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
293 29090000,-0.27,0.017,-0.0052,0.96,0.067,-0.05,0.81,0.066,-0.059,-2.3,-0.0013,-0.0058,-0.00019,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,3e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29090000,-0.28,0.016,-0.0052,0.96,0.067,-0.048,0.81,0.066,-0.056,-2.3,-0.0013,-0.0058,-0.00016,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,2.9e-07,3.2e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
294 29190000,-0.27,0.017,-0.0051,0.96,0.067,-0.049,0.8,0.067,-0.058,-2.2,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29190000,-0.28,0.017,-0.0051,0.96,0.067,-0.046,0.8,0.068,-0.055,-2.2,-0.0013,-0.0058,-0.00014,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.02,0.0053,0.12,0.12,0.031,3.4e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
295 29290000,-0.27,0.017,-0.0054,0.96,0.071,-0.054,0.81,0.076,-0.062,-2.1,-0.0013,-0.0058,-0.00017,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.021,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29290000,-0.28,0.017,-0.0054,0.96,0.072,-0.051,0.81,0.077,-0.06,-2.1,-0.0013,-0.0058,-0.00014,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00039,0.00034,0.045,0.018,0.021,0.0053,0.13,0.13,0.031,3.4e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
296 29390000,-0.27,0.016,-0.0059,0.96,0.067,-0.051,0.81,0.074,-0.059,-2,-0.0013,-0.0058,-0.00014,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,2.8e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29390000,-0.28,0.016,-0.0059,0.96,0.068,-0.048,0.81,0.075,-0.056,-2,-0.0013,-0.0058,-0.00011,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.02,0.0053,0.13,0.13,0.031,3.3e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
297 29490000,-0.27,0.016,-0.0059,0.96,0.07,-0.052,0.81,0.081,-0.065,-2,-0.0013,-0.0058,-0.00013,0.073,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29490000,-0.27,0.016,-0.0059,0.96,0.071,-0.049,0.81,0.082,-0.062,-2,-0.0013,-0.0058,-9.8e-05,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.9e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
298 29590000,-0.27,0.016,-0.0058,0.96,0.068,-0.05,0.81,0.08,-0.063,-1.9,-0.0013,-0.0058,-0.00011,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.018,0.021,0.0053,0.14,0.14,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00065,0.0012,1,1 29590000,-0.27,0.016,-0.0058,0.96,0.068,-0.047,0.81,0.08,-0.06,-1.9,-0.0013,-0.0058,-6.7e-05,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.083,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.018,0.021,0.0053,0.14,0.14,0.031,3.3e-07,2.8e-07,3.1e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
299 29690000,-0.27,0.016,-0.0058,0.96,0.072,-0.049,0.81,0.087,-0.068,-1.8,-0.0013,-0.0058,-9.8e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00038,0.00034,0.044,0.019,0.022,0.0053,0.15,0.15,0.031,3.2e-07,2.9e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 29690000,-0.27,0.016,-0.0058,0.96,0.072,-0.046,0.81,0.088,-0.065,-1.8,-0.0013,-0.0058,-5.9e-05,0.071,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.022,0.0053,0.15,0.15,0.031,3.3e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
300 29790000,-0.27,0.016,-0.0056,0.96,0.069,-0.042,0.8,0.084,-0.064,-1.7,-0.0013,-0.0058,-6.9e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0053,0.15,0.15,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 29790000,-0.27,0.016,-0.0056,0.96,0.069,-0.039,0.81,0.085,-0.061,-1.7,-0.0013,-0.0058,-2.7e-05,0.07,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00038,0.00034,0.045,0.019,0.021,0.0053,0.15,0.15,0.031,3.2e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
301 29890000,-0.27,0.016,-0.005,0.96,0.07,-0.044,0.8,0.092,-0.069,-1.7,-0.0013,-0.0058,-6.2e-05,0.072,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0053,0.15,0.16,0.031,3.2e-07,2.8e-07,2.7e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 29890000,-0.27,0.016,-0.005,0.96,0.071,-0.041,0.8,0.092,-0.065,-1.7,-0.0013,-0.0058,-1.9e-05,0.07,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.045,0.019,0.022,0.0053,0.15,0.16,0.031,3.2e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
302 29990000,-0.27,0.016,-0.0052,0.96,0.065,-0.041,0.8,0.087,-0.068,-1.6,-0.0013,-0.0058,-4.8e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.16,0.16,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 29990000,-0.27,0.016,-0.0052,0.96,0.065,-0.039,0.8,0.087,-0.064,-1.6,-0.0013,-0.0058,-3.3e-06,0.07,-0.033,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.045,0.019,0.021,0.0052,0.16,0.16,0.03,3.2e-07,2.8e-07,3e-06,0.029,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
303 30090000,-0.27,0.017,-0.0053,0.96,0.067,-0.041,0.8,0.094,-0.07,-1.5,-0.0013,-0.0058,-6.2e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.16,0.17,0.03,3.2e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30090000,-0.27,0.016,-0.0053,0.96,0.067,-0.038,0.8,0.095,-0.067,-1.5,-0.0013,-0.0058,-2e-05,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.16,0.17,0.03,3.2e-07,2.8e-07,3e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
304 30190000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.089,-0.061,-1.5,-0.0013,-0.0058,-5e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.021,0.0052,0.17,0.17,0.031,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30190000,-0.27,0.016,-0.0054,0.96,0.062,-0.032,0.8,0.089,-0.058,-1.5,-0.0013,-0.0058,-5.8e-06,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.17,0.17,0.031,3.1e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
305 30290000,-0.27,0.016,-0.0054,0.96,0.062,-0.034,0.8,0.096,-0.065,-1.4,-0.0013,-0.0058,-4.9e-05,0.072,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.17,0.18,0.03,3.1e-07,2.8e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30290000,-0.27,0.016,-0.0054,0.96,0.062,-0.032,0.8,0.096,-0.061,-1.4,-0.0013,-0.0058,-4.5e-06,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.17,0.18,0.031,3.2e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
306 30390000,-0.27,0.016,-0.0054,0.96,0.059,-0.029,0.8,0.095,-0.059,-1.3,-0.0013,-0.0058,-1.9e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.18,0.18,0.03,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30390000,-0.27,0.016,-0.0054,0.96,0.059,-0.026,0.8,0.095,-0.055,-1.3,-0.0012,-0.0058,2.8e-05,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.019,0.022,0.0052,0.17,0.18,0.03,3.1e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
307 30490000,-0.27,0.016,-0.0054,0.96,0.063,-0.028,0.8,0.1,-0.062,-1.2,-0.0013,-0.0058,-1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.18,0.19,0.031,3.1e-07,2.7e-07,2.6e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30490000,-0.27,0.016,-0.0054,0.96,0.063,-0.025,0.8,0.1,-0.058,-1.2,-0.0013,-0.0058,3.5e-05,0.07,-0.034,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.18,0.19,0.031,3.1e-07,2.7e-07,2.9e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
308 30590000,-0.27,0.017,-0.0056,0.96,0.061,-0.026,0.8,0.097,-0.058,-1.2,-0.0013,-0.0058,1.2e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.18,0.19,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30590000,-0.27,0.017,-0.0057,0.96,0.061,-0.023,0.8,0.097,-0.054,-1.2,-0.0012,-0.0058,6.1e-05,0.07,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.18,0.19,0.03,3.1e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
309 30690000,-0.27,0.017,-0.006,0.96,0.058,-0.026,0.8,0.1,-0.061,-1.1,-0.0013,-0.0058,1.1e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00035,0.044,0.02,0.023,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30690000,-0.27,0.017,-0.006,0.96,0.059,-0.023,0.8,0.1,-0.056,-1.1,-0.0012,-0.0058,6e-05,0.07,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.19,0.2,0.03,3.1e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
310 30790000,-0.27,0.016,-0.0058,0.96,0.052,-0.016,0.8,0.095,-0.049,-1,-0.0012,-0.0058,3.6e-05,0.072,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30790000,-0.27,0.016,-0.0058,0.96,0.052,-0.013,0.8,0.096,-0.044,-1,-0.0012,-0.0058,8.8e-05,0.07,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.19,0.2,0.03,3e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
311 30890000,-0.27,0.016,-0.0052,0.96,0.051,-0.012,0.79,0.099,-0.05,-0.95,-0.0012,-0.0058,2.6e-05,0.072,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30890000,-0.27,0.016,-0.0052,0.96,0.051,-0.0089,0.79,0.099,-0.045,-0.95,-0.0012,-0.0058,7.6e-05,0.071,-0.035,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.023,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.8e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
312 30990000,-0.27,0.016,-0.0054,0.96,0.046,-0.01,0.79,0.095,-0.048,-0.88,-0.0012,-0.0058,3e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.2,0.21,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 30990000,-0.27,0.016,-0.0054,0.96,0.047,-0.0072,0.79,0.095,-0.044,-0.88,-0.0012,-0.0058,8e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.2,0.21,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00012,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
313 31090000,-0.27,0.016,-0.0055,0.96,0.045,-0.0087,0.79,0.099,-0.049,-0.81,-0.0012,-0.0058,2.2e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.21,0.22,0.03,3e-07,2.7e-07,2.5e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 31090000,-0.27,0.016,-0.0055,0.96,0.045,-0.0058,0.79,0.099,-0.044,-0.81,-0.0012,-0.0058,7.1e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.21,0.22,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
314 31190000,-0.27,0.017,-0.0057,0.96,0.042,-0.0051,0.8,0.093,-0.044,-0.74,-0.0012,-0.0058,4.6e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00012,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 31190000,-0.27,0.016,-0.0057,0.96,0.042,-0.0023,0.8,0.093,-0.04,-0.74,-0.0012,-0.0058,9.7e-05,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0052,0.21,0.22,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
315 31290000,-0.27,0.017,-0.0059,0.96,0.039,-0.0033,0.8,0.096,-0.045,-0.67,-0.0012,-0.0058,5.2e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 31290000,-0.27,0.017,-0.0059,0.96,0.039,-0.0004,0.8,0.096,-0.041,-0.67,-0.0012,-0.0058,0.0001,0.071,-0.036,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.22,0.23,0.03,3e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
316 31390000,-0.27,0.016,-0.0057,0.96,0.035,0.0017,0.8,0.09,-0.042,-0.59,-0.0012,-0.0058,5.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.22,0.23,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00064,0.0012,1,1 31390000,-0.27,0.016,-0.0057,0.96,0.035,0.0044,0.8,0.09,-0.037,-0.59,-0.0012,-0.0058,0.0001,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.22,0.23,0.03,2.9e-07,2.6e-07,2.7e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
317 31490000,-0.27,0.017,-0.0054,0.96,0.036,0.0051,0.8,0.095,-0.041,-0.52,-0.0012,-0.0058,4.8e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 31490000,-0.27,0.017,-0.0054,0.96,0.036,0.0079,0.8,0.095,-0.036,-0.52,-0.0012,-0.0058,9.8e-05,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.021,0.023,0.0052,0.23,0.24,0.03,3e-07,2.6e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
318 31590000,-0.27,0.017,-0.0052,0.96,0.036,0.007,0.8,0.092,-0.037,-0.45,-0.0012,-0.0058,6.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.23,0.24,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.5e-05,0.0012,0.0011,0.00063,0.0012,1,1 31590000,-0.27,0.017,-0.0052,0.96,0.037,0.0097,0.8,0.093,-0.033,-0.45,-0.0012,-0.0058,0.00011,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.00039,0.00034,0.044,0.02,0.022,0.0051,0.23,0.24,0.03,2.9e-07,2.6e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
319 31690000,-0.27,0.017,-0.0052,0.96,0.04,0.0082,0.8,0.097,-0.037,-0.38,-0.0012,-0.0058,7.1e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.4e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 31690000,-0.27,0.017,-0.0052,0.96,0.04,0.011,0.8,0.097,-0.032,-0.38,-0.0012,-0.0058,0.00012,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.082,-0.033,-0.067,0,0,0.0004,0.00034,0.044,0.021,0.023,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
320 31790000,-0.27,0.018,-0.0054,0.96,0.034,0.014,0.8,0.093,-0.027,-0.3,-0.0012,-0.0058,9e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.24,0.25,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 31790000,-0.27,0.018,-0.0054,0.96,0.034,0.017,0.8,0.093,-0.023,-0.3,-0.0012,-0.0058,0.00014,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.0004,0.00034,0.044,0.02,0.022,0.0051,0.24,0.25,0.03,2.9e-07,2.5e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
321 31890000,-0.27,0.018,-0.0052,0.96,0.032,0.016,0.8,0.097,-0.025,-0.23,-0.0012,-0.0058,9.4e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.25,0.26,0.03,2.9e-07,2.6e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 31890000,-0.27,0.018,-0.0052,0.96,0.032,0.019,0.8,0.098,-0.021,-0.23,-0.0012,-0.0058,0.00015,0.071,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.0004,0.00034,0.044,0.021,0.023,0.0051,0.25,0.26,0.03,2.9e-07,2.5e-07,2.6e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
322 31990000,-0.27,0.017,-0.0055,0.96,0.029,0.017,0.79,0.094,-0.02,-0.17,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 31990000,-0.27,0.017,-0.0055,0.96,0.029,0.02,0.79,0.094,-0.016,-0.17,-0.0012,-0.0058,0.00014,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.25,0.26,0.03,2.9e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
323 32090000,-0.27,0.017,-0.0059,0.96,0.03,0.021,0.8,0.098,-0.018,-0.096,-0.0012,-0.0058,9.2e-05,0.073,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32090000,-0.27,0.017,-0.0059,0.96,0.03,0.024,0.8,0.098,-0.013,-0.095,-0.0012,-0.0058,0.00014,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.26,0.27,0.03,2.9e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
324 32190000,-0.27,0.017,-0.0061,0.96,0.027,0.029,0.8,0.093,-0.0092,-0.027,-0.0012,-0.0058,9.7e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32190000,-0.27,0.017,-0.0062,0.96,0.027,0.031,0.8,0.093,-0.0048,-0.027,-0.0012,-0.0058,0.00015,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.26,0.27,0.03,2.8e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
325 32290000,-0.27,0.017,-0.006,0.96,0.027,0.031,0.8,0.096,-0.0063,0.042,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.021,0.023,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.3e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32290000,-0.27,0.017,-0.006,0.96,0.027,0.034,0.8,0.096,-0.0016,0.042,-0.0012,-0.0058,0.00015,0.072,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.021,0.023,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
326 32390000,-0.27,0.017,-0.0062,0.96,0.023,0.033,0.79,0.092,-0.0029,0.12,-0.0012,-0.0058,0.0001,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.0004,0.00034,0.043,0.02,0.022,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32390000,-0.27,0.017,-0.0062,0.96,0.023,0.036,0.8,0.092,0.0015,0.12,-0.0012,-0.0058,0.00015,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00039,0.00034,0.043,0.02,0.022,0.0051,0.27,0.28,0.03,2.8e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
327 32490000,-0.27,0.016,-0.0092,0.96,-0.017,0.092,-0.077,0.091,0.0054,0.12,-0.0012,-0.0058,9.6e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.025,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32490000,-0.27,0.016,-0.0092,0.96,-0.017,0.094,-0.077,0.091,0.01,0.12,-0.0012,-0.0058,0.00015,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.025,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.5e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
328 32590000,-0.27,0.016,-0.0092,0.96,-0.014,0.09,-0.08,0.091,-0.0025,0.1,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.021,0.023,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32590000,-0.27,0.016,-0.0092,0.96,-0.015,0.093,-0.079,0.092,0.0017,0.1,-0.0012,-0.0058,0.00013,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.28,0.29,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1
329 32690000,-0.27,0.016,-0.0092,0.96,-0.01,0.097,-0.081,0.09,0.0069,0.088,-0.0012,-0.0058,8.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32690000,-0.27,0.015,-0.0092,0.96,-0.011,0.1,-0.081,0.09,0.011,0.088,-0.0012,-0.0058,0.00013,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00035,0.043,0.022,0.025,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
330 32790000,-0.27,0.016,-0.009,0.96,-0.0062,0.095,-0.082,0.092,-0.0016,0.073,-0.0012,-0.0058,7.5e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32790000,-0.27,0.016,-0.009,0.96,-0.0064,0.097,-0.082,0.092,0.0025,0.073,-0.0012,-0.0058,0.00012,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.29,0.3,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
331 32890000,-0.27,0.016,-0.009,0.96,-0.0066,0.1,-0.084,0.09,0.0078,0.058,-0.0012,-0.0058,8.1e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00038,0.00035,0.043,0.022,0.024,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.2e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32890000,-0.27,0.016,-0.009,0.96,-0.0068,0.1,-0.083,0.09,0.012,0.058,-0.0012,-0.0058,0.00013,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.3,0.31,0.03,2.8e-07,2.5e-07,2.4e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
332 32990000,-0.27,0.016,-0.0088,0.96,-0.0026,0.095,-0.083,0.091,-0.006,0.044,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 32990000,-0.27,0.016,-0.0088,0.96,-0.0028,0.098,-0.083,0.091,-0.002,0.044,-0.0012,-0.0058,0.00011,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
333 33090000,-0.27,0.016,-0.0088,0.96,0.0013,0.1,-0.08,0.091,0.0037,0.037,-0.0012,-0.0058,6.8e-05,0.074,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.31,0.32,0.03,2.7e-07,2.5e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33090000,-0.27,0.016,-0.0088,0.96,0.0011,0.1,-0.08,0.091,0.0079,0.037,-0.0012,-0.0058,0.00011,0.072,-0.039,-0.12,-0.11,-0.024,0.5,0.081,-0.033,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
334 33190000,-0.27,0.016,-0.0086,0.96,0.0057,0.096,-0.079,0.092,-0.012,0.029,-0.0012,-0.0058,4e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00035,0.043,0.021,0.023,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33190000,-0.27,0.016,-0.0087,0.96,0.0055,0.099,-0.079,0.092,-0.0081,0.029,-0.0012,-0.0058,8e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.0051,0.31,0.32,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
335 33290000,-0.27,0.016,-0.0087,0.96,0.0098,0.099,-0.079,0.093,-0.0027,0.021,-0.0013,-0.0058,5.7e-05,0.074,-0.038,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00035,0.043,0.021,0.024,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.029,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33290000,-0.27,0.016,-0.0087,0.96,0.0096,0.1,-0.079,0.093,0.0015,0.021,-0.0012,-0.0058,9.7e-05,0.072,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
336 33390000,-0.27,0.016,-0.0086,0.96,0.014,0.095,-0.077,0.092,-0.012,0.012,-0.0013,-0.0058,4.6e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33390000,-0.27,0.016,-0.0086,0.96,0.014,0.097,-0.077,0.093,-0.0077,0.013,-0.0013,-0.0058,8.4e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.0051,0.32,0.33,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
337 33490000,-0.27,0.016,-0.0086,0.96,0.02,0.099,-0.076,0.095,-0.0019,0.0028,-0.0013,-0.0058,5.4e-05,0.075,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.33,0.34,0.03,2.7e-07,2.4e-07,2.1e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33490000,-0.27,0.016,-0.0086,0.96,0.019,0.1,-0.076,0.095,0.0022,0.0031,-0.0013,-0.0058,9.3e-05,0.073,-0.037,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.33,0.34,0.03,2.7e-07,2.4e-07,2.3e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
338 33590000,-0.27,0.016,-0.0084,0.96,0.023,0.096,-0.073,0.094,-0.015,-0.0051,-0.0013,-0.0058,4.8e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.33,0.34,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33590000,-0.27,0.016,-0.0084,0.96,0.023,0.098,-0.073,0.095,-0.012,-0.0048,-0.0013,-0.0058,8.5e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.33,0.34,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
339 33690000,-0.27,0.016,-0.0084,0.96,0.026,0.099,-0.074,0.095,-0.0061,-0.013,-0.0013,-0.0058,5.3e-05,0.075,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.34,0.35,0.03,2.7e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33690000,-0.27,0.016,-0.0084,0.96,0.026,0.1,-0.074,0.096,-0.002,-0.013,-0.0013,-0.0058,9e-05,0.073,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.34,0.35,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
340 33790000,-0.27,0.016,-0.0083,0.96,0.029,0.096,-0.068,0.092,-0.02,-0.02,-0.0013,-0.0058,3.3e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.34,0.35,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33790000,-0.27,0.016,-0.0083,0.96,0.028,0.098,-0.068,0.092,-0.016,-0.02,-0.0013,-0.0058,6.7e-05,0.074,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.34,0.35,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
341 33890000,-0.27,0.016,-0.0083,0.96,0.033,0.097,-0.068,0.095,-0.01,-0.027,-0.0013,-0.0058,4.8e-05,0.076,-0.036,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33890000,-0.27,0.016,-0.0083,0.96,0.033,0.1,-0.068,0.096,-0.0064,-0.026,-0.0013,-0.0058,8.3e-05,0.074,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.35,0.36,0.03,2.7e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
342 33990000,-0.27,0.016,-0.0082,0.96,0.036,0.095,-0.064,0.094,-0.019,-0.03,-0.0013,-0.0057,3.3e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.02,0.023,0.005,0.35,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 33990000,-0.27,0.016,-0.0082,0.96,0.035,0.097,-0.064,0.094,-0.015,-0.03,-0.0013,-0.0058,6.6e-05,0.075,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.043,0.02,0.023,0.005,0.35,0.36,0.03,2.6e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
343 34090000,-0.27,0.016,-0.0081,0.96,0.039,0.1,-0.063,0.097,-0.0094,-0.035,-0.0013,-0.0057,3.6e-05,0.076,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,2e-06,0.029,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 34090000,-0.27,0.016,-0.0081,0.96,0.039,0.1,-0.063,0.097,-0.0055,-0.034,-0.0013,-0.0058,7e-05,0.075,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.043,0.021,0.024,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,2.2e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
344 34190000,-0.27,0.016,-0.0081,0.96,0.04,0.096,-0.06,0.092,-0.021,-0.038,-0.0013,-0.0057,3e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.081,-0.035,-0.067,0,0,0.00037,0.00034,0.043,0.02,0.022,0.005,0.36,0.36,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 34190000,-0.27,0.016,-0.0081,0.96,0.04,0.098,-0.06,0.092,-0.018,-0.038,-0.0013,-0.0057,6.1e-05,0.075,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.36,0.37,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
345 34290000,-0.26,0.016,-0.0079,0.96,0.041,0.1,-0.059,0.096,-0.012,-0.044,-0.0013,-0.0057,4e-05,0.077,-0.035,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.066,0,0,0.00037,0.00034,0.043,0.021,0.023,0.005,0.37,0.38,0.03,2.6e-07,2.4e-07,2e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00063,0.0012,1,1 34290000,-0.27,0.016,-0.0079,0.96,0.041,0.1,-0.059,0.096,-0.0076,-0.044,-0.0013,-0.0057,7.2e-05,0.075,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00037,0.00034,0.042,0.021,0.023,0.005,0.37,0.38,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
346 34390000,-0.26,0.016,-0.0078,0.96,0.043,0.095,-0.054,0.091,-0.023,-0.048,-0.0013,-0.0057,3e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.02,0.022,0.005,0.37,0.37,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.4e-05,0.0012,0.0011,0.00062,0.0012,1,1 34390000,-0.27,0.016,-0.0078,0.96,0.042,0.097,-0.054,0.092,-0.02,-0.048,-0.0013,-0.0057,6e-05,0.076,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.37,0.37,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
347 34490000,-0.26,0.016,-0.0079,0.96,0.046,0.099,-0.052,0.095,-0.014,-0.051,-0.0013,-0.0057,4.2e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00037,0.00034,0.042,0.021,0.023,0.005,0.38,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 34490000,-0.27,0.016,-0.0079,0.96,0.045,0.1,-0.052,0.095,-0.0099,-0.05,-0.0013,-0.0057,7.3e-05,0.076,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00034,0.042,0.021,0.023,0.005,0.38,0.39,0.03,2.6e-07,2.4e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
348 34590000,-0.26,0.016,-0.0078,0.96,0.049,0.092,0.74,0.09,-0.028,-0.022,-0.0013,-0.0057,3e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.005,0.38,0.38,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 34590000,-0.27,0.016,-0.0078,0.96,0.049,0.094,0.74,0.09,-0.024,-0.022,-0.0013,-0.0057,5.9e-05,0.076,-0.033,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.019,0.022,0.005,0.38,0.38,0.03,2.6e-07,2.3e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
349 34690000,-0.26,0.015,-0.0078,0.96,0.058,0.092,1.7,0.095,-0.019,0.097,-0.0013,-0.0057,3.5e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.022,0.0051,0.39,0.4,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 34690000,-0.27,0.015,-0.0078,0.96,0.058,0.095,1.7,0.096,-0.015,0.097,-0.0013,-0.0057,6.5e-05,0.076,-0.033,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.02,0.022,0.0051,0.39,0.4,0.03,2.6e-07,2.3e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
350 34790000,-0.26,0.015,-0.0077,0.96,0.063,0.086,2.7,0.088,-0.032,0.28,-0.0013,-0.0057,2.6e-05,0.078,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.02,0.021,0.005,0.39,0.39,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 34790000,-0.27,0.015,-0.0077,0.96,0.062,0.088,2.7,0.089,-0.028,0.28,-0.0013,-0.0057,5.4e-05,0.077,-0.034,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.02,0.021,0.005,0.39,0.39,0.03,2.6e-07,2.3e-07,2.1e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1
351 34890000,-0.26,0.015,-0.0077,0.96,0.071,0.086,3.7,0.094,-0.023,0.57,-0.0013,-0.0057,3.2e-05,0.079,-0.034,-0.12,-0.11,-0.024,0.5,0.08,-0.035,-0.067,0,0,0.00036,0.00034,0.042,0.021,0.023,0.005,0.4,0.41,0.03,2.6e-07,2.4e-07,1.9e-06,0.028,0.028,0.00011,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1 34890000,-0.27,0.015,-0.0077,0.96,0.071,0.089,3.7,0.095,-0.02,0.57,-0.0013,-0.0057,6e-05,0.077,-0.033,-0.12,-0.11,-0.024,0.5,0.081,-0.034,-0.067,0,0,0.00036,0.00033,0.042,0.021,0.023,0.005,0.4,0.41,0.03,2.6e-07,2.3e-07,2.1e-06,0.028,0.028,0.0001,0.0011,5.3e-05,0.0012,0.0011,0.00062,0.0012,1,1

View File

@ -314,13 +314,3 @@ float EkfWrapper::getMagHeadingNoise() const
{
return _ekf_params->mag_heading_noise;
}
void EkfWrapper::enableGyroBiasEstimation()
{
_ekf_params->imu_ctrl |= static_cast<int32_t>(ImuCtrl::GyroBias);
}
void EkfWrapper::disableGyroBiasEstimation()
{
_ekf_params->imu_ctrl &= ~static_cast<int32_t>(ImuCtrl::GyroBias);
}

View File

@ -128,9 +128,6 @@ public:
float getMagHeadingNoise() const;
void enableGyroBiasEstimation();
void disableGyroBiasEstimation();
private:
std::shared_ptr<Ekf> _ekf;

View File

@ -81,10 +81,9 @@ public:
void EkfGpsHeadingTest::runConvergenceScenario(float yaw_offset_rad, float antenna_offset_rad)
{
// GIVEN: an initial GPS yaw, not aligned with the current one
// The yaw antenna offset has already been corrected in the driver
float gps_heading = matrix::wrap_pi(_ekf_wrapper.getYawAngle());
float gps_heading = matrix::wrap_pi(_ekf_wrapper.getYawAngle() + yaw_offset_rad);
_sensor_simulator._gps.setYaw(gps_heading); // used to remove the correction to fuse the real measurement
_sensor_simulator._gps.setYaw(gps_heading);
_sensor_simulator._gps.setYawOffset(antenna_offset_rad);
// WHEN: the GPS yaw fusion is activated
@ -92,7 +91,7 @@ void EkfGpsHeadingTest::runConvergenceScenario(float yaw_offset_rad, float anten
_sensor_simulator.runSeconds(5);
// THEN: the estimate is reset and stays close to the measurement
checkConvergence(gps_heading, 0.01f);
checkConvergence(gps_heading, 0.05f);
}
void EkfGpsHeadingTest::checkConvergence(float truth, float tolerance_deg)

View File

@ -191,32 +191,6 @@ TEST_F(EkfInitializationTest, initializeWithZeroTiltNotAtRest)
learningCorrectAccelBias();
}
TEST_F(EkfInitializationTest, initializeWithTiltNoGyroBiasEstimate)
{
const float pitch = math::radians(30.0f);
const float roll = math::radians(-20.0f);
const Eulerf euler_angles_sim(roll, pitch, 0.0f);
const Quatf quat_sim(euler_angles_sim);
_ekf_wrapper.disableGyroBiasEstimation();
_sensor_simulator.simulateOrientation(quat_sim);
_sensor_simulator.runSeconds(_init_tilt_period);
EXPECT_TRUE(_ekf->control_status_flags().tilt_align);
initializedOrienationIsMatchingGroundTruth(quat_sim);
quaternionVarianceBigEnoughAfterOrientationInitialization(0.00001f);
velocityAndPositionCloseToZero();
positionVarianceBigEnoughAfterOrientationInitialization(0.00001f); // Fake position fusion obs var when at rest sq(0.5f)
velocityVarianceBigEnoughAfterOrientationInitialization(0.0001f);
_sensor_simulator.runSeconds(1.f);
learningCorrectAccelBias();
}
TEST_F(EkfInitializationTest, gyroBias)
{
// GIVEN: a healthy filter
@ -346,7 +320,7 @@ TEST_F(EkfInitializationTest, initializeWithTiltNotAtRest)
_ekf->set_vehicle_at_rest(false);
_sensor_simulator.simulateOrientation(quat_sim);
//_sensor_simulator.runSeconds(_init_tilt_period);
_sensor_simulator.runSeconds(10);
_sensor_simulator.runSeconds(7);
EXPECT_TRUE(_ekf->control_status_flags().tilt_align);

View File

@ -35,16 +35,60 @@
#include "EKF/ekf.h"
#include "test_helper/comparison_helper.h"
#include "../EKF/python/ekf_derivation/generated/compute_yaw_innov_var_and_h.h"
#include "../EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h.h"
#include "../EKF/python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h_alternate.h"
#include "../EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h.h"
#include "../EKF/python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h_alternate.h"
using namespace matrix;
Vector3f getRotVarNed(const Quatf &q, const SquareMatrixState &P)
TEST(YawFusionGenerated, singularityYawEquivalence)
{
constexpr auto S = State::quat_nominal;
matrix::SquareMatrix3f rot_cov_body = P.slice<S.dof, S.dof>(S.idx, S.idx);
auto R_to_earth = Dcmf(q);
return matrix::SquareMatrix<float, State::quat_nominal.dof>(R_to_earth * rot_cov_body * R_to_earth.T()).diag();
// GIVEN: an attitude that should give a singularity when transforming the
// rotation matrix to Euler yaw
StateSample state{};
state.quat_nominal = Eulerf(M_PI_F, 0.f, M_PI_F);
const float R = sq(radians(10.f));
SquareMatrixState P = createRandomCovarianceMatrix();
VectorState H_a;
VectorState H_b;
float innov_var_a;
float innov_var_b;
// WHEN: computing the innovation variance and H using two different
// alternate forms (one is singular at pi/2 and the other one at 0)
sym::ComputeYaw321InnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var_a, &H_a);
sym::ComputeYaw321InnovVarAndHAlternate(state.vector(), P, R, FLT_EPSILON, &innov_var_b, &H_b);
// THEN: Even at the singularity point, the result is still correct, thanks to epsilon
EXPECT_TRUE(isEqual(H_a, H_b));
EXPECT_NEAR(innov_var_a, innov_var_b, 1e-5f);
EXPECT_TRUE(innov_var_a < 50.f && innov_var_a > R) << "innov_var = " << innov_var_a;
}
TEST(YawFusionGenerated, gimbalLock321vs312)
{
// GIVEN: an attitude at gimbal lock position
StateSample state{};
state.quat_nominal = Eulerf(0.f, -M_PI_F / 2.f, M_PI_F);
const float R = sq(radians(10.f));
SquareMatrixState P = createRandomCovarianceMatrix();
VectorState H_321;
VectorState H_312;
float innov_var_321;
float innov_var_312;
sym::ComputeYaw321InnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var_321, &H_321);
sym::ComputeYaw312InnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var_312, &H_312);
// THEN: both computation are not equivalent, 321 is undefined but 312 is valid
EXPECT_FALSE(isEqual(H_321, H_312));
EXPECT_GT(fabsf(innov_var_321 - innov_var_312), 1e6f);
EXPECT_TRUE(innov_var_312 < 50.f && innov_var_312 > R) << "innov_var = " << innov_var_312;
}
TEST(YawFusionGenerated, positiveVarianceAllOrientations)
@ -55,14 +99,19 @@ TEST(YawFusionGenerated, positiveVarianceAllOrientations)
VectorState H;
float innov_var;
// GIVEN: all orientations
for (float yaw = 0.f; yaw < 2.f * M_PI_F; yaw += M_PI_F / 4.f) {
for (float pitch = 0.f; pitch < 2.f * M_PI_F; pitch += M_PI_F / 4.f) {
for (float roll = 0.f; roll < 2.f * M_PI_F; roll += M_PI_F / 4.f) {
// GIVEN: all orientations (90 deg steps)
for (float yaw = 0.f; yaw < 2.f * M_PI_F; yaw += M_PI_F / 2.f) {
for (float pitch = 0.f; pitch < 2.f * M_PI_F; pitch += M_PI_F / 2.f) {
for (float roll = 0.f; roll < 2.f * M_PI_F; roll += M_PI_F / 2.f) {
StateSample state{};
state.quat_nominal = Eulerf(roll, pitch, yaw);
sym::ComputeYawInnovVarAndH(state.vector(), P, R, &innov_var, &H);
if (shouldUse321RotationSequence(Dcmf(state.quat_nominal))) {
sym::ComputeYaw321InnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var, &H);
} else {
sym::ComputeYaw312InnovVarAndH(state.vector(), P, R, FLT_EPSILON, &innov_var, &H);
}
// THEN: the innovation variance must be positive and finite
EXPECT_TRUE(innov_var < 100.f && innov_var > R)
@ -70,18 +119,6 @@ TEST(YawFusionGenerated, positiveVarianceAllOrientations)
<< " pitch = " << degrees(pitch)
<< " roll = " << degrees(roll)
<< " innov_var = " << innov_var;
// AND: it should be the same as the "true" innovation variance obtained by summing
// the Z rotation variance in NED and the measurement variance
const float innov_var_true = getRotVarNed(state.quat_nominal, P)(2) + R;
EXPECT_NEAR(innov_var, innov_var_true, 1e-5f)
<< "yaw = " << degrees(yaw)
<< " pitch = " << degrees(pitch)
<< " roll = " << degrees(roll)
<< " innov_var = " << innov_var
<< " innov_var_true = " << innov_var_true;
EXPECT_TRUE(H.isAllFinite());
}
}
}

View File

@ -30,6 +30,7 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
add_subdirectory(fw_trim)
px4_add_module(
MODULE modules__fw_rate_control
@ -38,6 +39,7 @@ px4_add_module(
FixedwingRateControl.cpp
FixedwingRateControl.hpp
DEPENDS
FwTrim
px4_work_queue
RateControl
SlewRate

View File

@ -37,7 +37,6 @@ using namespace time_literals;
using namespace matrix;
using math::constrain;
using math::interpolate;
using math::radians;
FixedwingRateControl::FixedwingRateControl(bool vtol) :
@ -54,6 +53,7 @@ FixedwingRateControl::FixedwingRateControl(bool vtol) :
parameters_update();
_rate_ctrl_status_pub.advertise();
_trim_slew.setSlewRate(Vector3f(0.01f, 0.01f, 0.01f));
}
FixedwingRateControl::~FixedwingRateControl()
@ -96,6 +96,12 @@ FixedwingRateControl::parameters_update()
return PX4_OK;
}
void
FixedwingRateControl::save_params()
{
_trim.saveParams();
}
void
FixedwingRateControl::vehicle_manual_poll()
{
@ -127,13 +133,14 @@ FixedwingRateControl::vehicle_manual_poll()
} else {
// Manual/direct control, filled in FW-frame. Note that setpoints will get transformed to body frame prior publishing.
const Vector3f trim = _trim_slew.getState();
_vehicle_torque_setpoint.xyz[0] = math::constrain(_manual_control_setpoint.roll * _param_fw_man_r_sc.get() +
_param_trim_roll.get(), -1.f, 1.f);
trim(0), -1.f, 1.f);
_vehicle_torque_setpoint.xyz[1] = math::constrain(-_manual_control_setpoint.pitch * _param_fw_man_p_sc.get() +
_param_trim_pitch.get(), -1.f, 1.f);
trim(1), -1.f, 1.f);
_vehicle_torque_setpoint.xyz[2] = math::constrain(_manual_control_setpoint.yaw * _param_fw_man_y_sc.get() +
_param_trim_yaw.get(), -1.f, 1.f);
trim(2), -1.f, 1.f);
_vehicle_thrust_setpoint.xyz[0] = math::constrain((_manual_control_setpoint.throttle + 1.f) * .5f, 0.f, 1.f);
}
@ -256,7 +263,14 @@ void FixedwingRateControl::Run()
const bool is_fixed_wing = _vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING;
_in_fw_or_transition_wo_tailsitter_transition = is_fixed_wing || is_in_transition_except_tailsitter;
_vehicle_control_mode_sub.update(&_vcontrol_mode);
{
const bool armed_prev = _vcontrol_mode.flag_armed;
_vehicle_control_mode_sub.update(&_vcontrol_mode);
if (!_vcontrol_mode.flag_armed && armed_prev) {
save_params();
}
}
vehicle_land_detected_poll();
@ -321,78 +335,56 @@ void FixedwingRateControl::Run()
}
}
/* bi-linear interpolation over airspeed for actuator trim scheduling */
Vector3f trim(_param_trim_roll.get(), _param_trim_pitch.get(), _param_trim_yaw.get());
_trim.setAirspeed(airspeed);
_trim_slew.update(_trim.getTrim(), dt);
if (airspeed < _param_fw_airspd_trim.get()) {
trim(0) += interpolate(airspeed, _param_fw_airspd_min.get(), _param_fw_airspd_trim.get(),
_param_fw_dtrim_r_vmin.get(),
0.0f);
trim(1) += interpolate(airspeed, _param_fw_airspd_min.get(), _param_fw_airspd_trim.get(),
_param_fw_dtrim_p_vmin.get(),
0.0f);
trim(2) += interpolate(airspeed, _param_fw_airspd_min.get(), _param_fw_airspd_trim.get(),
_param_fw_dtrim_y_vmin.get(),
0.0f);
_rates_sp_sub.update(&_rates_sp);
} else {
trim(0) += interpolate(airspeed, _param_fw_airspd_trim.get(), _param_fw_airspd_max.get(), 0.0f,
_param_fw_dtrim_r_vmax.get());
trim(1) += interpolate(airspeed, _param_fw_airspd_trim.get(), _param_fw_airspd_max.get(), 0.0f,
_param_fw_dtrim_p_vmax.get());
trim(2) += interpolate(airspeed, _param_fw_airspd_trim.get(), _param_fw_airspd_max.get(), 0.0f,
_param_fw_dtrim_y_vmax.get());
Vector3f body_rates_setpoint = Vector3f(_rates_sp.roll, _rates_sp.pitch, _rates_sp.yaw);
// Tailsitter: rotate setpoint from hover to fixed-wing frame (controller is in fixed-wing frame, interface in hover)
if (_vehicle_status.is_vtol_tailsitter) {
body_rates_setpoint = Vector3f(-_rates_sp.yaw, _rates_sp.pitch, _rates_sp.roll);
}
if (_vcontrol_mode.flag_control_rates_enabled) {
_rates_sp_sub.update(&_rates_sp);
// Run attitude RATE controllers which need the desired attitudes from above, add trim.
const Vector3f angular_acceleration_setpoint = _rate_control.update(rates, body_rates_setpoint, angular_accel, dt,
_landed);
Vector3f body_rates_setpoint = Vector3f(_rates_sp.roll, _rates_sp.pitch, _rates_sp.yaw);
const Vector3f gain_ff(_param_fw_rr_ff.get(), _param_fw_pr_ff.get(), _param_fw_yr_ff.get());
const Vector3f feedforward = gain_ff.emult(body_rates_setpoint) * _airspeed_scaling;
// Tailsitter: rotate setpoint from hover to fixed-wing frame (controller is in fixed-wing frame, interface in hover)
if (_vehicle_status.is_vtol_tailsitter) {
body_rates_setpoint = Vector3f(-_rates_sp.yaw, _rates_sp.pitch, _rates_sp.roll);
}
Vector3f control_u = angular_acceleration_setpoint * _airspeed_scaling * _airspeed_scaling + feedforward;
// Run attitude RATE controllers which need the desired attitudes from above, add trim.
const Vector3f angular_acceleration_setpoint = _rate_control.update(rates, body_rates_setpoint, angular_accel, dt,
_landed);
// Special case yaw in Acro: if the parameter FW_ACRO_YAW_CTL is not set then don't control yaw
if (!_vcontrol_mode.flag_control_attitude_enabled && !_param_fw_acro_yaw_en.get()) {
control_u(2) = _manual_control_setpoint.yaw * _param_fw_man_y_sc.get();
_rate_control.resetIntegral(2);
}
const Vector3f gain_ff(_param_fw_rr_ff.get(), _param_fw_pr_ff.get(), _param_fw_yr_ff.get());
const Vector3f feedforward = gain_ff.emult(body_rates_setpoint) * _airspeed_scaling;
if (control_u.isAllFinite()) {
matrix::constrain(control_u + _trim_slew.getState(), -1.f, 1.f).copyTo(_vehicle_torque_setpoint.xyz);
Vector3f control_u = angular_acceleration_setpoint * _airspeed_scaling * _airspeed_scaling + feedforward;
} else {
_rate_control.resetIntegral();
_trim_slew.getState().copyTo(_vehicle_torque_setpoint.xyz);
}
// Special case yaw in Acro: if the parameter FW_ACRO_YAW_CTL is not set then don't control yaw
if (!_vcontrol_mode.flag_control_attitude_enabled && !_param_fw_acro_yaw_en.get()) {
control_u(2) = _manual_control_setpoint.yaw * _param_fw_man_y_sc.get();
_rate_control.resetIntegral(2);
}
/* throttle passed through if it is finite */
_vehicle_thrust_setpoint.xyz[0] = PX4_ISFINITE(_rates_sp.thrust_body[0]) ? _rates_sp.thrust_body[0] : 0.0f;
if (control_u.isAllFinite()) {
matrix::constrain(control_u + trim, -1.f, 1.f).copyTo(_vehicle_torque_setpoint.xyz);
/* scale effort by battery status */
if (_param_fw_bat_scale_en.get() && _vehicle_thrust_setpoint.xyz[0] > 0.1f) {
} else {
_rate_control.resetIntegral();
trim.copyTo(_vehicle_torque_setpoint.xyz);
}
if (_battery_status_sub.updated()) {
battery_status_s battery_status{};
/* throttle passed through if it is finite */
_vehicle_thrust_setpoint.xyz[0] = PX4_ISFINITE(_rates_sp.thrust_body[0]) ? _rates_sp.thrust_body[0] : 0.0f;
/* scale effort by battery status */
if (_param_fw_bat_scale_en.get() && _vehicle_thrust_setpoint.xyz[0] > 0.1f) {
if (_battery_status_sub.updated()) {
battery_status_s battery_status{};
if (_battery_status_sub.copy(&battery_status) && battery_status.connected && battery_status.scale > 0.f) {
_battery_scale = battery_status.scale;
}
if (_battery_status_sub.copy(&battery_status) && battery_status.connected && battery_status.scale > 0.f) {
_battery_scale = battery_status.scale;
}
_vehicle_thrust_setpoint.xyz[0] *= _battery_scale;
}
_vehicle_thrust_setpoint.xyz[0] *= _battery_scale;
}
// publish rate controller status
@ -405,6 +397,7 @@ void FixedwingRateControl::Run()
} else {
// full manual
_rate_control.resetIntegral();
_trim.reset();
}
// Add feed-forward from roll control output to yaw control output
@ -432,6 +425,8 @@ void FixedwingRateControl::Run()
_vehicle_torque_setpoint.timestamp_sample = angular_velocity.timestamp_sample;
_vehicle_torque_setpoint_pub.publish(_vehicle_torque_setpoint);
}
_trim.updateAutoTrim(Vector3f(_vehicle_torque_setpoint.xyz), dt);
}
updateActuatorControlsStatus(dt);

View File

@ -69,6 +69,8 @@
#include <uORB/topics/vehicle_thrust_setpoint.h>
#include <uORB/topics/vehicle_torque_setpoint.h>
#include "fw_trim/FwTrim.hpp"
using matrix::Eulerf;
using matrix::Quatf;
@ -170,13 +172,6 @@ private:
(ParamBool<px4::params::FW_BAT_SCALE_EN>) _param_fw_bat_scale_en,
(ParamFloat<px4::params::FW_DTRIM_P_VMAX>) _param_fw_dtrim_p_vmax,
(ParamFloat<px4::params::FW_DTRIM_P_VMIN>) _param_fw_dtrim_p_vmin,
(ParamFloat<px4::params::FW_DTRIM_R_VMAX>) _param_fw_dtrim_r_vmax,
(ParamFloat<px4::params::FW_DTRIM_R_VMIN>) _param_fw_dtrim_r_vmin,
(ParamFloat<px4::params::FW_DTRIM_Y_VMAX>) _param_fw_dtrim_y_vmax,
(ParamFloat<px4::params::FW_DTRIM_Y_VMIN>) _param_fw_dtrim_y_vmin,
(ParamFloat<px4::params::FW_MAN_P_SC>) _param_fw_man_p_sc,
(ParamFloat<px4::params::FW_MAN_R_SC>) _param_fw_man_r_sc,
(ParamFloat<px4::params::FW_MAN_Y_SC>) _param_fw_man_y_sc,
@ -200,15 +195,14 @@ private:
(ParamFloat<px4::params::FW_YR_P>) _param_fw_yr_p,
(ParamFloat<px4::params::FW_YR_D>) _param_fw_yr_d,
(ParamFloat<px4::params::TRIM_PITCH>) _param_trim_pitch,
(ParamFloat<px4::params::TRIM_ROLL>) _param_trim_roll,
(ParamFloat<px4::params::TRIM_YAW>) _param_trim_yaw,
(ParamInt<px4::params::FW_SPOILERS_MAN>) _param_fw_spoilers_man
)
RateControl _rate_control; ///< class for rate control calculations
FwTrim _trim{this};
SlewRate<matrix::Vector3f> _trim_slew{}; ///< prevents large trim changes
void updateActuatorControlsStatus(float dt);
/**
@ -216,6 +210,8 @@ private:
*/
int parameters_update();
void save_params();
void vehicle_manual_poll();
void vehicle_land_detected_poll();

View File

@ -295,6 +295,21 @@ PARAM_DEFINE_INT32(FW_BAT_SCALE_EN, 0);
*/
PARAM_DEFINE_INT32(FW_ARSP_SCALE_EN, 1);
/**
* Auto-Trim mode
*
* In calibration mode, the estimated trim is used to set the TRIM_ROLL/PITCH/YAW
* parameters after landing. The parameter is then changed to continuous mode.
* In continuous mode, part of the auto-trim estimated
* during flight is used to update the exitsting trim.
*
* @group FW Rate Control
* @value 0 Disabled
* @value 1 Calibration
* @value 2 Continuous
*/
PARAM_DEFINE_INT32(FW_ATRIM_MODE, 1);
/**
* Roll trim increment at minimum airspeed
*

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (c) 2024 ModalAI, Inc. All rights reserved.
# Copyright (c) 2024 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
@ -30,5 +30,10 @@
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_library(FwTrim
FwTrim.cpp
FwAutoTrim.cpp
)
include_directories(${PX4_BOARD_DIR}/libfc-sensor-api/inc)
# target_link_libraries(FwTrim)
target_include_directories(FwTrim PUBLIC ${CMAKE_CURRENT_SOURCE_DIR})

View File

@ -0,0 +1,203 @@
/****************************************************************************
*
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "FwAutoTrim.hpp"
#include <mathlib/mathlib.h>
using namespace time_literals;
using matrix::Vector3f;
FwAutoTrim::FwAutoTrim(ModuleParams *parent) :
ModuleParams(parent)
{
_auto_trim_status_pub.advertise();
updateParams();
}
FwAutoTrim::~FwAutoTrim()
{
perf_free(_cycle_perf);
}
void FwAutoTrim::updateParams()
{
ModuleParams::updateParams();
}
void FwAutoTrim::reset()
{
_state = state::idle;
_trim_estimate.reset();
_trim_test.reset();
_trim_validated.zero();
}
void FwAutoTrim::update(const Vector3f &torque_sp, const float dt)
{
if (_vehicle_land_detected_sub.updated()) {
vehicle_land_detected_s vehicle_land_detected;
if (_vehicle_land_detected_sub.copy(&vehicle_land_detected)) {
_landed = vehicle_land_detected.landed;
}
}
perf_begin(_cycle_perf);
if (_vehicle_status_sub.updated()) {
vehicle_status_s vehicle_status;
if (_vehicle_status_sub.copy(&vehicle_status)) {
_armed = (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED);
_fixed_wing = (vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_FIXED_WING);
_tailsitter = vehicle_status.is_vtol_tailsitter;
}
}
if (_airspeed_validated_sub.updated()) {
airspeed_validated_s airspeed_validated;
if (_airspeed_validated_sub.copy(&airspeed_validated)) {
if (PX4_ISFINITE(airspeed_validated.calibrated_airspeed_m_s)) {
_calibrated_airspeed_m_s = airspeed_validated.calibrated_airspeed_m_s;
} else {
_calibrated_airspeed_m_s = airspeed_validated.calibrated_ground_minus_wind_m_s;
}
}
}
if (_vehicle_attitude_sub.updated()) {
vehicle_attitude_s vehicle_attitude;
if (_vehicle_attitude_sub.copy(&vehicle_attitude)) {
const Vector3f earth_z_in_body_frame = matrix::Quatf(vehicle_attitude.q).rotateVectorInverse(Vector3f(0.f, 0.f, 1.f));
_cos_tilt = _tailsitter ? earth_z_in_body_frame(0) : earth_z_in_body_frame(2);
}
}
const hrt_abstime now = hrt_absolute_time();
const bool run_auto_trim = _fixed_wing
&& _armed
&& !_landed
&& (dt > 0.001f) && (dt < 0.1f)
&& torque_sp.isAllFinite()
&& ((_calibrated_airspeed_m_s >= _param_fw_airspd_min.get() && _calibrated_airspeed_m_s <= _param_fw_airspd_max.get())
|| (!PX4_ISFINITE(_calibrated_airspeed_m_s) && (_param_sys_has_num_aspd.get() == 0)))
&& _cos_tilt > cosf(math::radians(_kTiltMaxDeg));
if (run_auto_trim) {
switch (_state) {
default:
// fallthrough
case state::idle:
_trim_estimate.reset();
_trim_test.reset();
_state = state::sampling;
_state_start_time = now;
break;
case state::sampling:
// Average the torque setpoint over a long period of time
_trim_estimate.update(torque_sp);
if ((now - _state_start_time) > 5_s) {
_state = state::sampling_test;
_state_start_time = now;
}
break;
case state::sampling_test:
// Average a smaller amount of data to validate the trim estimate
_trim_test.update(torque_sp);
if ((now - _state_start_time) > 2_s) {
_state = state::verification;
_state_start_time = now;
}
break;
case state::verification: {
// Perform a statistical test between the estimated and test data
const float gate = 5.f;
const Vector3f innovation = _trim_test.mean() - _trim_estimate.mean();
const Vector3f innovation_variance = _trim_test.variance() + _trim_estimate.variance();
const float test_ratio = Vector3f(innovation.edivide(innovation_variance * gate * gate)) * innovation;
if ((test_ratio <= 1.f) && !innovation.longerThan(0.05f)) {
_trim_validated = _trim_estimate.mean();
_state = state::complete;
_state_start_time = now;
} else {
_state = state::fail;
}
} break;
case state::complete:
//TODO: depending on param, stay or restart
_state = state::idle;
break;
}
} else {
_state = state::fail;
}
publishStatus(now);
perf_end(_cycle_perf);
}
void FwAutoTrim::publishStatus(const hrt_abstime now)
{
auto_trim_status_s status_msg{};
_trim_validated.copyTo(status_msg.trim_validated);
_trim_estimate.mean().copyTo(status_msg.trim_estimate);
_trim_estimate.variance().copyTo(status_msg.trim_estimate_var);
_trim_test.mean().copyTo(status_msg.trim_test);
_trim_test.variance().copyTo(status_msg.trim_test_var);
status_msg.state = static_cast<int>(_state);
status_msg.timestamp = now;
status_msg.timestamp_sample = now;
_auto_trim_status_pub.publish(status_msg);
}

View File

@ -0,0 +1,111 @@
/****************************************************************************
*
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
#include <drivers/drv_hrt.h>
#include <lib/hysteresis/hysteresis.h>
#include <lib/perf/perf_counter.h>
#include <lib/mathlib/math/WelfordMeanVector.hpp>
#include <px4_platform_common/defines.h>
#include <px4_platform_common/module.h>
#include <px4_platform_common/module_params.h>
#include <px4_platform_common/posix.h>
#include <uORB/Publication.hpp>
#include <uORB/Subscription.hpp>
#include <uORB/topics/airspeed_validated.h>
#include <uORB/topics/auto_trim_status.h>
#include <uORB/topics/parameter_update.h>
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_land_detected.h>
#include <uORB/topics/vehicle_status.h>
using namespace time_literals;
class FwAutoTrim : public ModuleParams
{
public:
FwAutoTrim(ModuleParams *parent);
~FwAutoTrim();
void reset();
void update(const matrix::Vector3f &torque_sp, float dt);
const matrix::Vector3f &getTrim() const { return _trim_validated; }
protected:
void updateParams() override;
private:
void publishStatus(const hrt_abstime now);
uORB::Publication<auto_trim_status_s> _auto_trim_status_pub{ORB_ID(auto_trim_status)};
uORB::Subscription _vehicle_land_detected_sub{ORB_ID(vehicle_land_detected)};
uORB::Subscription _airspeed_validated_sub{ORB_ID(airspeed_validated)};
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
uORB::Subscription _vehicle_attitude_sub{ORB_ID(vehicle_attitude)};
enum class state {
idle = auto_trim_status_s::STATE_IDLE,
sampling = auto_trim_status_s::STATE_SAMPLING,
sampling_test = auto_trim_status_s::STATE_SAMPLING_TEST,
verification = auto_trim_status_s::STATE_VERIFICATION,
complete = auto_trim_status_s::STATE_COMPLETE,
fail = auto_trim_status_s::STATE_FAIL,
} _state{state::idle};
hrt_abstime _state_start_time{0};
bool _armed{false};
bool _landed{false};
bool _fixed_wing{false};
bool _tailsitter{false};
float _calibrated_airspeed_m_s{0.f};
float _cos_tilt{0.f};
math::WelfordMeanVector<float, 3> _trim_estimate{};
math::WelfordMeanVector<float, 3> _trim_test{};
matrix::Vector3f _trim_validated{};
perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, "[AutoTrim] cycle time")};
DEFINE_PARAMETERS(
(ParamInt<px4::params::SYS_HAS_NUM_ASPD>) _param_sys_has_num_aspd,
(ParamFloat<px4::params::FW_AIRSPD_MIN>) _param_fw_airspd_min,
(ParamFloat<px4::params::FW_AIRSPD_MAX>) _param_fw_airspd_max
)
static constexpr float _kTiltMaxDeg = 10.f;
};

View File

@ -0,0 +1,150 @@
/****************************************************************************
*
* Copyright (c) 2024 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include "FwTrim.hpp"
#include <mathlib/mathlib.h>
using namespace time_literals;
using matrix::Vector3f;
using math::interpolate;
FwTrim::FwTrim(ModuleParams *parent) :
ModuleParams(parent)
{
updateParams();
_airspeed = _param_fw_airspd_trim.get();
}
void FwTrim::updateParams()
{
ModuleParams::updateParams();
updateParameterizedTrim();
}
void FwTrim::saveParams()
{
const Vector3f autotrim = _auto_trim.getTrim();
bool updated = false;
const Vector3f trim_prev(_param_trim_roll.get(), _param_trim_pitch.get(), _param_trim_yaw.get());
if (_param_fw_atrim_mode.get() == static_cast<int32_t>(AutoTrimMode::kCalibration)) {
// Replace the current trim with the one identified during auto-trim
updated |= _param_trim_roll.commit_no_notification(_param_trim_roll.get() + autotrim(0));
updated |= _param_trim_pitch.commit_no_notification(_param_trim_pitch.get() + autotrim(1));
updated |= _param_trim_yaw.commit_no_notification(_param_trim_yaw.get() + autotrim(2));
if (updated) {
_param_fw_atrim_mode.set(static_cast<int32_t>(AutoTrimMode::kContinuous));
_param_fw_atrim_mode.commit();
}
} else if (_param_fw_atrim_mode.get() == static_cast<int32_t>(AutoTrimMode::kContinuous)) {
// In continuous trim mode, limit the amount of trim that can be applied back to the parameter
const Vector3f constrained_autotrim = matrix::constrain(autotrim, -0.05f, 0.05f);
updated |= _param_trim_roll.commit_no_notification(_param_trim_roll.get() + constrained_autotrim(0));
updated |= _param_trim_pitch.commit_no_notification(_param_trim_pitch.get() + constrained_autotrim(1));
updated |= _param_trim_yaw.commit_no_notification(_param_trim_yaw.get() + constrained_autotrim(2));
if (updated) {
_param_trim_yaw.commit();
}
} else {
// nothing to do
}
if (updated) {
const Vector3f trim_new(_param_trim_roll.get(), _param_trim_pitch.get(), _param_trim_yaw.get());
PX4_INFO("Trim offset committed: [%.3f %.3f %.3f]->[%.3f %.3f %.3f]",
(double)trim_prev(0), (double)trim_prev(1), (double)trim_prev(2),
(double)trim_new(0), (double)trim_new(1), (double)trim_new(2));
}
_auto_trim.reset();
}
void FwTrim::reset()
{
_auto_trim.reset();
}
void FwTrim::updateAutoTrim(const Vector3f &torque_sp, const float dt)
{
_auto_trim.update(torque_sp - _parameterized_trim, dt);
}
Vector3f FwTrim::getTrim() const
{
Vector3f trim = _parameterized_trim;
if (_param_fw_atrim_mode.get() > 0) {
trim += _auto_trim.getTrim();
}
return trim;
}
void FwTrim::setAirspeed(const float airspeed)
{
_airspeed = airspeed;
updateParameterizedTrim();
}
void FwTrim::updateParameterizedTrim()
{
/* bi-linear interpolation over airspeed for actuator trim scheduling */
Vector3f trim(_param_trim_roll.get(), _param_trim_pitch.get(), _param_trim_yaw.get());
if (_airspeed < _param_fw_airspd_trim.get()) {
trim(0) += interpolate(_airspeed, _param_fw_airspd_min.get(), _param_fw_airspd_trim.get(),
_param_fw_dtrim_r_vmin.get(),
0.0f);
trim(1) += interpolate(_airspeed, _param_fw_airspd_min.get(), _param_fw_airspd_trim.get(),
_param_fw_dtrim_p_vmin.get(),
0.0f);
trim(2) += interpolate(_airspeed, _param_fw_airspd_min.get(), _param_fw_airspd_trim.get(),
_param_fw_dtrim_y_vmin.get(),
0.0f);
} else {
trim(0) += interpolate(_airspeed, _param_fw_airspd_trim.get(), _param_fw_airspd_max.get(), 0.0f,
_param_fw_dtrim_r_vmax.get());
trim(1) += interpolate(_airspeed, _param_fw_airspd_trim.get(), _param_fw_airspd_max.get(), 0.0f,
_param_fw_dtrim_p_vmax.get());
trim(2) += interpolate(_airspeed, _param_fw_airspd_trim.get(), _param_fw_airspd_max.get(), 0.0f,
_param_fw_dtrim_y_vmax.get());
}
_parameterized_trim = trim;
}

Some files were not shown because too many files have changed in this diff Show More