mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-21 01:20:34 +08:00
Compare commits
59 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| c00ed78dda | |||
| ca112fea8a | |||
| 53210dd8f3 | |||
| 3dac9af09e | |||
| ee765e7859 | |||
| 6515935b52 | |||
| 774b6ed3b8 | |||
| c3d984703c | |||
| a6007e4b93 | |||
| c11c75d32e | |||
| 493c9e49db | |||
| 42f4e02d7e | |||
| cd93e2982c | |||
| 7982f54a6a | |||
| ff6966da57 | |||
| 3874b4c55d | |||
| 5d2fda6172 | |||
| 0e41f9730f | |||
| f3ef0d6610 | |||
| b0cb697f71 | |||
| e2969952d3 | |||
| 2de0af52e8 | |||
| 2f4d6b6fac | |||
| efe2a52eb4 | |||
| 752051470f | |||
| 993782cffa | |||
| 0379048ad2 | |||
| ae34e39b7e | |||
| f3d152741c | |||
| b36f47535e | |||
| a80c96e575 | |||
| 267cb9906e | |||
| f655d1be9b | |||
| 3beb57aae1 | |||
| d79c5f170b | |||
| 04e0d3475f | |||
| daa89ba30a | |||
| a4650fd70d | |||
| b5627f487f | |||
| d1db0addf9 | |||
| 032ae69eee | |||
| f8fe7c7aa3 | |||
| dfee9ca4c6 | |||
| 1206005ed2 | |||
| 42bca65cbf | |||
| b9d3b9f211 | |||
| f9e2ab8d44 | |||
| da35c4adce | |||
| ccbcbbe268 | |||
| 4f64acb352 | |||
| e1ffc2cdaa | |||
| a9962dc44d | |||
| 5bace785e0 | |||
| e4fd80b6ef | |||
| 6ebb2b33df | |||
| 8fe8f2fcb3 | |||
| 7c4507b6d6 | |||
| 21e550fdba | |||
| 4a13e495d7 |
@@ -47,7 +47,7 @@ pipeline {
|
||||
"ark_fmu-v6x_bootloader",
|
||||
"ark_fmu-v6x_default",
|
||||
"ark_pi6x_bootloader",
|
||||
"ark_pi6x_default"
|
||||
"ark_pi6x_default",
|
||||
"atl_mantis-edu_default",
|
||||
"av_x-v1_default",
|
||||
"bitcraze_crazyflie21_default",
|
||||
|
||||
+4
-2
@@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2017 - 2022 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2017 - 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
|
||||
@@ -132,7 +132,9 @@ list(GET VERSION_LIST 2 PX4_VERSION_PATCH)
|
||||
string(REPLACE "-" ";" PX4_VERSION_PATCH ${PX4_VERSION_PATCH})
|
||||
list(GET PX4_VERSION_PATCH 0 PX4_VERSION_PATCH)
|
||||
|
||||
message(STATUS "PX4 version: ${PX4_GIT_TAG} (${PX4_VERSION_MAJOR}.${PX4_VERSION_MINOR}.${PX4_VERSION_PATCH})")
|
||||
# # Capture only the hash part after 'g'
|
||||
string(REGEX MATCH "g([a-f0-9]+)$" GIT_HASH "${PX4_GIT_TAG}")
|
||||
set(PX4_GIT_HASH ${CMAKE_MATCH_1})
|
||||
|
||||
define_property(GLOBAL PROPERTY PX4_MODULE_LIBRARIES
|
||||
BRIEF_DOCS "PX4 module libs"
|
||||
|
||||
@@ -24,7 +24,6 @@ param set-default FW_RR_P 0.085
|
||||
param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_TAKEOFF_ALT 20
|
||||
param set-default MIS_DIST_1WP 2500
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
@@ -24,7 +24,6 @@ param set-default FW_RR_P 0.085
|
||||
param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_TAKEOFF_ALT 20
|
||||
param set-default MIS_DIST_1WP 2500
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
@@ -24,7 +24,6 @@ param set-default FW_RR_P 0.085
|
||||
param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_TAKEOFF_ALT 20
|
||||
param set-default MIS_DIST_1WP 2500
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
@@ -25,7 +25,6 @@ param set-default FW_W_EN 1
|
||||
|
||||
param set-default MIS_LTRMIN_ALT 30
|
||||
param set-default MIS_TAKEOFF_ALT 20
|
||||
param set-default MIS_DIST_1WP 2500
|
||||
|
||||
param set-default NAV_ACC_RAD 15
|
||||
param set-default NAV_DLL_ACT 2
|
||||
|
||||
@@ -66,7 +66,6 @@ param set-default MC_PITCHRATE_I 0.05
|
||||
param set-default MC_YAWRATE_MAX 20
|
||||
param set-default MC_AIRMODE 1
|
||||
|
||||
param set-default MIS_DIST_1WP 100
|
||||
param set-default MIS_TAKEOFF_ALT 15
|
||||
|
||||
param set-default MPC_XY_P 0.8
|
||||
@@ -74,7 +73,6 @@ param set-default MPC_XY_VEL_MAX 5
|
||||
param set-default MPC_LAND_SPEED 1.2
|
||||
param set-default MPC_TILTMAX_LND 35
|
||||
param set-default MPC_Z_VEL_MAX_UP 1.5
|
||||
param set-default MPC_Z_VEL_MAN_UP 1.5
|
||||
param set-default MPC_TKO_RAMP_T 0.8
|
||||
param set-default MPC_TILTMAX_AIR 25
|
||||
param set-default MPC_TILTMAX_LND 25
|
||||
|
||||
@@ -60,7 +60,6 @@ param set-default MPC_THR_HOVER 0.45
|
||||
param set-default MPC_TILTMAX_AIR 25
|
||||
param set-default MPC_YAWRAUTO_MAX 40
|
||||
param set-default MPC_Z_VEL_MAX_UP 2
|
||||
param set-default MPC_Z_VEL_MAN_UP 2
|
||||
|
||||
param set-default NAV_ACC_RAD 3
|
||||
|
||||
|
||||
@@ -123,7 +123,6 @@ param set-default MPC_TILTMAX_AIR 30
|
||||
param set-default MPC_XY_P 1
|
||||
param set-default MPC_Z_P 2
|
||||
param set-default MPC_Z_VEL_MAX_DN 2
|
||||
param set-default MPC_Z_VEL_MAN_DN 2
|
||||
|
||||
# gimbal configuration
|
||||
param set-default MNT_MODE_IN 0
|
||||
|
||||
@@ -123,6 +123,13 @@ else
|
||||
set PARAM_FILE /fs/mtd_params
|
||||
fi
|
||||
|
||||
# Check if /fs/mtd_params is a valid BSON file
|
||||
if ! bsondump docsize /fs/mtd_caldata
|
||||
then
|
||||
echo "New /fs/mtd_caldata size is:"
|
||||
bsondump docsize /fs/mtd_caldata
|
||||
fi
|
||||
|
||||
#
|
||||
# Load parameters.
|
||||
#
|
||||
|
||||
@@ -54,12 +54,21 @@ def extract_timer_from_channel(line, timer_names):
|
||||
|
||||
return None
|
||||
|
||||
def imxrt_is_dshot(line):
|
||||
|
||||
# NXP FlexPWM format format: initIOPWM(PWM::FlexPWM2),
|
||||
search = re.search('(initIOPWMDshot)', line, re.IGNORECASE)
|
||||
if search:
|
||||
return True
|
||||
|
||||
return False
|
||||
|
||||
def get_timer_groups(timer_config_file, verbose=False):
|
||||
with open(timer_config_file, 'r') as f:
|
||||
timer_config = f.read()
|
||||
|
||||
# timers
|
||||
dshot_support = {} # key: timer
|
||||
dshot_support = {str(i): False for i in range(16)}
|
||||
timers_start_marker = 'io_timers_t io_timers'
|
||||
timers_start = timer_config.find(timers_start_marker)
|
||||
if timers_start == -1:
|
||||
@@ -78,10 +87,9 @@ def get_timer_groups(timer_config_file, verbose=False):
|
||||
if timer_type == 'imxrt':
|
||||
if verbose: print('imxrt timer found')
|
||||
timer_names.append(timer)
|
||||
if imxrt_is_dshot(line):
|
||||
dshot_support[str(len(timers))] = True
|
||||
timers.append(str(len(timers)))
|
||||
dshot_support = {str(i): False for i in range(16)}
|
||||
for i in range(8): # First 8 channels support dshot
|
||||
dshot_support[str(i)] = True
|
||||
elif timer:
|
||||
if verbose: print('found timer def: {:}'.format(timer))
|
||||
dshot_support[timer] = 'DMA' in line
|
||||
|
||||
@@ -15,7 +15,7 @@ class ModuleDocumentation(object):
|
||||
# TOC in https://github.com/PX4/PX4-user_guide/blob/main/en/SUMMARY.md
|
||||
valid_categories = ['driver', 'estimator', 'controller', 'system',
|
||||
'communication', 'command', 'template', 'simulation', 'autotune']
|
||||
valid_subcategories = ['', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor',
|
||||
valid_subcategories = ['', 'camera', 'distance_sensor', 'imu', 'ins', 'airspeed_sensor',
|
||||
'magnetometer', 'baro', 'optical_flow', 'rpm_sensor', 'transponder']
|
||||
|
||||
max_line_length = 80 # wrap lines that are longer than this
|
||||
|
||||
+76
-49
@@ -1,7 +1,7 @@
|
||||
#!/usr/bin/env python3
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2012-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
|
||||
@@ -50,9 +50,6 @@
|
||||
# Currently only used for informational purposes.
|
||||
#
|
||||
|
||||
# for python2.7 compatibility
|
||||
from __future__ import print_function
|
||||
|
||||
import sys
|
||||
import argparse
|
||||
import binascii
|
||||
@@ -70,35 +67,32 @@ from sys import platform as _platform
|
||||
try:
|
||||
import serial
|
||||
except ImportError as e:
|
||||
print("Failed to import serial: " + str(e))
|
||||
print(f"Failed to import serial: {e}")
|
||||
print("")
|
||||
print("You may need to install it using:")
|
||||
print(" pip3 install --user pyserial")
|
||||
print(" python -m pip install pyserial")
|
||||
print("")
|
||||
sys.exit(1)
|
||||
|
||||
|
||||
# Define time to use time.time() by default
|
||||
def _time():
|
||||
return time.time()
|
||||
|
||||
# Detect python version
|
||||
if sys.version_info[0] < 3:
|
||||
runningPython3 = False
|
||||
else:
|
||||
runningPython3 = True
|
||||
if sys.version_info[1] >=3:
|
||||
# redefine to use monotonic time when available
|
||||
def _time():
|
||||
try:
|
||||
return time.monotonic()
|
||||
except Exception:
|
||||
return time.time()
|
||||
raise RuntimeError("Python 2 is not supported. Please try again using Python 3.")
|
||||
sys.exit(1)
|
||||
|
||||
|
||||
# Use monotonic time where available
|
||||
def _time():
|
||||
try:
|
||||
return time.monotonic()
|
||||
except Exception:
|
||||
return time.time()
|
||||
|
||||
class FirmwareNotSuitableException(Exception):
|
||||
def __init__(self, message):
|
||||
super(FirmwareNotSuitableException, self).__init__(message)
|
||||
|
||||
|
||||
class firmware(object):
|
||||
'''Loads a firmware file'''
|
||||
|
||||
@@ -163,13 +157,13 @@ class firmware(object):
|
||||
|
||||
def crc(self, padlen):
|
||||
state = self.__crc32(self.image, int(0))
|
||||
for i in range(len(self.image), (padlen - 1), 4):
|
||||
for _ in range(len(self.image), (padlen - 1), 4):
|
||||
state = self.__crc32(self.crcpad, state)
|
||||
return state
|
||||
|
||||
|
||||
class uploader(object):
|
||||
'''Uploads a firmware file to the PX FMU bootloader'''
|
||||
class uploader:
|
||||
'''Uploads a firmware file to the PX4 bootloader'''
|
||||
|
||||
# protocol bytes
|
||||
INSYNC = b'\x12'
|
||||
@@ -195,6 +189,8 @@ class uploader(object):
|
||||
GET_CHIP = b'\x2c' # rev5+ , get chip version
|
||||
SET_BOOT_DELAY = b'\x2d' # rev5+ , set boot delay
|
||||
GET_CHIP_DES = b'\x2e' # rev5+ , get chip description in ASCII
|
||||
GET_VERSION = b'\x2f' # rev5+ , get chip description in ASCII
|
||||
CHIP_FULL_ERASE = b'\x40' # full erase of flash, rev6+
|
||||
MAX_DES_LENGTH = 20
|
||||
|
||||
REBOOT = b'\x30'
|
||||
@@ -205,6 +201,7 @@ class uploader(object):
|
||||
INFO_BOARD_ID = b'\x02' # board type
|
||||
INFO_BOARD_REV = b'\x03' # board revision
|
||||
INFO_FLASH_SIZE = b'\x04' # max firmware size in bytes
|
||||
BL_VERSION = b'\x07' # get bootloader version, e.g. major.minor.patch.githash (up to 20 chars)
|
||||
|
||||
PROG_MULTI_MAX = 252 # protocol max is 255, must be multiple of 4
|
||||
READ_MULTI_MAX = 252 # protocol max is 255
|
||||
@@ -235,6 +232,7 @@ class uploader(object):
|
||||
self.baudrate_bootloader = baudrate_bootloader
|
||||
self.baudrate_flightstack = baudrate_flightstack
|
||||
self.baudrate_flightstack_idx = -1
|
||||
self.force_erase = False
|
||||
|
||||
def close(self):
|
||||
if self.port is not None:
|
||||
@@ -357,19 +355,22 @@ class uploader(object):
|
||||
self.port.baudrate = self.baudrate_bootloader * 2.33
|
||||
except NotImplementedError as e:
|
||||
# This error can occur because pySerial on Windows does not support odd baudrates
|
||||
print(str(e) + " -> could not check for FTDI device, assuming USB connection")
|
||||
print(f"{e} -> could not check for FTDI device, assuming USB connection")
|
||||
return
|
||||
|
||||
self.__send(uploader.GET_SYNC +
|
||||
uploader.EOC)
|
||||
try:
|
||||
self.__getSync(False)
|
||||
except:
|
||||
except RuntimeError:
|
||||
# if it fails we are on a real serial port - only leave this enabled on Windows
|
||||
if sys.platform.startswith('win'):
|
||||
self.ackWindowedMode = True
|
||||
finally:
|
||||
self.port.baudrate = self.baudrate_bootloader
|
||||
try:
|
||||
self.port.baudrate = self.baudrate_bootloader
|
||||
except Exception:
|
||||
pass
|
||||
|
||||
# send the GET_DEVICE command and wait for an info parameter
|
||||
def __getInfo(self, param):
|
||||
@@ -410,6 +411,17 @@ class uploader(object):
|
||||
pieces = value.split(b",")
|
||||
return pieces
|
||||
|
||||
def __getVersion(self):
|
||||
self.__send(uploader.GET_VERSION + uploader.EOC)
|
||||
try:
|
||||
length = self.__recv_int()
|
||||
value = self.__recv(length)
|
||||
self.__getSync()
|
||||
except RuntimeError:
|
||||
# Bootloader doesn't support version call
|
||||
return "unknown"
|
||||
return value.decode()
|
||||
|
||||
def __drawProgressBar(self, label, progress, maxVal):
|
||||
if maxVal < progress:
|
||||
progress = maxVal
|
||||
@@ -421,10 +433,16 @@ class uploader(object):
|
||||
|
||||
# send the CHIP_ERASE command and wait for the bootloader to become ready
|
||||
def __erase(self, label):
|
||||
print("Windowed mode: %s" % self.ackWindowedMode)
|
||||
print(f"Windowed mode: {self.ackWindowedMode}")
|
||||
print("\n", end='')
|
||||
self.__send(uploader.CHIP_ERASE +
|
||||
uploader.EOC)
|
||||
|
||||
if self.force_erase:
|
||||
print("Trying force erase of full chip...\n")
|
||||
self.__send(uploader.CHIP_FULL_ERASE +
|
||||
uploader.EOC)
|
||||
else:
|
||||
self.__send(uploader.CHIP_ERASE +
|
||||
uploader.EOC)
|
||||
|
||||
# erase is very slow, give it 30s
|
||||
deadline = _time() + 30.0
|
||||
@@ -441,9 +459,14 @@ class uploader(object):
|
||||
|
||||
if self.__trySync():
|
||||
self.__drawProgressBar(label, 10.0, 10.0)
|
||||
if self.force_erase:
|
||||
print("\nForce erase done.\n")
|
||||
return
|
||||
|
||||
raise RuntimeError("timed out waiting for erase")
|
||||
if self.force_erase:
|
||||
raise RuntimeError("timed out waiting for erase, force erase is likely not supported by bootloader!")
|
||||
else:
|
||||
raise RuntimeError("timed out waiting for erase")
|
||||
|
||||
# send a PROG_MULTI command to write a collection of bytes
|
||||
def __program_multi(self, data, windowMode):
|
||||
@@ -581,8 +604,11 @@ class uploader(object):
|
||||
self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV)
|
||||
self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
|
||||
|
||||
self.version = self.__getVersion()
|
||||
|
||||
# upload the firmware
|
||||
def upload(self, fw_list, force=False, boot_delay=None, boot_check=False):
|
||||
def upload(self, fw_list, force=False, boot_delay=None, boot_check=False, force_erase=False):
|
||||
self.force_erase = force_erase
|
||||
# select correct binary
|
||||
found_suitable_firmware = False
|
||||
for file in fw_list:
|
||||
@@ -611,6 +637,8 @@ class uploader(object):
|
||||
print("Loaded firmware for board id: %s,%s size: %d bytes (%.2f%%) " % (fw.property('board_id'), fw.property('board_revision'), fw.property('image_size'), percent))
|
||||
print()
|
||||
|
||||
print(f"Bootloader version: {self.version}")
|
||||
|
||||
# Make sure we are doing the right thing
|
||||
start = _time()
|
||||
if self.board_type != fw.property('board_id'):
|
||||
@@ -640,14 +668,14 @@ class uploader(object):
|
||||
self.otp_coa = self.otp[32:160]
|
||||
# show user:
|
||||
try:
|
||||
print("sn: ", end='')
|
||||
print("Sn: ", end='')
|
||||
for byte in range(0, 12, 4):
|
||||
x = self.__getSN(byte)
|
||||
x = x[::-1] # reverse the bytes
|
||||
self.sn = self.sn + x
|
||||
print(binascii.hexlify(x).decode('Latin-1'), end='') # show user
|
||||
print('')
|
||||
print("chip: %08x" % self.__getCHIP())
|
||||
print("Chip: %08x" % self.__getCHIP())
|
||||
|
||||
otp_id = self.otp_id.decode('Latin-1')
|
||||
if ("PX4" in otp_id):
|
||||
@@ -657,17 +685,19 @@ class uploader(object):
|
||||
print("OTP pid: " + binascii.hexlify(self.otp_pid).decode('Latin-1'))
|
||||
print("OTP coa: " + binascii.b2a_base64(self.otp_coa).decode('Latin-1'))
|
||||
|
||||
except Exception:
|
||||
except Exception as e:
|
||||
# ignore bad character encodings
|
||||
print(f"Exception ignored: {e}")
|
||||
pass
|
||||
|
||||
# Silicon errata check was added in v5
|
||||
if (self.bl_rev >= 5):
|
||||
des = self.__getCHIPDes()
|
||||
if (len(des) == 2):
|
||||
print("family: %s" % des[0])
|
||||
print("revision: %s" % des[1])
|
||||
print("flash: %d bytes" % self.fw_maxsize)
|
||||
family, revision = des
|
||||
print(f"Family: {family.decode()}")
|
||||
print(f"Revision: {revision.decode()}")
|
||||
print(f"Flash: {self.fw_maxsize} bytes")
|
||||
|
||||
# Prevent uploads where the maximum image size of the board config is smaller than the flash
|
||||
# of the board. This is a hint the user chose the wrong config and will lack features
|
||||
@@ -678,8 +708,7 @@ class uploader(object):
|
||||
# https://github.com/PX4/Firmware/blob/master/src/drivers/boards/common/stm32/board_mcu_version.c#L125-L144
|
||||
|
||||
if self.fw_maxsize > fw.property('image_maxsize') and not force:
|
||||
raise RuntimeError("Board can accept larger flash images (%u bytes) than board config (%u bytes). Please use the correct board configuration to avoid lacking critical functionality."
|
||||
% (self.fw_maxsize, fw.property('image_maxsize')))
|
||||
raise RuntimeError(f"Board can accept larger flash images ({self.fw_maxsize} bytes) than board config ({fw.property('image_maxsize')} bytes). Please use the correct board configuration to avoid lacking critical functionality.")
|
||||
else:
|
||||
# If we're still on bootloader v4 on a Pixhawk, we don't know if we
|
||||
# have the silicon errata and therefore need to flash px4_fmu-v2
|
||||
@@ -780,16 +809,13 @@ class uploader(object):
|
||||
|
||||
|
||||
def main():
|
||||
# Python2 is EOL
|
||||
if not runningPython3:
|
||||
raise RuntimeError("Python 2 is not supported. Please try again using Python 3.")
|
||||
|
||||
# Parse commandline arguments
|
||||
parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
|
||||
parser.add_argument('--port', action="store", required=True, help="Comma-separated list of serial port(s) to which the FMU may be attached")
|
||||
parser.add_argument('--baud-bootloader', action="store", type=int, default=115200, help="Baud rate of the serial port (default is 115200) when communicating with bootloader, only required for true serial ports.")
|
||||
parser.add_argument('--baud-flightstack', action="store", default="57600", help="Comma-separated list of baud rate of the serial port (default is 57600) when communicating with flight stack (Mavlink or NSH), only required for true serial ports.")
|
||||
parser.add_argument('--force', action='store_true', default=False, help='Override board type check, or silicon errata checks and continue loading')
|
||||
parser.add_argument('--force-erase', action="store_true", help="Do not perform the blank check, always erase every sector of the application space")
|
||||
parser.add_argument('--boot-delay', type=int, default=None, help='minimum boot delay to store in flash')
|
||||
parser.add_argument('--use-protocol-splitter-format', action='store_true', help='use protocol splitter format for reboot')
|
||||
parser.add_argument('firmware', action="store", nargs='+', help="Firmware file(s)")
|
||||
@@ -867,9 +893,10 @@ def main():
|
||||
# Windows, don't open POSIX ports
|
||||
if "/" not in port:
|
||||
up = uploader(port, args.baud_bootloader, baud_flightstack)
|
||||
except Exception:
|
||||
except Exception as e:
|
||||
# open failed, rate-limit our attempts
|
||||
time.sleep(0.05)
|
||||
print(f"Exception ignored: {e}")
|
||||
|
||||
# and loop to the next port
|
||||
continue
|
||||
@@ -884,10 +911,10 @@ def main():
|
||||
up.identify()
|
||||
found_bootloader = True
|
||||
print()
|
||||
print("Found board id: %s,%s bootloader version: %s on %s" % (up.board_type, up.board_rev, up.bl_rev, port))
|
||||
print(f"Found board id: {up.board_type},{up.board_rev} bootloader protocol revision {up.bl_rev} on {port}")
|
||||
break
|
||||
|
||||
except Exception:
|
||||
except (RuntimeError, serial.SerialException):
|
||||
|
||||
if not up.send_reboot(args.use_protocol_splitter_format):
|
||||
break
|
||||
@@ -907,14 +934,14 @@ def main():
|
||||
|
||||
try:
|
||||
# ok, we have a bootloader, try flashing it
|
||||
up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay)
|
||||
up.upload(args.firmware, force=args.force, boot_delay=args.boot_delay, force_erase=args.force_erase)
|
||||
|
||||
# if we made this far without raising exceptions, the upload was successful
|
||||
successful = True
|
||||
|
||||
except RuntimeError as ex:
|
||||
except RuntimeError as e:
|
||||
# print the error
|
||||
print("\nERROR: %s" % ex.args)
|
||||
print(f"\n\nError: {e}")
|
||||
|
||||
except FirmwareNotSuitableException:
|
||||
unsuitable_board = True
|
||||
|
||||
@@ -15,7 +15,6 @@ CONFIG_DRIVERS_CAMERA_CAPTURE=y
|
||||
CONFIG_DRIVERS_CAMERA_TRIGGER=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_COMMON_DISTANCE_SENSOR=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
CONFIG_DRIVERS_HEATER=y
|
||||
|
||||
Binary file not shown.
@@ -8,6 +8,7 @@ CONFIG_BOARD_SERIAL_RC="/dev/ttyS4"
|
||||
CONFIG_DRIVERS_ADC_BOARD_ADC=y
|
||||
CONFIG_DRIVERS_BAROMETER_BMP388=y
|
||||
CONFIG_COMMON_DIFFERENTIAL_PRESSURE=y
|
||||
CONFIG_DRIVERS_CDCACM_AUTOSTART=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_BROADCOM_AFBRS50=y
|
||||
CONFIG_DRIVERS_DSHOT=y
|
||||
CONFIG_DRIVERS_GPS=y
|
||||
|
||||
Binary file not shown.
Binary file not shown.
Binary file not shown.
@@ -97,9 +97,9 @@
|
||||
#define INTERFACE_USART_CONFIG "/dev/ttyS5,57600"
|
||||
#define BOOT_DELAY_ADDRESS 0x000001a0
|
||||
#define BOARD_TYPE 1013
|
||||
#define _FLASH_KBYTES (*(uint32_t *)0x1FF1E880)
|
||||
#define BOARD_FLASH_SECTORS (15)
|
||||
#define BOARD_FLASH_SIZE (_FLASH_KBYTES * 1024)
|
||||
#define BOARD_FLASH_SECTORS (14)
|
||||
#define BOARD_FLASH_SIZE (16 * 128 * 1024)
|
||||
#define APP_RESERVATION_SIZE (1 * 128 * 1024)
|
||||
|
||||
#define OSC_FREQ 16
|
||||
|
||||
|
||||
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
@@ -8,7 +8,7 @@ CONFIG_DRIVERS_IMU_ANALOG_DEVICES_ADIS16448=n
|
||||
CONFIG_DRIVERS_IRLOCK=n
|
||||
CONFIG_MODULES_FW_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_MC_AUTOTUNE_ATTITUDE_CONTROL=n
|
||||
CONFIG_MODULES_ROVER_POS_CONTROL=n
|
||||
CONFIG_MODULES_PAYLOAD_DELIVERER=n
|
||||
CONFIG_MODULES_SIMULATION_SIMULATOR_SIH=n
|
||||
CONFIG_BOARD_TESTING=y
|
||||
CONFIG_DRIVERS_DISTANCE_SENSOR_LIGHTWARE_LASER_SERIAL=y
|
||||
|
||||
@@ -48,7 +48,6 @@ 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
|
||||
|
||||
Binary file not shown.
Binary file not shown.
Binary file not shown.
Binary file not shown.
@@ -28,6 +28,7 @@ CONFIG_ARMV7M_ITCM=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU=y
|
||||
CONFIG_ARM_MPU_RESET=y
|
||||
CONFIG_BOARDCTL=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
|
||||
@@ -267,6 +267,10 @@
|
||||
|
||||
// This is the ENET_1G interface.
|
||||
|
||||
/* Dshot Disambiguation *******************************************************/
|
||||
|
||||
#define IOMUX_DSHOT_DEFAULT (IOMUX_DRIVE_HIGHSTRENGTH | IOMUX_SLEW_FAST)
|
||||
|
||||
// Compile time selection
|
||||
#if defined(CONFIG_ETH0_PHY_TJA1103)
|
||||
# define BOARD_PHY_ADDR (18)
|
||||
|
||||
@@ -29,6 +29,7 @@ CONFIG_ARMV7M_ITCM=y
|
||||
CONFIG_ARMV7M_MEMCPY=y
|
||||
CONFIG_ARMV7M_USEBASEPRI=y
|
||||
CONFIG_ARM_MPU=y
|
||||
CONFIG_ARM_MPU_RESET=y
|
||||
CONFIG_BOARDCTL_RESET=y
|
||||
CONFIG_BOARD_ASSERT_RESET_VALUE=0
|
||||
CONFIG_BOARD_BOOTLOADER_FIXUP=y
|
||||
@@ -86,7 +87,6 @@ CONFIG_IMXRT_ENET=y
|
||||
CONFIG_IMXRT_FLEXCAN1=y
|
||||
CONFIG_IMXRT_FLEXCAN2=y
|
||||
CONFIG_IMXRT_FLEXCAN3=y
|
||||
CONFIG_IMXRT_FLEXIO1=y
|
||||
CONFIG_IMXRT_FLEXSPI2=y
|
||||
CONFIG_IMXRT_GPIO13_IRQ=y
|
||||
CONFIG_IMXRT_GPIO1_0_15_IRQ=y
|
||||
|
||||
@@ -6,6 +6,7 @@
|
||||
*(.text.board_autoled_on)
|
||||
*(.text.clock_timer)
|
||||
*(.text.exception_common)
|
||||
*(.text.flexio_irq_handler)
|
||||
*(.text.hrt_absolute_time)
|
||||
*(.text.hrt_call_enter)
|
||||
*(.text.hrt_tim_isr)
|
||||
|
||||
@@ -114,7 +114,7 @@ const struct clock_configuration_s g_initial_clkconfig = {
|
||||
.div = 1,
|
||||
.mux = ACMP_CLK_ROOT_OSC_RC_48M_DIV2,
|
||||
},
|
||||
.flexio1_clk_root =
|
||||
.flexio1_clk_root = /* 240 / 2 = 120Mhz */
|
||||
{
|
||||
.enable = 1,
|
||||
.div = 2,
|
||||
|
||||
@@ -91,14 +91,14 @@
|
||||
|
||||
|
||||
constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule0, GPIO_FLEXIO1_FLEXIO23_1, 23),
|
||||
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule1, GPIO_FLEXIO1_FLEXIO25_1, 25),
|
||||
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule2, GPIO_FLEXIO1_FLEXIO27_1, 27),
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule0, GPIO_FLEXIO1_FLEXIO06_1, 6),
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule1, GPIO_FLEXIO1_FLEXIO08_1, 8),
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule2, GPIO_FLEXIO1_FLEXIO10_1, 10),
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule3, GPIO_FLEXIO1_FLEXIO19_1, 19),
|
||||
initIOPWMDshot(PWM::FlexPWM3, PWM::Submodule0, GPIO_FLEXIO1_FLEXIO29_1, 29),
|
||||
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule0),
|
||||
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule1),
|
||||
initIOPWMDshot(PWM::FlexPWM1, PWM::Submodule2),
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule0),
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule1),
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule2),
|
||||
initIOPWMDshot(PWM::FlexPWM2, PWM::Submodule3),
|
||||
initIOPWMDshot(PWM::FlexPWM3, PWM::Submodule0),
|
||||
initIOPWM(PWM::FlexPWM3, PWM::Submodule1),
|
||||
initIOPWM(PWM::FlexPWM3, PWM::Submodule3),
|
||||
initIOPWM(PWM::FlexPWM4, PWM::Submodule0),
|
||||
@@ -106,14 +106,14 @@ constexpr io_timers_t io_timers[MAX_IO_TIMERS] = {
|
||||
};
|
||||
|
||||
constexpr timer_io_channels_t timer_io_channels[MAX_TIMER_IO_CHANNELS] = {
|
||||
/* FMU_CH1 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_23),
|
||||
/* FMU_CH2 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_25),
|
||||
/* FMU_CH3 */ initIOTimerChannel(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_27),
|
||||
/* FMU_CH4 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_06),
|
||||
/* FMU_CH5 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_08),
|
||||
/* FMU_CH6 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_10),
|
||||
/* FMU_CH7 */ initIOTimerChannel(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_19),
|
||||
/* FMU_CH8 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_29),
|
||||
/* FMU_CH1 */ initIOTimerChannelDshot(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_23, GPIO_FLEXIO1_FLEXIO23_1 | IOMUX_DSHOT_DEFAULT, 23),
|
||||
/* FMU_CH2 */ initIOTimerChannelDshot(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_25, GPIO_FLEXIO1_FLEXIO25_1 | IOMUX_DSHOT_DEFAULT, 25),
|
||||
/* FMU_CH3 */ initIOTimerChannelDshot(io_timers, {PWM::PWM1_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_27, GPIO_FLEXIO1_FLEXIO27_1 | IOMUX_DSHOT_DEFAULT, 27),
|
||||
/* FMU_CH4 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_06, GPIO_FLEXIO1_FLEXIO06_1 | IOMUX_DSHOT_DEFAULT, 6),
|
||||
/* FMU_CH5 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_08, GPIO_FLEXIO1_FLEXIO08_1 | IOMUX_DSHOT_DEFAULT, 8),
|
||||
/* FMU_CH6 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule2}, IOMUX::Pad::GPIO_EMC_B1_10, GPIO_FLEXIO1_FLEXIO10_1 | IOMUX_DSHOT_DEFAULT, 10),
|
||||
/* FMU_CH7 */ initIOTimerChannelDshot(io_timers, {PWM::PWM2_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_19, GPIO_FLEXIO1_FLEXIO19_1 | IOMUX_DSHOT_DEFAULT, 19),
|
||||
/* FMU_CH8 */ initIOTimerChannelDshot(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_29, GPIO_FLEXIO1_FLEXIO29_1 | IOMUX_DSHOT_DEFAULT, 29),
|
||||
/* FMU_CH9 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule1}, IOMUX::Pad::GPIO_EMC_B1_31),
|
||||
/* FMU_CH10 */ initIOTimerChannel(io_timers, {PWM::PWM3_PWM_A, PWM::Submodule3}, IOMUX::Pad::GPIO_EMC_B1_21),
|
||||
/* FMU_CH11 */ initIOTimerChannel(io_timers, {PWM::PWM4_PWM_A, PWM::Submodule0}, IOMUX::Pad::GPIO_EMC_B1_00),
|
||||
|
||||
@@ -50,7 +50,6 @@ 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
|
||||
|
||||
@@ -308,7 +308,7 @@ class MavrosMissionTest(MavrosTestCommon):
|
||||
self.assertTrue(res['pitch_error_std'] < 5.0, str(res))
|
||||
|
||||
# TODO: fix by excluding initial heading init and reset preflight
|
||||
self.assertTrue(res['yaw_error_std'] < 13.0, str(res))
|
||||
self.assertTrue(res['yaw_error_std'] < 15.0, str(res))
|
||||
|
||||
|
||||
if __name__ == '__main__':
|
||||
|
||||
@@ -9,6 +9,8 @@ uint8 BACKEND_MAVLINK = 2
|
||||
uint8 BACKEND_ALL = 3
|
||||
uint8 backend
|
||||
|
||||
bool is_logging
|
||||
|
||||
float32 total_written_kb # total written to log in kiloBytes
|
||||
float32 write_rate_kb_s # write rate in kiloBytes/s
|
||||
|
||||
|
||||
+5
-5
@@ -8,8 +8,8 @@ bool has_vtol_approach # flag if approaches are defined for current RTL_
|
||||
uint8 rtl_type # Type of RTL chosen
|
||||
uint8 safe_point_index # index of the chosen safe point, if in RTL_STATUS_TYPE_DIRECT_SAFE_POINT mode
|
||||
|
||||
uint8 RTL_STATUS_TYPE_NONE=0 # RTL type is pending if evaluation can't pe performed currently e.g. when it is still loading the safe points
|
||||
uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # RTL type is chosen to directly go to a safe point or home position
|
||||
uint8 RTL_STATUS_TYPE_DIRECT_MISSION_LAND=2 # RTL type is going straight to the beginning of the mission landing
|
||||
uint8 RTL_STATUS_TYPE_FOLLOW_MISSION=3 # RTL type is following the mission from closest point to mission landing
|
||||
uint8 RTL_STATUS_TYPE_FOLLOW_MISSION_REVERSE=4 # RTL type is following the mission in reverse to the start position
|
||||
uint8 RTL_STATUS_TYPE_NONE=0 # pending if evaluation can't pe performed currently e.g. when it is still loading the safe points
|
||||
uint8 RTL_STATUS_TYPE_DIRECT_SAFE_POINT=1 # chosen to directly go to a safe point or home position
|
||||
uint8 RTL_STATUS_TYPE_DIRECT_MISSION_LAND=2 # going straight to the beginning of the mission landing
|
||||
uint8 RTL_STATUS_TYPE_FOLLOW_MISSION=3 # Following the mission from start index to mission landing. Start index is current WP if in Mission mode, and closest WP otherwise.
|
||||
uint8 RTL_STATUS_TYPE_FOLLOW_MISSION_REVERSE=4 # Following the mission in reverse from start index to the beginning of the mission. Start index is previous WP if in Mission mode, and closest WP otherwise.
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
uint64 timestamp # time since system start (microseconds)
|
||||
|
||||
# body angular rates in NED frame
|
||||
# body angular rates in FRD frame
|
||||
float32 roll # [rad/s] roll rate setpoint
|
||||
float32 pitch # [rad/s] pitch rate setpoint
|
||||
float32 yaw # [rad/s] yaw rate setpoint
|
||||
|
||||
@@ -62,6 +62,11 @@ public:
|
||||
{
|
||||
Node **p;
|
||||
|
||||
// Don't allow duplicates to be inserted
|
||||
if (find(node_name)) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (_top == nullptr) {
|
||||
p = &_top;
|
||||
|
||||
|
||||
Submodule platforms/nuttx/NuttX/nuttx updated: 0f401a6062...6fbb26eb52
@@ -37,6 +37,10 @@ add_library(bootloader
|
||||
crypto.c
|
||||
)
|
||||
|
||||
target_compile_definitions(bootloader
|
||||
PRIVATE BOOTLOADER_VERSION="PX4BLv${PX4_VERSION_MAJOR}.${PX4_VERSION_MINOR}.${PX4_VERSION_PATCH}g${PX4_GIT_HASH}"
|
||||
)
|
||||
|
||||
target_link_libraries(bootloader
|
||||
PRIVATE
|
||||
arch_bootloader
|
||||
|
||||
@@ -80,7 +80,7 @@
|
||||
// RESET finalise flash programming, reset chip and starts application
|
||||
//
|
||||
|
||||
#define BL_PROTOCOL_VERSION 5 // The revision of the bootloader protocol
|
||||
#define BL_PROTOCOL_REVISION 5 // The revision of the bootloader protocol
|
||||
//* Next revision needs to update
|
||||
|
||||
// protocol bytes
|
||||
@@ -106,14 +106,20 @@
|
||||
#define PROTO_GET_CHIP 0x2c // read chip version (MCU IDCODE)
|
||||
#define PROTO_SET_DELAY 0x2d // set minimum boot delay
|
||||
#define PROTO_GET_CHIP_DES 0x2e // read chip version In ASCII
|
||||
#define PROTO_GET_VERSION 0x2f // read version
|
||||
#define PROTO_BOOT 0x30 // boot the application
|
||||
#define PROTO_DEBUG 0x31 // emit debug information - format not defined
|
||||
#define PROTO_SET_BAUD 0x33 // set baud rate on uart
|
||||
|
||||
#define PROTO_RESERVED_0X36 0x36 // Reserved
|
||||
#define PROTO_RESERVED_0X37 0x37 // Reserved
|
||||
// Reserved for external flash programming
|
||||
// #define PROTO_EXTF_ERASE 0x34 // Erase sectors from external flash
|
||||
// #define PROTO_EXTF_PROG_MULTI 0x35 // write bytes at external flash program address and increment
|
||||
// #define PROTO_EXTF_READ_MULTI 0x36 // read bytes at address and increment
|
||||
// #define PROTO_EXTF_GET_CRC 0x37 // compute & return a CRC of data in external flash
|
||||
|
||||
#define PROTO_RESERVED_0X38 0x38 // Reserved
|
||||
#define PROTO_RESERVED_0X39 0x39 // Reserved
|
||||
#define PROTO_CHIP_FULL_ERASE 0x40 // Full erase, without any flash wear optimization
|
||||
|
||||
#define PROTO_PROG_MULTI_MAX 64 // maximum PROG_MULTI size
|
||||
#define PROTO_READ_MULTI_MAX 255 // size of the size field
|
||||
@@ -125,13 +131,6 @@
|
||||
#define PROTO_DEVICE_FW_SIZE 4 // size of flashable area
|
||||
#define PROTO_DEVICE_VEC_AREA 5 // contents of reserved vectors 7-10
|
||||
|
||||
#define STATE_PROTO_OK 0x10 // INSYNC/OK - 'ok' response
|
||||
#define STATE_PROTO_FAILED 0x11 // INSYNC/FAILED - 'fail' response
|
||||
#define STATE_PROTO_INVALID 0x13 // INSYNC/INVALID - 'invalid' response for bad commands
|
||||
#define STATE_PROTO_BAD_SILICON_REV 0x14 // On the F4 series there is an issue with < Rev 3 silicon
|
||||
#define STATE_PROTO_RESERVED_0X15 0x15 // Reserved
|
||||
|
||||
|
||||
// State
|
||||
#define STATE_PROTO_GET_SYNC 0x1 // Have Seen NOP for re-establishing sync
|
||||
#define STATE_PROTO_GET_DEVICE 0x2 // Have Seen get device ID bytes
|
||||
@@ -142,7 +141,8 @@
|
||||
#define STATE_PROTO_GET_SN 0x40 // Have Seen read a word from UDID area ( Serial) at the given address
|
||||
#define STATE_PROTO_GET_CHIP 0x80 // Have Seen read chip version (MCU IDCODE)
|
||||
#define STATE_PROTO_GET_CHIP_DES 0x100 // Have Seen read chip version In ASCII
|
||||
#define STATE_PROTO_BOOT 0x200 // Have Seen boot the application
|
||||
#define STATE_PROTO_GET_VERSION 0x200 // Have Seen get version
|
||||
#define STATE_PROTO_BOOT 0x400 // Have Seen boot the application
|
||||
|
||||
#if defined(TARGET_HW_PX4_PIO_V1)
|
||||
#define STATE_ALLOWS_ERASE (STATE_PROTO_GET_SYNC)
|
||||
@@ -157,6 +157,18 @@
|
||||
static uint8_t bl_type;
|
||||
static uint8_t last_input;
|
||||
|
||||
int get_version(int n, uint8_t *version_str)
|
||||
{
|
||||
int len = strlen(BOOTLOADER_VERSION);
|
||||
|
||||
if (len > n) {
|
||||
len = n;
|
||||
}
|
||||
|
||||
strncpy((char *)version_str, BOOTLOADER_VERSION, n);
|
||||
return len;
|
||||
}
|
||||
|
||||
inline void cinit(void *config, uint8_t interface)
|
||||
{
|
||||
#if INTERFACE_USB
|
||||
@@ -257,7 +269,7 @@ inline void cout(uint8_t *buf, unsigned len)
|
||||
|
||||
#endif
|
||||
|
||||
static const uint32_t bl_proto_rev = BL_PROTOCOL_VERSION; // value returned by PROTO_DEVICE_BL_REV
|
||||
static const uint32_t bl_proto_rev = BL_PROTOCOL_REVISION; // value returned by PROTO_DEVICE_BL_REV
|
||||
|
||||
static unsigned head, tail;
|
||||
static uint8_t rx_buf[256] USB_DATA_ALIGN;
|
||||
@@ -294,7 +306,7 @@ void
|
||||
jump_to_app()
|
||||
{
|
||||
const uint32_t *app_base = (const uint32_t *)APP_LOAD_ADDRESS;
|
||||
const uint32_t *vec_base = (const uint32_t *)app_base + APP_VECTOR_OFFSET;
|
||||
const uint32_t *vec_base = (const uint32_t *)((const uint32_t)app_base + APP_VECTOR_OFFSET);
|
||||
|
||||
/*
|
||||
* We refuse to program the first word of the app until the upload is marked
|
||||
@@ -649,6 +661,8 @@ bootloader(unsigned timeout)
|
||||
|
||||
led_on(LED_ACTIVITY);
|
||||
|
||||
bool full_erase = false;
|
||||
|
||||
// handle the command byte
|
||||
switch (c) {
|
||||
|
||||
@@ -728,6 +742,10 @@ bootloader(unsigned timeout)
|
||||
// success reply: INSYNC/OK
|
||||
// erase failure: INSYNC/FAILURE
|
||||
//
|
||||
case PROTO_CHIP_FULL_ERASE:
|
||||
full_erase = true;
|
||||
|
||||
// Fallthrough
|
||||
case PROTO_CHIP_ERASE:
|
||||
|
||||
/* expect EOC */
|
||||
@@ -755,17 +773,18 @@ bootloader(unsigned timeout)
|
||||
arch_flash_unlock();
|
||||
|
||||
for (int i = 0; flash_func_sector_size(i) != 0; i++) {
|
||||
flash_func_erase_sector(i);
|
||||
flash_func_erase_sector(i, full_erase);
|
||||
}
|
||||
|
||||
// disable the LED while verifying the erase
|
||||
led_set(LED_OFF);
|
||||
|
||||
// verify the erase
|
||||
for (address = 0; address < board_info.fw_size; address += 4)
|
||||
for (address = 0; address < board_info.fw_size; address += 4) {
|
||||
if (flash_func_read_word(address) != 0xffffffff) {
|
||||
goto cmd_fail;
|
||||
}
|
||||
}
|
||||
|
||||
address = 0;
|
||||
SET_BL_STATE(STATE_PROTO_CHIP_ERASE);
|
||||
@@ -965,7 +984,7 @@ bootloader(unsigned timeout)
|
||||
// read the chip description
|
||||
//
|
||||
// command: GET_CHIP_DES/EOC
|
||||
// reply: <value:4>/INSYNC/OK
|
||||
// reply: <length:4><buffer...>/INSYNC/OK
|
||||
case PROTO_GET_CHIP_DES: {
|
||||
uint8_t buffer[MAX_DES_LENGTH];
|
||||
unsigned len = MAX_DES_LENGTH;
|
||||
@@ -982,6 +1001,25 @@ bootloader(unsigned timeout)
|
||||
}
|
||||
break;
|
||||
|
||||
// read the bootloader version (not to be confused with protocol revision)
|
||||
//
|
||||
// command: GET_VERSION/EOC
|
||||
// reply: <length:4><buffer...>/INSYNC/OK
|
||||
case PROTO_GET_VERSION: {
|
||||
uint8_t buffer[MAX_VERSION_LENGTH];
|
||||
|
||||
// expect EOC
|
||||
if (!wait_for_eoc(2)) {
|
||||
goto cmd_bad;
|
||||
}
|
||||
|
||||
int len = get_version(sizeof(buffer), buffer);
|
||||
cout_word(len);
|
||||
cout(buffer, len);
|
||||
SET_BL_STATE(STATE_PROTO_GET_VERSION);
|
||||
}
|
||||
break;
|
||||
|
||||
#ifdef BOOT_DELAY_ADDRESS
|
||||
|
||||
case PROTO_SET_DELAY: {
|
||||
@@ -1099,4 +1137,4 @@ bad_silicon:
|
||||
continue;
|
||||
#endif
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -39,6 +39,8 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <stdbool.h>
|
||||
|
||||
/*****************************************************************************
|
||||
* Generic bootloader functions.
|
||||
*/
|
||||
@@ -94,6 +96,7 @@ extern int buf_get(void);
|
||||
#endif
|
||||
|
||||
#define MAX_DES_LENGTH 20
|
||||
#define MAX_VERSION_LENGTH 32
|
||||
|
||||
#define arraySize(a) (sizeof((a))/sizeof(((a)[0])))
|
||||
extern void led_on(unsigned led);
|
||||
@@ -105,7 +108,7 @@ extern void board_deinit(void);
|
||||
extern uint32_t board_get_devices(void);
|
||||
extern void clock_deinit(void);
|
||||
extern uint32_t flash_func_sector_size(unsigned sector);
|
||||
extern void flash_func_erase_sector(unsigned sector);
|
||||
extern void flash_func_erase_sector(unsigned sector, bool force);
|
||||
extern void flash_func_write_word(uintptr_t address, uint32_t word);
|
||||
extern uint32_t flash_func_read_word(uintptr_t address);
|
||||
extern uint32_t flash_func_read_otp(uintptr_t address);
|
||||
@@ -121,6 +124,8 @@ extern uint32_t get_mcu_id(void);
|
||||
int get_mcu_desc(int max, uint8_t *revstr);
|
||||
extern int check_silicon(void);
|
||||
|
||||
int get_version(int max, uint8_t *version_str);
|
||||
|
||||
/*****************************************************************************
|
||||
* Interface in/output.
|
||||
*/
|
||||
@@ -133,4 +138,4 @@ extern void cout(uint8_t *buf, unsigned len);
|
||||
#if !defined(APP_VECTOR_OFFSET)
|
||||
# define APP_VECTOR_OFFSET 0
|
||||
#endif
|
||||
#define APP_VECTOR_OFFSET_WORDS (APP_VECTOR_OFFSET/sizeof(uint32_t))
|
||||
#define APP_VECTOR_OFFSET_WORDS (APP_VECTOR_OFFSET/sizeof(uint32_t))
|
||||
@@ -16,6 +16,7 @@
|
||||
#include "imxrt_clockconfig.h"
|
||||
|
||||
#include <nvic.h>
|
||||
#include <mpu.h>
|
||||
#include <lib/systick.h>
|
||||
#include <lib/flash_cache.h>
|
||||
|
||||
@@ -395,6 +396,24 @@ flash_func_sector_size(unsigned sector)
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* imxRT uses Flash lib, not up_progmem so let's stub it here */
|
||||
ssize_t up_progmem_ispageerased(unsigned sector)
|
||||
{
|
||||
const uint32_t bytes_per_sector = flash_func_sector_size(sector);
|
||||
uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector));
|
||||
const uint32_t uint32_per_sector = bytes_per_sector / sizeof(*address);
|
||||
|
||||
int blank = 0; /* Assume it is Bank */
|
||||
|
||||
for (uint32_t i = 0; i < uint32_per_sector; i++) {
|
||||
if (address[i] != 0xffffffff) {
|
||||
blank = -1; /* It is not blank */
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return blank;
|
||||
}
|
||||
|
||||
/*!
|
||||
* @name Configuration Option
|
||||
@@ -407,31 +426,19 @@ flash_func_sector_size(unsigned sector)
|
||||
* */
|
||||
locate_code(".ramfunc")
|
||||
void
|
||||
flash_func_erase_sector(unsigned sector)
|
||||
flash_func_erase_sector(unsigned sector, bool force)
|
||||
{
|
||||
|
||||
if (sector > BOARD_FLASH_SECTORS || (int)sector < BOARD_FIRST_FLASH_SECTOR_TO_ERASE) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* blank-check the sector */
|
||||
const uint32_t bytes_per_sector = flash_func_sector_size(sector);
|
||||
uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector));
|
||||
const uint32_t uint32_per_sector = bytes_per_sector / sizeof(*address);
|
||||
bool blank = true;
|
||||
if (force || up_progmem_ispageerased(sector) != 0) {
|
||||
|
||||
for (uint32_t i = 0; i < uint32_per_sector; i++) {
|
||||
if (address[i] != 0xffffffff) {
|
||||
blank = false;
|
||||
break;
|
||||
}
|
||||
}
|
||||
struct flexspi_nor_config_s *pConfig = &g_bootConfig;
|
||||
|
||||
const uint32_t bytes_per_sector = flash_func_sector_size(sector);
|
||||
uint32_t *address = (uint32_t *)(IMXRT_FLEXSPI1_CIPHER_BASE + (sector * bytes_per_sector));
|
||||
|
||||
struct flexspi_nor_config_s *pConfig = &g_bootConfig;
|
||||
|
||||
/* erase the sector if it failed the blank check */
|
||||
if (!blank) {
|
||||
uintptr_t offset = ((uintptr_t) address) - IMXRT_FLEXSPI1_CIPHER_BASE;
|
||||
irqstate_t flags;
|
||||
flags = enter_critical_section();
|
||||
@@ -439,8 +446,6 @@ flash_func_erase_sector(unsigned sector)
|
||||
leave_critical_section(flags);
|
||||
UNUSED(status);
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
void
|
||||
@@ -577,6 +582,21 @@ led_toggle(unsigned led)
|
||||
void
|
||||
arch_do_jump(const uint32_t *app_base)
|
||||
{
|
||||
/* The MPU configuration after booting has ITCM set to MPU_RASR_AP_RORO
|
||||
* We add this overlaping region to allow the Application to copy code into
|
||||
* the ITCM when it is booted. With CONFIG_ARM_MPU_RESET defined. The mpu
|
||||
* init will clear any added regions (after the copy)
|
||||
*/
|
||||
|
||||
mpu_configure_region(IMXRT_ITCM_BASE, 256 * 1024,
|
||||
/* Instruction access Enabled */
|
||||
MPU_RASR_AP_RWRW | /* P:RW U:RW */
|
||||
MPU_RASR_TEX_NOR /* Normal */
|
||||
/* Not Cacheable */
|
||||
/* Not Bufferable */
|
||||
/* Not Shareable */
|
||||
/* No Subregion disable */
|
||||
);
|
||||
|
||||
/* extract the stack and entrypoint from the app vector table and go */
|
||||
uint32_t stacktop = app_base[APP_VECTOR_OFFSET_WORDS];
|
||||
|
||||
@@ -466,18 +466,13 @@ flash_func_sector_size(unsigned sector)
|
||||
}
|
||||
|
||||
void
|
||||
flash_func_erase_sector(unsigned sector)
|
||||
flash_func_erase_sector(unsigned sector, bool force)
|
||||
{
|
||||
if (sector > BOARD_FLASH_SECTORS || (int)sector < BOARD_FIRST_FLASH_SECTOR_TO_ERASE) {
|
||||
return;
|
||||
}
|
||||
|
||||
/* blank-check the sector */
|
||||
|
||||
bool blank = up_progmem_ispageerased(sector) == 0;
|
||||
|
||||
/* erase the sector if it failed the blank check */
|
||||
if (!blank) {
|
||||
if (force || (up_progmem_ispageerased(sector) != 0)) {
|
||||
up_progmem_eraseblock(sector);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -83,4 +83,4 @@ add_subdirectory(srgbled)
|
||||
if (DEFINED PX4_CRYPTO)
|
||||
add_library(px4_random nuttx_random.c)
|
||||
target_link_libraries(px4_random PRIVATE nuttx_crypto)
|
||||
endif()
|
||||
endif()
|
||||
@@ -33,145 +33,454 @@
|
||||
****************************************************************************/
|
||||
#include <px4_platform_common/px4_config.h>
|
||||
#include <px4_platform_common/micro_hal.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <imxrt_flexio.h>
|
||||
#include <hardware/imxrt_flexio.h>
|
||||
#include <imxrt_periphclks.h>
|
||||
#include <px4_arch/dshot.h>
|
||||
#include <px4_arch/io_timer.h>
|
||||
#include <drivers/drv_dshot.h>
|
||||
#include <stdio.h>
|
||||
#include "barriers.h"
|
||||
|
||||
#include "arm_internal.h"
|
||||
|
||||
#define FLEXIO_BASE IMXRT_FLEXIO1_BASE
|
||||
#define FLEXIO_PREQ 120000000
|
||||
#define DSHOT_TIMERS FLEXIO_SHIFTBUFNIS_COUNT
|
||||
#define DSHOT_THROTTLE_POSITION 5u
|
||||
#define DSHOT_TELEMETRY_POSITION 4u
|
||||
#define NIBBLES_SIZE 4u
|
||||
#define DSHOT_NUMBER_OF_NIBBLES 3u
|
||||
|
||||
#if defined(IOMUX_PULL_UP_47K)
|
||||
#define IOMUX_PULL_UP IOMUX_PULL_UP_47K
|
||||
#endif
|
||||
|
||||
static const uint32_t gcr_decode[32] = {
|
||||
0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0, 0x0,
|
||||
0x0, 0x9, 0xA, 0xB, 0x0, 0xD, 0xE, 0xF,
|
||||
0x0, 0x0, 0x2, 0x3, 0x0, 0x5, 0x6, 0x7,
|
||||
0x0, 0x0, 0x8, 0x1, 0x0, 0x4, 0xC, 0x0
|
||||
};
|
||||
|
||||
uint32_t erpms[DSHOT_TIMERS];
|
||||
|
||||
typedef enum {
|
||||
DSHOT_START = 0,
|
||||
DSHOT_12BIT_FIFO,
|
||||
DSHOT_12BIT_TRANSFERRED,
|
||||
DSHOT_TRANSMIT_COMPLETE,
|
||||
BDSHOT_RECEIVE,
|
||||
BDSHOT_RECEIVE_COMPLETE,
|
||||
} dshot_state;
|
||||
|
||||
typedef struct dshot_handler_t {
|
||||
bool init;
|
||||
uint32_t data_seg1;
|
||||
uint32_t irq_data;
|
||||
dshot_state state;
|
||||
bool bdshot;
|
||||
uint32_t raw_response;
|
||||
uint16_t erpm;
|
||||
uint32_t crc_error_cnt;
|
||||
uint32_t frame_error_cnt;
|
||||
uint32_t no_response_cnt;
|
||||
uint32_t last_no_response_cnt;
|
||||
} dshot_handler_t;
|
||||
|
||||
#define BDSHOT_OFFLINE_COUNT 400 // If there are no responses for 400 setpoints ESC is offline
|
||||
|
||||
static dshot_handler_t dshot_inst[DSHOT_TIMERS] = {};
|
||||
|
||||
struct flexio_dev_s *flexio_s;
|
||||
static uint32_t dshot_tcmp;
|
||||
static uint32_t bdshot_tcmp;
|
||||
static uint32_t dshot_mask;
|
||||
static uint32_t bdshot_recv_mask;
|
||||
static uint32_t bdshot_parsed_recv_mask;
|
||||
|
||||
static inline uint32_t flexio_getreg32(uint32_t offset)
|
||||
{
|
||||
return getreg32(FLEXIO_BASE + offset);
|
||||
}
|
||||
|
||||
static inline void flexio_modifyreg32(unsigned int offset,
|
||||
uint32_t clearbits,
|
||||
uint32_t setbits)
|
||||
{
|
||||
modifyreg32(FLEXIO_BASE + offset, clearbits, setbits);
|
||||
}
|
||||
|
||||
static inline void flexio_putreg32(uint32_t value, uint32_t offset)
|
||||
{
|
||||
putreg32(value, FLEXIO_BASE + offset);
|
||||
}
|
||||
|
||||
static inline void enable_shifter_status_interrupts(uint32_t mask)
|
||||
{
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_SHIFTSIEN_OFFSET, 0, mask);
|
||||
}
|
||||
|
||||
static inline void disable_shifter_status_interrupts(uint32_t mask)
|
||||
{
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_SHIFTSIEN_OFFSET, mask, 0);
|
||||
}
|
||||
|
||||
static inline uint32_t get_shifter_status_flags(void)
|
||||
{
|
||||
return flexio_getreg32(IMXRT_FLEXIO_SHIFTSTAT_OFFSET);
|
||||
}
|
||||
|
||||
static inline void clear_shifter_status_flags(uint32_t mask)
|
||||
{
|
||||
flexio_putreg32(mask, IMXRT_FLEXIO_SHIFTSTAT_OFFSET);
|
||||
}
|
||||
|
||||
static inline void enable_timer_status_interrupts(uint32_t mask)
|
||||
{
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_TIMIEN_OFFSET, 0, mask);
|
||||
}
|
||||
|
||||
static inline void disable_timer_status_interrupts(uint32_t mask)
|
||||
{
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_TIMIEN_OFFSET, mask, 0);
|
||||
}
|
||||
|
||||
static inline uint32_t get_timer_status_flags(void)
|
||||
{
|
||||
return flexio_getreg32(IMXRT_FLEXIO_TIMSTAT_OFFSET);
|
||||
}
|
||||
|
||||
static inline void clear_timer_status_flags(uint32_t mask)
|
||||
{
|
||||
flexio_putreg32(mask, IMXRT_FLEXIO_TIMSTAT_OFFSET);
|
||||
}
|
||||
|
||||
static void flexio_dshot_output(uint32_t channel, uint32_t pin, uint32_t timcmp, bool inverted)
|
||||
{
|
||||
/* Disable Shifter */
|
||||
flexio_putreg32(0, IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
/* No start bit, stop bit low */
|
||||
flexio_putreg32(FLEXIO_SHIFTCFG_INSRC(FLEXIO_SHIFTER_INPUT_FROM_PIN) |
|
||||
FLEXIO_SHIFTCFG_PWIDTH(0) |
|
||||
FLEXIO_SHIFTCFG_SSTOP(FLEXIO_SHIFTER_STOP_BIT_LOW) |
|
||||
FLEXIO_SHIFTCFG_SSTART(FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_ENABLE),
|
||||
IMXRT_FLEXIO_SHIFTCFG0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Transmit mode, output to FXIO pin, inverted output for bdshot */
|
||||
flexio_putreg32(FLEXIO_SHIFTCTL_TIMSEL(channel) |
|
||||
FLEXIO_SHIFTCTL_TIMPOL(FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE) |
|
||||
FLEXIO_SHIFTCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT) |
|
||||
FLEXIO_SHIFTCTL_PINSEL(pin) |
|
||||
FLEXIO_SHIFTCTL_PINPOL(inverted) |
|
||||
FLEXIO_SHIFTCTL_SMOD(FLEXIO_SHIFTER_MODE_TRANSMIT),
|
||||
IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Start transmitting on trigger, disable on compare */
|
||||
flexio_putreg32(FLEXIO_TIMCFG_TIMOUT(FLEXIO_TIMER_OUTPUT_ONE_NOT_AFFECTED_BY_RESET) |
|
||||
FLEXIO_TIMCFG_TIMDEC(FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT) |
|
||||
FLEXIO_TIMCFG_TIMRST(FLEXIO_TIMER_RESET_NEVER) |
|
||||
FLEXIO_TIMCFG_TIMDIS(FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE) |
|
||||
FLEXIO_TIMCFG_TIMENA(FLEXIO_TIMER_ENABLE_ON_TRIGGER_HIGH) |
|
||||
FLEXIO_TIMCFG_TSTOP(FLEXIO_TIMER_STOP_BIT_DISABLED) |
|
||||
FLEXIO_TIMCFG_TSTART(FLEXIO_TIMER_START_BIT_DISABLED),
|
||||
IMXRT_FLEXIO_TIMCFG0_OFFSET + channel * 0x4);
|
||||
|
||||
flexio_putreg32(timcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Baud mode, Trigger on shifter write */
|
||||
flexio_putreg32(FLEXIO_TIMCTL_TRGSEL((4 * channel) + 1) |
|
||||
FLEXIO_TIMCTL_TRGPOL(FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_LOW) |
|
||||
FLEXIO_TIMCTL_TRGSRC(FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL) |
|
||||
FLEXIO_TIMCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) |
|
||||
FLEXIO_TIMCTL_PINSEL(0) |
|
||||
FLEXIO_TIMCTL_PINPOL(FLEXIO_PIN_ACTIVE_LOW) |
|
||||
FLEXIO_TIMCTL_TIMOD(FLEXIO_TIMER_MODE_DUAL8_BIT_BAUD_BIT),
|
||||
IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
}
|
||||
|
||||
static int flexio_irq_handler(int irq, void *context, void *arg)
|
||||
{
|
||||
uint32_t flags = get_shifter_status_flags();
|
||||
uint32_t channel;
|
||||
|
||||
uint32_t flags = flexio_s->ops->get_shifter_status_flags(flexio_s);
|
||||
uint32_t instance;
|
||||
for (channel = 0; flags && channel < DSHOT_TIMERS; channel++) {
|
||||
if (flags & (1 << channel)) {
|
||||
disable_shifter_status_interrupts(1 << channel);
|
||||
|
||||
for (instance = 0; flags && instance < DSHOT_TIMERS; instance++) {
|
||||
if (flags & (1 << instance)) {
|
||||
flexio_s->ops->disable_shifter_status_interrupts(flexio_s, (1 << instance));
|
||||
flexio_s->ops->disable_timer_status_interrupts(flexio_s, (1 << instance));
|
||||
if (dshot_inst[channel].state == DSHOT_START) {
|
||||
dshot_inst[channel].state = DSHOT_12BIT_FIFO;
|
||||
flexio_putreg32(dshot_inst[channel].irq_data, IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4);
|
||||
|
||||
if (dshot_inst[instance].irq_data != 0) {
|
||||
uint32_t buf_adr = flexio_s->ops->get_shifter_buffer_address(flexio_s, FLEXIO_SHIFTER_BUFFER, instance);
|
||||
putreg32(dshot_inst[instance].irq_data, IMXRT_FLEXIO1_BASE + buf_adr);
|
||||
dshot_inst[instance].irq_data = 0;
|
||||
} else if (dshot_inst[channel].state == BDSHOT_RECEIVE) {
|
||||
dshot_inst[channel].state = BDSHOT_RECEIVE_COMPLETE;
|
||||
dshot_inst[channel].raw_response = flexio_getreg32(IMXRT_FLEXIO_SHIFTBUFBIS0_OFFSET + channel * 0x4);
|
||||
|
||||
bdshot_recv_mask |= (1 << channel);
|
||||
|
||||
if (bdshot_recv_mask == dshot_mask) {
|
||||
// Received telemetry on all channels
|
||||
// Schedule workqueue?
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
flags = get_timer_status_flags();
|
||||
|
||||
for (channel = 0; flags; (channel = (channel + 1) % DSHOT_TIMERS)) {
|
||||
flags = get_timer_status_flags();
|
||||
|
||||
if (flags & (1 << channel)) {
|
||||
clear_timer_status_flags(1 << channel);
|
||||
|
||||
if (dshot_inst[channel].state == DSHOT_12BIT_FIFO) {
|
||||
dshot_inst[channel].state = DSHOT_12BIT_TRANSFERRED;
|
||||
|
||||
} else if (!dshot_inst[channel].bdshot && dshot_inst[channel].state == DSHOT_12BIT_TRANSFERRED) {
|
||||
dshot_inst[channel].state = DSHOT_TRANSMIT_COMPLETE;
|
||||
|
||||
} else if (dshot_inst[channel].bdshot && dshot_inst[channel].state == DSHOT_12BIT_TRANSFERRED) {
|
||||
disable_shifter_status_interrupts(1 << channel);
|
||||
dshot_inst[channel].state = BDSHOT_RECEIVE;
|
||||
|
||||
/* Transmit done, disable timer and reconfigure to receive*/
|
||||
flexio_putreg32(0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Input data from pin, no start/stop bit*/
|
||||
flexio_putreg32(FLEXIO_SHIFTCFG_INSRC(FLEXIO_SHIFTER_INPUT_FROM_PIN) |
|
||||
FLEXIO_SHIFTCFG_PWIDTH(0) |
|
||||
FLEXIO_SHIFTCFG_SSTOP(FLEXIO_SHIFTER_STOP_BIT_DISABLE) |
|
||||
FLEXIO_SHIFTCFG_SSTART(FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_SHIFT),
|
||||
IMXRT_FLEXIO_SHIFTCFG0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Shifter receive mdoe, on FXIO pin input */
|
||||
flexio_putreg32(FLEXIO_SHIFTCTL_TIMSEL(channel) |
|
||||
FLEXIO_SHIFTCTL_TIMPOL(FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE) |
|
||||
FLEXIO_SHIFTCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) |
|
||||
FLEXIO_SHIFTCTL_PINSEL(timer_io_channels[channel].dshot.flexio_pin) |
|
||||
FLEXIO_SHIFTCTL_PINPOL(FLEXIO_PIN_ACTIVE_LOW) |
|
||||
FLEXIO_SHIFTCTL_SMOD(FLEXIO_SHIFTER_MODE_RECEIVE),
|
||||
IMXRT_FLEXIO_SHIFTCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Make sure there no shifter flags high from transmission */
|
||||
clear_shifter_status_flags(1 << channel);
|
||||
|
||||
/* Enable on pin transition, resychronize through reset on rising edge */
|
||||
flexio_putreg32(FLEXIO_TIMCFG_TIMOUT(FLEXIO_TIMER_OUTPUT_ONE_AFFECTED_BY_RESET) |
|
||||
FLEXIO_TIMCFG_TIMDEC(FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT) |
|
||||
FLEXIO_TIMCFG_TIMRST(FLEXIO_TIMER_RESET_ON_TIMER_PIN_RISING_EDGE) |
|
||||
FLEXIO_TIMCFG_TIMDIS(FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE) |
|
||||
FLEXIO_TIMCFG_TIMENA(FLEXIO_TIMER_ENABLE_ON_TRIGGER_BOTH_EDGE) |
|
||||
FLEXIO_TIMCFG_TSTOP(FLEXIO_TIMER_STOP_BIT_ENABLE_ON_TIMER_DISABLE) |
|
||||
FLEXIO_TIMCFG_TSTART(FLEXIO_TIMER_START_BIT_ENABLED),
|
||||
IMXRT_FLEXIO_TIMCFG0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Enable on pin transition, resychronize through reset on rising edge */
|
||||
flexio_putreg32(bdshot_tcmp, IMXRT_FLEXIO_TIMCMP0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Trigger on FXIO pin transition, Baud mode */
|
||||
flexio_putreg32(FLEXIO_TIMCTL_TRGSEL(2 * timer_io_channels[channel].dshot.flexio_pin) |
|
||||
FLEXIO_TIMCTL_TRGPOL(FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_HIGH) |
|
||||
FLEXIO_TIMCTL_TRGSRC(FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL) |
|
||||
FLEXIO_TIMCTL_PINCFG(FLEXIO_PIN_CONFIG_OUTPUT_DISABLED) |
|
||||
FLEXIO_TIMCTL_PINSEL(0) |
|
||||
FLEXIO_TIMCTL_PINPOL(FLEXIO_PIN_ACTIVE_LOW) |
|
||||
FLEXIO_TIMCTL_TIMOD(FLEXIO_TIMER_MODE_DUAL8_BIT_BAUD_BIT),
|
||||
IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
|
||||
|
||||
/* Enable shifter interrupt for receiving data */
|
||||
enable_shifter_status_interrupts(1 << channel);
|
||||
}
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
return OK;
|
||||
}
|
||||
|
||||
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq)
|
||||
|
||||
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot)
|
||||
{
|
||||
uint32_t timer_compare;
|
||||
/* Calculate dshot timings based on dshot_pwm_freq */
|
||||
dshot_tcmp = 0x2F00 | (((FLEXIO_PREQ / (dshot_pwm_freq * 3) / 2)) & 0xFF);
|
||||
bdshot_tcmp = 0x2900 | (((FLEXIO_PREQ / (dshot_pwm_freq * 5 / 4) / 2) - 1) & 0xFF);
|
||||
|
||||
if (dshot_pwm_freq == 150000) {
|
||||
timer_compare = 0x2F8A;
|
||||
/* Clock FlexIO peripheral */
|
||||
imxrt_clockall_flexio1();
|
||||
|
||||
} else if (dshot_pwm_freq == 300000) {
|
||||
timer_compare = 0x2F45;
|
||||
/* Reset FlexIO peripheral */
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET, 0,
|
||||
FLEXIO_CTRL_SWRST_MASK);
|
||||
flexio_putreg32(0, IMXRT_FLEXIO_CTRL_OFFSET);
|
||||
|
||||
} else if (dshot_pwm_freq == 600000) {
|
||||
timer_compare = 0x2F22;
|
||||
/* Initialize FlexIO peripheral */
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET,
|
||||
(FLEXIO_CTRL_DOZEN_MASK |
|
||||
FLEXIO_CTRL_DBGE_MASK |
|
||||
FLEXIO_CTRL_FASTACC_MASK |
|
||||
FLEXIO_CTRL_FLEXEN_MASK),
|
||||
(FLEXIO_CTRL_DBGE(1) |
|
||||
FLEXIO_CTRL_FASTACC(1) |
|
||||
FLEXIO_CTRL_FLEXEN(0)));
|
||||
|
||||
} else if (dshot_pwm_freq == 1200000) {
|
||||
timer_compare = 0x2F11;
|
||||
|
||||
} else {
|
||||
// Not supported Dshot frequency
|
||||
return 0;
|
||||
}
|
||||
|
||||
/* Init FlexIO peripheral */
|
||||
|
||||
flexio_s = imxrt_flexio_initialize(1);
|
||||
/* FlexIO IRQ handling */
|
||||
up_enable_irq(IMXRT_IRQ_FLEXIO1);
|
||||
irq_attach(IMXRT_IRQ_FLEXIO1, flexio_irq_handler, flexio_s);
|
||||
irq_attach(IMXRT_IRQ_FLEXIO1, flexio_irq_handler, 0);
|
||||
|
||||
dshot_mask = 0x0;
|
||||
|
||||
for (unsigned channel = 0; (channel_mask != 0) && (channel < DSHOT_TIMERS); channel++) {
|
||||
if (channel_mask & (1 << channel)) {
|
||||
uint8_t timer = timer_io_channels[channel].timer_index;
|
||||
|
||||
if (io_timers[timer].dshot.pinmux == 0) { // board does not configure dshot on this pin
|
||||
if (timer_io_channels[channel].dshot.pinmux == 0) { // board does not configure dshot on this pin
|
||||
continue;
|
||||
}
|
||||
|
||||
imxrt_config_gpio(io_timers[timer].dshot.pinmux);
|
||||
imxrt_config_gpio(timer_io_channels[channel].dshot.pinmux | IOMUX_PULL_UP);
|
||||
|
||||
struct flexio_shifter_config_s shft_cfg;
|
||||
shft_cfg.timer_select = channel;
|
||||
shft_cfg.timer_polarity = FLEXIO_SHIFTER_TIMER_POLARITY_ON_POSITIVE;
|
||||
shft_cfg.pin_config = FLEXIO_PIN_CONFIG_OUTPUT;
|
||||
shft_cfg.pin_select = io_timers[timer].dshot.flexio_pin;
|
||||
shft_cfg.pin_polarity = FLEXIO_PIN_ACTIVE_HIGH;
|
||||
shft_cfg.shifter_mode = FLEXIO_SHIFTER_MODE_TRANSMIT;
|
||||
shft_cfg.parallel_width = 0;
|
||||
shft_cfg.input_source = FLEXIO_SHIFTER_INPUT_FROM_PIN;
|
||||
shft_cfg.shifter_stop = FLEXIO_SHIFTER_STOP_BIT_LOW;
|
||||
shft_cfg.shifter_start = FLEXIO_SHIFTER_START_BIT_DISABLED_LOAD_DATA_ON_ENABLE;
|
||||
dshot_inst[channel].bdshot = enable_bidirectional_dshot;
|
||||
|
||||
flexio_s->ops->set_shifter_config(flexio_s, channel, &shft_cfg);
|
||||
|
||||
struct flexio_timer_config_s tmr_cfg;
|
||||
tmr_cfg.trigger_select = (4 * channel) + 1;
|
||||
tmr_cfg.trigger_polarity = FLEXIO_TIMER_TRIGGER_POLARITY_ACTIVE_LOW;
|
||||
tmr_cfg.trigger_source = FLEXIO_TIMER_TRIGGER_SOURCE_INTERNAL;
|
||||
tmr_cfg.pin_config = FLEXIO_PIN_CONFIG_OUTPUT_DISABLED;
|
||||
tmr_cfg.pin_select = 0;
|
||||
tmr_cfg.pin_polarity = FLEXIO_PIN_ACTIVE_LOW;
|
||||
tmr_cfg.timer_mode = FLEXIO_TIMER_MODE_DUAL8_BIT_BAUD_BIT;
|
||||
tmr_cfg.timer_output = FLEXIO_TIMER_OUTPUT_ONE_NOT_AFFECTED_BY_RESET;
|
||||
tmr_cfg.timer_decrement = FLEXIO_TIMER_DEC_SRC_ON_FLEX_IO_CLOCK_SHIFT_TIMER_OUTPUT;
|
||||
tmr_cfg.timer_reset = FLEXIO_TIMER_RESET_NEVER;
|
||||
tmr_cfg.timer_disable = FLEXIO_TIMER_DISABLE_ON_TIMER_COMPARE;
|
||||
tmr_cfg.timer_enable = FLEXIO_TIMER_ENABLE_ON_TRIGGER_HIGH;
|
||||
tmr_cfg.timer_stop = FLEXIO_TIMER_STOP_BIT_DISABLED;
|
||||
tmr_cfg.timer_start = FLEXIO_TIMER_START_BIT_DISABLED;
|
||||
tmr_cfg.timer_compare = timer_compare;
|
||||
flexio_s->ops->set_timer_config(flexio_s, channel, &tmr_cfg);
|
||||
flexio_dshot_output(channel, timer_io_channels[channel].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot);
|
||||
|
||||
dshot_inst[channel].init = true;
|
||||
|
||||
// Mask channel to be active on dshot
|
||||
dshot_mask |= (1 << channel);
|
||||
}
|
||||
}
|
||||
|
||||
flexio_s->ops->enable(flexio_s, true);
|
||||
flexio_modifyreg32(IMXRT_FLEXIO_CTRL_OFFSET, 0,
|
||||
FLEXIO_CTRL_FLEXEN_MASK);
|
||||
|
||||
return channel_mask;
|
||||
}
|
||||
|
||||
void up_bdshot_erpm(void)
|
||||
{
|
||||
uint32_t value;
|
||||
uint32_t data;
|
||||
uint32_t csum_data;
|
||||
uint8_t exponent;
|
||||
uint16_t period;
|
||||
uint16_t erpm;
|
||||
|
||||
bdshot_parsed_recv_mask = 0;
|
||||
|
||||
// Decode each individual channel
|
||||
for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) {
|
||||
if (bdshot_recv_mask & (1 << channel)) {
|
||||
value = ~dshot_inst[channel].raw_response & 0xFFFFF;
|
||||
|
||||
/* if lowest significant isn't 1 we've got a framing error */
|
||||
if (value & 0x1) {
|
||||
/* Decode RLL */
|
||||
value = (value ^ (value >> 1));
|
||||
|
||||
/* Decode GCR */
|
||||
data = gcr_decode[value & 0x1fU];
|
||||
data |= gcr_decode[(value >> 5U) & 0x1fU] << 4U;
|
||||
data |= gcr_decode[(value >> 10U) & 0x1fU] << 8U;
|
||||
data |= gcr_decode[(value >> 15U) & 0x1fU] << 12U;
|
||||
|
||||
/* Calculate checksum */
|
||||
csum_data = data;
|
||||
csum_data = csum_data ^ (csum_data >> 8U);
|
||||
csum_data = csum_data ^ (csum_data >> NIBBLES_SIZE);
|
||||
|
||||
if ((csum_data & 0xFU) != 0xFU) {
|
||||
dshot_inst[channel].crc_error_cnt++;
|
||||
|
||||
} else {
|
||||
data = (data >> 4) & 0xFFF;
|
||||
|
||||
if (data == 0xFFF) {
|
||||
erpm = 0;
|
||||
|
||||
} else {
|
||||
exponent = ((data >> 9U) & 0x7U); /* 3 bit: exponent */
|
||||
period = (data & 0x1ffU); /* 9 bit: period base */
|
||||
period = period << exponent; /* Period in usec */
|
||||
erpm = ((1000000U * 60U / 100U + period / 2U) / period);
|
||||
}
|
||||
|
||||
dshot_inst[channel].erpm = erpm;
|
||||
bdshot_parsed_recv_mask |= (1 << channel);
|
||||
dshot_inst[channel].last_no_response_cnt = dshot_inst[channel].no_response_cnt;
|
||||
}
|
||||
|
||||
} else {
|
||||
dshot_inst[channel].frame_error_cnt++;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
|
||||
int up_bdshot_get_erpm(uint8_t channel, int *erpm)
|
||||
{
|
||||
if (bdshot_parsed_recv_mask & (1 << channel)) {
|
||||
*erpm = (int)dshot_inst[channel].erpm;
|
||||
return 0;
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
int up_bdshot_channel_status(uint8_t channel)
|
||||
{
|
||||
if (channel < DSHOT_TIMERS) {
|
||||
return ((dshot_inst[channel].no_response_cnt - dshot_inst[channel].last_no_response_cnt) < BDSHOT_OFFLINE_COUNT);
|
||||
}
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
void up_bdshot_status(void)
|
||||
{
|
||||
|
||||
for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) {
|
||||
|
||||
if (dshot_inst[channel].init) {
|
||||
PX4_INFO("Channel %i %s Last erpm %i value", channel, up_bdshot_channel_status(channel) ? "online" : "offline",
|
||||
dshot_inst[channel].erpm);
|
||||
PX4_INFO("CRC errors Frame error No response");
|
||||
PX4_INFO("%10lu %11lu %11lu", dshot_inst[channel].crc_error_cnt, dshot_inst[channel].frame_error_cnt,
|
||||
dshot_inst[channel].no_response_cnt);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void up_dshot_trigger(void)
|
||||
{
|
||||
uint32_t buf_adr;
|
||||
// Calc data now since we're not event driven
|
||||
if (bdshot_recv_mask != 0x0) {
|
||||
up_bdshot_erpm();
|
||||
}
|
||||
|
||||
for (uint8_t motor_number = 0; (motor_number < DSHOT_TIMERS); motor_number++) {
|
||||
if (dshot_inst[motor_number].init && dshot_inst[motor_number].data_seg1 != 0) {
|
||||
buf_adr = flexio_s->ops->get_shifter_buffer_address(flexio_s, FLEXIO_SHIFTER_BUFFER, motor_number);
|
||||
putreg32(dshot_inst[motor_number].data_seg1, IMXRT_FLEXIO1_BASE + buf_adr);
|
||||
clear_timer_status_flags(0xFF);
|
||||
|
||||
for (uint8_t channel = 0; (channel < DSHOT_TIMERS); channel++) {
|
||||
if (dshot_inst[channel].bdshot && (bdshot_recv_mask & (1 << channel)) == 0) {
|
||||
dshot_inst[channel].no_response_cnt++;
|
||||
}
|
||||
|
||||
if (dshot_inst[channel].init && dshot_inst[channel].data_seg1 != 0) {
|
||||
flexio_putreg32(dshot_inst[channel].data_seg1, IMXRT_FLEXIO_SHIFTBUF0_OFFSET + channel * 0x4);
|
||||
}
|
||||
}
|
||||
|
||||
flexio_s->ops->clear_timer_status_flags(flexio_s, 0xFF);
|
||||
flexio_s->ops->enable_shifter_status_interrupts(flexio_s, 0xFF);
|
||||
bdshot_recv_mask = 0x0;
|
||||
|
||||
clear_timer_status_flags(0xFF);
|
||||
enable_shifter_status_interrupts(0xFF);
|
||||
enable_timer_status_interrupts(0xFF);
|
||||
}
|
||||
|
||||
/* Expand packet from 16 bits 48 to get T0H and T1H timing */
|
||||
uint64_t dshot_expand_data(uint16_t packet)
|
||||
{
|
||||
unsigned int mask;
|
||||
@@ -197,16 +506,22 @@ uint64_t dshot_expand_data(uint16_t packet)
|
||||
* bit 12 - dshot telemetry enable/disable
|
||||
* bits 13-16 - XOR checksum
|
||||
**/
|
||||
void dshot_motor_data_set(unsigned motor_number, uint16_t throttle, bool telemetry)
|
||||
void dshot_motor_data_set(unsigned channel, uint16_t throttle, bool telemetry)
|
||||
{
|
||||
if (motor_number < DSHOT_TIMERS && dshot_inst[motor_number].init) {
|
||||
if (channel < DSHOT_TIMERS && dshot_inst[channel].init) {
|
||||
uint16_t csum_data;
|
||||
uint16_t packet = 0;
|
||||
uint16_t checksum = 0;
|
||||
|
||||
packet |= throttle << DSHOT_THROTTLE_POSITION;
|
||||
packet |= ((uint16_t)telemetry & 0x01) << DSHOT_TELEMETRY_POSITION;
|
||||
|
||||
uint16_t csum_data = packet;
|
||||
if (dshot_inst[channel].bdshot) {
|
||||
csum_data = ~packet;
|
||||
|
||||
} else {
|
||||
csum_data = packet;
|
||||
}
|
||||
|
||||
/* XOR checksum calculation */
|
||||
csum_data >>= NIBBLES_SIZE;
|
||||
@@ -219,8 +534,20 @@ void dshot_motor_data_set(unsigned motor_number, uint16_t throttle, bool telemet
|
||||
packet |= (checksum & 0x0F);
|
||||
|
||||
uint64_t dshot_expanded = dshot_expand_data(packet);
|
||||
dshot_inst[motor_number].data_seg1 = (uint32_t)(dshot_expanded & 0xFFFFFF);
|
||||
dshot_inst[motor_number].irq_data = (uint32_t)(dshot_expanded >> 24);
|
||||
|
||||
dshot_inst[channel].data_seg1 = (uint32_t)(dshot_expanded & 0xFFFFFF);
|
||||
dshot_inst[channel].irq_data = (uint32_t)(dshot_expanded >> 24);
|
||||
dshot_inst[channel].state = DSHOT_START;
|
||||
|
||||
if (dshot_inst[channel].bdshot) {
|
||||
|
||||
flexio_putreg32(0x0, IMXRT_FLEXIO_TIMCTL0_OFFSET + channel * 0x4);
|
||||
disable_shifter_status_interrupts(1 << channel);
|
||||
|
||||
flexio_dshot_output(channel, timer_io_channels[channel].dshot.flexio_pin, dshot_tcmp, dshot_inst[channel].bdshot);
|
||||
|
||||
clear_timer_status_flags(0xFF);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -87,7 +87,6 @@ typedef struct io_timers_t {
|
||||
uint32_t clock_register; /* SIM_SCGCn */
|
||||
uint32_t clock_bit; /* SIM_SCGCn bit pos */
|
||||
uint32_t vectorno; /* IRQ number */
|
||||
dshot_conf_t dshot;
|
||||
} io_timers_t;
|
||||
|
||||
typedef struct io_timers_channel_mapping_element_t {
|
||||
@@ -112,6 +111,7 @@ typedef struct timer_io_channels_t {
|
||||
uint8_t sub_module; /* 0 based sub module offset */
|
||||
uint8_t sub_module_bits; /* LDOK and CLDOK bits */
|
||||
uint8_t timer_channel; /* Unused */
|
||||
dshot_conf_t dshot;
|
||||
} timer_io_channels_t;
|
||||
|
||||
#define SM0 0
|
||||
|
||||
@@ -36,7 +36,7 @@ add_subdirectory(../imxrt/adc adc)
|
||||
add_subdirectory(../imxrt/board_critmon board_critmon)
|
||||
add_subdirectory(../imxrt/board_hw_info board_hw_info)
|
||||
add_subdirectory(../imxrt/board_reset board_reset)
|
||||
#add_subdirectory(../imxrt/dshot dshot)
|
||||
add_subdirectory(../imxrt/dshot dshot)
|
||||
add_subdirectory(../imxrt/hrt hrt)
|
||||
add_subdirectory(../imxrt/led_pwm led_pwm)
|
||||
add_subdirectory(../imxrt/io_pins io_pins)
|
||||
|
||||
@@ -0,0 +1,36 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 "../../../imxrt/include/px4_arch/dshot.h"
|
||||
@@ -41,6 +41,7 @@
|
||||
#include <nuttx/irq.h>
|
||||
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include "dshot.h"
|
||||
|
||||
#pragma once
|
||||
__BEGIN_DECLS
|
||||
@@ -110,6 +111,7 @@ typedef struct timer_io_channels_t {
|
||||
uint8_t sub_module; /* 0 based sub module offset */
|
||||
uint8_t sub_module_bits; /* LDOK and CLDOK bits */
|
||||
uint8_t timer_channel; /* Unused */
|
||||
dshot_conf_t dshot;
|
||||
} timer_io_channels_t;
|
||||
|
||||
#define SM0 0
|
||||
|
||||
@@ -601,6 +601,16 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t
|
||||
return ret;
|
||||
}
|
||||
|
||||
static inline constexpr timer_io_channels_t initIOTimerChannelDshot(const io_timers_t io_timers_conf[MAX_IO_TIMERS],
|
||||
PWM::FlexPWMConfig pwm_config, IOMUX::Pad pad, uint32_t dshot_pinmux, uint32_t flexio_pin)
|
||||
{
|
||||
timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, pwm_config, pad);
|
||||
|
||||
ret.dshot.pinmux = dshot_pinmux;
|
||||
ret.dshot.flexio_pin = flexio_pin;
|
||||
return ret;
|
||||
}
|
||||
|
||||
static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub)
|
||||
{
|
||||
io_timers_t ret{};
|
||||
@@ -609,3 +619,14 @@ static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubm
|
||||
ret.submodle = sub;
|
||||
return ret;
|
||||
}
|
||||
|
||||
|
||||
|
||||
static inline constexpr io_timers_t initIOPWMDshot(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub)
|
||||
{
|
||||
io_timers_t ret{};
|
||||
|
||||
ret.base = getFlexPWMBaseRegister(pwm);
|
||||
ret.submodle = sub;
|
||||
return ret;
|
||||
}
|
||||
|
||||
@@ -690,6 +690,16 @@ static inline constexpr timer_io_channels_t initIOTimerChannel(const io_timers_t
|
||||
return ret;
|
||||
}
|
||||
|
||||
static inline constexpr timer_io_channels_t initIOTimerChannelDshot(const io_timers_t io_timers_conf[MAX_IO_TIMERS],
|
||||
PWM::FlexPWMConfig pwm_config, IOMUX::Pad pad, uint32_t dshot_pinmux, uint32_t flexio_pin)
|
||||
{
|
||||
timer_io_channels_t ret = initIOTimerChannel(io_timers_conf, pwm_config, pad);
|
||||
|
||||
ret.dshot.pinmux = dshot_pinmux;
|
||||
ret.dshot.flexio_pin = flexio_pin;
|
||||
return ret;
|
||||
}
|
||||
|
||||
static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub)
|
||||
{
|
||||
io_timers_t ret{};
|
||||
@@ -699,14 +709,13 @@ static inline constexpr io_timers_t initIOPWM(PWM::FlexPWM pwm, PWM::FlexPWMSubm
|
||||
return ret;
|
||||
}
|
||||
|
||||
static inline constexpr io_timers_t initIOPWMDshot(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub, uint32_t pinmux,
|
||||
uint32_t flexio_pin)
|
||||
|
||||
|
||||
static inline constexpr io_timers_t initIOPWMDshot(PWM::FlexPWM pwm, PWM::FlexPWMSubmodule sub)
|
||||
{
|
||||
io_timers_t ret{};
|
||||
|
||||
ret.base = getFlexPWMBaseRegister(pwm);
|
||||
ret.submodle = sub;
|
||||
ret.dshot.pinmux = pinmux;
|
||||
ret.dshot.flexio_pin = flexio_pin;
|
||||
return ret;
|
||||
}
|
||||
|
||||
@@ -82,7 +82,7 @@ static uint8_t dshot_burst_buffer_array[DSHOT_TIMERS * DSHOT_BURST_BUFFER_SIZE(M
|
||||
px4_cache_aligned_data() = {};
|
||||
static uint32_t *dshot_burst_buffer[DSHOT_TIMERS] = {};
|
||||
|
||||
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq)
|
||||
int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot)
|
||||
{
|
||||
unsigned buffer_offset = 0;
|
||||
|
||||
@@ -152,6 +152,22 @@ int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq)
|
||||
return ret_val == OK ? channels_init_mask : ret_val;
|
||||
}
|
||||
|
||||
int up_bdshot_get_erpm(uint8_t channel, int *erpm)
|
||||
{
|
||||
// Not implemented
|
||||
return -1;
|
||||
}
|
||||
|
||||
int up_bdshot_channel_status(uint8_t channel)
|
||||
{
|
||||
// Not implemented
|
||||
return -1;
|
||||
}
|
||||
|
||||
void up_bdshot_status(void)
|
||||
{
|
||||
}
|
||||
|
||||
void up_dshot_trigger(void)
|
||||
{
|
||||
for (uint8_t timer = 0; (timer < DSHOT_TIMERS); timer++) {
|
||||
|
||||
@@ -44,6 +44,7 @@ include_directories(
|
||||
|
||||
add_library(px4 SHARED
|
||||
${PX4_SOURCE_DIR}/platforms/qurt/unresolved_symbols.c
|
||||
${PX4_SOURCE_DIR}/platforms/qurt/new_delete.cpp
|
||||
${PX4_BINARY_DIR}/apps.cpp
|
||||
)
|
||||
|
||||
|
||||
@@ -0,0 +1,92 @@
|
||||
#include <stdlib.h>
|
||||
#include <new>
|
||||
|
||||
/*
|
||||
These are the heap access function exported by the SLPI DSP image.
|
||||
*/
|
||||
extern "C" {
|
||||
void *fc_heap_alloc(size_t size);
|
||||
void fc_heap_free(void *ptr);
|
||||
}
|
||||
|
||||
/*
|
||||
Globally override new and delete so that it can use the correct
|
||||
heap manager for the Qurt platform.
|
||||
|
||||
Note that new comes in multiple different variants. When new is used
|
||||
without std::nothrow the compiler is free to assume it will not fail
|
||||
as it assumes exceptions are enabled. This makes code like this
|
||||
unsafe when using -fno-exceptions:
|
||||
|
||||
a = new b;
|
||||
if (a == nullptr) {
|
||||
handle_error()
|
||||
}
|
||||
|
||||
The compiler may remove the error handling. With g++ you can use
|
||||
-fcheck-new to avoid this, but on clang++ the compiler accepts
|
||||
-fcheck-new as a valid flag, but doesn't implement it, and may remove
|
||||
the error checking. That makes using clang++ unsafe with
|
||||
-fno-exceptions if you ever call new without std::nothrow.
|
||||
..It has been verified that hexagon-clang++ will remove the nullptr checks
|
||||
after new if any optimization is selected for the compiler.
|
||||
*/
|
||||
|
||||
/*
|
||||
variant for new(std::nothrow), which is all that should be used in
|
||||
PX4
|
||||
*/
|
||||
void *operator new (size_t size, std::nothrow_t const ¬hrow) noexcept
|
||||
{
|
||||
if (size < 1) {
|
||||
size = 1;
|
||||
}
|
||||
|
||||
return (fc_heap_alloc(size));
|
||||
}
|
||||
|
||||
void *operator new[](size_t size, std::nothrow_t const ¬hrow) noexcept
|
||||
{
|
||||
if (size < 1) {
|
||||
size = 1;
|
||||
}
|
||||
|
||||
return (fc_heap_alloc(size));
|
||||
}
|
||||
|
||||
/*
|
||||
These variants are for new without std::nothrow. We don't want to ever
|
||||
use these from PX4 code
|
||||
*/
|
||||
void *operator new (size_t size)
|
||||
{
|
||||
if (size < 1) {
|
||||
size = 1;
|
||||
}
|
||||
|
||||
return (fc_heap_alloc(size));
|
||||
}
|
||||
|
||||
|
||||
void *operator new[](size_t size)
|
||||
{
|
||||
if (size < 1) {
|
||||
size = 1;
|
||||
}
|
||||
|
||||
return (fc_heap_alloc(size));
|
||||
}
|
||||
|
||||
/*
|
||||
Override delete to free up memory to correct heap
|
||||
*/
|
||||
|
||||
void operator delete (void *p) noexcept
|
||||
{
|
||||
if (p) { fc_heap_free(p); }
|
||||
}
|
||||
|
||||
void operator delete[](void *ptr) noexcept
|
||||
{
|
||||
if (ptr) { fc_heap_free(ptr); }
|
||||
}
|
||||
@@ -53,6 +53,7 @@
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <matrix/math.hpp>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <px4_platform_common/module.h>
|
||||
#include <systemlib/err.h>
|
||||
#include <parameters/param.h>
|
||||
|
||||
@@ -924,7 +925,45 @@ CameraTrigger::status()
|
||||
|
||||
static int usage()
|
||||
{
|
||||
PX4_INFO("usage: camera_trigger {start|stop|status|test|test_power}\n");
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
|
||||
Camera trigger driver.
|
||||
|
||||
This module triggers cameras that are connected to the flight-controller outputs,
|
||||
or simple MAVLink cameras that implement the MAVLink trigger protocol.
|
||||
|
||||
The driver responds to the following MAVLink trigger commands being found in missions or recieved over MAVLink:
|
||||
|
||||
- `MAV_CMD_DO_TRIGGER_CONTROL`
|
||||
- `MAV_CMD_DO_DIGICAM_CONTROL`
|
||||
- `MAV_CMD_DO_SET_CAM_TRIGG_DIST`
|
||||
- `MAV_CMD_OBLIQUE_SURVEY`
|
||||
|
||||
The commands cause the driver to trigger camera image capture based on time or distance.
|
||||
Each time an image capture is triggered, the `CAMERA_TRIGGER` MAVLink message is emitted.
|
||||
|
||||
A "simple MAVLink camera" is one that supports the above command set.
|
||||
When configured for this kind of camera, all the driver does is emit the `CAMERA_TRIGGER` MAVLink message as expected.
|
||||
The incoming commands must be forwarded to the MAVLink camera, and are automatically emitted to MAVLink channels
|
||||
when found in missions.
|
||||
|
||||
The driver is configured using [Camera Trigger parameters](../advanced_config/parameter_reference.md#camera-trigger).
|
||||
In particular:
|
||||
|
||||
- `TRIG_INTERFACE` - How the camera is connected to flight controller (PWM, GPIO, Seagull, MAVLink)
|
||||
- `TRIG_MODE` - Distance or time based triggering, with values set by `TRIG_DISTANCE` and `TRIG_INTERVAL`.
|
||||
|
||||
[Setup/usage information](../camera/index.md).
|
||||
)DESCR_STR");
|
||||
PRINT_MODULE_USAGE_NAME("camera_trigger", "driver");
|
||||
PRINT_MODULE_USAGE_SUBCATEGORY("camera");
|
||||
PRINT_MODULE_USAGE_COMMAND("start");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("stop","Stop driver");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("status","Print driver status information");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("test","Trigger one image (not logged or forwarded to GCS)");
|
||||
PRINT_MODULE_USAGE_COMMAND_DESCR("test_power","Toggle power");
|
||||
return 1;
|
||||
}
|
||||
|
||||
|
||||
@@ -39,8 +39,7 @@
|
||||
|
||||
#include <parameters/param.h>
|
||||
#include <px4_platform_common/log.h>
|
||||
|
||||
#define arraySize(a) (sizeof((a))/sizeof(((a)[0])))
|
||||
#include <systemlib/px4_macros.h>
|
||||
|
||||
class CameraInterface
|
||||
{
|
||||
|
||||
@@ -206,7 +206,8 @@ void CdcAcmAutostart::state_connecting()
|
||||
|
||||
if (_ttyacm_fd < 0) {
|
||||
PX4_DEBUG("can't open port");
|
||||
goto fail;
|
||||
// fail silently and keep trying to open the port
|
||||
return;
|
||||
}
|
||||
|
||||
if (_sys_usb_auto.get() == 2) {
|
||||
|
||||
+25
-1
@@ -91,7 +91,7 @@ typedef enum {
|
||||
* @param dshot_pwm_freq Frequency of DSHOT signal. Usually DSHOT150, DSHOT300, DSHOT600 or DSHOT1200
|
||||
* @return <0 on error, the initialized channels mask.
|
||||
*/
|
||||
__EXPORT extern int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq);
|
||||
__EXPORT extern int up_dshot_init(uint32_t channel_mask, unsigned dshot_pwm_freq, bool enable_bidirectional_dshot);
|
||||
|
||||
/**
|
||||
* Set Dshot motor data, used by up_dshot_motor_data_set() and up_dshot_motor_command() (internal method)
|
||||
@@ -137,4 +137,28 @@ __EXPORT extern void up_dshot_trigger(void);
|
||||
*/
|
||||
__EXPORT extern int up_dshot_arm(bool armed);
|
||||
|
||||
/**
|
||||
* Print bidrectional dshot status
|
||||
*/
|
||||
__EXPORT extern void up_bdshot_status(void);
|
||||
|
||||
|
||||
/**
|
||||
* Get bidrectional dshot erpm for a channel
|
||||
* @param channel Dshot channel
|
||||
* @param erpm pointer to write the erpm value
|
||||
* @return <0 on error, OK on succes
|
||||
*/
|
||||
__EXPORT extern int up_bdshot_get_erpm(uint8_t channel, int *erpm);
|
||||
|
||||
|
||||
/**
|
||||
* Get bidrectional dshot status for a channel
|
||||
* @param channel Dshot channel
|
||||
* @param erpm pointer to write the erpm value
|
||||
* @return <0 on error / not supported, 0 on offline, 1 on online
|
||||
*/
|
||||
__EXPORT extern int up_bdshot_channel_status(uint8_t channel);
|
||||
|
||||
|
||||
__END_DECLS
|
||||
|
||||
+106
-14
@@ -144,7 +144,9 @@ void DShot::enable_dshot_outputs(const bool enabled)
|
||||
}
|
||||
}
|
||||
|
||||
int ret = up_dshot_init(_output_mask, dshot_frequency);
|
||||
_bidirectional_dshot_enabled = _param_bidirectional_enable.get();
|
||||
|
||||
int ret = up_dshot_init(_output_mask, dshot_frequency, _bidirectional_dshot_enabled);
|
||||
|
||||
if (ret < 0) {
|
||||
PX4_ERR("up_dshot_init failed (%i)", ret);
|
||||
@@ -157,6 +159,7 @@ void DShot::enable_dshot_outputs(const bool enabled)
|
||||
for (unsigned i = 0; i < _num_outputs; ++i) {
|
||||
if (((1 << i) & _output_mask) == 0) {
|
||||
_mixing_output.disableFunction(i);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
@@ -167,6 +170,10 @@ void DShot::enable_dshot_outputs(const bool enabled)
|
||||
}
|
||||
|
||||
_outputs_initialized = true;
|
||||
|
||||
if (_bidirectional_dshot_enabled) {
|
||||
init_telemetry(NULL);
|
||||
}
|
||||
}
|
||||
|
||||
if (_outputs_initialized) {
|
||||
@@ -206,17 +213,20 @@ void DShot::init_telemetry(const char *device)
|
||||
|
||||
_telemetry->esc_status_pub.advertise();
|
||||
|
||||
int ret = _telemetry->handler.init(device);
|
||||
if (device != NULL) {
|
||||
int ret = _telemetry->handler.init(device);
|
||||
|
||||
if (ret != 0) {
|
||||
PX4_ERR("telemetry init failed (%i)", ret);
|
||||
if (ret != 0) {
|
||||
PX4_ERR("telemetry init failed (%i)", ret);
|
||||
}
|
||||
}
|
||||
|
||||
update_telemetry_num_motors();
|
||||
}
|
||||
|
||||
void DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data)
|
||||
int DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data)
|
||||
{
|
||||
int ret = 0;
|
||||
// fill in new motor data
|
||||
esc_status_s &esc_status = _telemetry->esc_status_pub.get();
|
||||
|
||||
@@ -239,18 +249,83 @@ void DShot::handle_new_telemetry_data(const int telemetry_index, const DShotTele
|
||||
esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_DSHOT;
|
||||
esc_status.esc_count = _telemetry->handler.numMotors();
|
||||
++esc_status.counter;
|
||||
// FIXME: mark all ESC's as online, otherwise commander complains even for a single dropout
|
||||
esc_status.esc_online_flags = (1 << esc_status.esc_count) - 1;
|
||||
esc_status.esc_armed_flags = (1 << esc_status.esc_count) - 1;
|
||||
|
||||
_telemetry->esc_status_pub.update();
|
||||
|
||||
// reset esc data (in case a motor times out, so we won't send stale data)
|
||||
memset(&esc_status.esc, 0, sizeof(_telemetry->esc_status_pub.get().esc));
|
||||
esc_status.esc_online_flags = 0;
|
||||
ret = 1; // Indicate we wrapped, so we publish data
|
||||
}
|
||||
|
||||
_telemetry->last_telemetry_index = telemetry_index;
|
||||
|
||||
return ret;
|
||||
}
|
||||
|
||||
void DShot::publish_esc_status(void)
|
||||
{
|
||||
esc_status_s &esc_status = _telemetry->esc_status_pub.get();
|
||||
int telemetry_index = 0;
|
||||
|
||||
// clear data of the esc that are offline
|
||||
for (int index = 0; (index < _telemetry->last_telemetry_index); index++) {
|
||||
if ((esc_status.esc_online_flags & (1 << index)) == 0) {
|
||||
memset(&esc_status.esc[index], 0, sizeof(struct esc_report_s));
|
||||
}
|
||||
}
|
||||
|
||||
// FIXME: mark all UART Telemetry ESC's as online, otherwise commander complains even for a single dropout
|
||||
esc_status.esc_count = _telemetry->handler.numMotors();
|
||||
esc_status.esc_online_flags = (1 << esc_status.esc_count) - 1;
|
||||
esc_status.esc_armed_flags = (1 << esc_status.esc_count) - 1;
|
||||
|
||||
if (_bidirectional_dshot_enabled) {
|
||||
for (unsigned i = 0; i < _num_outputs; i++) {
|
||||
if (_mixing_output.isFunctionSet(i)) {
|
||||
if (up_bdshot_channel_status(i)) {
|
||||
esc_status.esc_online_flags |= 1 << i;
|
||||
|
||||
} else {
|
||||
esc_status.esc_online_flags &= ~(1 << i);
|
||||
}
|
||||
|
||||
++telemetry_index;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// ESC telem wrap around or bdshot update
|
||||
_telemetry->esc_status_pub.update();
|
||||
|
||||
// reset esc online flags
|
||||
esc_status.esc_online_flags = 0;
|
||||
}
|
||||
|
||||
int DShot::handle_new_bdshot_erpm(void)
|
||||
{
|
||||
int num_erpms = 0;
|
||||
int telemetry_index = 0;
|
||||
int erpm;
|
||||
esc_status_s &esc_status = _telemetry->esc_status_pub.get();
|
||||
|
||||
esc_status.timestamp = hrt_absolute_time();
|
||||
esc_status.counter = _esc_status_counter++;
|
||||
esc_status.esc_connectiontype = esc_status_s::ESC_CONNECTION_TYPE_DSHOT;
|
||||
esc_status.esc_armed_flags = _outputs_on;
|
||||
|
||||
for (unsigned i = 0; i < _num_outputs; i++) {
|
||||
if (_mixing_output.isFunctionSet(i)) {
|
||||
if (up_bdshot_get_erpm(i, &erpm) == 0) {
|
||||
num_erpms++;
|
||||
esc_status.esc_online_flags |= 1 << telemetry_index;
|
||||
esc_status.esc[telemetry_index].timestamp = hrt_absolute_time();
|
||||
esc_status.esc[telemetry_index].esc_rpm = (erpm * 100) / (_param_mot_pole_count.get() / 2);
|
||||
esc_status.esc[telemetry_index].actuator_function = _telemetry->actuator_functions[telemetry_index];
|
||||
}
|
||||
|
||||
++telemetry_index;
|
||||
}
|
||||
|
||||
|
||||
}
|
||||
|
||||
return num_erpms;
|
||||
}
|
||||
|
||||
int DShot::send_command_thread_safe(const dshot_command_t command, const int num_repetitions, const int motor_index)
|
||||
@@ -463,6 +538,7 @@ void DShot::Run()
|
||||
|
||||
if (_telemetry) {
|
||||
int telem_update = _telemetry->handler.update();
|
||||
int need_to_publish = 0;
|
||||
|
||||
// Are we waiting for ESC info?
|
||||
if (_waiting_for_esc_info) {
|
||||
@@ -472,10 +548,21 @@ void DShot::Run()
|
||||
}
|
||||
|
||||
} else if (telem_update >= 0) {
|
||||
handle_new_telemetry_data(telem_update, _telemetry->handler.latestESCData());
|
||||
need_to_publish = handle_new_telemetry_data(telem_update, _telemetry->handler.latestESCData());
|
||||
}
|
||||
|
||||
if (_bidirectional_dshot_enabled) {
|
||||
// Add bdshot data to esc status
|
||||
need_to_publish += handle_new_bdshot_erpm();
|
||||
}
|
||||
|
||||
if (need_to_publish > 0) {
|
||||
// ESC telem wrap around or bdshot update
|
||||
publish_esc_status();
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
if (_parameter_update_sub.updated()) {
|
||||
update_params();
|
||||
}
|
||||
@@ -713,6 +800,11 @@ int DShot::print_status()
|
||||
_telemetry->handler.printStatus();
|
||||
}
|
||||
|
||||
/* Print dshot status */
|
||||
if (_bidirectional_dshot_enabled) {
|
||||
up_bdshot_status();
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
||||
@@ -131,7 +131,11 @@ private:
|
||||
|
||||
void init_telemetry(const char *device);
|
||||
|
||||
void handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data);
|
||||
int handle_new_telemetry_data(const int telemetry_index, const DShotTelemetry::EscData &data);
|
||||
|
||||
void publish_esc_status(void);
|
||||
|
||||
int handle_new_bdshot_erpm(void);
|
||||
|
||||
int request_esc_info();
|
||||
|
||||
@@ -158,6 +162,7 @@ private:
|
||||
bool _outputs_initialized{false};
|
||||
bool _outputs_on{false};
|
||||
bool _waiting_for_esc_info{false};
|
||||
bool _bidirectional_dshot_enabled{false};
|
||||
|
||||
static constexpr unsigned _num_outputs{DIRECT_PWM_OUTPUT_CHANNELS};
|
||||
uint32_t _output_mask{0};
|
||||
@@ -169,12 +174,14 @@ private:
|
||||
uORB::SubscriptionInterval _parameter_update_sub{ORB_ID(parameter_update), 1_s};
|
||||
uORB::Subscription _vehicle_command_sub{ORB_ID(vehicle_command)};
|
||||
uORB::Publication<vehicle_command_ack_s> _command_ack_pub{ORB_ID(vehicle_command_ack)};
|
||||
uint16_t _esc_status_counter{0};
|
||||
|
||||
DEFINE_PARAMETERS(
|
||||
(ParamFloat<px4::params::DSHOT_MIN>) _param_dshot_min,
|
||||
(ParamBool<px4::params::DSHOT_3D_ENABLE>) _param_dshot_3d_enable,
|
||||
(ParamInt<px4::params::DSHOT_3D_DEAD_H>) _param_dshot_3d_dead_h,
|
||||
(ParamInt<px4::params::DSHOT_3D_DEAD_L>) _param_dshot_3d_dead_l,
|
||||
(ParamInt<px4::params::MOT_POLE_COUNT>) _param_mot_pole_count
|
||||
(ParamInt<px4::params::MOT_POLE_COUNT>) _param_mot_pole_count,
|
||||
(ParamBool<px4::params::DSHOT_BIDIR_EN>) _param_bidirectional_enable
|
||||
)
|
||||
};
|
||||
|
||||
@@ -183,6 +183,9 @@ bool DShotTelemetry::decodeByte(uint8_t byte, bool &successful_decoding)
|
||||
_latest_data.erpm);
|
||||
++_num_successful_responses;
|
||||
successful_decoding = true;
|
||||
|
||||
} else {
|
||||
++_num_checksum_errors;
|
||||
}
|
||||
|
||||
return true;
|
||||
@@ -195,6 +198,7 @@ void DShotTelemetry::printStatus() const
|
||||
{
|
||||
PX4_INFO("Number of successful ESC frames: %i", _num_successful_responses);
|
||||
PX4_INFO("Number of timeouts: %i", _num_timeouts);
|
||||
PX4_INFO("Number of CRC errors: %i", _num_checksum_errors);
|
||||
}
|
||||
|
||||
uint8_t DShotTelemetry::updateCrc8(uint8_t crc, uint8_t crc_seed)
|
||||
|
||||
@@ -140,4 +140,5 @@ private:
|
||||
// statistics
|
||||
int _num_timeouts{0};
|
||||
int _num_successful_responses{0};
|
||||
int _num_checksum_errors{0};
|
||||
};
|
||||
|
||||
@@ -33,6 +33,16 @@ parameters:
|
||||
When mixer outputs 1000 or value inside DSHOT 3D deadband, DShot 0 is sent.
|
||||
type: boolean
|
||||
default: 0
|
||||
DSHOT_BIDIR_EN:
|
||||
description:
|
||||
short: Enable bidirectional DShot
|
||||
long: |
|
||||
This parameter enables bidirectional DShot which provides RPM feedback.
|
||||
Note that this requires ESCs that support bidirectional DSHot, e.g. BlHeli32.
|
||||
This is not the same as DShot telemetry which requires an additional serial connection.
|
||||
type: boolean
|
||||
default: 0
|
||||
reboot_required: true
|
||||
DSHOT_3D_DEAD_H:
|
||||
description:
|
||||
short: DSHOT 3D deadband high
|
||||
|
||||
@@ -314,7 +314,7 @@ void RCInput::swap_rx_tx()
|
||||
# ifdef TIOCSSINGLEWIRE
|
||||
|
||||
if (rv != OK) {
|
||||
ioctl(_rcs_fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED);
|
||||
ioctl(_rcs_fd, TIOCSSINGLEWIRE, SER_SINGLEWIRE_ENABLED | SER_SINGLEWIRE_PUSHPULL);
|
||||
}
|
||||
|
||||
# else
|
||||
|
||||
@@ -78,7 +78,9 @@ def run(logfile, use_gnss, scale_init):
|
||||
if scale_init is None:
|
||||
scale_init = 1.0
|
||||
|
||||
state = np.array([0.0, 0.0, scale_init])
|
||||
# The estimator estimates the inverse scale factor to have a simpler measurement jacobian
|
||||
inverse_scale_init = 1 / scale_init
|
||||
state = np.array([0.0, 0.0, inverse_scale_init])
|
||||
P = np.diag([1.0, 1.0, 1e-4])
|
||||
wind_nsd = 1e-2
|
||||
scale_nsd = 1e-4
|
||||
@@ -118,7 +120,7 @@ def run(logfile, use_gnss, scale_init):
|
||||
|
||||
wind_est_n[i] = state[0]
|
||||
wind_est_e[i] = state[1]
|
||||
scale_est[i] = state[2]
|
||||
scale_est[i] = 1 / state[2]
|
||||
|
||||
plt.figure(1)
|
||||
ax1 = plt.subplot(2, 1, 1)
|
||||
|
||||
@@ -194,6 +194,25 @@ CameraFeedback::print_usage(const char *reason)
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
|
||||
The camera_feedback module publishes `CameraCapture` UORB topics when image capture has been triggered.
|
||||
|
||||
If camera capture is enabled, then trigger information from the camera capture pin is published;
|
||||
otherwise trigger information at the point the camera was commanded to trigger is published
|
||||
(from the `camera_trigger` module).
|
||||
|
||||
The `CAMERA_IMAGE_CAPTURED` message is then emitted (by streaming code) following `CameraCapture` updates.
|
||||
`CameraCapture` topics are also logged and can be used for geotagging.
|
||||
|
||||
### Implementation
|
||||
|
||||
`CameraTrigger` topics are published by the `camera_trigger` module (`feedback` field set `false`)
|
||||
when image capture is triggered, and may also be published by the `camera_capture` driver
|
||||
(with `feedback` field set `true`) if the camera capture pin is activated.
|
||||
|
||||
The `camera_feedback` module subscribes to `CameraTrigger`.
|
||||
It discards topics from the `camera_trigger` module if camera capture is enabled.
|
||||
For the topics that are not discarded it creates a `CameraCapture` topic with the timestamp information
|
||||
from the `CameraTrigger` and position information from the vehicle.
|
||||
|
||||
)DESCR_STR");
|
||||
|
||||
|
||||
@@ -50,6 +50,7 @@ px4_add_library(health_and_arming_checks
|
||||
checks/gyroCheck.cpp
|
||||
checks/homePositionCheck.cpp
|
||||
checks/imuConsistencyCheck.cpp
|
||||
checks/loggerCheck.cpp
|
||||
checks/magnetometerCheck.cpp
|
||||
checks/manualControlCheck.cpp
|
||||
checks/missionCheck.cpp
|
||||
|
||||
@@ -51,6 +51,7 @@
|
||||
#include "checks/failureDetectorCheck.hpp"
|
||||
#include "checks/gyroCheck.hpp"
|
||||
#include "checks/imuConsistencyCheck.hpp"
|
||||
#include "checks/loggerCheck.hpp"
|
||||
#include "checks/magnetometerCheck.hpp"
|
||||
#include "checks/manualControlCheck.hpp"
|
||||
#include "checks/homePositionCheck.hpp"
|
||||
@@ -130,6 +131,7 @@ private:
|
||||
FailureDetectorChecks _failure_detector_checks;
|
||||
GyroChecks _gyro_checks;
|
||||
ImuConsistencyChecks _imu_consistency_checks;
|
||||
LoggerChecks _logger_checks;
|
||||
MagnetometerChecks _magnetometer_checks;
|
||||
ManualControlChecks _manual_control_checks;
|
||||
HomePositionChecks _home_position_checks;
|
||||
@@ -167,6 +169,7 @@ private:
|
||||
&_failure_detector_checks,
|
||||
&_gyro_checks,
|
||||
&_imu_consistency_checks,
|
||||
&_logger_checks,
|
||||
&_magnetometer_checks,
|
||||
&_manual_control_checks,
|
||||
&_home_position_checks,
|
||||
|
||||
@@ -0,0 +1,60 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 "loggerCheck.hpp"
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
LoggerChecks::LoggerChecks()
|
||||
: _param_sdlog_mode_handle(param_find("SDLOG_MODE"))
|
||||
{
|
||||
param_get(_param_sdlog_mode_handle, &_sdlog_mode);
|
||||
}
|
||||
|
||||
void LoggerChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
{
|
||||
bool active = false;
|
||||
|
||||
if (_sdlog_mode >= 0) {
|
||||
if (_logger_status_sub.advertised()) {
|
||||
logger_status_s status;
|
||||
_logger_status_sub.copy(&status);
|
||||
|
||||
if (hrt_elapsed_time(&status.timestamp) < 3_s && status.is_logging) {
|
||||
active = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
reporter.setHealth(health_component_t::logging, active, false, false);
|
||||
}
|
||||
@@ -0,0 +1,54 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* 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 "../Common.hpp"
|
||||
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/SubscriptionMultiArray.hpp>
|
||||
#include <uORB/topics/logger_status.h>
|
||||
|
||||
class LoggerChecks : public HealthAndArmingCheckBase
|
||||
{
|
||||
public:
|
||||
LoggerChecks();
|
||||
~LoggerChecks() = default;
|
||||
|
||||
void checkAndReport(const Context &context, Report &reporter) override;
|
||||
|
||||
private:
|
||||
uORB::Subscription _logger_status_sub{ORB_ID::logger_status};
|
||||
const param_t _param_sdlog_mode_handle;
|
||||
int32_t _sdlog_mode = -1;
|
||||
};
|
||||
@@ -50,10 +50,6 @@ void MagnetometerChecks::checkAndReport(const Context &context, Report &reporter
|
||||
bool is_mag_fault = false;
|
||||
const bool is_required = instance == 0 || isMagRequired(instance, is_mag_fault);
|
||||
|
||||
if (!is_required) {
|
||||
continue;
|
||||
}
|
||||
|
||||
const bool exists = _sensor_mag_sub[instance].advertised();
|
||||
bool is_valid = false;
|
||||
bool is_calibration_valid = false;
|
||||
@@ -83,6 +79,11 @@ void MagnetometerChecks::checkAndReport(const Context &context, Report &reporter
|
||||
reporter.setIsPresent(health_component_t::magnetometer);
|
||||
}
|
||||
|
||||
// Do not raise errors if a mag is not required
|
||||
if (!is_required) {
|
||||
continue;
|
||||
}
|
||||
|
||||
const bool is_sensor_ok = is_valid && is_calibration_valid && !is_mag_fault;
|
||||
|
||||
if (!is_sensor_ok) {
|
||||
|
||||
@@ -142,6 +142,36 @@ void PowerChecks::checkAndReport(const Context &context, Report &reporter)
|
||||
power_module_count, _param_com_power_count.get());
|
||||
}
|
||||
}
|
||||
|
||||
// Overcurrent detection
|
||||
if (system_power.hipower_5v_oc) {
|
||||
/* EVENT
|
||||
* @description
|
||||
* Check the power supply
|
||||
*/
|
||||
reporter.healthFailure(NavModes::All, health_component_t::system,
|
||||
events::ID("check_power_oc_hipower"),
|
||||
events::Log::Error, "Overcurrent detected for the hipower 5V supply");
|
||||
}
|
||||
|
||||
if (system_power.periph_5v_oc) {
|
||||
/* EVENT
|
||||
* @description
|
||||
* Check the power supply
|
||||
*/
|
||||
reporter.healthFailure(NavModes::All, health_component_t::system,
|
||||
events::ID("check_power_oc_periph"),
|
||||
events::Log::Error, "Overcurrent detected for the peripheral 5V supply");
|
||||
}
|
||||
|
||||
if (system_power.hipower_5v_oc || system_power.periph_5v_oc) {
|
||||
if (context.isArmed() && !_overcurrent_warning_sent) {
|
||||
_overcurrent_warning_sent = true;
|
||||
events::send(events::ID("check_power_oc_report"),
|
||||
events::Log::Error,
|
||||
"5V overcurrent detected, landing advised");
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
} else {
|
||||
|
||||
@@ -48,6 +48,7 @@ public:
|
||||
|
||||
private:
|
||||
uORB::Subscription _system_power_sub{ORB_ID(system_power)};
|
||||
bool _overcurrent_warning_sent{false};
|
||||
|
||||
DEFINE_PARAMETERS_CUSTOM_PARENT(HealthAndArmingCheckBase,
|
||||
(ParamInt<px4::params::CBRK_SUPPLY_CHK>) _param_cbrk_supply_chk,
|
||||
|
||||
@@ -320,7 +320,8 @@ bool Ekf::shouldResetGpsFusion() const
|
||||
#endif // CONFIG_EKF2_OPTICAL_FLOW
|
||||
|
||||
const bool is_reset_required = has_horizontal_aiding_timed_out
|
||||
|| isTimedOut(_time_last_hor_pos_fuse, 2 * _params.reset_timeout_max);
|
||||
|| (isTimedOut(_time_last_hor_pos_fuse, 2 * _params.reset_timeout_max)
|
||||
&& (_params.gnss_ctrl & static_cast<int32_t>(GnssCtrl::HPOS)));
|
||||
|
||||
const bool is_inflight_nav_failure = _control_status.flags.in_air
|
||||
&& isTimedOut(_time_last_hor_vel_fuse, _params.reset_timeout_max)
|
||||
|
||||
@@ -59,13 +59,6 @@ void Ekf::controlMagFusion()
|
||||
return;
|
||||
}
|
||||
|
||||
// stop mag (require a reset before using again) if there was an external yaw reset (yaw estimator, GPS yaw, etc)
|
||||
if (_mag_decl_cov_reset && (_state_reset_status.reset_count.quat != _state_reset_count_prev.quat)) {
|
||||
ECL_INFO("yaw reset, stopping mag fusion to force reinitialization");
|
||||
stopMagFusion();
|
||||
resetMagCov();
|
||||
}
|
||||
|
||||
magSample mag_sample;
|
||||
|
||||
if (_mag_buffer && _mag_buffer->pop_first_older_than(_time_delayed_us, &mag_sample)) {
|
||||
@@ -154,11 +147,13 @@ void Ekf::controlMagFusion()
|
||||
|
||||
// WMM update can occur on the last epoch, just after mag fusion
|
||||
const bool wmm_updated = (_wmm_gps_time_last_set >= aid_src.time_last_fuse);
|
||||
const bool using_ne_aiding = _control_status.flags.gps || _control_status.flags.aux_gpos;
|
||||
|
||||
|
||||
{
|
||||
const bool mag_consistent_or_no_gnss = _control_status.flags.mag_heading_consistent || !_control_status.flags.gps;
|
||||
const bool mag_consistent_or_no_ne_aiding = _control_status.flags.mag_heading_consistent || !using_ne_aiding;
|
||||
const bool common_conditions_passing = _control_status.flags.mag
|
||||
&& ((_control_status.flags.yaw_align && mag_consistent_or_no_gnss)
|
||||
&& ((_control_status.flags.yaw_align && mag_consistent_or_no_ne_aiding)
|
||||
|| (!_control_status.flags.ev_yaw && !_control_status.flags.yaw_align))
|
||||
&& !_control_status.flags.mag_fault
|
||||
&& !_control_status.flags.mag_field_disturbed
|
||||
@@ -185,74 +180,47 @@ void Ekf::controlMagFusion()
|
||||
|
||||
// if we are using 3-axis magnetometer fusion, but without external NE aiding,
|
||||
// then the declination must be fused as an observation to prevent long term heading drift
|
||||
// fusing declination when gps aiding is available is optional.
|
||||
const bool not_using_ne_aiding = !_control_status.flags.gps && !_control_status.flags.aux_gpos;
|
||||
_control_status.flags.mag_dec = _control_status.flags.mag
|
||||
&& (not_using_ne_aiding || !_control_status.flags.mag_aligned_in_flight);
|
||||
const bool no_ne_aiding_or_pre_takeoff = !using_ne_aiding || !_control_status.flags.in_air;
|
||||
_control_status.flags.mag_dec = _control_status.flags.mag && no_ne_aiding_or_pre_takeoff;
|
||||
|
||||
if (_control_status.flags.mag) {
|
||||
|
||||
if (continuing_conditions_passing && _control_status.flags.yaw_align) {
|
||||
|
||||
if (mag_sample.reset || checkHaglYawResetReq() || wmm_updated) {
|
||||
if (mag_sample.reset || checkHaglYawResetReq() || (wmm_updated && no_ne_aiding_or_pre_takeoff)) {
|
||||
ECL_INFO("reset to %s", AID_SRC_NAME);
|
||||
resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D);
|
||||
aid_src.time_last_fuse = _time_delayed_us;
|
||||
|
||||
} else {
|
||||
if (!_mag_decl_cov_reset) {
|
||||
// After any magnetic field covariance reset event the earth field state
|
||||
// covariances need to be corrected to incorporate knowledge of the declination
|
||||
// before fusing magnetometer data to prevent rapid rotation of the earth field
|
||||
// states for the first few observations.
|
||||
fuseDeclination(0.02f);
|
||||
_mag_decl_cov_reset = true;
|
||||
fuseMag(mag_sample.mag, R_MAG, H, aid_src);
|
||||
// The normal sequence is to fuse the magnetometer data first before fusing
|
||||
// declination angle at a higher uncertainty to allow some learning of
|
||||
// declination angle over time.
|
||||
const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg;
|
||||
const bool update_tilt = _control_status.flags.mag_3D;
|
||||
fuseMag(mag_sample.mag, R_MAG, H, aid_src, update_all_states, update_tilt);
|
||||
|
||||
} else {
|
||||
// The normal sequence is to fuse the magnetometer data first before fusing
|
||||
// declination angle at a higher uncertainty to allow some learning of
|
||||
// declination angle over time.
|
||||
const bool update_all_states = _control_status.flags.mag_3D || _control_status.flags.mag_hdg;
|
||||
const bool update_tilt = _control_status.flags.mag_3D;
|
||||
fuseMag(mag_sample.mag, R_MAG, H, aid_src, update_all_states, update_tilt);
|
||||
// the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned
|
||||
if (update_all_states && update_tilt) {
|
||||
_fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]);
|
||||
_fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]);
|
||||
_fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]);
|
||||
}
|
||||
|
||||
// the innovation variance contribution from the state covariances is negative which means the covariance matrix is badly conditioned
|
||||
if (update_all_states && update_tilt) {
|
||||
_fault_status.flags.bad_mag_x = (aid_src.innovation_variance[0] < aid_src.observation_variance[0]);
|
||||
_fault_status.flags.bad_mag_y = (aid_src.innovation_variance[1] < aid_src.observation_variance[1]);
|
||||
_fault_status.flags.bad_mag_z = (aid_src.innovation_variance[2] < aid_src.observation_variance[2]);
|
||||
}
|
||||
|
||||
if (_control_status.flags.mag_dec) {
|
||||
fuseDeclination(0.5f);
|
||||
}
|
||||
if (_control_status.flags.mag_dec) {
|
||||
fuseDeclination(0.5f);
|
||||
}
|
||||
}
|
||||
|
||||
const bool is_fusion_failing = isTimedOut(aid_src.time_last_fuse, _params.reset_timeout_max);
|
||||
|
||||
if (is_fusion_failing) {
|
||||
if (_nb_mag_3d_reset_available > 0) {
|
||||
// Data seems good, attempt a reset (mag states only unless mag_3D currently active)
|
||||
if (no_ne_aiding_or_pre_takeoff) {
|
||||
ECL_WARN("%s fusion failing, resetting", AID_SRC_NAME);
|
||||
resetMagStates(_mag_lpf.getState(), _control_status.flags.mag_hdg || _control_status.flags.mag_3D);
|
||||
aid_src.time_last_fuse = _time_delayed_us;
|
||||
|
||||
if (_control_status.flags.in_air) {
|
||||
_nb_mag_3d_reset_available--;
|
||||
}
|
||||
|
||||
} else if (starting_conditions_passing) {
|
||||
// Data seems good, but previous reset did not fix the issue
|
||||
// something else must be wrong, declare the sensor faulty and stop the fusion
|
||||
//_control_status.flags.mag_fault = true;
|
||||
ECL_WARN("stopping %s fusion, starting conditions failing", AID_SRC_NAME);
|
||||
stopMagFusion();
|
||||
|
||||
} else {
|
||||
// A reset did not fix the issue but all the starting checks are not passing
|
||||
// This could be a temporary issue, stop the fusion without declaring the sensor faulty
|
||||
ECL_WARN("stopping %s, fusion failing", AID_SRC_NAME);
|
||||
stopMagFusion();
|
||||
}
|
||||
@@ -267,12 +235,9 @@ void Ekf::controlMagFusion()
|
||||
} else {
|
||||
if (starting_conditions_passing) {
|
||||
|
||||
_control_status.flags.mag = true;
|
||||
|
||||
// activate fusion, reset mag states and initialize variance if first init or in flight reset
|
||||
if (!_control_status.flags.yaw_align
|
||||
|| wmm_updated
|
||||
|| !_mag_decl_cov_reset
|
||||
|| !_state.mag_I.longerThan(0.f)
|
||||
|| (getStateVariance<State::mag_I>().min() < kMagVarianceMin)
|
||||
|| (getStateVariance<State::mag_B>().min() < kMagVarianceMin)
|
||||
@@ -283,16 +248,17 @@ void Ekf::controlMagFusion()
|
||||
|
||||
resetMagStates(_mag_lpf.getState(), reset_heading);
|
||||
aid_src.time_last_fuse = _time_delayed_us;
|
||||
_nb_mag_3d_reset_available = 2;
|
||||
|
||||
if (reset_heading) {
|
||||
_control_status.flags.yaw_align = true;
|
||||
}
|
||||
|
||||
_control_status.flags.mag = true;
|
||||
|
||||
} else {
|
||||
if (fuseMag(mag_sample.mag, R_MAG, H, aid_src)) {
|
||||
ECL_INFO("starting %s fusion", AID_SRC_NAME);
|
||||
_nb_mag_3d_reset_available = 2;
|
||||
_control_status.flags.mag = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -367,23 +333,7 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading)
|
||||
* Vector3f(_mag_strength_gps, 0, 0);
|
||||
|
||||
// mag_B: reset
|
||||
#if defined(CONFIG_EKF2_GNSS)
|
||||
|
||||
if (isYawEmergencyEstimateAvailable()) {
|
||||
|
||||
const Dcmf R_to_earth = updateYawInRotMat(_yawEstimator.getYaw(), _R_to_earth);
|
||||
const Dcmf R_to_body = R_to_earth.transpose();
|
||||
|
||||
// mag_B: reset using WMM and yaw estimator
|
||||
_state.mag_B = mag - (R_to_body * mag_earth_pred);
|
||||
|
||||
ECL_INFO("resetMagStates using yaw estimator");
|
||||
|
||||
} else if (!reset_heading && _control_status.flags.yaw_align) {
|
||||
#else
|
||||
|
||||
if (!reset_heading && _control_status.flags.yaw_align) {
|
||||
#endif
|
||||
// mag_B: reset using WMM
|
||||
const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal);
|
||||
_state.mag_B = mag - (R_to_body * mag_earth_pred);
|
||||
@@ -399,9 +349,6 @@ void Ekf::resetMagStates(const Vector3f &mag, bool reset_heading)
|
||||
resetMagHeading(mag);
|
||||
}
|
||||
|
||||
// earth field was reset to WMM, skip initial declination fusion
|
||||
_mag_decl_cov_reset = true;
|
||||
|
||||
} else {
|
||||
// mag_B: reset
|
||||
_state.mag_B.zero();
|
||||
|
||||
@@ -103,7 +103,13 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima
|
||||
|
||||
VectorState Kfusion = P * H / aid_src.innovation_variance[index];
|
||||
|
||||
if (!update_all_states) {
|
||||
if (update_all_states) {
|
||||
if (!update_tilt) {
|
||||
Kfusion(State::quat_nominal.idx + 0) = 0.f;
|
||||
Kfusion(State::quat_nominal.idx + 1) = 0.f;
|
||||
}
|
||||
|
||||
} else {
|
||||
// zero non-mag Kalman gains if not updating all states
|
||||
|
||||
// copy mag_I and mag_B Kalman gains
|
||||
@@ -116,14 +122,8 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima
|
||||
Kfusion.slice<State::mag_B.dof, 1>(State::mag_B.idx, 0) = K_mag_B;
|
||||
}
|
||||
|
||||
if (!update_tilt) {
|
||||
Kfusion(State::quat_nominal.idx + 0) = 0.f;
|
||||
Kfusion(State::quat_nominal.idx + 1) = 0.f;
|
||||
}
|
||||
|
||||
if (measurementUpdate(Kfusion, H, aid_src.observation_variance[index], aid_src.innovation[index])) {
|
||||
fused[index] = true;
|
||||
limitDeclination();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -149,10 +149,6 @@ bool Ekf::fuseMag(const Vector3f &mag, const float R_MAG, VectorState &H, estima
|
||||
|
||||
bool Ekf::fuseDeclination(float decl_sigma)
|
||||
{
|
||||
if (!_control_status.flags.mag) {
|
||||
return false;
|
||||
}
|
||||
|
||||
float decl_measurement = NAN;
|
||||
|
||||
if ((_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL)
|
||||
@@ -191,87 +187,12 @@ bool Ekf::fuseDeclination(float decl_sigma)
|
||||
|
||||
_fault_status.flags.bad_mag_decl = !is_fused;
|
||||
|
||||
if (is_fused) {
|
||||
limitDeclination();
|
||||
}
|
||||
|
||||
return is_fused;
|
||||
}
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
void Ekf::limitDeclination()
|
||||
{
|
||||
const Vector3f mag_I_before = _state.mag_I;
|
||||
|
||||
// get a reference value for the earth field declinaton and minimum plausible horizontal field strength
|
||||
float decl_reference = NAN;
|
||||
float h_field_min = 0.001f;
|
||||
|
||||
if (_params.mag_declination_source & GeoDeclinationMask::USE_GEO_DECL
|
||||
&& (PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps) && PX4_ISFINITE(_mag_inclination_gps))
|
||||
) {
|
||||
decl_reference = _mag_declination_gps;
|
||||
|
||||
// set to 50% of the horizontal strength from geo tables if location is known
|
||||
h_field_min = fmaxf(h_field_min, 0.5f * _mag_strength_gps * cosf(_mag_inclination_gps));
|
||||
|
||||
} else if ((_params.mag_declination_source & GeoDeclinationMask::SAVE_GEO_DECL)
|
||||
&& PX4_ISFINITE(_params.mag_declination_deg) && (fabsf(_params.mag_declination_deg) > 0.f)
|
||||
) {
|
||||
// use parameter value if GPS isn't available
|
||||
decl_reference = math::radians(_params.mag_declination_deg);
|
||||
}
|
||||
|
||||
if (!PX4_ISFINITE(decl_reference)) {
|
||||
return;
|
||||
}
|
||||
|
||||
// do not allow the horizontal field length to collapse - this will make the declination fusion badly conditioned
|
||||
// and can result in a reversal of the NE field states which the filter cannot recover from
|
||||
// apply a circular limit
|
||||
float h_field = sqrtf(_state.mag_I(0) * _state.mag_I(0) + _state.mag_I(1) * _state.mag_I(1));
|
||||
|
||||
if (h_field < h_field_min) {
|
||||
if (h_field > 0.001f * h_field_min) {
|
||||
const float h_scaler = h_field_min / h_field;
|
||||
_state.mag_I(0) *= h_scaler;
|
||||
_state.mag_I(1) *= h_scaler;
|
||||
|
||||
} else {
|
||||
// too small to scale radially so set to expected value
|
||||
_state.mag_I(0) = 2.0f * h_field_min * cosf(decl_reference);
|
||||
_state.mag_I(1) = 2.0f * h_field_min * sinf(decl_reference);
|
||||
}
|
||||
|
||||
h_field = h_field_min;
|
||||
}
|
||||
|
||||
// do not allow the declination estimate to vary too much relative to the reference value
|
||||
constexpr float decl_tolerance = 0.5f;
|
||||
const float decl_max = decl_reference + decl_tolerance;
|
||||
const float decl_min = decl_reference - decl_tolerance;
|
||||
const float decl_estimate = atan2f(_state.mag_I(1), _state.mag_I(0));
|
||||
|
||||
if (decl_estimate > decl_max) {
|
||||
_state.mag_I(0) = h_field * cosf(decl_max);
|
||||
_state.mag_I(1) = h_field * sinf(decl_max);
|
||||
|
||||
} else if (decl_estimate < decl_min) {
|
||||
_state.mag_I(0) = h_field * cosf(decl_min);
|
||||
_state.mag_I(1) = h_field * sinf(decl_min);
|
||||
}
|
||||
|
||||
if ((mag_I_before - _state.mag_I).longerThan(0.01f)) {
|
||||
ECL_DEBUG("declination limited mag I [%.3f, %.3f, %.3f] -> [%.3f, %.3f, %.3f] (decl: %.3f)",
|
||||
(double)mag_I_before(0), (double)mag_I_before(1), (double)mag_I_before(2),
|
||||
(double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2),
|
||||
(double)decl_reference
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
float Ekf::calculate_synthetic_mag_z_measurement(const Vector3f &mag_meas, const Vector3f &mag_earth_predicted)
|
||||
{
|
||||
// theoretical magnitude of the magnetometer Z component value given X and Y sensor measurement and our knowledge
|
||||
|
||||
@@ -163,22 +163,26 @@ void Ekf::predictCovariance(const imuSample &imu_delayed)
|
||||
|
||||
|
||||
#if defined(CONFIG_EKF2_MAGNETOMETER)
|
||||
if (_control_status.flags.mag) {
|
||||
// mag_I: add process noise
|
||||
float mag_I_sig = dt * math::constrain(_params.mage_p_noise, 0.f, 1.f);
|
||||
float mag_I_process_noise = sq(mag_I_sig);
|
||||
// mag_I: add process noise
|
||||
float mag_I_sig = dt * math::constrain(_params.mage_p_noise, 0.f, 1.f);
|
||||
float mag_I_process_noise = sq(mag_I_sig);
|
||||
|
||||
for (unsigned index = 0; index < State::mag_I.dof; index++) {
|
||||
const unsigned i = State::mag_I.idx + index;
|
||||
for (unsigned index = 0; index < State::mag_I.dof; index++) {
|
||||
const unsigned i = State::mag_I.idx + index;
|
||||
|
||||
if (P(i, i) < sq(_params.mag_noise)) {
|
||||
P(i, i) += mag_I_process_noise;
|
||||
}
|
||||
}
|
||||
|
||||
// mag_B: add process noise
|
||||
float mag_B_sig = dt * math::constrain(_params.magb_p_noise, 0.f, 1.f);
|
||||
float mag_B_process_noise = sq(mag_B_sig);
|
||||
// mag_B: add process noise
|
||||
float mag_B_sig = dt * math::constrain(_params.magb_p_noise, 0.f, 1.f);
|
||||
float mag_B_process_noise = sq(mag_B_sig);
|
||||
|
||||
for (unsigned index = 0; index < State::mag_B.dof; index++) {
|
||||
const unsigned i = State::mag_B.idx + index;
|
||||
for (unsigned index = 0; index < State::mag_B.dof; index++) {
|
||||
const unsigned i = State::mag_B.idx + index;
|
||||
|
||||
if (P(i, i) < sq(_params.mag_noise)) {
|
||||
P(i, i) += mag_B_process_noise;
|
||||
}
|
||||
}
|
||||
@@ -304,10 +308,7 @@ void Ekf::resetAccelBiasCov()
|
||||
#if defined(CONFIG_EKF2_MAGNETOMETER)
|
||||
void Ekf::resetMagCov()
|
||||
{
|
||||
if (_mag_decl_cov_reset) {
|
||||
ECL_INFO("reset mag covariance");
|
||||
_mag_decl_cov_reset = false;
|
||||
}
|
||||
ECL_INFO("reset mag covariance");
|
||||
|
||||
P.uncorrelateCovarianceSetVariance<State::mag_I.dof>(State::mag_I.idx, sq(_params.mag_noise));
|
||||
P.uncorrelateCovarianceSetVariance<State::mag_B.dof>(State::mag_B.idx, sq(_params.mag_noise));
|
||||
|
||||
@@ -705,8 +705,6 @@ private:
|
||||
// used by magnetometer fusion mode selection
|
||||
bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable
|
||||
AlphaFilter<float> _mag_heading_innov_lpf{0.1f};
|
||||
bool _mag_decl_cov_reset{false}; ///< true after the fuseDeclination() function has been used to modify the earth field covariances after a magnetic field reset event.
|
||||
uint8_t _nb_mag_3d_reset_available{0};
|
||||
uint32_t _min_mag_health_time_us{1'000'000}; ///< magnetometer is marked as healthy only after this amount of time
|
||||
|
||||
estimator_aid_source3d_s _aid_src_mag{};
|
||||
@@ -764,8 +762,6 @@ private:
|
||||
// argument passed in is the declination uncertainty in radians
|
||||
bool fuseDeclination(float decl_sigma);
|
||||
|
||||
// apply sensible limits to the declination and length of the NE mag field states estimates
|
||||
void limitDeclination();
|
||||
#endif // CONFIG_EKF2_MAGNETOMETER
|
||||
|
||||
#if defined(CONFIG_EKF2_AIRSPEED)
|
||||
|
||||
@@ -220,172 +220,172 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
||||
21790000,0.78,-0.016,-0.0032,-0.63,-0.0054,-0.0054,0.016,-0.0081,-0.01,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.013,0.014,0.008,0.042,0.043,0.038,5.4e-07,6.6e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1
|
||||
21890000,0.78,-0.016,-0.0033,-0.63,-0.006,-0.0063,0.016,-0.0088,-0.011,-3.7e+02,-0.0013,-0.0059,4.8e-05,0.061,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.9e-05,9.4e-05,0.048,0.014,0.015,0.0079,0.046,0.047,0.038,5.3e-07,6.5e-07,2.3e-06,0.0059,0.0064,0.00028,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1
|
||||
21990000,0.78,-0.016,-0.0032,-0.63,-0.0059,-0.0035,0.017,-0.0082,-0.0069,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.013,0.0078,0.041,0.042,0.038,5.2e-07,6.4e-07,2.2e-06,0.0058,0.0064,0.00027,0.0011,6.5e-05,0.0012,0.0006,0.0012,0.0012,1,1
|
||||
22090000,0.78,-0.016,-0.0032,-0.63,-0.0056,-0.0051,0.015,-0.0086,-0.0073,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0058,0.0063,0.00027,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22190000,0.78,-0.016,-0.0032,-0.63,-0.0043,-0.0057,0.015,-0.0072,-0.0066,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0058,0.0063,0.00026,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22290000,0.78,-0.016,-0.0032,-0.63,-0.0038,-0.0053,0.016,-0.0079,-0.007,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0058,0.0063,0.00025,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22390000,0.78,-0.016,-0.0032,-0.63,-0.0013,-0.0053,0.017,-0.0061,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0057,0.0062,0.00025,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22490000,0.78,-0.016,-0.0033,-0.63,-0.00016,-0.006,0.018,-0.0055,-0.0068,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22590000,0.78,-0.016,-0.0032,-0.63,0.0017,-0.0049,0.017,-0.0038,-0.0062,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22690000,0.78,-0.016,-0.0033,-0.63,0.0032,-0.0063,0.019,-0.0031,-0.0072,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.059,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22790000,0.78,-0.016,-0.0032,-0.63,0.0043,-0.0056,0.02,-0.0026,-0.0059,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0061,0.00023,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22890000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0065,0.021,-0.0027,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0056,0.0061,0.00023,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22990000,0.78,-0.016,-0.0032,-0.63,0.0047,-0.0067,0.022,-0.0028,-0.0075,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23090000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0064,0.023,-0.0026,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23190000,0.78,-0.016,-0.0032,-0.63,0.0025,-0.0052,0.024,-0.0053,-0.0071,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23290000,0.78,-0.016,-0.0031,-0.63,0.0021,-0.005,0.025,-0.0057,-0.0081,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.5e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23390000,0.78,-0.016,-0.0032,-0.63,-0.0012,-0.0048,0.022,-0.0098,-0.0083,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0055,0.006,0.00021,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23490000,0.78,-0.013,-0.0053,-0.63,0.0044,-0.0044,-0.011,-0.01,-0.0098,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0055,0.006,0.0002,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23590000,0.78,-0.0046,-0.0096,-0.63,0.015,-0.00046,-0.043,-0.0096,-0.006,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.2e-05,8.6e-05,0.048,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23690000,0.78,0.001,-0.0086,-0.63,0.043,0.013,-0.093,-0.0072,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23790000,0.78,-0.0026,-0.0061,-0.63,0.064,0.031,-0.15,-0.0072,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.0059,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23890000,0.78,-0.0089,-0.0042,-0.63,0.078,0.042,-0.2,0.00037,-0.00011,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.091,-0.067,0,0,8.1e-05,8.6e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23990000,0.78,-0.014,-0.0033,-0.63,0.073,0.042,-0.25,-0.0051,-0.0016,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
24090000,0.78,-0.012,-0.0045,-0.63,0.073,0.041,-0.3,0.0013,0.0017,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0058,0.00019,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
24190000,0.78,-0.01,-0.0053,-0.62,0.071,0.04,-0.35,-0.0059,-0.00053,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
24290000,0.78,-0.0092,-0.0057,-0.62,0.079,0.044,-0.4,0.0006,0.0037,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
24390000,0.78,-0.0096,-0.0058,-0.62,0.076,0.043,-0.46,-0.012,-0.0026,-3.7e+02,-0.0012,-0.0059,6.8e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
24490000,0.78,-0.0054,-0.0062,-0.62,0.087,0.05,-0.51,-0.0037,0.002,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
24590000,0.78,-0.0019,-0.0064,-0.62,0.091,0.054,-0.56,-0.017,-0.0069,-3.7e+02,-0.0012,-0.0059,6.3e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0027,-0.091,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,6.3e-05,0.0012,0.00059,0.0011,0.0012,1,1
|
||||
24690000,0.78,-0.001,-0.0064,-0.62,0.11,0.069,-0.64,-0.0078,-0.002,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0028,-0.09,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,6.3e-05,0.0012,0.00059,0.0011,0.0012,1,1
|
||||
24790000,0.78,-0.0025,-0.0063,-0.62,0.11,0.078,-0.73,-0.027,-0.0066,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0026,-0.09,-0.068,0,0,8e-05,8.4e-05,0.047,0.018,0.019,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,6.3e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
24890000,0.78,-0.00067,-0.0078,-0.62,0.13,0.092,-0.75,-0.016,0.0019,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0027,-0.089,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
24990000,0.78,0.0011,-0.0094,-0.62,0.14,0.1,-0.81,-0.038,-0.0043,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0024,-0.089,-0.069,0,0,8e-05,8.4e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
25090000,0.78,0.00051,-0.0098,-0.62,0.16,0.12,-0.86,-0.023,0.0068,-3.7e+02,-0.0011,-0.0059,4.1e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0025,-0.088,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
25190000,0.78,-0.0014,-0.0095,-0.62,0.15,0.11,-0.91,-0.067,-0.015,-3.7e+02,-0.0011,-0.0058,2.2e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0022,-0.088,-0.069,0,0,8e-05,8.3e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.2e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
25290000,0.78,0.0055,-0.011,-0.62,0.18,0.12,-0.96,-0.051,-0.0042,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0023,-0.087,-0.069,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,6.1e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
25390000,0.79,0.012,-0.011,-0.62,0.18,0.13,-1,-0.099,-0.028,-3.7e+02,-0.001,-0.0058,4.9e-06,0.078,-0.03,-0.13,-0.12,-0.025,0.5,-0.0021,-0.087,-0.069,0,0,8e-05,8.3e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00016,0.0011,6.1e-05,0.0012,0.00057,0.0011,0.0012,1,1
|
||||
25490000,0.78,0.013,-0.011,-0.62,0.22,0.16,-1.1,-0.08,-0.015,-3.7e+02,-0.001,-0.0058,1.4e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0024,-0.086,-0.069,0,0,8.1e-05,8.4e-05,0.046,0.022,0.023,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,6e-05,0.0012,0.00057,0.0011,0.0011,1,1
|
||||
25590000,0.78,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.057,0.00062,-3.7e+02,-0.001,-0.0058,1.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0027,-0.085,-0.068,0,0,8.2e-05,8.4e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,6e-05,0.0011,0.00057,0.0011,0.0011,1,1
|
||||
25690000,0.78,0.018,-0.014,-0.62,0.3,0.21,-1.2,-0.03,0.019,-3.7e+02,-0.00099,-0.0058,2.7e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0031,-0.084,-0.068,0,0,8.2e-05,8.5e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.9e-05,0.0011,0.00057,0.0011,0.0011,1,1
|
||||
25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0028,0.039,-3.7e+02,-0.00099,-0.0058,3.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0035,-0.083,-0.067,0,0,8.3e-05,8.5e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.8e-05,0.0011,0.00056,0.001,0.0011,1,1
|
||||
25890000,0.78,0.025,-0.016,-0.63,0.41,0.28,-1.3,0.042,0.061,-3.7e+02,-0.00099,-0.0058,5.3e-05,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0041,-0.081,-0.066,0,0,8.4e-05,8.6e-05,0.045,0.029,0.031,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.00098,5.7e-05,0.0011,0.00056,0.001,0.0011,1,1
|
||||
25990000,0.78,0.022,-0.016,-0.63,0.47,0.32,-1.3,0.086,0.089,-3.7e+02,-0.00099,-0.0058,6.2e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0045,-0.08,-0.065,0,0,8.4e-05,8.6e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00096,5.6e-05,0.0011,0.00055,0.001,0.0011,1,1
|
||||
26090000,0.78,0.032,-0.02,-0.62,0.53,0.35,-1.3,0.14,0.12,-3.7e+02,-0.00098,-0.0058,6e-05,0.079,-0.031,-0.13,-0.12,-0.027,0.5,-0.0046,-0.079,-0.065,0,0,8.5e-05,8.7e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00094,5.5e-05,0.0011,0.00055,0.00098,0.0011,1,1
|
||||
26190000,0.78,0.042,-0.021,-0.62,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.1e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.5,-0.0054,-0.075,-0.063,0,0,8.6e-05,8.7e-05,0.043,0.036,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00014,0.00091,5.4e-05,0.001,0.00054,0.00094,0.001,1,1
|
||||
26290000,0.78,0.044,-0.022,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.4e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.49,-0.0058,-0.073,-0.061,0,0,8.7e-05,8.8e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00088,5.2e-05,0.001,0.00053,0.00091,0.00099,1,1
|
||||
26390000,0.78,0.041,-0.022,-0.63,0.76,0.5,-1.3,0.33,0.24,-3.7e+02,-0.00097,-0.0058,8.2e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0063,-0.071,-0.06,0,0,8.8e-05,8.9e-05,0.041,0.041,0.047,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00085,5.1e-05,0.00097,0.00051,0.00088,0.00096,1,1
|
||||
26490000,0.77,0.057,-0.028,-0.63,0.84,0.55,-1.3,0.41,0.29,-3.7e+02,-0.00097,-0.0058,8.7e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0066,-0.069,-0.058,0,0,8.9e-05,8.9e-05,0.039,0.044,0.051,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00081,4.9e-05,0.00093,0.0005,0.00084,0.00093,1,1
|
||||
26590000,0.77,0.074,-0.033,-0.63,0.96,0.63,-1.3,0.49,0.35,-3.7e+02,-0.00096,-0.0058,8.1e-05,0.08,-0.032,-0.13,-0.14,-0.03,0.49,-0.0062,-0.066,-0.057,0,0,9e-05,9e-05,0.038,0.048,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00077,4.7e-05,0.00088,0.00048,0.0008,0.00088,1,1
|
||||
26690000,0.77,0.077,-0.034,-0.64,1.1,0.71,-1.3,0.6,0.41,-3.7e+02,-0.00096,-0.0058,9.7e-05,0.08,-0.032,-0.13,-0.14,-0.031,0.49,-0.0073,-0.061,-0.052,0,0,9e-05,9.1e-05,0.035,0.052,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00071,4.4e-05,0.00082,0.00045,0.00074,0.00082,1,1
|
||||
26790000,0.77,0.071,-0.033,-0.64,1.2,0.79,-1.3,0.71,0.48,-3.7e+02,-0.00095,-0.0058,9.8e-05,0.08,-0.032,-0.13,-0.14,-0.032,0.48,-0.0071,-0.057,-0.049,0,0,9.1e-05,9.1e-05,0.032,0.055,0.068,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00067,4.2e-05,0.00078,0.00042,0.00069,0.00077,1,1
|
||||
26890000,0.76,0.093,-0.04,-0.64,1.4,0.86,-1.3,0.85,0.56,-3.7e+02,-0.00095,-0.0058,0.0001,0.08,-0.032,-0.13,-0.15,-0.033,0.48,-0.0077,-0.053,-0.047,0,0,9.2e-05,9.2e-05,0.03,0.059,0.073,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00063,4e-05,0.00073,0.00039,0.00065,0.00073,1,1
|
||||
26990000,0.76,0.12,-0.045,-0.64,1.5,0.97,-1.3,0.99,0.65,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.034,0.48,-0.0079,-0.047,-0.043,0,0,9.2e-05,9.2e-05,0.027,0.062,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00058,3.7e-05,0.00066,0.00036,0.00059,0.00066,1,1
|
||||
27090000,0.76,0.12,-0.045,-0.64,1.7,1.1,-1.3,1.2,0.75,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.035,0.47,-0.0078,-0.043,-0.038,0,0,9.3e-05,9.3e-05,0.024,0.066,0.086,0.0061,0.36,0.37,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00052,3.4e-05,0.00059,0.00032,0.00053,0.00059,1,1
|
||||
27190000,0.76,0.11,-0.043,-0.64,1.9,1.2,-1.2,1.3,0.87,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.16,-0.036,0.47,-0.0075,-0.04,-0.035,0,0,9.3e-05,9.3e-05,0.021,0.07,0.092,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00048,3.2e-05,0.00055,0.00029,0.00049,0.00054,1,1
|
||||
27290000,0.76,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,0.99,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.036,0.47,-0.0075,-0.036,-0.033,0,0,9.4e-05,9.4e-05,0.019,0.071,0.095,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00045,3.1e-05,0.00052,0.00026,0.00046,0.00051,1,1
|
||||
27390000,0.76,0.078,-0.033,-0.64,2.2,1.4,-1.2,1.7,1.1,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.037,0.47,-0.0074,-0.035,-0.032,0,0,9.4e-05,9.4e-05,0.017,0.072,0.095,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00043,3e-05,0.0005,0.00024,0.00044,0.00049,1,1
|
||||
27490000,0.76,0.062,-0.029,-0.64,2.2,1.4,-1.2,2,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.029,-0.13,-0.17,-0.037,0.47,-0.0071,-0.034,-0.032,0,0,9.5e-05,9.5e-05,0.015,0.073,0.094,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00042,2.9e-05,0.00049,0.00022,0.00043,0.00048,1,1
|
||||
27590000,0.77,0.049,-0.025,-0.64,2.3,1.5,-1.2,2.2,1.4,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.028,-0.13,-0.17,-0.037,0.47,-0.0066,-0.033,-0.031,0,0,9.6e-05,9.5e-05,0.014,0.073,0.093,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00041,2.9e-05,0.00048,0.0002,0.00042,0.00048,1,1
|
||||
27690000,0.77,0.048,-0.025,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,9.9e-05,0.081,-0.027,-0.13,-0.17,-0.037,0.47,-0.0062,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.013,0.073,0.091,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00013,0.00041,2.9e-05,0.00048,0.00019,0.00042,0.00047,1,1
|
||||
27790000,0.77,0.05,-0.025,-0.64,2.3,1.5,-1.2,2.6,1.7,-3.7e+02,-0.00095,-0.0058,9.4e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0056,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.012,0.073,0.09,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.0004,2.8e-05,0.00047,0.00018,0.00041,0.00047,1,1
|
||||
27890000,0.77,0.048,-0.024,-0.64,2.4,1.6,-1.2,2.9,1.9,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.46,-0.0056,-0.031,-0.031,0,0,9.8e-05,9.7e-05,0.011,0.074,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.8e-05,0.00047,0.00017,0.0004,0.00047,1,1
|
||||
27990000,0.77,0.044,-0.024,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.1e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0056,-0.031,-0.031,0,0,9.9e-05,9.7e-05,0.01,0.075,0.089,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.8e-05,0.00047,0.00016,0.0004,0.00046,1,1
|
||||
28090000,0.77,0.057,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.2,-3.7e+02,-0.00095,-0.0058,8.6e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.0051,-0.03,-0.03,0,0,0.0001,9.8e-05,0.0096,0.076,0.089,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00038,2.7e-05,0.00046,0.00015,0.00039,0.00046,1,1
|
||||
28190000,0.77,0.071,-0.032,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,8.5e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.0051,-0.03,-0.03,0,0,0.0001,9.9e-05,0.0091,0.077,0.089,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00037,2.7e-05,0.00046,0.00015,0.00038,0.00045,1,1
|
||||
28290000,0.77,0.053,-0.026,-0.63,2.5,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.1e-05,0.083,-0.024,-0.13,-0.17,-0.038,0.46,-0.0048,-0.029,-0.029,0,0,0.0001,9.9e-05,0.0086,0.076,0.087,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00014,0.00038,0.00045,1,1
|
||||
28390000,0.77,0.02,-0.013,-0.64,2.4,1.7,0.79,4,2.7,-3.7e+02,-0.00095,-0.0058,7.7e-05,0.083,-0.023,-0.13,-0.17,-0.038,0.46,-0.0046,-0.028,-0.029,0,0,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00014,0.00037,0.00045,1,1
|
||||
28490000,0.77,0.0015,-0.0059,-0.64,2.4,1.7,1.1,4.3,2.9,-3.7e+02,-0.00096,-0.0058,7.2e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0079,0.076,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00013,0.00037,0.00045,1,1
|
||||
28590000,0.77,-0.0022,-0.0045,-0.63,2.3,1.6,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7.1e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00013,0.00037,0.00044,1,1
|
||||
28690000,0.77,-0.0032,-0.0039,-0.63,2.3,1.6,0.99,4.8,3.2,-3.7e+02,-0.00097,-0.0058,6.6e-05,0.082,-0.022,-0.12,-0.17,-0.038,0.46,-0.0044,-0.028,-0.029,0,0,0.0001,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00045,0.00013,0.00037,0.00044,1,1
|
||||
28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.4,-3.7e+02,-0.00097,-0.0058,6.2e-05,0.082,-0.021,-0.12,-0.17,-0.038,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.6e-05,0.00044,0.00012,0.00037,0.00044,1,1
|
||||
28890000,0.78,-0.0033,-0.0037,-0.63,2.2,1.5,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,5.8e-05,0.081,-0.021,-0.12,-0.17,-0.038,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0067,0.079,0.083,0.006,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.6e-05,0.00044,0.00012,0.00037,0.00044,1,1
|
||||
28990000,0.78,-0.0029,-0.0038,-0.63,2.1,1.5,0.98,5.4,3.7,-3.7e+02,-0.00099,-0.0058,5.1e-05,0.08,-0.02,-0.12,-0.17,-0.038,0.46,-0.0039,-0.028,-0.028,0,0,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.6e-05,0.00044,0.00012,0.00037,0.00044,1,1
|
||||
29090000,0.78,-0.0024,-0.004,-0.63,2,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0063,0.081,0.086,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.6e-05,0.00044,0.00011,0.00037,0.00043,1,1
|
||||
29190000,0.78,-0.0022,-0.004,-0.63,2,1.5,0.97,5.9,4,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0061,0.082,0.088,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.6e-05,0.00044,0.00011,0.00037,0.00043,1,1
|
||||
29290000,0.78,-0.0013,-0.0043,-0.63,1.9,1.4,0.99,6.1,4.2,-3.7e+02,-0.001,-0.0058,4.2e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.6e-05,0.00044,0.00011,0.00037,0.00043,1,1
|
||||
29390000,0.78,7.3e-05,-0.0046,-0.63,1.9,1.4,1,6.2,4.3,-3.7e+02,-0.001,-0.0058,3.6e-05,0.079,-0.018,-0.12,-0.17,-0.038,0.46,-0.0034,-0.028,-0.028,0,0,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.6e-05,0.00043,0.00011,0.00037,0.00043,1,1
|
||||
29490000,0.78,0.0012,-0.005,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.4e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.6e-05,0.00043,0.00011,0.00037,0.00043,1,1
|
||||
29590000,0.78,0.0023,-0.0052,-0.63,1.8,1.4,1,6.6,4.6,-3.7e+02,-0.001,-0.0057,3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.00011,0.00037,0.00043,1,1
|
||||
29690000,0.78,0.0029,-0.0055,-0.63,1.7,1.3,0.99,6.8,4.7,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.016,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00043,1,1
|
||||
29790000,0.78,0.0034,-0.0056,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0057,2.3e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.027,0,0,0.00011,0.0001,0.0053,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00042,1,1
|
||||
29890000,0.78,0.0035,-0.0057,-0.63,1.7,1.3,0.97,7.2,5,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.003,-0.028,-0.027,0,0,0.00012,0.0001,0.0053,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00042,1,1
|
||||
29990000,0.78,0.0036,-0.0057,-0.63,1.6,1.3,0.95,7.3,5.1,-3.7e+02,-0.001,-0.0057,1.2e-05,0.077,-0.014,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.6e-05,0.00043,0.0001,0.00037,0.00042,1,1
|
||||
30090000,0.78,0.0035,-0.0057,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0057,8.6e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00043,0.0001,0.00036,0.00042,1,1
|
||||
30190000,0.78,0.0032,-0.0057,-0.63,1.6,1.3,0.93,7.6,5.4,-3.7e+02,-0.001,-0.0057,9.7e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00043,9.9e-05,0.00036,0.00042,1,1
|
||||
30290000,0.78,0.003,-0.0056,-0.63,1.5,1.2,0.92,7.8,5.5,-3.7e+02,-0.001,-0.0057,6.7e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00043,9.8e-05,0.00036,0.00042,1,1
|
||||
30390000,0.78,0.0028,-0.0056,-0.63,1.5,1.2,0.9,8,5.6,-3.7e+02,-0.0011,-0.0057,2.5e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.11,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.8e-05,0.00036,0.00042,1,1
|
||||
30490000,0.78,0.0025,-0.0055,-0.63,1.5,1.2,0.89,8.1,5.8,-3.7e+02,-0.0011,-0.0057,1.4e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.7e-05,0.00036,0.00042,1,1
|
||||
30590000,0.78,0.002,-0.0054,-0.63,1.4,1.2,0.85,8.3,5.9,-3.7e+02,-0.0011,-0.0057,-7.1e-07,0.076,-0.011,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.6e-05,0.00036,0.00042,1,1
|
||||
30690000,0.78,0.0017,-0.0053,-0.63,1.4,1.2,0.84,8.4,6,-3.7e+02,-0.0011,-0.0057,-4e-06,0.075,-0.0099,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.0059,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.6e-05,0.00036,0.00042,1,1
|
||||
30790000,0.78,0.0013,-0.0052,-0.63,1.4,1.2,0.84,8.6,6.1,-3.7e+02,-0.0011,-0.0057,-7.1e-06,0.075,-0.0097,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2.6e-05,0.00042,9.5e-05,0.00036,0.00042,1,1
|
||||
30890000,0.78,0.00088,-0.0051,-0.63,1.4,1.1,0.82,8.7,6.2,-3.7e+02,-0.0011,-0.0057,-1e-05,0.074,-0.0089,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00035,2.6e-05,0.00042,9.5e-05,0.00036,0.00042,1,1
|
||||
30990000,0.78,0.00029,-0.005,-0.63,1.3,1.1,0.82,8.9,6.3,-3.7e+02,-0.0011,-0.0057,-1.4e-05,0.074,-0.0081,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00013,0.0001,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0052,9.9e-05,0.00035,2.6e-05,0.00042,9.4e-05,0.00036,0.00041,1,1
|
||||
31090000,0.78,-0.00026,-0.0048,-0.63,1.3,1.1,0.81,9,6.5,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0074,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0048,0.0052,9.8e-05,0.00035,2.6e-05,0.00042,9.4e-05,0.00036,0.00041,1,1
|
||||
31190000,0.78,-0.00067,-0.0047,-0.63,1.3,1.1,0.8,9.1,6.6,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.074,-0.0066,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2.6e-05,0.00042,9.3e-05,0.00036,0.00041,1,1
|
||||
31290000,0.78,-0.0013,-0.0046,-0.63,1.2,1.1,0.8,9.3,6.7,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.073,-0.0059,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2.6e-05,0.00042,9.3e-05,0.00036,0.00041,1,1
|
||||
31390000,0.78,-0.002,-0.0044,-0.63,1.2,1.1,0.8,9.4,6.8,-3.7e+02,-0.0011,-0.0057,-2.6e-05,0.073,-0.0053,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.6e-05,0.00035,2.6e-05,0.00042,9.3e-05,0.00036,0.00041,1,1
|
||||
31490000,0.78,-0.0026,-0.0042,-0.63,1.2,1,0.79,9.5,6.9,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.073,-0.0045,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00035,2.6e-05,0.00042,9.2e-05,0.00036,0.00041,1,1
|
||||
31590000,0.78,-0.003,-0.0042,-0.63,1.1,1,0.79,9.6,7,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.072,-0.0039,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00035,2.6e-05,0.00041,9.2e-05,0.00036,0.00041,1,1
|
||||
31690000,0.78,-0.0037,-0.004,-0.63,1.1,1,0.8,9.8,7.1,-3.7e+02,-0.0011,-0.0057,-3.5e-05,0.072,-0.0032,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.14,0.21,0.0059,2.9,3.6,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00035,2.6e-05,0.00041,9.2e-05,0.00036,0.00041,1,1
|
||||
31790000,0.78,-0.0044,-0.0038,-0.63,1.1,0.99,0.8,9.9,7.2,-3.7e+02,-0.0011,-0.0057,-3.7e-05,0.071,-0.0023,-0.12,-0.17,-0.038,0.46,-0.0021,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00035,2.6e-05,0.00041,9.2e-05,0.00036,0.00041,1,1
|
||||
31890000,0.78,-0.0051,-0.0037,-0.63,1.1,0.97,0.79,10,7.3,-3.7e+02,-0.0011,-0.0057,-4.1e-05,0.071,-0.0015,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00035,2.6e-05,0.00041,9.1e-05,0.00036,0.00041,1,1
|
||||
31990000,0.78,-0.0057,-0.0035,-0.63,1,0.96,0.79,10,7.4,-3.7e+02,-0.0011,-0.0057,-4.7e-05,0.07,-0.00054,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00035,2.6e-05,0.00041,9.1e-05,0.00036,0.00041,1,1
|
||||
32090000,0.78,-0.0064,-0.0033,-0.63,1,0.94,0.8,10,7.5,-3.7e+02,-0.0012,-0.0057,-5.1e-05,0.07,0.00015,-0.11,-0.17,-0.038,0.46,-0.0019,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.2e-05,0.00035,2.6e-05,0.00041,9.1e-05,0.00036,0.0004,1,1
|
||||
32190000,0.78,-0.0074,-0.0031,-0.63,0.97,0.92,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-6e-05,0.069,0.0011,-0.11,-0.17,-0.038,0.46,-0.0018,-0.029,-0.025,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2.6e-05,0.00041,9.1e-05,0.00036,0.0004,1,1
|
||||
32290000,0.78,-0.0081,-0.003,-0.63,0.94,0.9,0.79,10,7.7,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.069,0.0021,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2.6e-05,0.00041,9e-05,0.00036,0.0004,1,1
|
||||
32390000,0.78,-0.0087,-0.0029,-0.63,0.91,0.88,0.79,11,7.8,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.068,0.0027,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2.6e-05,0.00041,9e-05,0.00036,0.0004,1,1
|
||||
32490000,0.78,-0.009,-0.0028,-0.62,0.88,0.86,0.8,11,7.9,-3.7e+02,-0.0012,-0.0057,-6.7e-05,0.068,0.0035,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1
|
||||
32590000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7e-05,0.067,0.0038,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1
|
||||
32690000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0044,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1
|
||||
32790000,0.78,-0.0093,-0.0028,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0048,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.024,0,0,0.00014,0.0001,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1
|
||||
32890000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.5e-05,0.066,0.0053,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,9e-05,0.00036,0.0004,1,1
|
||||
32990000,0.78,-0.0092,-0.003,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.9e-05,0.065,0.0058,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,8.9e-05,0.00036,0.00039,1,1
|
||||
33090000,0.78,-0.0092,-0.003,-0.62,-1.6,-0.86,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,8.9e-05,0.00036,0.00039,1,1
|
||||
33190000,0.78,-0.0079,-0.0062,-0.62,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.065,0.0061,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2.6e-05,0.0004,8.9e-05,0.00036,0.00039,1,1
|
||||
33290000,0.83,-0.0058,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.7e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2.5e-05,0.0004,8.9e-05,0.00035,0.00039,1,1
|
||||
33390000,0.89,-0.0065,-0.015,-0.45,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.064,0.0057,-0.11,-0.18,-0.039,0.46,-0.00096,-0.027,-0.024,0,0,0.00015,0.0001,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00031,2.4e-05,0.0004,8.6e-05,0.00032,0.00039,1,1
|
||||
33490000,0.95,-0.0051,-0.0068,-0.3,-1.5,-0.87,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.5e-05,0.064,0.0057,-0.11,-0.18,-0.04,0.46,-0.00044,-0.02,-0.024,0,0,0.00015,0.0001,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00023,2.1e-05,0.00039,7.7e-05,0.00024,0.00039,1,1
|
||||
33590000,0.99,-0.0082,-2.9e-05,-0.14,-1.5,-0.85,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.5e-05,0.064,0.0057,-0.11,-0.19,-0.042,0.46,0.00035,-0.013,-0.024,0,0,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00015,1.7e-05,0.00039,6.3e-05,0.00015,0.00039,1,1
|
||||
33690000,1,-0.012,0.0042,0.031,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2.1e-05,0.064,0.0057,-0.11,-0.19,-0.043,0.46,0.00017,-0.0091,-0.025,0,0,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0047,0.0051,8.8e-05,0.0001,1.4e-05,0.00039,5e-05,9.7e-05,0.00038,1,1
|
||||
33790000,0.98,-0.013,0.0066,0.2,-1.6,-0.89,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.6e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00053,-0.0066,-0.025,0,0,0.00015,0.0001,0.0024,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,6.9e-05,1.3e-05,0.00038,3.7e-05,6.2e-05,0.00038,1,1
|
||||
33890000,0.93,-0.013,0.0087,0.36,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.8e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00075,-0.0053,-0.025,0,0,0.00015,0.0001,0.0021,0.04,0.046,0.042,0.32,0.32,0.065,2.8e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,5.1e-05,1.2e-05,0.00038,2.8e-05,4.2e-05,0.00038,1,1
|
||||
33990000,0.87,-0.015,0.0073,0.5,-1.7,-0.97,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0055,-0.11,-0.2,-0.044,0.46,0.00052,-0.0039,-0.025,0,0,0.00014,9.8e-05,0.0018,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,4e-05,1.1e-05,0.00038,2.1e-05,3e-05,0.00038,1,1
|
||||
34090000,0.8,-0.016,0.0065,0.6,-1.7,-1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.064,0.0049,-0.11,-0.2,-0.044,0.46,0.00019,-0.0032,-0.025,0,0,0.00014,9.7e-05,0.0017,0.038,0.046,0.033,0.33,0.33,0.063,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,3.4e-05,1.1e-05,0.00038,1.8e-05,2.4e-05,0.00038,1,1
|
||||
34190000,0.75,-0.014,0.0071,0.66,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0047,-0.11,-0.2,-0.044,0.46,0.0002,-0.0027,-0.025,0,0,0.00014,9.7e-05,0.0016,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,3e-05,1.1e-05,0.00038,1.5e-05,1.9e-05,0.00038,1,1
|
||||
34290000,0.71,-0.011,0.0086,0.7,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0044,-0.11,-0.2,-0.044,0.46,0.00016,-0.0023,-0.025,0,0,0.00014,9.7e-05,0.0015,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.7e-05,1.1e-05,0.00038,1.3e-05,1.6e-05,0.00038,1,1
|
||||
34390000,0.69,-0.0076,0.01,0.72,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0041,-0.11,-0.2,-0.044,0.46,8.9e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0015,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.5e-05,1.1e-05,0.00038,1.1e-05,1.4e-05,0.00038,1,1
|
||||
34490000,0.67,-0.0054,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.004,-0.11,-0.2,-0.044,0.46,4.7e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0014,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.4e-05,1.1e-05,0.00038,1e-05,1.2e-05,0.00038,1,1
|
||||
34590000,0.67,-0.004,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0039,-0.11,-0.2,-0.044,0.46,-5e-05,-0.0019,-0.025,0,0,0.00014,9.5e-05,0.0014,0.057,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.2e-05,1e-05,0.00038,9.2e-06,1.1e-05,0.00038,1,1
|
||||
34690000,0.66,-0.0032,0.013,0.75,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0038,-0.11,-0.2,-0.044,0.46,1.5e-05,-0.0016,-0.025,0,0,0.00014,9.5e-05,0.0014,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,2.2e-05,1e-05,0.00038,8.5e-06,9.9e-06,0.00038,1,1
|
||||
34790000,0.66,-0.0027,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0038,-0.11,-0.2,-0.044,0.46,0.00014,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0014,0.068,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,2.1e-05,1e-05,0.00038,7.9e-06,9.1e-06,0.00038,1,1
|
||||
34890000,0.65,-0.0025,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0036,-0.11,-0.2,-0.044,0.46,8.7e-05,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0013,0.074,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,2e-05,1e-05,0.00038,7.4e-06,8.4e-06,0.00038,1,1
|
||||
34990000,0.65,-0.006,0.02,0.76,-3.1,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0002,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0013,0.091,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,2e-05,1e-05,0.00038,7.1e-06,7.9e-06,0.00038,1,1
|
||||
35090000,0.65,-0.006,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00022,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0013,0.1,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.9e-05,1e-05,0.00038,6.7e-06,7.4e-06,0.00038,1,1
|
||||
35190000,0.65,-0.0061,0.02,0.76,-3.2,-2.7,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00026,-0.0015,-0.025,0,0,0.00013,9.3e-05,0.0013,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.9e-05,1e-05,0.00038,6.4e-06,7e-06,0.00038,1,1
|
||||
35290000,0.65,-0.0063,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0003,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0013,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.8e-05,1e-05,0.00038,6.1e-06,6.6e-06,0.00038,1,1
|
||||
35390000,0.65,-0.0063,0.02,0.76,-3.3,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00038,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0013,0.13,0.18,0.012,0.57,0.62,0.053,2.8e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.8e-05,1e-05,0.00038,5.9e-06,6.3e-06,0.00038,1,1
|
||||
35490000,0.65,-0.0063,0.02,0.76,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00045,-0.0016,-0.025,0,0,0.00013,9.2e-05,0.0013,0.14,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.8e-05,1e-05,0.00038,5.7e-06,6e-06,0.00038,1,1
|
||||
35590000,0.65,-0.0064,0.02,0.76,-3.3,-3,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00042,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0013,0.15,0.21,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.5e-06,5.8e-06,0.00038,1,1
|
||||
35690000,0.65,-0.0063,0.02,0.76,-3.4,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00048,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0013,0.16,0.22,0.011,0.69,0.78,0.05,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.4e-06,5.6e-06,0.00038,1,1
|
||||
35790000,0.65,-0.0064,0.02,0.76,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9.1e-05,0.0013,0.17,0.23,0.01,0.74,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.2e-06,5.3e-06,0.00038,1,1
|
||||
35890000,0.65,-0.0065,0.02,0.76,-3.4,-3.2,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0036,-0.11,-0.2,-0.044,0.46,0.0005,-0.0015,-0.025,0,0,0.00013,9e-05,0.0013,0.18,0.25,0.0096,0.79,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0047,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5.1e-06,5.2e-06,0.00038,1,1
|
||||
35990000,0.65,-0.0065,0.02,0.76,-3.5,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00047,-0.0015,-0.025,0,0,0.00013,9e-05,0.0013,0.19,0.27,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,1e-05,0.00038,5e-06,5e-06,0.00037,1,1
|
||||
36090000,0.65,-0.0065,0.02,0.76,-3.5,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0016,-0.025,0,0,0.00013,9e-05,0.0013,0.21,0.28,0.0089,0.9,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.6e-05,1e-05,0.00038,4.9e-06,4.8e-06,0.00037,1,1
|
||||
36190000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0037,-0.11,-0.2,-0.044,0.46,0.00057,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0012,0.22,0.3,0.0086,0.97,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,1e-05,0.00038,4.8e-06,4.7e-06,0.00037,1,1
|
||||
36290000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00059,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0012,0.23,0.32,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,1e-05,0.00038,4.7e-06,4.6e-06,0.00037,1,1
|
||||
36390000,0.65,-0.0066,0.02,0.76,-3.6,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,8.9e-05,0.0012,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,1e-05,0.00038,4.6e-06,4.4e-06,0.00037,1,1
|
||||
36490000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.058,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00055,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.26,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,1e-05,0.00038,4.6e-06,4.3e-06,0.00037,1,1
|
||||
36590000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0035,-0.11,-0.2,-0.044,0.46,0.00059,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.28,0.37,0.0076,1.3,1.6,0.042,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,1e-05,0.00038,4.5e-06,4.2e-06,0.00037,1,1
|
||||
36690000,0.65,-0.0067,0.02,0.76,-3.7,-3.8,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00061,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.29,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,1e-05,0.00038,4.4e-06,4.1e-06,0.00037,1,1
|
||||
36790000,0.65,-0.0067,0.021,0.76,-3.7,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0036,-0.11,-0.2,-0.044,0.46,0.00065,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0012,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.4e-06,4e-06,0.00037,1,1
|
||||
36890000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00068,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0012,0.33,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.3e-06,3.9e-06,0.00037,1,1
|
||||
36990000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.066,0.0039,-0.11,-0.2,-0.044,0.46,0.00069,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0012,0.34,0.45,0.0071,1.7,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.3e-06,3.9e-06,0.00037,1,1
|
||||
37090000,0.65,-0.0067,0.021,0.76,-3.8,-4.1,-0.0065,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.6e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0012,0.36,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.2e-06,3.8e-06,0.00037,1,1
|
||||
37190000,0.65,-0.0067,0.021,0.76,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.6e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0012,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.2e-06,3.7e-06,0.00037,1,1
|
||||
37290000,0.65,-0.0068,0.021,0.76,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.3e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.0007,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.4,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.2e-06,3.7e-06,0.00037,1,1
|
||||
37390000,0.65,-0.0067,0.021,0.76,-3.9,-4.3,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00072,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.42,0.54,0.0067,2.3,3,0.038,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.1e-06,3.6e-06,0.00037,1,1
|
||||
37490000,0.65,-0.0067,0.021,0.76,-3.9,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.4e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.44,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.1e-06,3.5e-06,0.00037,1,1
|
||||
37590000,0.65,-0.0067,0.021,0.76,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00075,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0012,0.46,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4.1e-06,3.5e-06,0.00037,1,1
|
||||
37690000,0.65,-0.0068,0.021,0.76,-3.9,-4.6,0.043,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.4e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.0012,0.48,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,1e-05,0.00038,4e-06,3.4e-06,0.00037,1,1
|
||||
37790000,0.65,-0.0068,0.021,0.76,-4,-4.6,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.0012,0.5,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.5e-05,1e-05,0.00038,4e-06,3.4e-06,0.00037,1,1
|
||||
37890000,0.65,-0.0069,0.021,0.76,-4,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7e-05,0.068,0.0043,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.0012,0.52,0.65,0.0065,3.3,4.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,4e-06,3.3e-06,0.00037,1,1
|
||||
37990000,0.65,-0.0069,0.021,0.76,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.0012,0.54,0.67,0.0065,3.6,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,4e-06,3.3e-06,0.00037,1,1
|
||||
38090000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.079,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.0012,0.56,0.7,0.0065,3.8,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,4e-06,3.2e-06,0.00037,1,1
|
||||
38190000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00079,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.0012,0.58,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3.2e-06,0.00037,1,1
|
||||
38290000,0.65,-0.0069,0.021,0.76,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00079,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.0012,0.61,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3.1e-06,0.00037,1,1
|
||||
38390000,0.65,-0.0069,0.021,0.76,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.0039,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.63,0.77,0.0065,4.7,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3.1e-06,0.00037,1,1
|
||||
38490000,0.65,-0.0069,0.021,0.76,-4.2,-5.1,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.3e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.65,0.8,0.0065,5,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3e-06,0.00037,1,1
|
||||
38590000,0.65,-0.0068,0.021,0.76,-4.2,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.4e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.68,0.82,0.0065,5.4,6.9,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3e-06,0.00037,1,1
|
||||
38690000,0.65,-0.0068,0.021,0.76,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6e-05,0.067,0.0044,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.7,0.85,0.0065,5.7,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,3e-06,0.00037,1,1
|
||||
38790000,0.65,-0.0068,0.021,0.76,-4.3,-5.3,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,5.9e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00081,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.72,0.88,0.0065,6.1,7.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.9e-06,2.9e-06,0.00037,1,1
|
||||
38890000,0.65,-0.0069,0.021,0.76,-4.3,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,5.9e-05,0.067,0.0043,-0.11,-0.2,-0.044,0.46,0.00081,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.0012,0.74,0.89,0.0065,6.5,8.2,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,1e-05,0.00038,3.8e-06,2.9e-06,0.00037,1,1
|
||||
22090000,0.78,-0.016,-0.0032,-0.63,-0.0056,-0.0051,0.015,-0.0086,-0.0073,-3.7e+02,-0.0013,-0.0059,5.5e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.8e-05,9.3e-05,0.048,0.013,0.014,0.0078,0.045,0.045,0.037,5.2e-07,6.3e-07,2.2e-06,0.0058,0.0063,0.00027,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22190000,0.78,-0.016,-0.0032,-0.63,-0.0043,-0.0057,0.015,-0.0072,-0.0066,-3.7e+02,-0.0013,-0.0059,5.8e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.012,0.013,0.0076,0.04,0.04,0.037,5.1e-07,6.2e-07,2.2e-06,0.0058,0.0063,0.00026,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22290000,0.78,-0.016,-0.0032,-0.63,-0.0038,-0.0053,0.016,-0.0079,-0.007,-3.7e+02,-0.0013,-0.0059,5.7e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.7e-05,9.2e-05,0.048,0.013,0.014,0.0076,0.043,0.044,0.037,5e-07,6.1e-07,2.2e-06,0.0058,0.0063,0.00025,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22390000,0.78,-0.016,-0.0032,-0.63,-0.0013,-0.0053,0.017,-0.0061,-0.0063,-3.7e+02,-0.0013,-0.0059,6.1e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.012,0.013,0.0075,0.039,0.04,0.037,4.9e-07,6e-07,2.2e-06,0.0057,0.0062,0.00025,0.0011,6.4e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22490000,0.78,-0.016,-0.0033,-0.63,-0.00016,-0.006,0.018,-0.0055,-0.0068,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.013,0.014,0.0074,0.042,0.043,0.037,4.9e-07,5.9e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22590000,0.78,-0.016,-0.0032,-0.63,0.0017,-0.0049,0.017,-0.0038,-0.0062,-3.7e+02,-0.0014,-0.0059,6.5e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.013,0.014,0.0073,0.045,0.045,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22690000,0.78,-0.016,-0.0033,-0.63,0.0032,-0.0063,0.019,-0.0031,-0.0072,-3.7e+02,-0.0014,-0.0059,6.9e-05,0.059,-0.028,-0.13,-0.11,-0.024,0.5,-0.0027,-0.092,-0.068,0,0,8.6e-05,9.1e-05,0.048,0.014,0.015,0.0073,0.048,0.049,0.036,4.8e-07,5.8e-07,2.2e-06,0.0057,0.0062,0.00024,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22790000,0.78,-0.016,-0.0032,-0.63,0.0043,-0.0056,0.02,-0.0026,-0.0059,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.014,0.015,0.0072,0.051,0.052,0.036,4.7e-07,5.7e-07,2.2e-06,0.0057,0.0061,0.00023,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22890000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0065,0.021,-0.0027,-0.0066,-3.7e+02,-0.0014,-0.0059,6.2e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.015,0.016,0.0072,0.055,0.056,0.036,4.7e-07,5.7e-07,2.2e-06,0.0056,0.0061,0.00023,0.0011,6.3e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
22990000,0.78,-0.016,-0.0032,-0.63,0.0047,-0.0067,0.022,-0.0028,-0.0075,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.015,0.016,0.0071,0.057,0.059,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23090000,0.78,-0.016,-0.0032,-0.63,0.0049,-0.0064,0.023,-0.0026,-0.0072,-3.7e+02,-0.0014,-0.0059,6.3e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.5e-05,9e-05,0.048,0.016,0.017,0.007,0.062,0.064,0.036,4.6e-07,5.6e-07,2.2e-06,0.0056,0.0061,0.00022,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23190000,0.78,-0.016,-0.0032,-0.63,0.0025,-0.0052,0.024,-0.0053,-0.0071,-3.7e+02,-0.0014,-0.0059,6.6e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.9e-05,0.048,0.016,0.017,0.0069,0.065,0.066,0.035,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23290000,0.78,-0.016,-0.0031,-0.63,0.0021,-0.005,0.025,-0.0057,-0.0081,-3.7e+02,-0.0014,-0.0059,6.7e-05,0.059,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.5e-05,8.9e-05,0.048,0.016,0.018,0.0069,0.07,0.071,0.036,4.5e-07,5.4e-07,2.2e-06,0.0056,0.006,0.00021,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23390000,0.78,-0.016,-0.0032,-0.63,-0.0012,-0.0048,0.022,-0.0098,-0.0083,-3.7e+02,-0.0013,-0.0059,6.9e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.093,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.016,0.017,0.0068,0.072,0.074,0.035,4.4e-07,5.3e-07,2.2e-06,0.0055,0.006,0.00021,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23490000,0.78,-0.013,-0.0053,-0.63,0.0044,-0.0044,-0.011,-0.01,-0.0098,-3.7e+02,-0.0013,-0.0059,7.3e-05,0.06,-0.029,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.4e-05,8.8e-05,0.048,0.017,0.018,0.0068,0.078,0.08,0.035,4.3e-07,5.3e-07,2.2e-06,0.0055,0.006,0.0002,0.0011,6.2e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23590000,0.78,-0.0046,-0.0096,-0.63,0.015,-0.00046,-0.043,-0.0096,-0.006,-3.7e+02,-0.0013,-0.0059,7.6e-05,0.06,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.092,-0.068,0,0,8.2e-05,8.6e-05,0.047,0.014,0.015,0.0067,0.062,0.063,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.1e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23690000,0.78,0.001,-0.0086,-0.63,0.043,0.013,-0.093,-0.0072,-0.0058,-3.7e+02,-0.0013,-0.0059,7.8e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.068,0,0,8.2e-05,8.7e-05,0.047,0.015,0.016,0.0067,0.066,0.068,0.035,4.2e-07,5.1e-07,2.2e-06,0.0055,0.0059,0.0002,0.0011,6.1e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23790000,0.78,-0.0026,-0.0061,-0.63,0.064,0.031,-0.15,-0.0072,-0.0038,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.092,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.013,0.014,0.0066,0.055,0.056,0.035,4.1e-07,4.9e-07,2.1e-06,0.0055,0.0059,0.00019,0.0011,6.1e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23890000,0.78,-0.0089,-0.0042,-0.63,0.078,0.042,-0.2,0.00037,-0.00011,-3.7e+02,-0.0013,-0.0059,8.5e-05,0.061,-0.03,-0.13,-0.11,-0.024,0.5,-0.003,-0.091,-0.067,0,0,8.1e-05,8.6e-05,0.047,0.014,0.015,0.0066,0.059,0.06,0.035,4.1e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
23990000,0.78,-0.014,-0.0033,-0.63,0.073,0.042,-0.25,-0.0051,-0.0016,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.062,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.014,0.015,0.0066,0.061,0.063,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0059,0.00019,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
24090000,0.78,-0.012,-0.0045,-0.63,0.073,0.041,-0.3,0.0013,0.0017,-3.7e+02,-0.0013,-0.0059,8.7e-05,0.063,-0.03,-0.13,-0.11,-0.024,0.5,-0.0029,-0.091,-0.067,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.066,0.067,0.035,4e-07,4.9e-07,2.1e-06,0.0054,0.0058,0.00019,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
24190000,0.78,-0.01,-0.0053,-0.62,0.071,0.04,-0.35,-0.0059,-0.00053,-3.7e+02,-0.0013,-0.0059,8.4e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.015,0.016,0.0065,0.069,0.07,0.034,4e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
24290000,0.78,-0.0092,-0.0057,-0.62,0.079,0.044,-0.4,0.0006,0.0037,-3.7e+02,-0.0013,-0.0059,8.3e-05,0.064,-0.03,-0.13,-0.11,-0.024,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0065,0.074,0.075,0.034,3.9e-07,4.8e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6e-05,0.0012,0.00059,0.0012,0.0012,1,1
|
||||
24390000,0.78,-0.0096,-0.0058,-0.62,0.076,0.043,-0.46,-0.012,-0.0026,-3.7e+02,-0.0012,-0.0059,6.8e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.016,0.017,0.0064,0.076,0.078,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,6e-05,0.0012,0.00058,0.0012,0.0012,1,1
|
||||
24490000,0.78,-0.0054,-0.0062,-0.62,0.087,0.05,-0.51,-0.0037,0.002,-3.7e+02,-0.0012,-0.0059,6.9e-05,0.065,-0.03,-0.13,-0.11,-0.025,0.5,-0.0028,-0.091,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.017,0.018,0.0064,0.082,0.083,0.034,3.9e-07,4.7e-07,2.1e-06,0.0054,0.0058,0.00018,0.0011,5.9e-05,0.0012,0.00058,0.0012,0.0012,1,1
|
||||
24590000,0.78,-0.0019,-0.0064,-0.62,0.091,0.054,-0.56,-0.017,-0.0069,-3.7e+02,-0.0012,-0.0059,6.3e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0027,-0.091,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.017,0.018,0.0063,0.084,0.086,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,5.9e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
24690000,0.78,-0.001,-0.0064,-0.62,0.11,0.069,-0.64,-0.0078,-0.002,-3.7e+02,-0.0012,-0.0059,7e-05,0.067,-0.029,-0.13,-0.11,-0.025,0.5,-0.0028,-0.09,-0.068,0,0,8.1e-05,8.5e-05,0.047,0.018,0.019,0.0063,0.09,0.092,0.034,3.8e-07,4.6e-07,2.1e-06,0.0053,0.0058,0.00017,0.0011,5.9e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
24790000,0.78,-0.0025,-0.0063,-0.62,0.11,0.078,-0.73,-0.027,-0.0066,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0026,-0.09,-0.068,0,0,8e-05,8.4e-05,0.047,0.018,0.019,0.0062,0.092,0.094,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,5.9e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
24890000,0.78,-0.00067,-0.0078,-0.62,0.13,0.092,-0.75,-0.016,0.0019,-3.7e+02,-0.0012,-0.0059,5.9e-05,0.069,-0.03,-0.13,-0.11,-0.025,0.5,-0.0027,-0.089,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.019,0.02,0.0062,0.099,0.1,0.034,3.7e-07,4.6e-07,2.1e-06,0.0053,0.0057,0.00017,0.0011,5.8e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
24990000,0.78,0.0011,-0.0094,-0.62,0.14,0.1,-0.81,-0.038,-0.0043,-3.7e+02,-0.0011,-0.0059,4.4e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0024,-0.089,-0.069,0,0,8e-05,8.4e-05,0.047,0.019,0.019,0.0062,0.1,0.1,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.8e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
25090000,0.78,0.00051,-0.0098,-0.62,0.16,0.12,-0.86,-0.023,0.0068,-3.7e+02,-0.0011,-0.0059,4.1e-05,0.071,-0.03,-0.13,-0.11,-0.025,0.5,-0.0025,-0.088,-0.068,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0062,0.11,0.11,0.034,3.7e-07,4.5e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.8e-05,0.0012,0.00058,0.0011,0.0012,1,1
|
||||
25190000,0.78,-0.0014,-0.0095,-0.62,0.15,0.11,-0.91,-0.067,-0.015,-3.7e+02,-0.0011,-0.0058,2.2e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0022,-0.088,-0.069,0,0,8e-05,8.3e-05,0.047,0.019,0.02,0.0061,0.11,0.11,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.7e-05,0.0012,0.00057,0.0011,0.0012,1,1
|
||||
25290000,0.78,0.0055,-0.011,-0.62,0.18,0.12,-0.96,-0.051,-0.0042,-3.7e+02,-0.0011,-0.0058,2.4e-05,0.074,-0.03,-0.13,-0.11,-0.025,0.5,-0.0023,-0.087,-0.069,0,0,8.1e-05,8.4e-05,0.047,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0053,0.0057,0.00016,0.0011,5.7e-05,0.0012,0.00057,0.0011,0.0012,1,1
|
||||
25390000,0.79,0.012,-0.011,-0.62,0.18,0.13,-1,-0.099,-0.028,-3.7e+02,-0.001,-0.0058,4.9e-06,0.078,-0.03,-0.13,-0.12,-0.025,0.5,-0.0021,-0.087,-0.069,0,0,8e-05,8.3e-05,0.046,0.02,0.021,0.0061,0.12,0.12,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00016,0.0011,5.6e-05,0.0012,0.00057,0.0011,0.0012,1,1
|
||||
25490000,0.78,0.013,-0.011,-0.62,0.22,0.16,-1.1,-0.08,-0.015,-3.7e+02,-0.001,-0.0058,1.4e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0024,-0.086,-0.069,0,0,8.1e-05,8.4e-05,0.046,0.022,0.023,0.0061,0.13,0.13,0.033,3.6e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.5e-05,0.0012,0.00057,0.0011,0.0011,1,1
|
||||
25590000,0.78,0.011,-0.011,-0.62,0.25,0.19,-1.1,-0.057,0.00062,-3.7e+02,-0.001,-0.0058,1.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0027,-0.085,-0.068,0,0,8.2e-05,8.4e-05,0.046,0.023,0.024,0.0061,0.14,0.14,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.5e-05,0.0011,0.00057,0.0011,0.0011,1,1
|
||||
25690000,0.78,0.018,-0.014,-0.62,0.3,0.21,-1.2,-0.03,0.019,-3.7e+02,-0.00099,-0.0058,2.7e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0031,-0.084,-0.068,0,0,8.2e-05,8.5e-05,0.046,0.025,0.026,0.0061,0.14,0.15,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.4e-05,0.0011,0.00056,0.0011,0.0011,1,1
|
||||
25790000,0.78,0.025,-0.016,-0.62,0.35,0.25,-1.2,0.0028,0.039,-3.7e+02,-0.00099,-0.0058,3.9e-05,0.078,-0.03,-0.13,-0.12,-0.026,0.5,-0.0035,-0.083,-0.067,0,0,8.3e-05,8.5e-05,0.045,0.027,0.028,0.0061,0.15,0.16,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.001,5.3e-05,0.0011,0.00056,0.001,0.0011,1,1
|
||||
25890000,0.78,0.025,-0.016,-0.63,0.41,0.28,-1.3,0.042,0.061,-3.7e+02,-0.00099,-0.0058,5.3e-05,0.078,-0.03,-0.13,-0.12,-0.027,0.5,-0.0041,-0.081,-0.066,0,0,8.4e-05,8.6e-05,0.045,0.029,0.031,0.0061,0.16,0.17,0.033,3.5e-07,4.4e-07,2.1e-06,0.0052,0.0057,0.00015,0.00098,5.2e-05,0.0011,0.00056,0.001,0.0011,1,1
|
||||
25990000,0.78,0.022,-0.016,-0.63,0.47,0.32,-1.3,0.086,0.089,-3.7e+02,-0.00099,-0.0058,6.2e-05,0.079,-0.03,-0.13,-0.12,-0.027,0.5,-0.0045,-0.08,-0.065,0,0,8.4e-05,8.6e-05,0.045,0.031,0.033,0.0061,0.18,0.18,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00096,5.1e-05,0.0011,0.00055,0.001,0.0011,1,1
|
||||
26090000,0.78,0.032,-0.02,-0.62,0.53,0.35,-1.3,0.14,0.12,-3.7e+02,-0.00098,-0.0058,6e-05,0.079,-0.031,-0.13,-0.12,-0.027,0.5,-0.0046,-0.079,-0.065,0,0,8.5e-05,8.7e-05,0.044,0.033,0.036,0.0061,0.19,0.19,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00015,0.00094,5e-05,0.0011,0.00055,0.00098,0.0011,1,1
|
||||
26190000,0.78,0.042,-0.021,-0.62,0.6,0.4,-1.3,0.19,0.16,-3.7e+02,-0.00098,-0.0058,7.1e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.5,-0.0054,-0.075,-0.063,0,0,8.6e-05,8.7e-05,0.043,0.035,0.039,0.0061,0.2,0.21,0.033,3.5e-07,4.4e-07,2e-06,0.0052,0.0057,0.00014,0.00091,4.9e-05,0.001,0.00054,0.00094,0.001,1,1
|
||||
26290000,0.78,0.044,-0.022,-0.63,0.68,0.45,-1.3,0.25,0.2,-3.7e+02,-0.00097,-0.0058,7.4e-05,0.079,-0.031,-0.13,-0.13,-0.028,0.49,-0.0057,-0.073,-0.061,0,0,8.7e-05,8.8e-05,0.042,0.039,0.043,0.0061,0.21,0.22,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00088,4.7e-05,0.001,0.00053,0.00091,0.00099,1,1
|
||||
26390000,0.78,0.041,-0.022,-0.63,0.76,0.5,-1.3,0.33,0.24,-3.7e+02,-0.00097,-0.0058,8.2e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0063,-0.071,-0.06,0,0,8.8e-05,8.9e-05,0.041,0.041,0.047,0.0061,0.23,0.23,0.033,3.5e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00085,4.6e-05,0.00097,0.00051,0.00088,0.00096,1,1
|
||||
26490000,0.77,0.057,-0.028,-0.63,0.84,0.55,-1.3,0.41,0.29,-3.7e+02,-0.00097,-0.0058,8.7e-05,0.079,-0.032,-0.13,-0.13,-0.029,0.49,-0.0065,-0.069,-0.058,0,0,8.9e-05,8.9e-05,0.039,0.044,0.051,0.0061,0.24,0.25,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00081,4.4e-05,0.00093,0.00049,0.00084,0.00093,1,1
|
||||
26590000,0.77,0.074,-0.033,-0.63,0.96,0.63,-1.3,0.49,0.35,-3.7e+02,-0.00096,-0.0058,8.1e-05,0.08,-0.032,-0.13,-0.14,-0.03,0.49,-0.0062,-0.066,-0.057,0,0,9e-05,9e-05,0.038,0.048,0.056,0.0061,0.26,0.27,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00077,4.2e-05,0.00088,0.00047,0.0008,0.00088,1,1
|
||||
26690000,0.77,0.077,-0.034,-0.64,1.1,0.71,-1.3,0.6,0.41,-3.7e+02,-0.00096,-0.0058,9.7e-05,0.08,-0.032,-0.13,-0.14,-0.031,0.49,-0.0073,-0.061,-0.052,0,0,9e-05,9.1e-05,0.035,0.052,0.062,0.0061,0.28,0.29,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0057,0.00014,0.00071,3.9e-05,0.00082,0.00045,0.00074,0.00082,1,1
|
||||
26790000,0.77,0.071,-0.033,-0.64,1.2,0.79,-1.3,0.71,0.48,-3.7e+02,-0.00095,-0.0058,9.8e-05,0.08,-0.032,-0.13,-0.14,-0.032,0.48,-0.0071,-0.057,-0.049,0,0,9.1e-05,9.1e-05,0.032,0.055,0.068,0.0061,0.3,0.3,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00067,3.7e-05,0.00078,0.00042,0.00069,0.00077,1,1
|
||||
26890000,0.76,0.093,-0.04,-0.64,1.4,0.86,-1.3,0.85,0.56,-3.7e+02,-0.00095,-0.0058,0.0001,0.08,-0.032,-0.13,-0.15,-0.033,0.48,-0.0077,-0.053,-0.047,0,0,9.2e-05,9.2e-05,0.03,0.059,0.073,0.0061,0.32,0.32,0.033,3.6e-07,4.5e-07,2e-06,0.0052,0.0056,0.00014,0.00063,3.5e-05,0.00073,0.00039,0.00065,0.00073,1,1
|
||||
26990000,0.76,0.12,-0.045,-0.64,1.5,0.97,-1.3,0.99,0.65,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.032,-0.13,-0.15,-0.034,0.48,-0.0079,-0.047,-0.043,0,0,9.2e-05,9.2e-05,0.027,0.062,0.079,0.0061,0.34,0.35,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00057,3.2e-05,0.00066,0.00035,0.00059,0.00066,1,1
|
||||
27090000,0.76,0.12,-0.045,-0.64,1.7,1.1,-1.3,1.2,0.75,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.035,0.47,-0.0078,-0.043,-0.038,0,0,9.3e-05,9.3e-05,0.024,0.066,0.086,0.0061,0.36,0.37,0.033,3.6e-07,4.5e-07,2e-06,0.0051,0.0056,0.00013,0.00052,2.9e-05,0.00059,0.00032,0.00053,0.00059,1,1
|
||||
27190000,0.76,0.11,-0.043,-0.64,1.9,1.2,-1.2,1.3,0.87,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.031,-0.13,-0.16,-0.036,0.47,-0.0074,-0.04,-0.035,0,0,9.3e-05,9.3e-05,0.021,0.07,0.092,0.0061,0.38,0.39,0.034,3.6e-07,4.4e-07,2e-06,0.0051,0.0056,0.00013,0.00048,2.7e-05,0.00055,0.00029,0.00049,0.00054,1,1
|
||||
27290000,0.76,0.094,-0.038,-0.64,2,1.3,-1.2,1.5,0.99,-3.7e+02,-0.00096,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.036,0.47,-0.0075,-0.036,-0.033,0,0,9.4e-05,9.4e-05,0.019,0.071,0.095,0.0061,0.4,0.42,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00045,2.6e-05,0.00052,0.00026,0.00046,0.00051,1,1
|
||||
27390000,0.76,0.078,-0.034,-0.64,2.2,1.4,-1.2,1.7,1.1,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.03,-0.13,-0.17,-0.037,0.47,-0.0074,-0.035,-0.032,0,0,9.4e-05,9.4e-05,0.017,0.072,0.095,0.0061,0.43,0.44,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00043,2.5e-05,0.0005,0.00023,0.00044,0.00049,1,1
|
||||
27490000,0.76,0.062,-0.029,-0.64,2.2,1.4,-1.2,2,1.3,-3.7e+02,-0.00095,-0.0058,0.00011,0.08,-0.029,-0.13,-0.17,-0.037,0.47,-0.0071,-0.034,-0.032,0,0,9.5e-05,9.5e-05,0.015,0.073,0.094,0.0061,0.45,0.47,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00042,2.4e-05,0.00049,0.00021,0.00043,0.00048,1,1
|
||||
27590000,0.77,0.049,-0.025,-0.64,2.3,1.5,-1.2,2.2,1.4,-3.7e+02,-0.00095,-0.0058,0.0001,0.081,-0.028,-0.13,-0.17,-0.037,0.47,-0.0066,-0.033,-0.031,0,0,9.6e-05,9.5e-05,0.014,0.073,0.093,0.0061,0.48,0.5,0.033,3.6e-07,4.4e-07,2e-06,0.0051,0.0055,0.00013,0.00041,2.4e-05,0.00048,0.0002,0.00042,0.00048,1,1
|
||||
27690000,0.77,0.048,-0.025,-0.64,2.3,1.5,-1.2,2.4,1.6,-3.7e+02,-0.00095,-0.0058,9.9e-05,0.081,-0.027,-0.13,-0.17,-0.037,0.47,-0.0062,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.013,0.073,0.091,0.0061,0.51,0.53,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00013,0.0004,2.4e-05,0.00048,0.00018,0.00042,0.00047,1,1
|
||||
27790000,0.77,0.05,-0.025,-0.64,2.3,1.5,-1.2,2.6,1.7,-3.7e+02,-0.00095,-0.0058,9.4e-05,0.082,-0.026,-0.13,-0.17,-0.037,0.47,-0.0056,-0.032,-0.031,0,0,9.7e-05,9.6e-05,0.012,0.073,0.09,0.0061,0.54,0.56,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.0004,2.3e-05,0.00047,0.00017,0.00041,0.00047,1,1
|
||||
27890000,0.77,0.048,-0.024,-0.64,2.4,1.6,-1.2,2.9,1.9,-3.7e+02,-0.00095,-0.0058,9.3e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.46,-0.0056,-0.031,-0.031,0,0,9.8e-05,9.7e-05,0.011,0.074,0.089,0.0061,0.57,0.6,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.3e-05,0.00047,0.00016,0.0004,0.00047,1,1
|
||||
27990000,0.77,0.044,-0.024,-0.64,2.4,1.6,-1.2,3.1,2.1,-3.7e+02,-0.00095,-0.0058,9.1e-05,0.082,-0.026,-0.13,-0.17,-0.038,0.47,-0.0055,-0.031,-0.031,0,0,9.9e-05,9.7e-05,0.01,0.075,0.089,0.0061,0.61,0.63,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0055,0.00012,0.00039,2.3e-05,0.00047,0.00016,0.0004,0.00046,1,1
|
||||
28090000,0.77,0.057,-0.028,-0.63,2.4,1.6,-1.2,3.3,2.2,-3.7e+02,-0.00095,-0.0058,8.6e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.8e-05,0.0096,0.076,0.089,0.0061,0.64,0.67,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00038,2.2e-05,0.00046,0.00015,0.00039,0.00046,1,1
|
||||
28190000,0.77,0.071,-0.032,-0.63,2.5,1.6,-0.93,3.6,2.4,-3.7e+02,-0.00095,-0.0058,8.5e-05,0.082,-0.025,-0.13,-0.17,-0.038,0.46,-0.005,-0.03,-0.03,0,0,0.0001,9.9e-05,0.0091,0.077,0.089,0.0061,0.68,0.71,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00037,2.2e-05,0.00046,0.00014,0.00038,0.00045,1,1
|
||||
28290000,0.77,0.053,-0.026,-0.63,2.5,1.7,-0.069,3.8,2.6,-3.7e+02,-0.00094,-0.0058,8.1e-05,0.083,-0.024,-0.13,-0.17,-0.038,0.46,-0.0047,-0.029,-0.029,0,0,0.0001,9.9e-05,0.0086,0.076,0.087,0.0061,0.71,0.75,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00014,0.00038,0.00045,1,1
|
||||
28390000,0.77,0.02,-0.013,-0.64,2.4,1.7,0.79,4,2.7,-3.7e+02,-0.00095,-0.0058,7.7e-05,0.083,-0.023,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0082,0.076,0.084,0.0061,0.75,0.79,0.033,3.7e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00013,0.00037,0.00045,1,1
|
||||
28490000,0.77,0.0015,-0.0059,-0.64,2.4,1.7,1.1,4.3,2.9,-3.7e+02,-0.00096,-0.0058,7.2e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0079,0.076,0.083,0.0061,0.79,0.83,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00013,0.00037,0.00045,1,1
|
||||
28590000,0.77,-0.0022,-0.0045,-0.63,2.3,1.6,0.98,4.5,3.1,-3.7e+02,-0.00096,-0.0058,7e-05,0.082,-0.022,-0.13,-0.17,-0.038,0.46,-0.0045,-0.028,-0.029,0,0,0.0001,0.0001,0.0075,0.077,0.082,0.0061,0.83,0.87,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00012,0.00037,0.00044,1,1
|
||||
28690000,0.77,-0.0032,-0.0039,-0.63,2.3,1.6,0.99,4.8,3.2,-3.7e+02,-0.00097,-0.0058,6.6e-05,0.082,-0.022,-0.12,-0.17,-0.038,0.46,-0.0044,-0.028,-0.029,0,0,0.0001,0.0001,0.0072,0.077,0.082,0.0061,0.87,0.91,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00045,0.00012,0.00037,0.00044,1,1
|
||||
28790000,0.78,-0.0035,-0.0037,-0.63,2.2,1.6,0.99,5,3.4,-3.7e+02,-0.00097,-0.0058,6.2e-05,0.082,-0.021,-0.12,-0.17,-0.038,0.46,-0.0042,-0.028,-0.029,0,0,0.00011,0.0001,0.0069,0.078,0.082,0.006,0.91,0.96,0.033,3.6e-07,4.4e-07,2e-06,0.005,0.0054,0.00012,0.00036,2.1e-05,0.00044,0.00012,0.00037,0.00044,1,1
|
||||
28890000,0.78,-0.0033,-0.0037,-0.63,2.2,1.5,0.98,5.2,3.6,-3.7e+02,-0.00098,-0.0058,5.8e-05,0.081,-0.021,-0.12,-0.17,-0.038,0.46,-0.0041,-0.028,-0.029,0,0,0.00011,0.0001,0.0067,0.079,0.083,0.006,0.96,1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00036,2.1e-05,0.00044,0.00011,0.00037,0.00044,1,1
|
||||
28990000,0.78,-0.0029,-0.0038,-0.63,2.1,1.5,0.98,5.4,3.7,-3.7e+02,-0.00099,-0.0058,5.1e-05,0.08,-0.02,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0065,0.08,0.084,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.00011,0.00037,0.00044,1,1
|
||||
29090000,0.78,-0.0024,-0.004,-0.63,2,1.5,0.97,5.7,3.9,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0037,-0.028,-0.028,0,0,0.00011,0.0001,0.0063,0.081,0.086,0.006,1,1.1,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.00011,0.00037,0.00043,1,1
|
||||
29190000,0.78,-0.0022,-0.004,-0.63,2,1.5,0.97,5.9,4,-3.7e+02,-0.001,-0.0058,4.7e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0038,-0.028,-0.028,0,0,0.00011,0.0001,0.0061,0.082,0.088,0.006,1.1,1.2,0.033,3.5e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.00011,0.00037,0.00043,1,1
|
||||
29290000,0.78,-0.0013,-0.0043,-0.63,1.9,1.4,0.99,6.1,4.2,-3.7e+02,-0.001,-0.0058,4.2e-05,0.08,-0.019,-0.12,-0.17,-0.038,0.46,-0.0036,-0.028,-0.028,0,0,0.00011,0.0001,0.006,0.084,0.09,0.006,1.1,1.2,0.033,3.4e-07,4.5e-07,2e-06,0.005,0.0054,0.00011,0.00035,2.1e-05,0.00044,0.0001,0.00037,0.00043,1,1
|
||||
29390000,0.78,7.2e-05,-0.0046,-0.63,1.9,1.4,1,6.2,4.3,-3.7e+02,-0.001,-0.0058,3.6e-05,0.079,-0.018,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0058,0.085,0.092,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.1e-05,0.00043,0.0001,0.00037,0.00043,1,1
|
||||
29490000,0.78,0.0012,-0.005,-0.63,1.8,1.4,1,6.4,4.5,-3.7e+02,-0.001,-0.0058,3.3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0033,-0.028,-0.028,0,0,0.00011,0.0001,0.0057,0.087,0.095,0.006,1.2,1.3,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0054,0.00011,0.00035,2.1e-05,0.00043,0.0001,0.00037,0.00043,1,1
|
||||
29590000,0.78,0.0023,-0.0052,-0.63,1.8,1.4,1,6.6,4.6,-3.7e+02,-0.001,-0.0057,3e-05,0.079,-0.017,-0.12,-0.17,-0.038,0.46,-0.0032,-0.028,-0.028,0,0,0.00011,0.0001,0.0056,0.089,0.098,0.006,1.3,1.4,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,0.0001,0.00037,0.00043,1,1
|
||||
29690000,0.78,0.0029,-0.0055,-0.63,1.7,1.3,0.99,6.8,4.7,-3.7e+02,-0.001,-0.0057,2.6e-05,0.078,-0.016,-0.12,-0.17,-0.038,0.46,-0.0031,-0.028,-0.028,0,0,0.00011,0.0001,0.0054,0.09,0.1,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,9.9e-05,0.00037,0.00043,1,1
|
||||
29790000,0.78,0.0034,-0.0056,-0.63,1.7,1.3,0.98,7,4.9,-3.7e+02,-0.001,-0.0057,2.2e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0031,-0.028,-0.027,0,0,0.00011,0.0001,0.0053,0.092,0.11,0.006,1.4,1.5,0.033,3.4e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,9.8e-05,0.00037,0.00042,1,1
|
||||
29890000,0.78,0.0035,-0.0057,-0.63,1.7,1.3,0.97,7.2,5,-3.7e+02,-0.001,-0.0057,1.6e-05,0.078,-0.015,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.094,0.11,0.006,1.5,1.6,0.033,3.3e-07,4.5e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2.1e-05,0.00043,9.6e-05,0.00037,0.00042,1,1
|
||||
29990000,0.78,0.0036,-0.0057,-0.63,1.6,1.3,0.95,7.3,5.1,-3.7e+02,-0.001,-0.0057,1.2e-05,0.077,-0.014,-0.12,-0.17,-0.038,0.46,-0.0029,-0.028,-0.027,0,0,0.00012,0.0001,0.0052,0.096,0.11,0.006,1.5,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.00011,0.00035,2e-05,0.00043,9.5e-05,0.00036,0.00042,1,1
|
||||
30090000,0.78,0.0035,-0.0057,-0.63,1.6,1.3,0.94,7.5,5.3,-3.7e+02,-0.001,-0.0057,8.5e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0051,0.098,0.12,0.006,1.6,1.7,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1
|
||||
30190000,0.78,0.0032,-0.0057,-0.63,1.6,1.3,0.93,7.6,5.4,-3.7e+02,-0.001,-0.0057,9.6e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0028,-0.028,-0.027,0,0,0.00012,0.0001,0.005,0.1,0.12,0.006,1.7,1.8,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00043,9.4e-05,0.00036,0.00042,1,1
|
||||
30290000,0.78,0.003,-0.0056,-0.63,1.5,1.2,0.92,7.8,5.5,-3.7e+02,-0.001,-0.0057,6.6e-06,0.077,-0.013,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.7,1.9,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00043,9.3e-05,0.00036,0.00042,1,1
|
||||
30390000,0.78,0.0028,-0.0056,-0.63,1.5,1.2,0.9,8,5.6,-3.7e+02,-0.0011,-0.0057,2.4e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0049,0.1,0.13,0.006,1.8,2,0.033,3.3e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9.2e-05,0.00036,0.00042,1,1
|
||||
30490000,0.78,0.0025,-0.0055,-0.63,1.5,1.2,0.89,8.1,5.8,-3.7e+02,-0.0011,-0.0057,1.3e-06,0.076,-0.012,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,1.9,2.1,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1
|
||||
30590000,0.78,0.002,-0.0054,-0.63,1.4,1.2,0.85,8.3,5.9,-3.7e+02,-0.0011,-0.0057,-8.2e-07,0.076,-0.011,-0.12,-0.17,-0.038,0.46,-0.0027,-0.028,-0.027,0,0,0.00012,0.0001,0.0048,0.11,0.14,0.006,2,2.2,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9.1e-05,0.00036,0.00042,1,1
|
||||
30690000,0.78,0.0017,-0.0053,-0.63,1.4,1.2,0.84,8.4,6,-3.7e+02,-0.0011,-0.0057,-4.1e-06,0.075,-0.0099,-0.12,-0.17,-0.038,0.46,-0.0026,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.0059,2,2.3,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9e-05,0.00036,0.00042,1,1
|
||||
30790000,0.78,0.0013,-0.0052,-0.63,1.4,1.2,0.84,8.6,6.1,-3.7e+02,-0.0011,-0.0057,-7.2e-06,0.075,-0.0096,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.0001,0.0047,0.11,0.15,0.006,2.1,2.4,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,0.0001,0.00035,2e-05,0.00042,9e-05,0.00036,0.00042,1,1
|
||||
30890000,0.78,0.00088,-0.0051,-0.63,1.4,1.1,0.82,8.7,6.2,-3.7e+02,-0.0011,-0.0057,-1e-05,0.074,-0.0089,-0.12,-0.17,-0.038,0.46,-0.0025,-0.028,-0.027,0,0,0.00012,0.0001,0.0046,0.12,0.16,0.0059,2.2,2.5,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0053,9.9e-05,0.00035,2e-05,0.00042,8.9e-05,0.00036,0.00042,1,1
|
||||
30990000,0.78,0.00029,-0.005,-0.63,1.3,1.1,0.82,8.9,6.3,-3.7e+02,-0.0011,-0.0057,-1.4e-05,0.074,-0.0081,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0046,0.12,0.16,0.0059,2.3,2.6,0.033,3.2e-07,4.6e-07,2e-06,0.0049,0.0052,9.9e-05,0.00035,2e-05,0.00042,8.9e-05,0.00036,0.00041,1,1
|
||||
31090000,0.78,-0.00026,-0.0048,-0.63,1.3,1.1,0.81,9,6.5,-3.7e+02,-0.0011,-0.0057,-1.8e-05,0.074,-0.0074,-0.12,-0.17,-0.038,0.46,-0.0024,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.17,0.0059,2.4,2.7,0.033,3.1e-07,4.6e-07,2e-06,0.0048,0.0052,9.8e-05,0.00035,2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1
|
||||
31190000,0.78,-0.00067,-0.0047,-0.63,1.3,1.1,0.8,9.1,6.6,-3.7e+02,-0.0011,-0.0057,-2.1e-05,0.074,-0.0066,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.12,0.18,0.0059,2.5,2.9,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2e-05,0.00042,8.8e-05,0.00036,0.00041,1,1
|
||||
31290000,0.78,-0.0013,-0.0046,-0.63,1.2,1.1,0.8,9.3,6.7,-3.7e+02,-0.0011,-0.0057,-2.3e-05,0.073,-0.0059,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0045,0.13,0.18,0.0059,2.6,3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.7e-05,0.00035,2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1
|
||||
31390000,0.78,-0.002,-0.0044,-0.63,1.2,1.1,0.8,9.4,6.8,-3.7e+02,-0.0011,-0.0057,-2.6e-05,0.073,-0.0053,-0.12,-0.17,-0.038,0.46,-0.0023,-0.028,-0.027,0,0,0.00013,0.0001,0.0044,0.13,0.19,0.0059,2.6,3.1,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.6e-05,0.00034,2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1
|
||||
31490000,0.78,-0.0026,-0.0042,-0.63,1.2,1,0.79,9.5,6.9,-3.7e+02,-0.0011,-0.0057,-3.2e-05,0.073,-0.0045,-0.12,-0.17,-0.038,0.46,-0.0022,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.2,0.0059,2.7,3.3,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00034,2e-05,0.00042,8.7e-05,0.00036,0.00041,1,1
|
||||
31590000,0.78,-0.003,-0.0042,-0.63,1.1,1,0.79,9.6,7,-3.7e+02,-0.0011,-0.0057,-3.3e-05,0.072,-0.0038,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.13,0.21,0.0059,2.8,3.4,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.5e-05,0.00034,2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1
|
||||
31690000,0.78,-0.0037,-0.004,-0.63,1.1,1,0.8,9.8,7.1,-3.7e+02,-0.0011,-0.0057,-3.5e-05,0.072,-0.0032,-0.12,-0.17,-0.038,0.46,-0.0021,-0.028,-0.026,0,0,0.00013,0.0001,0.0044,0.14,0.21,0.0059,2.9,3.5,0.033,3.1e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00034,2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1
|
||||
31790000,0.78,-0.0044,-0.0038,-0.63,1.1,0.99,0.8,9.9,7.2,-3.7e+02,-0.0011,-0.0057,-3.7e-05,0.071,-0.0023,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.22,0.0059,3.1,3.7,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.4e-05,0.00034,2e-05,0.00041,8.6e-05,0.00036,0.00041,1,1
|
||||
31890000,0.78,-0.0051,-0.0037,-0.63,1.1,0.97,0.79,10,7.3,-3.7e+02,-0.0011,-0.0057,-4.1e-05,0.071,-0.0014,-0.12,-0.17,-0.038,0.46,-0.002,-0.029,-0.026,0,0,0.00013,0.0001,0.0043,0.14,0.23,0.0059,3.2,3.9,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.00041,1,1
|
||||
31990000,0.78,-0.0057,-0.0035,-0.63,1,0.96,0.79,10,7.4,-3.7e+02,-0.0011,-0.0057,-4.7e-05,0.07,-0.00053,-0.12,-0.17,-0.038,0.46,-0.0019,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.14,0.24,0.0058,3.3,4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.3e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.00041,1,1
|
||||
32090000,0.78,-0.0064,-0.0033,-0.63,1,0.94,0.8,10,7.5,-3.7e+02,-0.0012,-0.0057,-5.1e-05,0.07,0.00016,-0.11,-0.17,-0.038,0.46,-0.0018,-0.029,-0.026,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.4,4.2,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0052,9.2e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1
|
||||
32190000,0.78,-0.0074,-0.0031,-0.63,0.97,0.92,0.8,10,7.6,-3.7e+02,-0.0012,-0.0057,-6e-05,0.069,0.0011,-0.11,-0.17,-0.038,0.46,-0.0017,-0.029,-0.025,0,0,0.00014,0.0001,0.0043,0.15,0.25,0.0058,3.5,4.4,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1
|
||||
32290000,0.78,-0.0081,-0.003,-0.63,0.94,0.9,0.79,10,7.7,-3.7e+02,-0.0012,-0.0057,-6.4e-05,0.069,0.0021,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.15,0.26,0.0058,3.6,4.6,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9.1e-05,0.00034,2e-05,0.00041,8.5e-05,0.00036,0.0004,1,1
|
||||
32390000,0.78,-0.0087,-0.0029,-0.63,0.91,0.88,0.79,11,7.8,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.068,0.0027,-0.11,-0.17,-0.038,0.46,-0.0016,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.27,0.0058,3.7,4.8,0.033,3e-07,4.7e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2e-05,0.00041,8.4e-05,0.00036,0.0004,1,1
|
||||
32490000,0.78,-0.009,-0.0028,-0.62,0.88,0.86,0.8,11,7.9,-3.7e+02,-0.0012,-0.0057,-6.7e-05,0.068,0.0035,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.16,0.28,0.0058,3.9,5,0.033,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1
|
||||
32590000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.84,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7e-05,0.067,0.0038,-0.11,-0.17,-0.038,0.46,-0.0015,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.56,0.25,0.25,0.035,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1
|
||||
32690000,0.78,-0.0093,-0.0028,-0.62,-1.6,-0.86,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.4e-05,0.067,0.0044,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.025,0,0,0.00014,0.0001,0.0042,0.25,0.25,0.55,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1
|
||||
32790000,0.78,-0.0093,-0.0028,-0.62,-1.5,-0.84,0.61,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.5e-05,0.066,0.0048,-0.11,-0.17,-0.038,0.46,-0.0014,-0.029,-0.024,0,0,0.00014,0.0001,0.0042,0.13,0.13,0.27,0.26,0.26,0.047,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.9e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.0004,1,1
|
||||
32890000,0.78,-0.0092,-0.0029,-0.62,-1.6,-0.86,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-8.5e-05,0.066,0.0053,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0042,0.13,0.13,0.26,0.27,0.27,0.058,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.4e-05,0.00036,0.00039,1,1
|
||||
32990000,0.78,-0.0092,-0.003,-0.62,-1.5,-0.85,0.59,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.9e-05,0.065,0.0058,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.17,0.27,0.27,0.056,2.9e-07,4.8e-07,2e-06,0.0048,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1
|
||||
33090000,0.78,-0.0092,-0.003,-0.62,-1.6,-0.86,0.57,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.6e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.084,0.085,0.16,0.28,0.28,0.065,2.9e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1
|
||||
33190000,0.78,-0.0079,-0.0062,-0.62,-1.5,-0.85,0.52,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.3e-05,0.065,0.0061,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.063,0.065,0.11,0.28,0.28,0.062,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00036,0.00039,1,1
|
||||
33290000,0.83,-0.0058,-0.018,-0.56,-1.5,-0.87,0.5,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-7.8e-05,0.065,0.006,-0.11,-0.17,-0.038,0.46,-0.0013,-0.029,-0.024,0,0,0.00015,0.0001,0.0041,0.064,0.066,0.1,0.29,0.29,0.067,2.8e-07,4.8e-07,2e-06,0.0047,0.0051,8.8e-05,0.00034,2e-05,0.0004,8.3e-05,0.00035,0.00039,1,1
|
||||
33390000,0.89,-0.0065,-0.015,-0.45,-1.5,-0.86,0.7,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-6.5e-05,0.064,0.0057,-0.11,-0.18,-0.039,0.46,-0.0009,-0.027,-0.024,0,0,0.00015,0.0001,0.004,0.051,0.053,0.082,0.29,0.29,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00031,1.8e-05,0.0004,8e-05,0.00032,0.00039,1,1
|
||||
33490000,0.95,-0.0051,-0.0068,-0.3,-1.5,-0.87,0.71,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,-4.6e-05,0.064,0.0057,-0.11,-0.18,-0.04,0.46,-0.00041,-0.02,-0.024,0,0,0.00015,0.0001,0.0037,0.052,0.054,0.075,0.3,0.3,0.068,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00023,1.5e-05,0.00039,7.3e-05,0.00024,0.00039,1,1
|
||||
33590000,0.99,-0.0082,-3.1e-05,-0.14,-1.5,-0.85,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,1.5e-05,0.064,0.0057,-0.11,-0.19,-0.042,0.46,0.00035,-0.013,-0.024,0,0,0.00015,0.0001,0.0032,0.044,0.046,0.061,0.3,0.3,0.065,2.8e-07,4.7e-07,2e-06,0.0047,0.0051,8.8e-05,0.00015,1.1e-05,0.00039,6e-05,0.00015,0.00039,1,1
|
||||
33690000,1,-0.012,0.0042,0.031,-1.6,-0.88,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,2e-05,0.064,0.0057,-0.11,-0.19,-0.043,0.46,0.00018,-0.0091,-0.025,0,0,0.00015,0.0001,0.0028,0.044,0.048,0.056,0.31,0.31,0.067,2.8e-07,4.6e-07,2e-06,0.0047,0.0051,8.8e-05,0.0001,8.4e-06,0.00039,4.7e-05,9.7e-05,0.00038,1,1
|
||||
33790000,0.98,-0.013,0.0066,0.2,-1.6,-0.89,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,6.6e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00052,-0.0066,-0.025,0,0,0.00015,0.0001,0.0023,0.039,0.043,0.047,0.31,0.31,0.064,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,6.9e-05,6.8e-06,0.00038,3.5e-05,6.2e-05,0.00038,1,1
|
||||
33890000,0.93,-0.013,0.0087,0.36,-1.7,-0.95,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.9e-05,0.064,0.0057,-0.11,-0.2,-0.043,0.46,0.00074,-0.0053,-0.025,0,0,0.00015,0.0001,0.002,0.04,0.046,0.042,0.32,0.32,0.065,2.7e-07,4.5e-07,1.9e-06,0.0047,0.0051,8.8e-05,5.1e-05,5.9e-06,0.00038,2.7e-05,4.2e-05,0.00038,1,1
|
||||
33990000,0.87,-0.015,0.0073,0.5,-1.7,-0.97,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0055,-0.11,-0.2,-0.044,0.46,0.00052,-0.0039,-0.025,0,0,0.00014,9.7e-05,0.0017,0.036,0.042,0.036,0.32,0.32,0.062,2.7e-07,4.4e-07,1.9e-06,0.0047,0.005,8.8e-05,4e-05,5.4e-06,0.00038,2.1e-05,3e-05,0.00038,1,1
|
||||
34090000,0.8,-0.016,0.0065,0.6,-1.7,-1,0.64,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.065,0.0049,-0.11,-0.2,-0.044,0.46,0.00019,-0.0032,-0.025,0,0,0.00014,9.7e-05,0.0016,0.038,0.046,0.033,0.33,0.33,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,3.4e-05,5.1e-06,0.00038,1.7e-05,2.4e-05,0.00038,1,1
|
||||
34190000,0.75,-0.014,0.0071,0.66,-1.8,-1.1,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.064,0.0047,-0.11,-0.2,-0.044,0.46,0.0002,-0.0027,-0.025,0,0,0.00014,9.7e-05,0.0015,0.041,0.051,0.031,0.34,0.34,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,3e-05,4.9e-06,0.00038,1.4e-05,1.9e-05,0.00038,1,1
|
||||
34290000,0.71,-0.011,0.0086,0.7,-1.8,-1.2,0.65,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.064,0.0044,-0.11,-0.2,-0.044,0.46,0.00016,-0.0023,-0.025,0,0,0.00014,9.6e-05,0.0014,0.044,0.056,0.028,0.35,0.35,0.062,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,2.7e-05,4.7e-06,0.00038,1.2e-05,1.6e-05,0.00038,1,1
|
||||
34390000,0.69,-0.0076,0.01,0.72,-1.9,-1.3,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0041,-0.11,-0.2,-0.044,0.46,9e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0013,0.048,0.061,0.026,0.36,0.37,0.063,2.8e-07,4.3e-07,1.9e-06,0.0047,0.005,8.8e-05,2.5e-05,4.6e-06,0.00038,1.1e-05,1.4e-05,0.00038,1,1
|
||||
34490000,0.67,-0.0054,0.011,0.74,-1.9,-1.4,0.66,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.004,-0.11,-0.2,-0.044,0.46,4.8e-05,-0.002,-0.025,0,0,0.00014,9.6e-05,0.0013,0.052,0.068,0.024,0.38,0.38,0.062,2.8e-07,4.3e-07,1.8e-06,0.0047,0.005,8.8e-05,2.3e-05,4.6e-06,0.00038,9.9e-06,1.2e-05,0.00038,1,1
|
||||
34590000,0.67,-0.004,0.012,0.75,-2,-1.4,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0039,-0.11,-0.2,-0.044,0.46,-4.8e-05,-0.0019,-0.025,0,0,0.00014,9.5e-05,0.0012,0.056,0.075,0.022,0.39,0.4,0.06,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.2e-05,4.5e-06,0.00038,9e-06,1.1e-05,0.00038,1,1
|
||||
34690000,0.66,-0.0032,0.013,0.75,-2,-1.5,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0038,-0.11,-0.2,-0.044,0.46,1.5e-05,-0.0016,-0.025,0,0,0.00014,9.5e-05,0.0012,0.062,0.082,0.02,0.41,0.41,0.06,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.8e-05,2.1e-05,4.5e-06,0.00038,8.3e-06,9.9e-06,0.00038,1,1
|
||||
34790000,0.66,-0.0027,0.013,0.76,-2.1,-1.6,0.67,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0038,-0.11,-0.2,-0.044,0.46,0.00014,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0012,0.067,0.09,0.018,0.42,0.43,0.059,2.8e-07,4.3e-07,1.8e-06,0.0046,0.005,8.9e-05,2e-05,4.4e-06,0.00038,7.8e-06,9.1e-06,0.00038,1,1
|
||||
34890000,0.65,-0.0025,0.013,0.76,-2.1,-1.7,0.68,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0036,-0.11,-0.2,-0.044,0.46,8.6e-05,-0.0016,-0.025,0,0,0.00014,9.4e-05,0.0012,0.074,0.099,0.017,0.44,0.46,0.058,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,2e-05,4.4e-06,0.00038,7.3e-06,8.4e-06,0.00038,1,1
|
||||
34990000,0.65,-0.006,0.02,0.76,-3.1,-2.6,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0002,-0.0016,-0.025,0,0,0.00014,9.3e-05,0.0012,0.09,0.13,0.016,0.46,0.48,0.057,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.9e-05,4.3e-06,0.00038,6.9e-06,7.9e-06,0.00038,1,1
|
||||
35090000,0.65,-0.006,0.02,0.76,-3.2,-2.7,-0.18,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00021,-0.0016,-0.025,0,0,0.00013,9.3e-05,0.0012,0.098,0.14,0.015,0.49,0.51,0.056,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.9e-05,4.3e-06,0.00038,6.6e-06,7.4e-06,0.00038,1,1
|
||||
35190000,0.65,-0.0061,0.02,0.76,-3.2,-2.7,-0.17,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00025,-0.0015,-0.025,0,0,0.00013,9.3e-05,0.0011,0.11,0.15,0.014,0.51,0.54,0.055,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,4.3e-06,0.00038,6.2e-06,7e-06,0.00038,1,1
|
||||
35290000,0.65,-0.0063,0.02,0.76,-3.2,-2.8,-0.16,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.0003,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.12,0.17,0.013,0.54,0.58,0.053,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,4.3e-06,0.00038,6e-06,6.6e-06,0.00038,1,1
|
||||
35390000,0.65,-0.0063,0.02,0.76,-3.3,-2.9,-0.15,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00038,-0.0015,-0.025,0,0,0.00013,9.2e-05,0.0011,0.13,0.18,0.012,0.57,0.62,0.053,2.8e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.8e-05,4.2e-06,0.00038,5.8e-06,6.3e-06,0.00037,1,1
|
||||
35490000,0.65,-0.0063,0.02,0.76,-3.3,-3,-0.14,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00044,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.13,0.19,0.012,0.61,0.67,0.052,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.6e-06,6e-06,0.00037,1,1
|
||||
35590000,0.65,-0.0064,0.02,0.76,-3.3,-3,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0037,-0.11,-0.2,-0.044,0.46,0.00041,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.15,0.2,0.011,0.65,0.72,0.05,2.9e-07,4.4e-07,1.8e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.4e-06,5.8e-06,0.00037,1,1
|
||||
35690000,0.65,-0.0063,0.02,0.76,-3.4,-3.1,-0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00014,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00047,-0.0016,-0.025,0,0,0.00013,9.1e-05,0.0011,0.16,0.22,0.011,0.69,0.77,0.05,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.3e-06,5.6e-06,0.00037,1,1
|
||||
35790000,0.65,-0.0064,0.02,0.76,-3.4,-3.2,-0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9e-05,0.0011,0.17,0.23,0.01,0.73,0.84,0.049,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5.1e-06,5.3e-06,0.00037,1,1
|
||||
35890000,0.65,-0.0065,0.02,0.76,-3.4,-3.2,-0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0036,-0.11,-0.2,-0.044,0.46,0.00049,-0.0015,-0.025,0,0,0.00013,9e-05,0.0011,0.18,0.25,0.0096,0.78,0.9,0.048,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.7e-05,4.2e-06,0.00038,5e-06,5.2e-06,0.00037,1,1
|
||||
35990000,0.65,-0.0065,0.02,0.76,-3.5,-3.3,-0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.064,0.0035,-0.11,-0.2,-0.044,0.46,0.00046,-0.0016,-0.025,0,0,0.00013,9e-05,0.0011,0.19,0.26,0.0093,0.84,0.98,0.047,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.9e-06,5e-06,0.00037,1,1
|
||||
36090000,0.65,-0.0065,0.02,0.76,-3.5,-3.4,-0.093,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00013,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00049,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0011,0.2,0.28,0.0089,0.9,1.1,0.046,2.9e-07,4.4e-07,1.9e-06,0.0046,0.005,8.9e-05,1.6e-05,4.2e-06,0.00038,4.8e-06,4.8e-06,0.00037,1,1
|
||||
36190000,0.65,-0.0066,0.02,0.76,-3.5,-3.5,-0.083,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0037,-0.11,-0.2,-0.044,0.46,0.00057,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0011,0.22,0.3,0.0086,0.96,1.1,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,4.1e-06,0.00038,4.7e-06,4.7e-06,0.00037,1,1
|
||||
36290000,0.65,-0.0065,0.02,0.76,-3.5,-3.5,-0.073,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00058,-0.0016,-0.025,0,0,0.00013,8.9e-05,0.0011,0.23,0.32,0.0083,1,1.2,0.045,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,4.1e-06,0.00038,4.6e-06,4.6e-06,0.00037,1,1
|
||||
36390000,0.65,-0.0066,0.02,0.76,-3.6,-3.6,-0.066,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0036,-0.11,-0.2,-0.044,0.46,0.00057,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.25,0.33,0.0081,1.1,1.4,0.044,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,8.9e-05,1.6e-05,4.1e-06,0.00038,4.5e-06,4.4e-06,0.00037,1,1
|
||||
36490000,0.65,-0.0066,0.02,0.76,-3.6,-3.7,-0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.065,0.0035,-0.11,-0.2,-0.044,0.46,0.00054,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.26,0.35,0.0078,1.2,1.5,0.043,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.6e-05,4.1e-06,0.00038,4.4e-06,4.3e-06,0.00037,1,1
|
||||
36590000,0.65,-0.0066,0.02,0.76,-3.6,-3.8,-0.048,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0035,-0.11,-0.2,-0.044,0.46,0.00058,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.28,0.37,0.0076,1.3,1.6,0.042,2.9e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.4e-06,4.2e-06,0.00037,1,1
|
||||
36690000,0.65,-0.0067,0.02,0.76,-3.7,-3.8,-0.04,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00012,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00061,-0.0015,-0.025,0,0,0.00012,8.8e-05,0.0011,0.29,0.39,0.0075,1.4,1.7,0.042,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.3e-06,4.1e-06,0.00037,1,1
|
||||
36790000,0.65,-0.0067,0.021,0.76,-3.7,-3.9,-0.031,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.00011,0.066,0.0036,-0.11,-0.2,-0.044,0.46,0.00064,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0011,0.31,0.41,0.0073,1.5,1.9,0.041,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.3e-06,4e-06,0.00037,1,1
|
||||
36890000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.023,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0038,-0.11,-0.2,-0.044,0.46,0.00067,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0011,0.32,0.43,0.0072,1.6,2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1
|
||||
36990000,0.65,-0.0067,0.021,0.76,-3.7,-4,-0.015,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,0.0001,0.066,0.0039,-0.11,-0.2,-0.044,0.46,0.00069,-0.0015,-0.025,0,0,0.00012,8.7e-05,0.0011,0.34,0.45,0.0071,1.7,2.2,0.04,3e-07,4.4e-07,1.9e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.2e-06,3.9e-06,0.00037,1,1
|
||||
37090000,0.65,-0.0067,0.021,0.76,-3.8,-4.1,-0.0065,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.067,0.004,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.7e-05,0.0011,0.36,0.47,0.007,1.9,2.4,0.04,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.1e-06,3.8e-06,0.00037,1,1
|
||||
37190000,0.65,-0.0067,0.021,0.76,-3.8,-4.2,0.0016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.8e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00068,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0011,0.38,0.49,0.0069,2,2.6,0.039,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1
|
||||
37290000,0.65,-0.0068,0.021,0.76,-3.8,-4.3,0.0094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.5e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00069,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.0011,0.39,0.51,0.0068,2.2,2.8,0.039,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4.1e-06,3.7e-06,0.00037,1,1
|
||||
37390000,0.65,-0.0067,0.021,0.76,-3.9,-4.3,0.016,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,9.2e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00071,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.41,0.54,0.0067,2.3,3,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4e-06,3.6e-06,0.00037,1,1
|
||||
37490000,0.65,-0.0067,0.021,0.76,-3.9,-4.4,0.024,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.6e-05,0.067,0.0041,-0.11,-0.2,-0.044,0.46,0.00074,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.43,0.56,0.0067,2.5,3.2,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4e-06,3.5e-06,0.00037,1,1
|
||||
37590000,0.65,-0.0067,0.021,0.76,-3.9,-4.5,0.033,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0057,8.2e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00075,-0.0014,-0.025,0,0,0.00012,8.6e-05,0.001,0.45,0.58,0.0067,2.7,3.5,0.038,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.5e-05,4.1e-06,0.00038,4e-06,3.5e-06,0.00037,1,1
|
||||
37690000,0.65,-0.0068,0.021,0.76,-3.9,-4.6,0.042,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.6e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.001,0.47,0.6,0.0066,2.9,3.7,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1
|
||||
37790000,0.65,-0.0069,0.021,0.76,-4,-4.6,0.051,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.5e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00076,-0.0014,-0.025,0,0,0.00012,8.5e-05,0.001,0.49,0.63,0.0066,3.1,4,0.037,3e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.4e-06,0.00037,1,1
|
||||
37890000,0.65,-0.0069,0.021,0.76,-4,-4.7,0.059,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.2e-05,0.068,0.0043,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.001,0.51,0.65,0.0065,3.3,4.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1
|
||||
37990000,0.65,-0.0069,0.021,0.76,-4,-4.8,0.068,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,7.3e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00077,-0.0014,-0.025,0,0,0.00011,8.5e-05,0.001,0.53,0.67,0.0065,3.5,4.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.3e-06,0.00037,1,1
|
||||
38090000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.078,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.5e-05,0.001,0.55,0.7,0.0065,3.8,4.9,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0049,9.1e-05,1.4e-05,4.1e-06,0.00038,3.9e-06,3.2e-06,0.00037,1,1
|
||||
38190000,0.65,-0.0069,0.021,0.76,-4.1,-4.9,0.086,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.5e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.001,0.58,0.72,0.0065,4.1,5.3,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.2e-06,0.00037,1,1
|
||||
38290000,0.65,-0.0069,0.021,0.76,-4.1,-5,0.094,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.0041,-0.11,-0.2,-0.044,0.46,0.00078,-0.0014,-0.025,0,0,0.00011,8.4e-05,0.001,0.6,0.75,0.0065,4.4,5.6,0.036,3.1e-07,4.4e-07,1.8e-06,0.0046,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1
|
||||
38390000,0.65,-0.0069,0.021,0.76,-4.1,-5.1,0.1,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.068,0.0039,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.62,0.77,0.0065,4.6,6,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3.1e-06,0.00037,1,1
|
||||
38490000,0.65,-0.0069,0.021,0.76,-4.2,-5.1,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.6e-05,0.068,0.004,-0.11,-0.2,-0.044,0.46,0.00079,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.64,0.8,0.0065,5,6.4,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1
|
||||
38590000,0.65,-0.0068,0.021,0.76,-4.2,-5.2,0.11,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.7e-05,0.067,0.0042,-0.11,-0.2,-0.044,0.46,0.00078,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.67,0.82,0.0065,5.3,6.9,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1
|
||||
38690000,0.65,-0.0068,0.021,0.76,-4.2,-5.3,0.12,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.067,0.0045,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.69,0.85,0.0065,5.6,7.3,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,3e-06,0.00037,1,1
|
||||
38790000,0.65,-0.0068,0.021,0.76,-4.3,-5.3,0.13,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.2e-05,0.067,0.0043,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.4e-05,0.001,0.72,0.88,0.0065,6,7.8,0.035,3.1e-07,4.4e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.8e-06,2.9e-06,0.00037,1,1
|
||||
38890000,0.65,-0.0069,0.021,0.76,-4.3,-5.4,0.63,-1e+06,1.2e+04,-3.7e+02,-0.0012,-0.0056,6.1e-05,0.067,0.0044,-0.11,-0.2,-0.044,0.46,0.0008,-0.0013,-0.025,0,0,0.00011,8.3e-05,0.001,0.73,0.89,0.0065,6.4,8.2,0.035,3.1e-07,4.3e-07,1.8e-06,0.0045,0.0048,9.1e-05,1.4e-05,4.1e-06,0.00038,3.7e-06,2.9e-06,0.00037,1,1
|
||||
|
||||
|
@@ -201,151 +201,151 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
||||
19890000,-0.28,0.015,-0.0052,0.96,-0.023,0.013,0.023,-0.02,0.01,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.6e-05,5.2e-05,0.05,0.016,0.017,0.0077,0.049,0.049,0.035,9.5e-07,8.4e-07,2.2e-06,0.002,0.0023,0.00027,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1
|
||||
19990000,-0.28,0.015,-0.0052,0.96,-0.02,0.014,0.021,-0.015,0.0093,0.012,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.014,0.015,0.0076,0.043,0.044,0.035,9.2e-07,8.1e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1
|
||||
20090000,-0.28,0.015,-0.0052,0.96,-0.023,0.017,0.021,-0.018,0.011,0.015,-0.0011,-0.0058,-0.00013,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0076,0.047,0.048,0.035,9.1e-07,8e-07,2.2e-06,0.002,0.0023,0.00026,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1
|
||||
20190000,-0.28,0.015,-0.0052,0.96,-0.023,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1
|
||||
20290000,-0.28,0.015,-0.0052,0.96,-0.022,0.017,0.022,-0.021,0.013,0.016,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.023,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1
|
||||
20390000,-0.28,0.015,-0.0051,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1
|
||||
20490000,-0.28,0.015,-0.0051,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.7e-05,0.0012,0.0012,0.00068,0.0012,1,1
|
||||
20590000,-0.28,0.015,-0.005,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.3e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
|
||||
20690000,-0.28,0.015,-0.0049,0.96,-0.017,0.017,0.023,-0.024,0.014,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
|
||||
20790000,-0.28,0.015,-0.0043,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
|
||||
20890000,-0.29,0.01,0.0044,0.96,-0.0062,0.0017,-0.11,-0.02,0.011,0.0065,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.7e-05,0.0012,0.0011,0.00068,0.0012,1,1
|
||||
20990000,-0.29,0.0064,0.0073,0.96,0.0086,-0.015,-0.25,-0.017,0.0083,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.7e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21090000,-0.29,0.0069,0.0058,0.96,0.022,-0.028,-0.37,-0.015,0.0064,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.8e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21190000,-0.29,0.0088,0.0032,0.96,0.028,-0.034,-0.5,-0.013,0.0048,-0.076,-0.0011,-0.0057,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21290000,-0.29,0.01,0.0011,0.96,0.027,-0.036,-0.63,-0.01,0.0022,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21390000,-0.29,0.011,-0.00034,0.96,0.021,-0.029,-0.75,-0.012,0.0054,-0.2,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21490000,-0.29,0.012,-0.0011,0.96,0.014,-0.028,-0.89,-0.0097,0.0023,-0.28,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21590000,-0.29,0.012,-0.0016,0.96,0.0024,-0.022,-1,-0.014,0.0069,-0.37,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21690000,-0.29,0.012,-0.0019,0.96,-0.0028,-0.019,-1.1,-0.014,0.0041,-0.49,-0.0011,-0.0058,-0.00011,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21790000,-0.29,0.012,-0.0023,0.96,-0.0086,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21890000,-0.29,0.012,-0.0026,0.96,-0.014,-0.007,-1.4,-0.016,0.0098,-0.75,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21990000,-0.29,0.012,-0.0033,0.96,-0.02,0.0012,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.8e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22090000,-0.29,0.013,-0.004,0.96,-0.023,0.0045,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22190000,-0.29,0.013,-0.0044,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0021,0.00019,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22290000,-0.29,0.014,-0.0051,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22390000,-0.29,0.014,-0.0054,0.96,-0.045,0.023,-1.4,-0.038,0.03,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22490000,-0.29,0.014,-0.0055,0.96,-0.052,0.029,-1.4,-0.043,0.033,-1.6,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22590000,-0.29,0.015,-0.0054,0.96,-0.057,0.035,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22690000,-0.29,0.015,-0.0053,0.96,-0.061,0.04,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22790000,-0.29,0.016,-0.0052,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22890000,-0.29,0.016,-0.0053,0.96,-0.073,0.049,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22990000,-0.29,0.016,-0.0051,0.96,-0.076,0.049,-1.4,-0.066,0.045,-2.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.05,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
23090000,-0.29,0.017,-0.0051,0.96,-0.082,0.053,-1.4,-0.073,0.05,-2.5,-0.0011,-0.0058,-7e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
23190000,-0.29,0.017,-0.005,0.96,-0.083,0.048,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
23290000,-0.29,0.017,-0.0055,0.96,-0.09,0.052,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
23390000,-0.28,0.017,-0.0054,0.96,-0.089,0.055,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.9e-05,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23490000,-0.28,0.017,-0.0055,0.96,-0.096,0.055,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23590000,-0.29,0.017,-0.0056,0.96,-0.094,0.049,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.7e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23690000,-0.29,0.018,-0.0062,0.96,-0.093,0.052,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.3e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23790000,-0.29,0.021,-0.0077,0.96,-0.079,0.049,-0.95,-0.08,0.048,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23890000,-0.29,0.025,-0.011,0.96,-0.073,0.052,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23990000,-0.29,0.028,-0.012,0.96,-0.064,0.051,-0.13,-0.075,0.047,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
24090000,-0.29,0.027,-0.012,0.96,-0.071,0.059,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
24190000,-0.29,0.022,-0.0094,0.96,-0.075,0.055,0.088,-0.067,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
24290000,-0.29,0.019,-0.0074,0.96,-0.08,0.057,0.066,-0.074,0.045,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
24390000,-0.29,0.018,-0.0065,0.96,-0.064,0.051,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
24490000,-0.29,0.018,-0.0067,0.96,-0.058,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
24590000,-0.29,0.018,-0.0073,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
24690000,-0.29,0.018,-0.0078,0.96,-0.045,0.045,0.075,-0.047,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6.6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
24790000,-0.29,0.017,-0.0079,0.96,-0.038,0.043,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.1e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
24890000,-0.29,0.017,-0.0078,0.96,-0.037,0.046,0.056,-0.038,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
24990000,-0.29,0.016,-0.0076,0.96,-0.025,0.046,0.049,-0.023,0.027,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25090000,-0.29,0.016,-0.0079,0.96,-0.02,0.046,0.047,-0.024,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25190000,-0.29,0.016,-0.0081,0.96,-0.01,0.042,0.047,-0.0082,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25290000,-0.29,0.015,-0.0083,0.96,-0.0055,0.045,0.042,-0.0089,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25390000,-0.29,0.015,-0.0084,0.96,0.0035,0.043,0.04,0.0011,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25490000,-0.29,0.015,-0.0085,0.96,0.0079,0.044,0.04,0.00081,0.025,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25590000,-0.29,0.015,-0.0086,0.96,0.013,0.04,0.041,0.0082,0.0099,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0012,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25690000,-0.29,0.014,-0.0081,0.96,0.014,0.039,0.03,0.0097,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25790000,-0.29,0.014,-0.008,0.96,0.024,0.034,0.03,0.017,0.0038,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25890000,-0.29,0.014,-0.008,0.96,0.03,0.034,0.033,0.02,0.008,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25990000,-0.29,0.014,-0.008,0.96,0.033,0.029,0.026,0.017,-0.0032,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26090000,-0.29,0.014,-0.0077,0.96,0.038,0.029,0.025,0.02,-0.0011,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26190000,-0.29,0.014,-0.0075,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26290000,-0.29,0.015,-0.0075,0.96,0.043,0.019,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26390000,-0.29,0.015,-0.0069,0.96,0.04,0.01,0.019,0.019,-0.029,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26490000,-0.29,0.015,-0.0067,0.96,0.043,0.0083,0.028,0.023,-0.028,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26590000,-0.29,0.015,-0.0061,0.96,0.042,-0.0016,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26690000,-0.29,0.015,-0.006,0.96,0.044,-0.0052,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26790000,-0.29,0.014,-0.0058,0.96,0.047,-0.011,0.026,0.024,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26890000,-0.29,0.014,-0.0052,0.96,0.053,-0.014,0.022,0.029,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26990000,-0.29,0.015,-0.0046,0.96,0.054,-0.02,0.021,0.022,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27090000,-0.29,0.015,-0.0044,0.96,0.056,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27190000,-0.29,0.015,-0.0045,0.96,0.057,-0.031,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27290000,-0.29,0.016,-0.0045,0.96,0.064,-0.034,0.14,0.024,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27390000,-0.29,0.018,-0.0057,0.96,0.067,-0.026,0.46,0.0069,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27490000,-0.29,0.02,-0.0069,0.96,0.071,-0.029,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27590000,-0.29,0.019,-0.0069,0.96,0.063,-0.031,0.87,0.0076,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27690000,-0.29,0.016,-0.006,0.96,0.057,-0.028,0.78,0.013,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27790000,-0.29,0.015,-0.0048,0.96,0.054,-0.027,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27890000,-0.29,0.015,-0.0045,0.96,0.06,-0.032,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27990000,-0.29,0.015,-0.0048,0.96,0.061,-0.035,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
28090000,-0.29,0.015,-0.0051,0.96,0.064,-0.035,0.8,0.026,-0.028,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
28190000,-0.29,0.015,-0.0045,0.96,0.062,-0.034,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
28290000,-0.29,0.016,-0.0039,0.96,0.066,-0.037,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
28390000,-0.29,0.016,-0.0039,0.96,0.067,-0.039,0.81,0.035,-0.035,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
28490000,-0.29,0.017,-0.0041,0.96,0.07,-0.042,0.81,0.042,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
28590000,-0.29,0.017,-0.0041,0.96,0.063,-0.043,0.81,0.043,-0.042,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
28690000,-0.29,0.016,-0.004,0.96,0.062,-0.044,0.81,0.049,-0.046,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
28790000,-0.29,0.016,-0.0034,0.96,0.06,-0.043,0.81,0.05,-0.045,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
28890000,-0.29,0.015,-0.0032,0.96,0.063,-0.045,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
28990000,-0.29,0.016,-0.0029,0.96,0.062,-0.043,0.81,0.057,-0.05,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
29090000,-0.29,0.016,-0.0028,0.96,0.065,-0.044,0.81,0.064,-0.054,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
29190000,-0.29,0.016,-0.0027,0.96,0.066,-0.043,0.8,0.066,-0.053,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
29290000,-0.29,0.016,-0.0029,0.96,0.07,-0.049,0.81,0.075,-0.057,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
29390000,-0.29,0.015,-0.0035,0.96,0.067,-0.046,0.81,0.073,-0.054,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
29490000,-0.29,0.015,-0.0034,0.96,0.07,-0.047,0.81,0.081,-0.06,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
29590000,-0.29,0.015,-0.0033,0.96,0.067,-0.046,0.81,0.079,-0.058,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
29690000,-0.29,0.015,-0.0034,0.96,0.072,-0.045,0.81,0.087,-0.063,-1.8,-0.0013,-0.0058,-0.00011,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
29790000,-0.29,0.015,-0.0031,0.96,0.069,-0.039,0.8,0.084,-0.06,-1.7,-0.0013,-0.0058,-9.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
29890000,-0.29,0.015,-0.0025,0.96,0.07,-0.04,0.8,0.092,-0.064,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
29990000,-0.29,0.016,-0.0027,0.96,0.065,-0.038,0.8,0.086,-0.063,-1.6,-0.0013,-0.0058,-8.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30090000,-0.29,0.016,-0.0028,0.96,0.067,-0.038,0.8,0.094,-0.065,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30190000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.088,-0.057,-1.5,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30290000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.095,-0.06,-1.4,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30390000,-0.29,0.015,-0.0028,0.96,0.06,-0.026,0.8,0.095,-0.054,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30490000,-0.29,0.015,-0.0028,0.96,0.063,-0.026,0.8,0.1,-0.058,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30590000,-0.29,0.016,-0.0031,0.96,0.061,-0.025,0.8,0.097,-0.054,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30690000,-0.29,0.016,-0.0034,0.96,0.059,-0.024,0.8,0.1,-0.057,-1.1,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30790000,-0.29,0.016,-0.0032,0.96,0.052,-0.015,0.79,0.096,-0.045,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30890000,-0.29,0.015,-0.0026,0.96,0.051,-0.011,0.79,0.099,-0.046,-0.95,-0.0012,-0.0058,-4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30990000,-0.29,0.015,-0.0027,0.96,0.047,-0.0093,0.79,0.095,-0.044,-0.88,-0.0012,-0.0058,-3.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31090000,-0.29,0.015,-0.0029,0.96,0.046,-0.008,0.79,0.099,-0.045,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31190000,-0.29,0.016,-0.003,0.96,0.043,-0.0048,0.8,0.093,-0.041,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31290000,-0.29,0.016,-0.0032,0.96,0.04,-0.0033,0.8,0.096,-0.042,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31390000,-0.29,0.015,-0.003,0.96,0.035,0.0017,0.8,0.09,-0.038,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31490000,-0.29,0.016,-0.0027,0.96,0.037,0.005,0.8,0.095,-0.037,-0.52,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31590000,-0.29,0.016,-0.0025,0.96,0.037,0.0068,0.8,0.093,-0.034,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31690000,-0.29,0.016,-0.0025,0.96,0.041,0.0079,0.8,0.098,-0.033,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31790000,-0.29,0.017,-0.0027,0.96,0.035,0.013,0.8,0.094,-0.024,-0.3,-0.0012,-0.0058,-3e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31890000,-0.29,0.017,-0.0024,0.96,0.034,0.015,0.8,0.099,-0.022,-0.24,-0.0012,-0.0058,2.1e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31990000,-0.29,0.016,-0.0027,0.96,0.03,0.016,0.79,0.095,-0.017,-0.17,-0.0012,-0.0058,1.2e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32090000,-0.29,0.016,-0.0032,0.96,0.031,0.02,0.8,0.099,-0.015,-0.096,-0.0012,-0.0058,8.1e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32190000,-0.28,0.016,-0.0034,0.96,0.028,0.027,0.8,0.094,-0.006,-0.028,-0.0012,-0.0058,3.9e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32290000,-0.28,0.016,-0.0033,0.96,0.028,0.03,0.79,0.097,-0.0033,0.042,-0.0012,-0.0058,7.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32390000,-0.28,0.016,-0.0034,0.96,0.024,0.032,0.79,0.093,0.00041,0.12,-0.0012,-0.0058,5.9e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32490000,-0.28,0.015,-0.0065,0.96,-0.015,0.085,-0.078,0.092,0.0081,0.12,-0.0012,-0.0058,3.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32590000,-0.29,0.015,-0.0065,0.96,-0.013,0.084,-0.081,0.092,0.0011,0.1,-0.0012,-0.0058,-1.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32690000,-0.29,0.015,-0.0065,0.96,-0.0087,0.091,-0.082,0.091,0.0099,0.087,-0.0012,-0.0058,-1.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32790000,-0.29,0.015,-0.0063,0.96,-0.0048,0.09,-0.083,0.092,0.0024,0.072,-0.0012,-0.0058,-6.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32890000,-0.29,0.015,-0.0063,0.96,-0.0052,0.096,-0.085,0.091,0.011,0.057,-0.0012,-0.0058,-2.3e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32990000,-0.29,0.015,-0.0062,0.96,-0.0014,0.091,-0.084,0.092,-0.0019,0.043,-0.0013,-0.0058,-1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
33090000,-0.29,0.015,-0.0061,0.96,0.0025,0.097,-0.081,0.092,0.0074,0.036,-0.0013,-0.0058,-9.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
33190000,-0.29,0.015,-0.0061,0.96,0.0066,0.093,-0.08,0.092,-0.0072,0.028,-0.0013,-0.0058,-2.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33290000,-0.29,0.015,-0.0061,0.96,0.011,0.096,-0.08,0.094,0.0015,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33390000,-0.29,0.015,-0.006,0.96,0.015,0.092,-0.078,0.093,-0.0067,0.011,-0.0013,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33490000,-0.29,0.015,-0.006,0.96,0.021,0.097,-0.077,0.096,0.0026,0.0017,-0.0013,-0.0058,-2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33590000,-0.29,0.014,-0.0058,0.96,0.024,0.094,-0.074,0.096,-0.01,-0.0062,-0.0013,-0.0058,-2.6e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33690000,-0.29,0.015,-0.0058,0.96,0.027,0.098,-0.075,0.097,-0.0013,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33790000,-0.29,0.015,-0.0058,0.96,0.029,0.095,-0.069,0.093,-0.014,-0.021,-0.0013,-0.0058,-3.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33890000,-0.29,0.014,-0.0057,0.96,0.034,0.097,-0.069,0.097,-0.0054,-0.028,-0.0013,-0.0058,-2.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33990000,-0.29,0.015,-0.0056,0.96,0.036,0.095,-0.065,0.095,-0.014,-0.032,-0.0013,-0.0057,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34090000,-0.29,0.015,-0.0056,0.96,0.039,0.1,-0.064,0.098,-0.0041,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34190000,-0.29,0.015,-0.0055,0.96,0.041,0.097,-0.061,0.093,-0.016,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34290000,-0.29,0.015,-0.0054,0.96,0.042,0.1,-0.06,0.098,-0.0061,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34390000,-0.29,0.015,-0.0053,0.96,0.043,0.096,-0.055,0.093,-0.018,-0.049,-0.0013,-0.0057,-3.8e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34490000,-0.29,0.015,-0.0053,0.96,0.046,0.1,-0.053,0.097,-0.0082,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34590000,-0.29,0.014,-0.0052,0.96,0.046,0.097,0.74,0.091,-0.022,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34690000,-0.29,0.014,-0.0052,0.96,0.051,0.1,1.7,0.096,-0.012,0.095,-0.0013,-0.0057,-3.6e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34790000,-0.29,0.014,-0.0052,0.96,0.052,0.098,2.7,0.09,-0.026,0.27,-0.0013,-0.0057,-4.6e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34890000,-0.29,0.014,-0.0052,0.96,0.057,0.1,3.7,0.095,-0.016,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,6.5e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
20190000,-0.28,0.015,-0.0052,0.96,-0.023,0.014,0.022,-0.019,0.011,0.015,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.015,0.016,0.0075,0.05,0.05,0.035,8.8e-07,7.8e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.6e-05,0.0012,0.0012,0.00068,0.0012,1,1
|
||||
20290000,-0.28,0.015,-0.0052,0.96,-0.022,0.017,0.022,-0.021,0.013,0.016,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.016,0.017,0.0075,0.054,0.054,0.035,8.7e-07,7.7e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.6e-05,0.0012,0.0012,0.00068,0.0012,1,1
|
||||
20390000,-0.28,0.015,-0.0051,0.96,-0.02,0.015,0.022,-0.021,0.012,0.017,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.016,0.017,0.0075,0.056,0.057,0.035,8.5e-07,7.5e-07,2.2e-06,0.002,0.0023,0.00025,0.0012,6.6e-05,0.0012,0.0012,0.00068,0.0012,1,1
|
||||
20490000,-0.28,0.015,-0.0051,0.96,-0.018,0.017,0.022,-0.023,0.013,0.015,-0.0011,-0.0058,-0.00013,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5.1e-05,0.05,0.017,0.018,0.0075,0.061,0.062,0.035,8.4e-07,7.4e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.6e-05,0.0012,0.0011,0.00068,0.0012,1,1
|
||||
20590000,-0.28,0.015,-0.005,0.96,-0.018,0.016,0.022,-0.023,0.012,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.4e-05,5e-05,0.05,0.017,0.018,0.0074,0.064,0.064,0.035,8.2e-07,7.3e-07,2.2e-06,0.002,0.0022,0.00024,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1
|
||||
20690000,-0.28,0.015,-0.0049,0.96,-0.017,0.017,0.023,-0.024,0.014,0.014,-0.0011,-0.0058,-0.00013,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.034,-0.069,0,0,5.5e-05,5e-05,0.05,0.018,0.019,0.0074,0.069,0.07,0.035,8.1e-07,7.2e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1
|
||||
20790000,-0.28,0.015,-0.0043,0.96,-0.011,0.012,0.0077,-0.019,0.01,0.013,-0.0011,-0.0058,-0.00014,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.015,0.016,0.0073,0.056,0.057,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1
|
||||
20890000,-0.29,0.01,0.0044,0.96,-0.0062,0.0017,-0.11,-0.02,0.011,0.0065,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.9e-05,0.05,0.016,0.017,0.0073,0.061,0.062,0.035,7.8e-07,6.9e-07,2.2e-06,0.002,0.0022,0.00023,0.0012,6.5e-05,0.0012,0.0011,0.00068,0.0012,1,1
|
||||
20990000,-0.29,0.0064,0.0073,0.96,0.0086,-0.015,-0.25,-0.017,0.0083,-0.0084,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.2e-05,4.8e-05,0.05,0.015,0.015,0.0072,0.051,0.052,0.034,7.5e-07,6.7e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.5e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21090000,-0.29,0.0069,0.0058,0.96,0.022,-0.028,-0.37,-0.015,0.0064,-0.039,-0.0011,-0.0058,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.3e-05,4.8e-05,0.05,0.016,0.016,0.0072,0.056,0.056,0.035,7.5e-07,6.6e-07,2.2e-06,0.002,0.0022,0.00022,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21190000,-0.29,0.0088,0.0032,0.96,0.028,-0.034,-0.5,-0.013,0.0048,-0.076,-0.0011,-0.0057,-0.00014,0.069,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.014,0.015,0.0071,0.048,0.048,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00022,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21290000,-0.29,0.01,0.0011,0.96,0.027,-0.036,-0.63,-0.01,0.0022,-0.13,-0.0011,-0.0058,-0.00014,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.015,0.016,0.0071,0.052,0.052,0.035,7.2e-07,6.4e-07,2.1e-06,0.002,0.0022,0.00021,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21390000,-0.29,0.011,-0.00034,0.96,0.021,-0.029,-0.75,-0.012,0.0054,-0.2,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.015,0.016,0.007,0.054,0.055,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.4e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21490000,-0.29,0.012,-0.0011,0.96,0.014,-0.028,-0.89,-0.0097,0.0023,-0.28,-0.0011,-0.0058,-0.00013,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.8e-05,0.05,0.016,0.017,0.007,0.059,0.059,0.035,7e-07,6.2e-07,2.1e-06,0.0019,0.0022,0.00021,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21590000,-0.29,0.012,-0.0016,0.96,0.0024,-0.022,-1,-0.014,0.0069,-0.37,-0.0011,-0.0058,-0.00012,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.016,0.017,0.0069,0.061,0.062,0.034,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21690000,-0.29,0.012,-0.0019,0.96,-0.0028,-0.019,-1.1,-0.014,0.0041,-0.49,-0.0011,-0.0058,-0.00011,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.2e-05,4.7e-05,0.05,0.017,0.018,0.0069,0.066,0.067,0.035,6.8e-07,6e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21790000,-0.29,0.012,-0.0023,0.96,-0.0086,-0.011,-1.3,-0.015,0.01,-0.61,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.017,0.018,0.0069,0.069,0.069,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.0002,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21890000,-0.29,0.012,-0.0026,0.96,-0.014,-0.007,-1.4,-0.016,0.0098,-0.75,-0.0011,-0.0058,-0.0001,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.7e-05,0.05,0.018,0.019,0.0068,0.074,0.075,0.034,6.6e-07,5.8e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
21990000,-0.29,0.012,-0.0033,0.96,-0.02,0.0012,-1.4,-0.023,0.017,-0.89,-0.001,-0.0058,-8.8e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.018,0.019,0.0068,0.076,0.077,0.034,6.4e-07,5.7e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.3e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22090000,-0.29,0.013,-0.004,0.96,-0.023,0.0045,-1.4,-0.023,0.016,-1,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,5.1e-05,4.6e-05,0.05,0.019,0.02,0.0068,0.082,0.084,0.034,6.4e-07,5.6e-07,2.1e-06,0.0019,0.0022,0.00019,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22190000,-0.29,0.013,-0.0044,0.96,-0.03,0.011,-1.4,-0.028,0.024,-1.2,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.6e-05,0.05,0.018,0.02,0.0067,0.085,0.086,0.034,6.2e-07,5.5e-07,2.1e-06,0.0019,0.0021,0.00019,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22290000,-0.29,0.014,-0.0051,0.96,-0.038,0.016,-1.4,-0.032,0.025,-1.3,-0.0011,-0.0058,-7.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5.1e-05,4.6e-05,0.05,0.019,0.021,0.0067,0.091,0.093,0.034,6.2e-07,5.4e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22390000,-0.29,0.014,-0.0054,0.96,-0.045,0.023,-1.4,-0.038,0.03,-1.5,-0.001,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.019,0.02,0.0066,0.093,0.095,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22490000,-0.29,0.014,-0.0055,0.96,-0.052,0.029,-1.4,-0.043,0.033,-1.6,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.021,0.0066,0.1,0.1,0.034,6e-07,5.3e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22590000,-0.29,0.015,-0.0054,0.96,-0.057,0.035,-1.4,-0.044,0.036,-1.7,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.019,0.021,0.0065,0.1,0.1,0.034,5.8e-07,5.2e-07,2.1e-06,0.0019,0.0021,0.00018,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22690000,-0.29,0.015,-0.0053,0.96,-0.061,0.04,-1.4,-0.051,0.04,-1.9,-0.001,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,5e-05,4.5e-05,0.05,0.02,0.022,0.0065,0.11,0.11,0.034,5.8e-07,5.1e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00067,0.0012,1,1
|
||||
22790000,-0.29,0.016,-0.0052,0.96,-0.068,0.044,-1.4,-0.056,0.043,-2,-0.001,-0.0058,-7.3e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.4e-05,0.05,0.02,0.021,0.0065,0.11,0.11,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
22890000,-0.29,0.016,-0.0053,0.96,-0.073,0.049,-1.4,-0.063,0.046,-2.2,-0.0011,-0.0058,-6.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.069,0,0,4.9e-05,4.5e-05,0.05,0.021,0.022,0.0064,0.12,0.12,0.034,5.6e-07,5e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
22990000,-0.29,0.016,-0.0051,0.96,-0.076,0.049,-1.4,-0.066,0.045,-2.3,-0.0011,-0.0058,-7.1e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.05,0.02,0.022,0.0064,0.12,0.12,0.034,5.5e-07,4.9e-07,2.1e-06,0.0019,0.0021,0.00017,0.0012,6.2e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23090000,-0.29,0.017,-0.0051,0.96,-0.082,0.053,-1.4,-0.073,0.05,-2.5,-0.0011,-0.0058,-7e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.9e-05,4.4e-05,0.05,0.021,0.023,0.0064,0.13,0.13,0.034,5.5e-07,4.8e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23190000,-0.29,0.017,-0.005,0.96,-0.083,0.048,-1.4,-0.072,0.047,-2.6,-0.0011,-0.0058,-8.2e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.02,0.022,0.0063,0.13,0.13,0.033,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23290000,-0.29,0.017,-0.0055,0.96,-0.09,0.052,-1.4,-0.08,0.051,-2.8,-0.0011,-0.0058,-7.9e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.4e-05,0.049,0.021,0.023,0.0063,0.14,0.14,0.034,5.3e-07,4.7e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23390000,-0.28,0.017,-0.0054,0.96,-0.089,0.055,-1.4,-0.075,0.053,-2.9,-0.0011,-0.0058,-8.9e-05,0.068,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0063,0.14,0.14,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23490000,-0.28,0.017,-0.0055,0.96,-0.096,0.055,-1.4,-0.086,0.057,-3,-0.0011,-0.0058,-8.4e-05,0.069,0.011,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.8e-05,4.3e-05,0.049,0.021,0.023,0.0063,0.15,0.15,0.033,5.2e-07,4.6e-07,2.1e-06,0.0019,0.0021,0.00016,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23590000,-0.29,0.017,-0.0056,0.96,-0.094,0.049,-1.4,-0.081,0.048,-3.2,-0.0011,-0.0058,-9.7e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0062,0.15,0.15,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23690000,-0.29,0.018,-0.0062,0.96,-0.093,0.052,-1.3,-0.09,0.052,-3.3,-0.0011,-0.0058,-9.3e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.022,0.023,0.0062,0.16,0.16,0.033,5e-07,4.5e-07,2.1e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23790000,-0.29,0.021,-0.0077,0.96,-0.079,0.049,-0.95,-0.08,0.048,-3.4,-0.0012,-0.0058,-9.8e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0061,0.16,0.16,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23890000,-0.29,0.025,-0.011,0.96,-0.073,0.052,-0.52,-0.087,0.052,-3.5,-0.0012,-0.0058,-9.5e-05,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.068,0,0,4.7e-05,4.3e-05,0.049,0.021,0.022,0.0061,0.17,0.17,0.033,4.9e-07,4.4e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
23990000,-0.29,0.028,-0.012,0.96,-0.064,0.051,-0.13,-0.075,0.047,-3.6,-0.0012,-0.0058,-0.0001,0.068,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.0061,0.17,0.17,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6.1e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
24090000,-0.29,0.027,-0.012,0.96,-0.071,0.059,0.098,-0.08,0.052,-3.6,-0.0012,-0.0058,-0.0001,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.022,0.0061,0.18,0.18,0.033,4.8e-07,4.3e-07,2e-06,0.0019,0.0021,0.00015,0.0012,6e-05,0.0012,0.0011,0.00066,0.0012,1,1
|
||||
24190000,-0.29,0.022,-0.0094,0.96,-0.075,0.055,0.088,-0.067,0.039,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.021,0.006,0.18,0.18,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
24290000,-0.29,0.019,-0.0074,0.96,-0.08,0.057,0.066,-0.074,0.045,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.7e-05,4.2e-05,0.049,0.021,0.023,0.006,0.19,0.19,0.033,4.7e-07,4.2e-07,2e-06,0.0019,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
24390000,-0.29,0.018,-0.0065,0.96,-0.064,0.051,0.082,-0.055,0.035,-3.6,-0.0012,-0.0058,-0.00012,0.067,0.012,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.006,0.19,0.19,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
24490000,-0.29,0.018,-0.0067,0.96,-0.058,0.047,0.08,-0.061,0.038,-3.6,-0.0012,-0.0058,-0.00011,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.006,0.2,0.2,0.033,4.6e-07,4.1e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
24590000,-0.29,0.018,-0.0073,0.96,-0.047,0.045,0.076,-0.042,0.033,-3.6,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.02,0.022,0.0059,0.2,0.2,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
24690000,-0.29,0.018,-0.0078,0.96,-0.045,0.045,0.075,-0.047,0.037,-3.5,-0.0013,-0.0058,-0.00012,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.21,0.21,0.033,4.5e-07,4e-07,2e-06,0.0018,0.0021,0.00014,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
24790000,-0.29,0.017,-0.0079,0.96,-0.038,0.043,0.067,-0.034,0.029,-3.5,-0.0013,-0.0058,-0.00013,0.067,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.1e-05,0.049,0.02,0.022,0.0059,0.21,0.21,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
24890000,-0.29,0.017,-0.0078,0.96,-0.037,0.046,0.056,-0.038,0.032,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.6e-05,4.2e-05,0.049,0.021,0.023,0.0059,0.22,0.22,0.032,4.4e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
24990000,-0.29,0.016,-0.0076,0.96,-0.025,0.046,0.049,-0.023,0.027,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.22,0.22,0.032,4.3e-07,3.9e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25090000,-0.29,0.016,-0.0079,0.96,-0.02,0.046,0.047,-0.024,0.031,-3.5,-0.0013,-0.0058,-0.00013,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.021,0.023,0.0058,0.23,0.23,0.032,4.3e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25190000,-0.29,0.016,-0.0081,0.96,-0.01,0.042,0.047,-0.0082,0.021,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0058,0.23,0.23,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25290000,-0.29,0.015,-0.0083,0.96,-0.0055,0.045,0.042,-0.0089,0.026,-3.5,-0.0013,-0.0059,-0.00015,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.2e-05,0.048,0.022,0.023,0.0058,0.24,0.24,0.032,4.2e-07,3.8e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25390000,-0.29,0.015,-0.0084,0.96,0.0035,0.043,0.04,0.0011,0.02,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.24,0.24,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0012,6e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25490000,-0.29,0.015,-0.0085,0.96,0.0079,0.044,0.04,0.00081,0.025,-3.5,-0.0013,-0.0059,-0.00016,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0058,0.25,0.25,0.032,4.2e-07,3.7e-07,2e-06,0.0018,0.0021,0.00013,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25590000,-0.29,0.015,-0.0086,0.96,0.013,0.04,0.041,0.0082,0.0099,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.25,0.032,4.1e-07,3.6e-07,2e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25690000,-0.29,0.014,-0.0081,0.96,0.014,0.039,0.03,0.0097,0.013,-3.5,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.26,0.26,0.032,4.1e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25790000,-0.29,0.014,-0.008,0.96,0.024,0.034,0.03,0.017,0.0038,-3.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0057,0.25,0.26,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25890000,-0.29,0.014,-0.008,0.96,0.03,0.034,0.033,0.02,0.008,-3.5,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.6e-05,4.1e-05,0.048,0.022,0.023,0.0057,0.27,0.27,0.032,4e-07,3.6e-07,1.9e-06,0.0018,0.0021,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
25990000,-0.29,0.014,-0.008,0.96,0.033,0.029,0.026,0.017,-0.0032,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.021,0.022,0.0056,0.26,0.27,0.032,4e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26090000,-0.29,0.014,-0.0077,0.96,0.038,0.029,0.025,0.02,-0.0011,-3.5,-0.0014,-0.0058,-0.00019,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.28,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26190000,-0.29,0.014,-0.0075,0.96,0.042,0.02,0.02,0.024,-0.017,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.27,0.28,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26290000,-0.29,0.015,-0.0075,0.96,0.043,0.019,0.015,0.027,-0.015,-3.5,-0.0014,-0.0058,-0.0002,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.29,0.29,0.032,3.9e-07,3.5e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26390000,-0.29,0.015,-0.0069,0.96,0.04,0.01,0.019,0.019,-0.029,-3.5,-0.0014,-0.0058,-0.00021,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.28,0.29,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00012,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26490000,-0.29,0.015,-0.0067,0.96,0.043,0.0083,0.028,0.023,-0.028,-3.5,-0.0014,-0.0058,-0.00022,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.066,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.3,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26590000,-0.29,0.015,-0.0061,0.96,0.042,-0.0016,0.028,0.023,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0056,0.29,0.3,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26690000,-0.29,0.015,-0.006,0.96,0.044,-0.0052,0.027,0.027,-0.041,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4.1e-05,0.048,0.022,0.023,0.0056,0.31,0.31,0.032,3.8e-07,3.4e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26790000,-0.29,0.014,-0.0058,0.96,0.047,-0.011,0.026,0.024,-0.054,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.3,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26890000,-0.29,0.014,-0.0052,0.96,0.053,-0.014,0.022,0.029,-0.056,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.31,0.32,0.032,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
26990000,-0.29,0.015,-0.0046,0.96,0.054,-0.02,0.021,0.022,-0.063,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.31,0.31,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27090000,-0.29,0.015,-0.0044,0.96,0.056,-0.026,0.025,0.028,-0.065,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.32,0.33,0.031,3.7e-07,3.3e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27190000,-0.29,0.015,-0.0045,0.96,0.057,-0.031,0.027,0.018,-0.069,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.021,0.022,0.0055,0.32,0.32,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27290000,-0.29,0.016,-0.0045,0.96,0.064,-0.034,0.14,0.024,-0.072,-3.5,-0.0014,-0.0058,-0.00025,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.022,0.023,0.0055,0.33,0.34,0.031,3.6e-07,3.2e-07,1.9e-06,0.0018,0.002,0.00011,0.0011,5.9e-05,0.0012,0.0011,0.00065,0.0012,1,1
|
||||
27390000,-0.29,0.018,-0.0057,0.96,0.067,-0.026,0.46,0.0069,-0.027,-3.5,-0.0014,-0.0058,-0.00023,0.066,0.014,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.015,0.016,0.0054,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
27490000,-0.29,0.02,-0.0069,0.96,0.071,-0.029,0.78,0.014,-0.029,-3.5,-0.0014,-0.0058,-0.00024,0.066,0.013,-0.13,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,4e-05,0.048,0.015,0.016,0.0055,0.15,0.15,0.031,3.5e-07,3.2e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
27590000,-0.29,0.019,-0.0069,0.96,0.063,-0.031,0.87,0.0076,-0.02,-3.4,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.096,0.096,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.00011,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
27690000,-0.29,0.016,-0.006,0.96,0.057,-0.028,0.78,0.013,-0.023,-3.3,-0.0014,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.1,0.1,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
27790000,-0.29,0.015,-0.0048,0.96,0.054,-0.027,0.77,0.011,-0.019,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.013,0.014,0.0054,0.073,0.074,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
27890000,-0.29,0.015,-0.0045,0.96,0.06,-0.032,0.81,0.016,-0.021,-3.2,-0.0013,-0.0058,-0.00023,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.076,0.077,0.031,3.5e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
27990000,-0.29,0.015,-0.0048,0.96,0.061,-0.035,0.8,0.019,-0.024,-3.1,-0.0013,-0.0058,-0.00022,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.4e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.079,0.079,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
28090000,-0.29,0.015,-0.0051,0.96,0.064,-0.035,0.8,0.026,-0.028,-3,-0.0013,-0.0058,-0.00022,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.016,0.0054,0.082,0.083,0.031,3.4e-07,3.1e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
28190000,-0.29,0.015,-0.0045,0.96,0.062,-0.034,0.81,0.026,-0.03,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.014,0.015,0.0054,0.084,0.085,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
28290000,-0.29,0.016,-0.0039,0.96,0.066,-0.037,0.81,0.032,-0.034,-2.9,-0.0013,-0.0058,-0.00021,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,4e-05,0.048,0.015,0.016,0.0054,0.088,0.089,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
28390000,-0.29,0.016,-0.0039,0.96,0.067,-0.039,0.81,0.035,-0.035,-2.8,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.015,0.016,0.0053,0.091,0.092,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,0.0001,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
28490000,-0.29,0.017,-0.0041,0.96,0.07,-0.042,0.81,0.042,-0.038,-2.7,-0.0013,-0.0058,-0.0002,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0054,0.095,0.096,0.031,3.4e-07,3e-07,1.8e-06,0.0018,0.002,9.9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
28590000,-0.29,0.017,-0.0041,0.96,0.063,-0.043,0.81,0.043,-0.042,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.017,0.0053,0.098,0.099,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
28690000,-0.29,0.016,-0.004,0.96,0.062,-0.044,0.81,0.049,-0.046,-2.6,-0.0013,-0.0058,-0.00019,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.083,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.1,0.031,3.3e-07,3e-07,1.8e-06,0.0018,0.002,9.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
28790000,-0.29,0.016,-0.0034,0.96,0.06,-0.043,0.81,0.05,-0.045,-2.5,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.016,0.018,0.0053,0.1,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
28890000,-0.29,0.015,-0.0032,0.96,0.063,-0.045,0.81,0.056,-0.049,-2.4,-0.0013,-0.0058,-0.00018,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.3e-07,2.9e-07,1.8e-06,0.0018,0.002,9.7e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
28990000,-0.29,0.016,-0.0029,0.96,0.062,-0.043,0.81,0.057,-0.05,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.018,0.0053,0.11,0.11,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.6e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
29090000,-0.29,0.016,-0.0028,0.96,0.065,-0.044,0.81,0.064,-0.054,-2.3,-0.0013,-0.0058,-0.00017,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.8e-06,0.0018,0.002,9.5e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
29190000,-0.29,0.016,-0.0027,0.96,0.066,-0.043,0.8,0.066,-0.053,-2.2,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.017,0.019,0.0053,0.12,0.12,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.5e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
29290000,-0.29,0.016,-0.0029,0.96,0.07,-0.049,0.81,0.075,-0.057,-2.1,-0.0013,-0.0058,-0.00016,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.02,0.0053,0.13,0.13,0.031,3.2e-07,2.9e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
29390000,-0.29,0.015,-0.0035,0.96,0.067,-0.046,0.81,0.073,-0.054,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0053,0.13,0.13,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.4e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
29490000,-0.29,0.015,-0.0034,0.96,0.07,-0.047,0.81,0.081,-0.06,-2,-0.0013,-0.0058,-0.00014,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.14,0.031,3.2e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
29590000,-0.29,0.015,-0.0033,0.96,0.067,-0.046,0.81,0.079,-0.058,-1.9,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.018,0.019,0.0052,0.14,0.14,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.3e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
29690000,-0.29,0.015,-0.0034,0.96,0.072,-0.045,0.81,0.087,-0.063,-1.8,-0.0013,-0.0058,-0.00012,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.02,0.0053,0.14,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.2e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
29790000,-0.29,0.015,-0.0031,0.96,0.069,-0.039,0.8,0.084,-0.06,-1.7,-0.0013,-0.0058,-9.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.018,0.02,0.0052,0.15,0.15,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
29890000,-0.29,0.015,-0.0025,0.96,0.07,-0.04,0.8,0.092,-0.064,-1.7,-0.0013,-0.0058,-9.3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.9e-05,0.048,0.019,0.021,0.0053,0.15,0.16,0.031,3.1e-07,2.8e-07,1.7e-06,0.0018,0.002,9.1e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
29990000,-0.29,0.016,-0.0027,0.96,0.065,-0.038,0.8,0.086,-0.063,-1.6,-0.0013,-0.0058,-8.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.16,0.16,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30090000,-0.29,0.016,-0.0028,0.96,0.067,-0.038,0.8,0.094,-0.065,-1.5,-0.0013,-0.0058,-9.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.16,0.17,0.03,3e-07,2.8e-07,1.7e-06,0.0018,0.002,9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30190000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.088,-0.057,-1.5,-0.0013,-0.0058,-8.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.02,0.0052,0.17,0.17,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30290000,-0.29,0.016,-0.0028,0.96,0.062,-0.032,0.8,0.095,-0.06,-1.4,-0.0013,-0.0058,-8.6e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.9e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30390000,-0.29,0.015,-0.0028,0.96,0.06,-0.026,0.8,0.095,-0.054,-1.3,-0.0013,-0.0058,-6.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.17,0.18,0.03,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30490000,-0.29,0.015,-0.0028,0.96,0.063,-0.026,0.8,0.1,-0.058,-1.2,-0.0013,-0.0058,-6.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.5e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.18,0.19,0.031,3e-07,2.7e-07,1.7e-06,0.0018,0.002,8.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30590000,-0.29,0.016,-0.0031,0.96,0.061,-0.025,0.8,0.097,-0.054,-1.2,-0.0013,-0.0058,-4.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.18,0.19,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.8e-05,0.0011,5.8e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30690000,-0.29,0.016,-0.0034,0.96,0.059,-0.024,0.8,0.1,-0.057,-1.1,-0.0013,-0.0058,-5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30790000,-0.29,0.016,-0.0032,0.96,0.052,-0.015,0.79,0.096,-0.045,-1,-0.0013,-0.0058,-3.4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.019,0.021,0.0052,0.19,0.2,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30890000,-0.29,0.015,-0.0026,0.96,0.051,-0.011,0.79,0.099,-0.046,-0.95,-0.0012,-0.0058,-4e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.2,0.21,0.03,2.9e-07,2.7e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
30990000,-0.29,0.015,-0.0027,0.96,0.047,-0.0093,0.79,0.095,-0.044,-0.88,-0.0012,-0.0058,-3.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.2,0.21,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31090000,-0.29,0.015,-0.0029,0.96,0.046,-0.008,0.79,0.099,-0.045,-0.81,-0.0012,-0.0058,-4.2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.21,0.22,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31190000,-0.29,0.016,-0.003,0.96,0.043,-0.0048,0.8,0.093,-0.041,-0.74,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.02,0.021,0.0052,0.21,0.22,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31290000,-0.29,0.016,-0.0032,0.96,0.04,-0.0032,0.8,0.096,-0.042,-0.67,-0.0012,-0.0058,-2.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.8e-05,0.048,0.02,0.022,0.0052,0.22,0.23,0.03,2.9e-07,2.6e-07,1.6e-06,0.0018,0.002,8.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31390000,-0.29,0.015,-0.003,0.96,0.036,0.0017,0.8,0.09,-0.038,-0.59,-0.0012,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.22,0.23,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31490000,-0.29,0.016,-0.0027,0.96,0.037,0.0051,0.8,0.095,-0.037,-0.52,-0.0012,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0052,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.4e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31590000,-0.29,0.016,-0.0025,0.96,0.037,0.0068,0.8,0.093,-0.034,-0.45,-0.0012,-0.0058,-1.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.021,0.0051,0.23,0.24,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31690000,-0.29,0.016,-0.0025,0.96,0.041,0.0079,0.8,0.098,-0.033,-0.38,-0.0012,-0.0058,-1.3e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.4e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.3e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31790000,-0.29,0.017,-0.0027,0.96,0.035,0.013,0.8,0.094,-0.024,-0.3,-0.0012,-0.0058,-4.3e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.24,0.25,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31890000,-0.29,0.017,-0.0024,0.96,0.034,0.015,0.8,0.099,-0.022,-0.24,-0.0012,-0.0058,2e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.022,0.0051,0.25,0.26,0.03,2.8e-07,2.6e-07,1.6e-06,0.0018,0.002,8.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
31990000,-0.29,0.016,-0.0028,0.96,0.03,0.016,0.79,0.095,-0.017,-0.17,-0.0012,-0.0058,1.1e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.25,0.26,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.2e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32090000,-0.28,0.016,-0.0032,0.96,0.031,0.02,0.8,0.099,-0.015,-0.096,-0.0012,-0.0058,6.9e-07,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32190000,-0.28,0.016,-0.0034,0.96,0.028,0.027,0.8,0.094,-0.0059,-0.028,-0.0012,-0.0058,3.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.26,0.27,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32290000,-0.28,0.016,-0.0033,0.96,0.028,0.03,0.79,0.097,-0.0033,0.042,-0.0012,-0.0058,7.6e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.021,0.023,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8.1e-05,0.0011,5.7e-05,0.0012,0.0011,0.00064,0.0012,1,1
|
||||
32390000,-0.28,0.016,-0.0034,0.96,0.024,0.032,0.79,0.093,0.00043,0.12,-0.0012,-0.0058,5.8e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.02,0.022,0.0051,0.27,0.28,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
32490000,-0.28,0.015,-0.0065,0.96,-0.015,0.085,-0.078,0.092,0.0081,0.12,-0.0012,-0.0058,3.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.048,0.022,0.024,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
32590000,-0.29,0.015,-0.0065,0.96,-0.013,0.084,-0.081,0.092,0.0012,0.1,-0.0012,-0.0058,-1.5e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.28,0.29,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
32690000,-0.29,0.015,-0.0065,0.96,-0.0087,0.091,-0.082,0.091,0.0099,0.087,-0.0012,-0.0058,-1.4e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.3e-05,3.7e-05,0.047,0.022,0.024,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
32790000,-0.29,0.015,-0.0063,0.96,-0.0048,0.09,-0.083,0.092,0.0024,0.072,-0.0012,-0.0058,-7e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.29,0.3,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
32890000,-0.29,0.015,-0.0063,0.96,-0.0052,0.096,-0.085,0.091,0.011,0.057,-0.0012,-0.0058,-2.5e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.033,-0.067,0,0,4.2e-05,3.7e-05,0.047,0.022,0.023,0.0051,0.3,0.31,0.03,2.7e-07,2.5e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
32990000,-0.29,0.015,-0.0062,0.96,-0.0014,0.091,-0.084,0.092,-0.0018,0.043,-0.0013,-0.0058,-1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.3,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33090000,-0.29,0.015,-0.0061,0.96,0.0025,0.097,-0.081,0.092,0.0074,0.036,-0.0013,-0.0058,-9.5e-06,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.022,0.023,0.0051,0.31,0.32,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33190000,-0.29,0.015,-0.0061,0.96,0.0066,0.093,-0.08,0.092,-0.0072,0.028,-0.0013,-0.0058,-2.9e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.31,0.31,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33290000,-0.29,0.015,-0.0061,0.96,0.011,0.096,-0.08,0.094,0.0015,0.02,-0.0013,-0.0058,-1.8e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.32,0.33,0.03,2.6e-07,2.4e-07,1.5e-06,0.0018,0.002,7.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33390000,-0.29,0.015,-0.006,0.96,0.015,0.092,-0.078,0.093,-0.0067,0.011,-0.0013,-0.0058,-2.5e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.0051,0.32,0.32,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33490000,-0.29,0.015,-0.006,0.96,0.021,0.097,-0.077,0.096,0.0027,0.0017,-0.0013,-0.0058,-2e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.2e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.33,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.9e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33590000,-0.29,0.014,-0.0058,0.96,0.024,0.094,-0.074,0.096,-0.01,-0.0062,-0.0013,-0.0058,-2.7e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.33,0.33,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33690000,-0.29,0.015,-0.0058,0.96,0.027,0.098,-0.075,0.097,-0.0013,-0.014,-0.0013,-0.0058,-2.1e-05,0.066,0.012,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.34,0.35,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33790000,-0.29,0.015,-0.0058,0.96,0.029,0.095,-0.069,0.093,-0.014,-0.021,-0.0013,-0.0058,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.34,0.34,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.8e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33890000,-0.29,0.014,-0.0057,0.96,0.034,0.097,-0.069,0.097,-0.0054,-0.028,-0.0013,-0.0058,-2.4e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.35,0.36,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
33990000,-0.29,0.015,-0.0056,0.96,0.036,0.095,-0.065,0.095,-0.014,-0.032,-0.0013,-0.0057,-3.5e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.35,0.35,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34090000,-0.29,0.015,-0.0056,0.96,0.039,0.1,-0.064,0.098,-0.0041,-0.036,-0.0013,-0.0057,-3.2e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.0051,0.36,0.37,0.03,2.6e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34190000,-0.29,0.015,-0.0055,0.96,0.041,0.097,-0.061,0.093,-0.016,-0.039,-0.0013,-0.0057,-3.7e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.36,0.36,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.7e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34290000,-0.29,0.015,-0.0054,0.96,0.042,0.1,-0.06,0.098,-0.0061,-0.045,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.023,0.005,0.37,0.37,0.03,2.5e-07,2.4e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00063,0.0012,1,1
|
||||
34390000,-0.29,0.015,-0.0053,0.96,0.043,0.097,-0.055,0.093,-0.018,-0.049,-0.0013,-0.0057,-3.8e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.084,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.02,0.022,0.005,0.37,0.37,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1
|
||||
34490000,-0.29,0.015,-0.0053,0.96,0.046,0.1,-0.053,0.097,-0.0082,-0.052,-0.0013,-0.0057,-3e-05,0.066,0.013,-0.12,-0.11,-0.024,0.5,0.085,-0.032,-0.067,0,0,4.1e-05,3.6e-05,0.047,0.021,0.022,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.6e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1
|
||||
34590000,-0.29,0.014,-0.0052,0.96,0.046,0.097,0.74,0.091,-0.022,-0.024,-0.0013,-0.0057,-4e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.38,0.38,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1
|
||||
34690000,-0.29,0.014,-0.0052,0.96,0.051,0.1,1.7,0.096,-0.012,0.095,-0.0013,-0.0057,-3.7e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.02,0.021,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1
|
||||
34790000,-0.29,0.014,-0.0052,0.96,0.052,0.098,2.7,0.09,-0.026,0.27,-0.0013,-0.0057,-4.7e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.39,0.39,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1
|
||||
34890000,-0.29,0.014,-0.0052,0.96,0.057,0.1,3.7,0.095,-0.016,0.56,-0.0013,-0.0057,-4.3e-05,0.066,0.014,-0.12,-0.11,-0.024,0.5,0.085,-0.031,-0.067,0,0,4.1e-05,3.6e-05,0.046,0.019,0.019,0.005,0.4,0.4,0.03,2.5e-07,2.3e-07,1.4e-06,0.0018,0.002,7.5e-05,0.0011,5.7e-05,0.0012,0.0011,0.00062,0.0012,1,1
|
||||
|
||||
|
@@ -117,12 +117,6 @@ void FlightModeManager::Run()
|
||||
|
||||
if (isAnyTaskActive()) {
|
||||
generateTrajectorySetpoint(dt, vehicle_local_position);
|
||||
|
||||
} else {
|
||||
// Publish empty constraints (constraints from previous flight tasks must be overridden)
|
||||
vehicle_constraints_s vehicle_constraints = FlightTask::empty_constraints;
|
||||
vehicle_constraints.timestamp = time_stamp_now;
|
||||
_vehicle_constraints_pub.publish(vehicle_constraints);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
+2
-2
@@ -50,8 +50,8 @@ bool FlightTaskManualAccelerationSlow::update()
|
||||
// Limits which can only slow down from the nominal configuration we initialize with here
|
||||
// This is ensured by the executing classes
|
||||
float velocity_horizontal = _param_mpc_vel_manual.get();
|
||||
float velocity_up = _param_mpc_z_v_man_up.get();
|
||||
float velocity_down = _param_mpc_z_v_man_dn.get();
|
||||
float velocity_up = _param_mpc_z_vel_max_up.get();
|
||||
float velocity_down = _param_mpc_z_vel_max_dn.get();
|
||||
float yaw_rate = math::radians(_param_mpc_man_y_max.get());
|
||||
|
||||
// MAVLink commanded limits
|
||||
|
||||
+2
@@ -81,6 +81,8 @@ private:
|
||||
(ParamFloat<px4::params::MC_SLOW_DEF_VVEL>) _param_mc_slow_def_vvel,
|
||||
(ParamFloat<px4::params::MC_SLOW_DEF_YAWR>) _param_mc_slow_def_yawr,
|
||||
(ParamFloat<px4::params::MPC_VEL_MANUAL>) _param_mpc_vel_manual,
|
||||
(ParamFloat<px4::params::MPC_Z_VEL_MAX_UP>) _param_mpc_z_vel_max_up,
|
||||
(ParamFloat<px4::params::MPC_Z_VEL_MAX_DN>) _param_mpc_z_vel_max_dn,
|
||||
(ParamFloat<px4::params::MPC_MAN_Y_MAX>) _param_mpc_man_y_max
|
||||
)
|
||||
};
|
||||
|
||||
@@ -72,15 +72,6 @@ bool FlightTaskManualAltitude::activate(const trajectory_setpoint_s &last_setpoi
|
||||
return ret;
|
||||
}
|
||||
|
||||
void FlightTaskManualAltitude::_setDefaultConstraints()
|
||||
{
|
||||
FlightTask::_setDefaultConstraints();
|
||||
|
||||
// Apply velocity limits for manual modes
|
||||
_constraints.speed_up = _param_mpc_z_v_man_up.get();
|
||||
_constraints.speed_down = _param_mpc_z_v_man_dn.get();
|
||||
}
|
||||
|
||||
void FlightTaskManualAltitude::_updateConstraintsFromEstimator()
|
||||
{
|
||||
if (PX4_ISFINITE(_sub_vehicle_local_position.get().hagl_min)) {
|
||||
@@ -101,8 +92,8 @@ void FlightTaskManualAltitude::_updateConstraintsFromEstimator()
|
||||
void FlightTaskManualAltitude::_scaleSticks()
|
||||
{
|
||||
// Use sticks input with deadzone and exponential curve for vertical velocity
|
||||
const float vel_max_up = fminf(_param_mpc_z_v_man_up.get(), _velocity_constraint_up);
|
||||
const float vel_max_down = fminf(_param_mpc_z_v_man_dn.get(), _velocity_constraint_down);
|
||||
const float vel_max_up = fminf(_param_mpc_z_vel_max_up.get(), _velocity_constraint_up);
|
||||
const float vel_max_down = fminf(_param_mpc_z_vel_max_dn.get(), _velocity_constraint_down);
|
||||
const float vel_max_z = (_sticks.getPosition()(2) > 0.0f) ? vel_max_down : vel_max_up;
|
||||
_velocity_setpoint(2) = vel_max_z * _sticks.getPositionExpo()(2);
|
||||
}
|
||||
@@ -243,10 +234,10 @@ void FlightTaskManualAltitude::_respectMaxAltitude()
|
||||
// TODO: manipulate the velocity setpoint instead of tweaking the saturation of the controller
|
||||
if (PX4_ISFINITE(_max_distance_to_ground)) {
|
||||
_constraints.speed_up = math::constrain(_param_mpc_z_p.get() * (_max_distance_to_ground - _dist_to_bottom),
|
||||
-_param_mpc_z_v_man_dn.get(), _param_mpc_z_v_man_up.get());
|
||||
-_param_mpc_z_vel_max_dn.get(), _param_mpc_z_vel_max_up.get());
|
||||
|
||||
} else {
|
||||
_constraints.speed_up = _param_mpc_z_v_man_up.get();
|
||||
_constraints.speed_up = _param_mpc_z_vel_max_up.get();
|
||||
}
|
||||
|
||||
// if distance to bottom exceeded maximum distance, slowly approach maximum distance
|
||||
@@ -256,10 +247,10 @@ void FlightTaskManualAltitude::_respectMaxAltitude()
|
||||
// set position setpoint to maximum distance to ground
|
||||
_position_setpoint(2) = _position(2) + delta_distance_to_max;
|
||||
// limit speed downwards to 0.7m/s
|
||||
_constraints.speed_down = math::min(_param_mpc_z_v_man_dn.get(), 0.7f);
|
||||
_constraints.speed_down = math::min(_param_mpc_z_vel_max_dn.get(), 0.7f);
|
||||
|
||||
} else {
|
||||
_constraints.speed_down = _param_mpc_z_v_man_dn.get();
|
||||
_constraints.speed_down = _param_mpc_z_vel_max_dn.get();
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -59,7 +59,6 @@ protected:
|
||||
virtual void _updateSetpoints(); /**< updates all setpoints */
|
||||
virtual void _scaleSticks(); /**< scales sticks to velocity in z */
|
||||
bool _checkTakeoff() override;
|
||||
void _setDefaultConstraints() override;
|
||||
void _updateConstraintsFromEstimator();
|
||||
|
||||
/**
|
||||
@@ -84,8 +83,6 @@ protected:
|
||||
(ParamInt<px4::params::MPC_ALT_MODE>) _param_mpc_alt_mode,
|
||||
(ParamFloat<px4::params::MPC_HOLD_MAX_XY>) _param_mpc_hold_max_xy,
|
||||
(ParamFloat<px4::params::MPC_Z_P>) _param_mpc_z_p, /**< position controller altitude propotional gain */
|
||||
(ParamFloat<px4::params::MPC_Z_V_MAN_UP>) _param_mpc_z_v_man_up, /**< maximum upwards velocity */
|
||||
(ParamFloat<px4::params::MPC_Z_V_MAN_DN>) _param_mpc_z_v_man_dn, /**< maximum downwards velocity */
|
||||
(ParamFloat<px4::params::MPC_LAND_ALT1>) _param_mpc_land_alt1, /**< altitude at which to start downwards slowdown */
|
||||
(ParamFloat<px4::params::MPC_LAND_ALT2>) _param_mpc_land_alt2, /**< altitude below which to land with land speed */
|
||||
(ParamFloat<px4::params::MPC_LAND_SPEED>)
|
||||
|
||||
@@ -1037,6 +1037,12 @@ void Logger::publish_logger_status()
|
||||
if (hrt_elapsed_time(&_logger_status_last) >= 1_s) {
|
||||
for (int i = 0; i < (int)LogType::Count; ++i) {
|
||||
|
||||
logger_status_s status = {};
|
||||
status.type = i;
|
||||
status.backend = _writer.backend();
|
||||
status.num_messages = _num_subscriptions;
|
||||
status.timestamp = hrt_absolute_time();
|
||||
|
||||
const LogType log_type = static_cast<LogType>(i);
|
||||
|
||||
if (_writer.is_started(log_type)) {
|
||||
@@ -1046,19 +1052,16 @@ void Logger::publish_logger_status()
|
||||
const float kb_written = _writer.get_total_written_file(log_type) / 1024.0f;
|
||||
const float seconds = hrt_elapsed_time(&_statistics[i].start_time_file) * 1e-6f;
|
||||
|
||||
logger_status_s status;
|
||||
status.type = i;
|
||||
status.backend = _writer.backend();
|
||||
status.is_logging = true;
|
||||
status.total_written_kb = kb_written;
|
||||
status.write_rate_kb_s = kb_written / seconds;
|
||||
status.dropouts = _statistics[i].write_dropouts;
|
||||
status.message_gaps = _message_gaps;
|
||||
status.buffer_used_bytes = buffer_fill_count_file;
|
||||
status.buffer_size_bytes = _writer.get_buffer_size_file(log_type);
|
||||
status.num_messages = _num_subscriptions;
|
||||
status.timestamp = hrt_absolute_time();
|
||||
_logger_status_pub[i].publish(status);
|
||||
}
|
||||
|
||||
_logger_status_pub[i].publish(status);
|
||||
}
|
||||
|
||||
_logger_status_last = hrt_absolute_time();
|
||||
|
||||
@@ -1963,10 +1963,6 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
break;
|
||||
#endif
|
||||
|
||||
// case 'e':
|
||||
// _mavlink_link_termination_allowed = true;
|
||||
// break;
|
||||
|
||||
case 'm': {
|
||||
|
||||
int mode;
|
||||
|
||||
@@ -597,8 +597,6 @@ private:
|
||||
*/
|
||||
unsigned int _mavlink_param_queue_index{0};
|
||||
|
||||
bool _mavlink_link_termination_allowed{false};
|
||||
|
||||
char *_subscribe_to_stream{nullptr};
|
||||
float _subscribe_to_stream_rate{0.0f}; ///< rate of stream to subscribe to (0=disable, -1=unlimited, -2=default)
|
||||
bool _udp_initialised{false};
|
||||
|
||||
@@ -151,6 +151,7 @@ private:
|
||||
fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_GPS, health_component_t::gps, msg);
|
||||
fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_RC_RECEIVER, health_component_t::remote_control, msg);
|
||||
fillOutComponent(health_report, MAV_SYS_STATUS_AHRS, health_component_t::local_position_estimate, msg);
|
||||
fillOutComponent(health_report, MAV_SYS_STATUS_LOGGING, health_component_t::logging, msg);
|
||||
fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_ABSOLUTE_PRESSURE, health_component_t::absolute_pressure, msg);
|
||||
fillOutComponent(health_report, MAV_SYS_STATUS_SENSOR_DIFFERENTIAL_PRESSURE, health_component_t::differential_pressure,
|
||||
msg);
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user