mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-06-10 17:10:06 +08:00
Compare commits
33 Commits
| Author | SHA1 | Date | |
|---|---|---|---|
| ac7e369418 | |||
| 740d2fccb1 | |||
| bcae7e550b | |||
| a242a0210e | |||
| c32cf21b63 | |||
| a7b909234b | |||
| 6f861ba889 | |||
| f9f466854b | |||
| 26c36a96f2 | |||
| bf98503dec | |||
| f771c7ff63 | |||
| 96a305322a | |||
| 1c5750b292 | |||
| c35ae7260b | |||
| 4e6c094a54 | |||
| 128e49358e | |||
| ed558e199f | |||
| c267cf71c3 | |||
| 67b2c835e0 | |||
| d8e483ae20 | |||
| 4afd19f037 | |||
| 96e7ea7a08 | |||
| f0a0a3e545 | |||
| 2f3ea88099 | |||
| 7786437a19 | |||
| 5030b21d2e | |||
| fb3adc3faa | |||
| b400b7fcc4 | |||
| 89bc28e836 | |||
| 2549054b28 | |||
| 7115d5643c | |||
| a7124d3738 | |||
| 487b84e90b |
+1
-1
@@ -410,7 +410,7 @@ if(BUILD_TESTING)
|
||||
include(gtest)
|
||||
|
||||
add_custom_target(test_results
|
||||
COMMAND GTEST_COLOR=1 ${CMAKE_CTEST_COMMAND} --output-on-failure -T Test -R ${TESTFILTER} USES_TERMINAL
|
||||
COMMAND GTEST_COLOR=1 ${CMAKE_CTEST_COMMAND} --output-on-failure -T Test -R \"${TESTFILTER}\" USES_TERMINAL
|
||||
DEPENDS
|
||||
px4
|
||||
examples__dyn_hello
|
||||
|
||||
@@ -386,6 +386,8 @@ tests_coverage:
|
||||
@mkdir -p coverage
|
||||
@lcov --directory build/px4_sitl_test --base-directory build/px4_sitl_test --gcov-tool gcov --capture -o coverage/lcov.info
|
||||
|
||||
test_unit:
|
||||
@$(MAKE) tests TESTFILTER="unit\|functional"
|
||||
|
||||
rostest: px4_sitl_default
|
||||
@$(MAKE) --no-print-directory px4_sitl_default sitl_gazebo
|
||||
@@ -550,21 +552,6 @@ check_px4: $(call make_list,nuttx,"px4") \
|
||||
check_nxp: $(call make_list,nuttx,"nxp") \
|
||||
sizes
|
||||
|
||||
ifneq ($(ROS2_WS_DIR),)
|
||||
ROS2_WS_DIR := $(basename ${ROS2_WS_DIR})
|
||||
else
|
||||
ROS2_WS_DIR := ~/colcon_ws
|
||||
endif
|
||||
|
||||
update_ros2_bridge:
|
||||
@Tools/update_px4_ros2_bridge.sh --ws_dir ${ROS2_WS_DIR} --all
|
||||
|
||||
update_px4_ros_com:
|
||||
@Tools/update_px4_ros2_bridge.sh --ws_dir ${ROS2_WS_DIR} --px4_ros_com
|
||||
|
||||
update_px4_msgs:
|
||||
@Tools/update_px4_ros2_bridge.sh --ws_dir ${ROS2_WS_DIR} --px4_msgs
|
||||
|
||||
.PHONY: failsafe_web run_failsafe_web_server
|
||||
failsafe_web:
|
||||
@if ! command -v emcc; then echo -e "Install emscripten first: https://emscripten.org/docs/getting_started/downloads.html\nAnd source the env: source <path>/emsdk_env.sh"; exit 1; fi
|
||||
|
||||
@@ -144,7 +144,6 @@ function(px4_add_common_flags)
|
||||
list(APPEND c_flags
|
||||
-fno-common
|
||||
|
||||
-Wbad-function-cast
|
||||
-Wnested-externs
|
||||
-Wstrict-prototypes
|
||||
)
|
||||
|
||||
+1
-1
@@ -1,4 +1,4 @@
|
||||
## Used to command an actuation in the gripper, which is mapped to a specific output in the mixer module
|
||||
## Used to command an actuation in the gripper, which is mapped to a specific output in the control allocation module
|
||||
|
||||
uint64 timestamp
|
||||
|
||||
|
||||
@@ -44,12 +44,7 @@
|
||||
#include <stdint.h>
|
||||
#include <unistd.h>
|
||||
#include <fcntl.h>
|
||||
|
||||
#if defined(__PX4_QURT)
|
||||
#include <dspal_types.h>
|
||||
#else
|
||||
#include <sys/types.h>
|
||||
#endif
|
||||
|
||||
#include "sem.h"
|
||||
|
||||
|
||||
@@ -43,7 +43,7 @@
|
||||
|
||||
#include <stdint.h>
|
||||
#include <queue.h>
|
||||
#include <px4_platform_types.h>
|
||||
#include <sys/types.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
|
||||
@@ -69,6 +69,8 @@ function(px4_os_add_flags)
|
||||
|
||||
add_compile_options($<$<COMPILE_LANGUAGE:CXX>:-fno-sized-deallocation>)
|
||||
|
||||
add_compile_options($<$<COMPILE_LANGUAGE:C>:-Wbad-function-cast>)
|
||||
|
||||
add_definitions(
|
||||
-D__PX4_NUTTX
|
||||
|
||||
|
||||
@@ -238,6 +238,8 @@ function(px4_os_add_flags)
|
||||
|
||||
endif()
|
||||
|
||||
add_compile_options($<$<COMPILE_LANGUAGE:C>:-Wbad-function-cast>)
|
||||
|
||||
endfunction()
|
||||
|
||||
#=============================================================================
|
||||
|
||||
@@ -1,3 +0,0 @@
|
||||
#ifdef __PX4_QURT
|
||||
#include <dspal_types.h>
|
||||
#endif
|
||||
@@ -0,0 +1,55 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2022 ModalAI, Inc. 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 <stdarg.h>
|
||||
#include <stdio.h>
|
||||
#include <stdint.h>
|
||||
|
||||
__BEGIN_DECLS
|
||||
|
||||
//Defining hap_debug
|
||||
void HAP_debug(const char *msg, int level, const char *filename, int line);
|
||||
|
||||
static __inline void qurt_log(int level, const char *file, int line,
|
||||
const char *format, ...)
|
||||
{
|
||||
char buf[256];
|
||||
va_list args;
|
||||
va_start(args, format);
|
||||
vsnprintf(buf, sizeof(buf), format, args);
|
||||
va_end(args);
|
||||
HAP_debug(buf, level, file, line);
|
||||
}
|
||||
|
||||
__END_DECLS
|
||||
@@ -25,6 +25,10 @@ param set IMU_GYRO_FFT_SNR 10
|
||||
#param set IMU_GYRO_DNF_EN 2
|
||||
param set IMU_GYRO_DNF_EN 3
|
||||
|
||||
param set IMU_GYRO_DNF_BW 15
|
||||
param set IMU_GYRO_DNF_HMC 3
|
||||
param set IMU_GYRO_DNF_MIN 25
|
||||
|
||||
# test values
|
||||
param set IMU_GYRO_CUTOFF 60
|
||||
param set IMU_DGYRO_CUTOFF 40
|
||||
|
||||
@@ -76,6 +76,7 @@ px4_add_module(
|
||||
SagetechMXS.cpp
|
||||
SagetechMXS.hpp
|
||||
DEPENDS
|
||||
adsb
|
||||
px4_work_queue
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
|
||||
@@ -39,168 +39,6 @@
|
||||
* @author Check Faber chuck.faber@sagetech.com
|
||||
*/
|
||||
|
||||
/**
|
||||
* ADSB-Out squawk code configuration
|
||||
*
|
||||
* This parameter defines the squawk code. Value should be between 0000 and 7777.
|
||||
*
|
||||
* @reboot_required false
|
||||
* @min 0
|
||||
* @max 7777
|
||||
* @group Transponder
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_SQUAWK, 1200);
|
||||
|
||||
/**
|
||||
* ADSB-Out Ident Configuration
|
||||
*
|
||||
* Enable Identification of Position feature
|
||||
*
|
||||
* @boolean
|
||||
* @reboot_required false
|
||||
* @group Transponder
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_IDENT, 0);
|
||||
|
||||
/**
|
||||
* ADSB-In Vehicle List Size
|
||||
*
|
||||
* Change number of targets to track
|
||||
*
|
||||
* @min 0
|
||||
* @max 50
|
||||
* @reboot_required true
|
||||
* @group Transponder
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_LIST_MAX, 25);
|
||||
|
||||
/**
|
||||
* ADSB-Out ICAO configuration
|
||||
*
|
||||
* Defines the ICAO ID of the vehicle
|
||||
*
|
||||
* @reboot_required true
|
||||
* @min -1
|
||||
* @max 16777215
|
||||
* @group Transponder
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_ICAO_ID, 1194684);
|
||||
|
||||
/**
|
||||
* ADSB-Out Vehicle Size Configuration
|
||||
*
|
||||
* Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size.
|
||||
*
|
||||
* @reboot_required true
|
||||
* @min 0
|
||||
* @max 15
|
||||
* @group Transponder
|
||||
*
|
||||
* @value 0 SizeUnknown
|
||||
* @value 1 Len15_Wid23
|
||||
* @value 2 Len25_Wid28
|
||||
* @value 3 Len25_Wid34
|
||||
* @value 4 Len35_Wid33
|
||||
* @value 5 Len35_Wid38
|
||||
* @value 6 Len45_Wid39
|
||||
* @value 7 Len45_Wid45
|
||||
* @value 8 Len55_Wid45
|
||||
* @value 9 Len55_Wid52
|
||||
* @value 10 Len65_Wid59
|
||||
* @value 11 Len65_Wid67
|
||||
* @value 12 Len75_Wid72
|
||||
* @value 13 Len75_Wid80
|
||||
* @value 14 Len85_Wid80
|
||||
* @value 15 Len85_Wid90
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_LEN_WIDTH, 1);
|
||||
|
||||
/**
|
||||
* ADSB-Out Vehicle Emitter Type
|
||||
*
|
||||
* Configure the emitter type of the vehicle.
|
||||
*
|
||||
* @reboot_required true
|
||||
* @min 0
|
||||
* @max 15
|
||||
* @group Transponder
|
||||
*
|
||||
* @value 0 Unknown
|
||||
* @value 1 Light
|
||||
* @value 2 Small
|
||||
* @value 3 Large
|
||||
* @value 4 HighVortex
|
||||
* @value 5 Heavy
|
||||
* @value 6 Performance
|
||||
* @value 7 Rotorcraft
|
||||
* @value 8 RESERVED
|
||||
* @value 9 Glider
|
||||
* @value 10 LightAir
|
||||
* @value 11 Parachute
|
||||
* @value 12 UltraLight
|
||||
* @value 13 RESERVED
|
||||
* @value 14 UAV
|
||||
* @value 15 Space
|
||||
* @value 16 RESERVED
|
||||
* @value 17 EmergencySurf
|
||||
* @value 18 ServiceSurf
|
||||
* @value 19 PointObstacle
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_EMIT_TYPE, 14);
|
||||
|
||||
/**
|
||||
* ADSB-Out Vehicle Max Speed
|
||||
*
|
||||
* Informs ADSB vehicles of this vehicle's max speed capability
|
||||
*
|
||||
* @reboot_required true
|
||||
* @min 0
|
||||
* @max 6
|
||||
* @value 0 UnknownMaxSpeed
|
||||
* @value 1 75Kts
|
||||
* @value 2 150Kts
|
||||
* @value 3 300Kts
|
||||
* @value 4 600Kts
|
||||
* @value 5 1200Kts
|
||||
* @value 6 Over1200Kts
|
||||
* @group Transponder
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_MAX_SPEED, 0);
|
||||
|
||||
/**
|
||||
* ADSB-In Special ICAO configuration
|
||||
*
|
||||
* This vehicle is always tracked. Use 0 to disable.
|
||||
*
|
||||
* @reboot_required false
|
||||
* @min 0
|
||||
* @max 16777215
|
||||
* @group Transponder
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_ICAO_SPECL, 0);
|
||||
|
||||
/**
|
||||
* ADSB-Out Emergency State
|
||||
*
|
||||
* Sets the vehicle emergency state
|
||||
*
|
||||
* @reboot_required false
|
||||
* @min 0
|
||||
* @max 6
|
||||
* @value 0 NoEmergency
|
||||
* @value 1 General
|
||||
* @value 2 Medical
|
||||
* @value 3 LowFuel
|
||||
* @value 4 NoCommunications
|
||||
* @value 5 Interference
|
||||
* @value 6 Downed
|
||||
* @group Transponder
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_EMERGC, 0);
|
||||
|
||||
/**
|
||||
* Sagetech MXS mode configuration
|
||||
*
|
||||
|
||||
@@ -31,6 +31,7 @@
|
||||
#
|
||||
############################################################################
|
||||
|
||||
add_subdirectory(adsb)
|
||||
add_subdirectory(airspeed)
|
||||
add_subdirectory(avoidance)
|
||||
add_subdirectory(battery)
|
||||
|
||||
@@ -0,0 +1,34 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2022 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
# are met:
|
||||
#
|
||||
# 1. Redistributions of source code must retain the above copyright
|
||||
# notice, this list of conditions and the following disclaimer.
|
||||
# 2. Redistributions in binary form must reproduce the above copyright
|
||||
# notice, this list of conditions and the following disclaimer in
|
||||
# the documentation and/or other materials provided with the
|
||||
# distribution.
|
||||
# 3. Neither the name PX4 nor the names of its contributors may be
|
||||
# used to endorse or promote products derived from this software
|
||||
# without specific prior written permission.
|
||||
#
|
||||
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
# POSSIBILITY OF SUCH DAMAGE.
|
||||
#
|
||||
############################################################################
|
||||
|
||||
px4_add_library(adsb adsb.cpp)
|
||||
@@ -0,0 +1,32 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
@@ -0,0 +1,228 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* ADSB-Out squawk code configuration
|
||||
*
|
||||
* This parameter defines the squawk code. Value should be between 0000 and 7777.
|
||||
*
|
||||
* @reboot_required false
|
||||
* @min 0
|
||||
* @max 7777
|
||||
* @group ADSB
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_SQUAWK, 1200);
|
||||
|
||||
/**
|
||||
* ADSB-Out Ident Configuration
|
||||
*
|
||||
* Enable Identification of Position feature
|
||||
*
|
||||
* @boolean
|
||||
* @reboot_required false
|
||||
* @group ADSB
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_IDENT, 0);
|
||||
|
||||
/**
|
||||
* ADSB-In Vehicle List Size
|
||||
*
|
||||
* Change number of targets to track
|
||||
*
|
||||
* @min 0
|
||||
* @max 50
|
||||
* @reboot_required true
|
||||
* @group ADSB
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_LIST_MAX, 25);
|
||||
|
||||
/**
|
||||
* ADSB-Out ICAO configuration
|
||||
*
|
||||
* Defines the ICAO ID of the vehicle
|
||||
*
|
||||
* @reboot_required true
|
||||
* @min -1
|
||||
* @max 16777215
|
||||
* @group ADSB
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_ICAO_ID, 1194684);
|
||||
|
||||
/**
|
||||
* ADSB-Out Vehicle Size Configuration
|
||||
*
|
||||
* Report the length and width of the vehicle in meters. In most cases, use '1' for the smallest vehicle size.
|
||||
*
|
||||
* @reboot_required true
|
||||
* @min 0
|
||||
* @max 15
|
||||
* @group ADSB
|
||||
*
|
||||
* @value 0 SizeUnknown
|
||||
* @value 1 Len15_Wid23
|
||||
* @value 2 Len25_Wid28
|
||||
* @value 3 Len25_Wid34
|
||||
* @value 4 Len35_Wid33
|
||||
* @value 5 Len35_Wid38
|
||||
* @value 6 Len45_Wid39
|
||||
* @value 7 Len45_Wid45
|
||||
* @value 8 Len55_Wid45
|
||||
* @value 9 Len55_Wid52
|
||||
* @value 10 Len65_Wid59
|
||||
* @value 11 Len65_Wid67
|
||||
* @value 12 Len75_Wid72
|
||||
* @value 13 Len75_Wid80
|
||||
* @value 14 Len85_Wid80
|
||||
* @value 15 Len85_Wid90
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_LEN_WIDTH, 1);
|
||||
|
||||
/**
|
||||
* ADSB-Out Vehicle Emitter Type
|
||||
*
|
||||
* Configure the emitter type of the vehicle.
|
||||
*
|
||||
* @reboot_required true
|
||||
* @min 0
|
||||
* @max 15
|
||||
* @group ADSB
|
||||
*
|
||||
* @value 0 Unknown
|
||||
* @value 1 Light
|
||||
* @value 2 Small
|
||||
* @value 3 Large
|
||||
* @value 4 HighVortex
|
||||
* @value 5 Heavy
|
||||
* @value 6 Performance
|
||||
* @value 7 Rotorcraft
|
||||
* @value 8 RESERVED
|
||||
* @value 9 Glider
|
||||
* @value 10 LightAir
|
||||
* @value 11 Parachute
|
||||
* @value 12 UltraLight
|
||||
* @value 13 RESERVED
|
||||
* @value 14 UAV
|
||||
* @value 15 Space
|
||||
* @value 16 RESERVED
|
||||
* @value 17 EmergencySurf
|
||||
* @value 18 ServiceSurf
|
||||
* @value 19 PointObstacle
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_EMIT_TYPE, 14);
|
||||
|
||||
/**
|
||||
* ADSB-Out Vehicle Max Speed
|
||||
*
|
||||
* Informs ADSB vehicles of this vehicle's max speed capability
|
||||
*
|
||||
* @reboot_required true
|
||||
* @min 0
|
||||
* @max 6
|
||||
* @value 0 UnknownMaxSpeed
|
||||
* @value 1 75Kts
|
||||
* @value 2 150Kts
|
||||
* @value 3 300Kts
|
||||
* @value 4 600Kts
|
||||
* @value 5 1200Kts
|
||||
* @value 6 Over1200Kts
|
||||
* @group ADSB
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_MAX_SPEED, 0);
|
||||
|
||||
/**
|
||||
* ADSB-In Special ICAO configuration
|
||||
*
|
||||
* This vehicle is always tracked. Use 0 to disable.
|
||||
*
|
||||
* @reboot_required false
|
||||
* @min 0
|
||||
* @max 16777215
|
||||
* @group ADSB
|
||||
*
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_ICAO_SPECL, 0);
|
||||
|
||||
/**
|
||||
* ADSB-Out Emergency State
|
||||
*
|
||||
* Sets the vehicle emergency state
|
||||
*
|
||||
* @reboot_required false
|
||||
* @min 0
|
||||
* @max 6
|
||||
* @value 0 NoEmergency
|
||||
* @value 1 General
|
||||
* @value 2 Medical
|
||||
* @value 3 LowFuel
|
||||
* @value 4 NoCommunications
|
||||
* @value 5 Interference
|
||||
* @value 6 Downed
|
||||
* @group ADSB
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_EMERGC, 0);
|
||||
|
||||
/**
|
||||
* ADSB-Out GPS Offset lat
|
||||
*
|
||||
* Sets GPS lataral offset encoding
|
||||
*
|
||||
* @reboot_required false
|
||||
* @min 0
|
||||
* @max 7
|
||||
* @value 0 NoData
|
||||
* @value 1 LatLeft2M
|
||||
* @value 2 LatLeft4M
|
||||
* @value 3 LatLeft6M
|
||||
* @value 4 LatRight0M
|
||||
* @value 5 LatRight2M
|
||||
* @value 6 LatRight4M
|
||||
* @value 7 LatRight6M
|
||||
* @group ADSB
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_GPS_OFF_LAT, 0);
|
||||
|
||||
/**
|
||||
* ADSB-Out GPS Offset lon
|
||||
*
|
||||
* Sets GPS longitudinal offset encoding
|
||||
*
|
||||
* @reboot_required false
|
||||
* @min 0
|
||||
* @max 1
|
||||
* @value 0 NoData
|
||||
* @value 1 AppliedBySensor
|
||||
* @group ADSB
|
||||
*/
|
||||
PARAM_DEFINE_INT32(ADSB_GPS_OFF_LON, 0);
|
||||
@@ -104,7 +104,7 @@ void TECS::_update_speed_states(float equivalent_airspeed_setpoint, float equiva
|
||||
const float dt = constrain((now - _speed_update_timestamp) * 1.0e-6f, DT_MIN, DT_MAX);
|
||||
|
||||
// Convert equivalent airspeed quantities to true airspeed
|
||||
_EAS_setpoint = equivalent_airspeed_setpoint;
|
||||
_EAS_setpoint = PX4_ISFINITE(equivalent_airspeed_setpoint) ? equivalent_airspeed_setpoint : _equivalent_airspeed_trim;
|
||||
_TAS_setpoint = _EAS_setpoint * EAS2TAS;
|
||||
_TAS_max = _equivalent_airspeed_max * EAS2TAS;
|
||||
_TAS_min = _equivalent_airspeed_min * EAS2TAS;
|
||||
|
||||
@@ -37,6 +37,7 @@
|
||||
*/
|
||||
|
||||
#include "WindEstimator.hpp"
|
||||
#include "python/generated/init_wind_using_airspeed.h"
|
||||
|
||||
bool
|
||||
WindEstimator::initialise(const matrix::Vector3f &velI, const float hor_vel_variance, const float heading_rad,
|
||||
@@ -44,34 +45,19 @@ WindEstimator::initialise(const matrix::Vector3f &velI, const float hor_vel_vari
|
||||
{
|
||||
if (PX4_ISFINITE(tas_meas) && PX4_ISFINITE(tas_variance)) {
|
||||
|
||||
const float cos_heading = cosf(heading_rad);
|
||||
const float sin_heading = sinf(heading_rad);
|
||||
constexpr float initial_heading_var = sq(math::radians(INITIAL_HEADING_ERROR_DEG));
|
||||
constexpr float initial_sideslip_var = sq(math::radians(INITIAL_BETA_ERROR_DEG));
|
||||
|
||||
// initialise wind states assuming zero side slip and horizontal flight
|
||||
_state(INDEX_W_N) = velI(0) - tas_meas * cos_heading;
|
||||
_state(INDEX_W_E) = velI(1) - tas_meas * sin_heading;
|
||||
matrix::SquareMatrix<float, 2> P_wind_init;
|
||||
matrix::Vector2f wind_init;
|
||||
|
||||
sym::InitWindUsingAirspeed(velI, heading_rad, tas_meas, hor_vel_variance, initial_heading_var, initial_sideslip_var,
|
||||
tas_variance,
|
||||
&wind_init, &P_wind_init);
|
||||
|
||||
_state.xy() = wind_init;
|
||||
_state(INDEX_TAS_SCALE) = _scale_init;
|
||||
|
||||
constexpr float initial_sideslip_uncertainty = math::radians(INITIAL_BETA_ERROR_DEG);
|
||||
const float initial_wind_var_body_y = sq(tas_meas * sinf(initial_sideslip_uncertainty));
|
||||
constexpr float heading_variance = sq(math::radians(INITIAL_HEADING_ERROR_DEG));
|
||||
|
||||
// rotate wind velocity into earth frame aligned with vehicle yaw
|
||||
const float Wx = _state(INDEX_W_N) * cos_heading + _state(INDEX_W_E) * sin_heading;
|
||||
const float Wy = -_state(INDEX_W_N) * sin_heading + _state(INDEX_W_E) * cos_heading;
|
||||
|
||||
_P(INDEX_W_N, INDEX_W_N) = tas_variance * sq(cos_heading) + heading_variance * sq(-Wx * sin_heading - Wy * cos_heading)
|
||||
+ initial_wind_var_body_y * sq(sin_heading);
|
||||
_P(INDEX_W_N, INDEX_W_E) = tas_variance * sin_heading * cos_heading + heading_variance *
|
||||
(-Wx * sin_heading - Wy * cos_heading) * (Wx * cos_heading - Wy * sin_heading) -
|
||||
initial_wind_var_body_y * sin_heading * cos_heading;
|
||||
_P(INDEX_W_E, INDEX_W_N) = _P(INDEX_W_N, INDEX_W_E);
|
||||
_P(INDEX_W_E, INDEX_W_E) = tas_variance * sq(sin_heading) + heading_variance * sq(Wx * cos_heading - Wy * sin_heading) +
|
||||
initial_wind_var_body_y * sq(cos_heading);
|
||||
|
||||
// Now add the variance due to uncertainty in vehicle velocity that was used to calculate the initial wind speed
|
||||
_P(INDEX_W_N, INDEX_W_N) += hor_vel_variance;
|
||||
_P(INDEX_W_E, INDEX_W_E) += hor_vel_variance;
|
||||
_P.slice<2, 2>(0, 0) = P_wind_init;
|
||||
|
||||
} else {
|
||||
// no airspeed available
|
||||
@@ -81,10 +67,6 @@ WindEstimator::initialise(const matrix::Vector3f &velI, const float hor_vel_vari
|
||||
_P(INDEX_W_N, INDEX_W_N) = _P(INDEX_W_E, INDEX_W_E) = sq(INITIAL_WIND_ERROR);
|
||||
}
|
||||
|
||||
// reset the timestamp for measurement rejection
|
||||
_time_rejected_tas = 0;
|
||||
_time_rejected_beta = 0;
|
||||
|
||||
_wind_estimator_reset = true;
|
||||
|
||||
return true;
|
||||
@@ -143,20 +125,14 @@ WindEstimator::fuse_airspeed(uint64_t time_now, const float true_airspeed, const
|
||||
sym::FuseAirspeed(velI, _state, _P, true_airspeed, _tas_var, FLT_EPSILON,
|
||||
&H_tas, &K, &_tas_innov_var, &_tas_innov);
|
||||
|
||||
bool reinit_filter = false;
|
||||
bool meas_is_rejected = false;
|
||||
const bool meas_is_rejected = check_if_meas_is_rejected(_tas_innov, _tas_innov_var, _tas_gate);
|
||||
|
||||
// note: _time_rejected_tas and reinit_filter are not used anymore as filter can't get reset due to tas rejection
|
||||
meas_is_rejected = check_if_meas_is_rejected(time_now, _tas_innov, _tas_innov_var, _tas_gate, _time_rejected_tas,
|
||||
reinit_filter);
|
||||
if (_tas_innov_var < 0.0f) {
|
||||
// re init filter in case of a negative variance, and trigger early return to not fuse measurement
|
||||
_initialised = initialise(velI, hor_vel_variance, matrix::Eulerf(q_att).psi(), true_airspeed, _tas_var);
|
||||
return;
|
||||
|
||||
if (meas_is_rejected || _tas_innov_var < 0.f) {
|
||||
// only reset filter if _tas_innov_var gets unfeasible
|
||||
if (_tas_innov_var < 0.0f) {
|
||||
_initialised = initialise(velI, hor_vel_variance, matrix::Eulerf(q_att).psi(), true_airspeed, _tas_var);
|
||||
}
|
||||
|
||||
// we either did a filter reset or the current measurement was rejected so do not fuse
|
||||
} else if (meas_is_rejected) {
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -187,71 +163,21 @@ WindEstimator::fuse_beta(uint64_t time_now, const matrix::Vector3f &velI, const
|
||||
|
||||
_time_last_beta_fuse = time_now;
|
||||
|
||||
const float v_n = velI(0);
|
||||
const float v_e = velI(1);
|
||||
const float v_d = velI(2);
|
||||
|
||||
// compute sideslip observation vector
|
||||
float HB0 = 2.0f * q_att(0);
|
||||
float HB1 = HB0 * q_att(3);
|
||||
float HB2 = 2.0f * q_att(1);
|
||||
float HB3 = HB2 * q_att(2);
|
||||
float HB4 = v_e - _state(INDEX_W_E);
|
||||
float HB5 = HB1 + HB3;
|
||||
float HB6 = v_n - _state(INDEX_W_N);
|
||||
float HB7 = q_att(0) * q_att(0);
|
||||
float HB8 = q_att(3) * q_att(3);
|
||||
float HB9 = HB7 - HB8;
|
||||
float HB10 = q_att(1) * q_att(1);
|
||||
float HB11 = q_att(2) * q_att(2);
|
||||
float HB12 = HB10 - HB11;
|
||||
float HB13 = HB12 + HB9;
|
||||
float HB14 = HB13 * HB6 + HB4 * HB5 + v_d * (-HB0 * q_att(2) + HB2 * q_att(3));
|
||||
float HB15 = 1.0f / HB14;
|
||||
float HB16 = (HB4 * (-HB10 + HB11 + HB9) + HB6 * (-HB1 + HB3) + v_d * (HB0 * q_att(1) + 2.0f * q_att(2) * q_att(3))) /
|
||||
(HB14 * HB14);
|
||||
|
||||
matrix::Matrix<float, 1, 3> H_beta;
|
||||
H_beta(0, 0) = HB13 * HB16 + HB15 * (HB1 - HB3);
|
||||
H_beta(0, 1) = HB15 * (HB12 - HB7 + HB8) + HB16 * HB5;
|
||||
H_beta(0, 2) = 0;
|
||||
matrix::Matrix<float, 3, 1> K;
|
||||
|
||||
// compute innovation covariance S
|
||||
const matrix::Matrix<float, 1, 1> S = H_beta * _P * H_beta.transpose() + _beta_var;
|
||||
sym::FuseBeta(velI, _state, _P, q_att, _beta_var, FLT_EPSILON,
|
||||
&H_beta, &K, &_beta_innov_var, &_beta_innov);
|
||||
|
||||
// compute Kalman gain
|
||||
matrix::Matrix<float, 3, 1> K = _P * H_beta.transpose();
|
||||
K /= S(0, 0);
|
||||
const bool meas_is_rejected = check_if_meas_is_rejected(_beta_innov, _beta_innov_var, _beta_gate);
|
||||
|
||||
// compute predicted side slip angle
|
||||
matrix::Vector3f rel_wind(velI(0) - _state(INDEX_W_N), velI(1) - _state(INDEX_W_E), velI(2));
|
||||
matrix::Dcmf R_body_to_earth(q_att);
|
||||
rel_wind = R_body_to_earth.transpose() * rel_wind;
|
||||
|
||||
if (fabsf(rel_wind(0)) < 0.1f) {
|
||||
if (_beta_innov_var < 0.0f) {
|
||||
// re init filter in case of a negative variance, and trigger early return to not fuse measurement
|
||||
_initialised = initialise(velI, hor_vel_variance, matrix::Eulerf(q_att).psi());
|
||||
return;
|
||||
}
|
||||
|
||||
// use small angle approximation, sin(x) = x for small x
|
||||
const float beta_pred = rel_wind(1) / rel_wind(0);
|
||||
|
||||
_beta_innov = 0.0f - beta_pred;
|
||||
_beta_innov_var = S(0, 0);
|
||||
|
||||
bool reinit_filter = false;
|
||||
bool meas_is_rejected = false;
|
||||
|
||||
meas_is_rejected = check_if_meas_is_rejected(time_now, _beta_innov, _beta_innov_var, _beta_gate, _time_rejected_beta,
|
||||
reinit_filter);
|
||||
|
||||
reinit_filter |= _beta_innov_var < 0.0f;
|
||||
|
||||
if (meas_is_rejected || reinit_filter) {
|
||||
if (reinit_filter) {
|
||||
_initialised = initialise(velI, hor_vel_variance, matrix::Eulerf(q_att).psi());
|
||||
}
|
||||
|
||||
// we either did a filter reset or the current measurement was rejected so do not fuse
|
||||
} else if (meas_is_rejected) {
|
||||
return;
|
||||
}
|
||||
|
||||
@@ -301,17 +227,7 @@ WindEstimator::run_sanity_checks()
|
||||
}
|
||||
|
||||
bool
|
||||
WindEstimator::check_if_meas_is_rejected(uint64_t time_now, float innov, float innov_var, uint8_t gate_size,
|
||||
uint64_t &time_meas_rejected, bool &reinit_filter)
|
||||
WindEstimator::check_if_meas_is_rejected(float innov, float innov_var, uint8_t gate_size)
|
||||
{
|
||||
if (innov * innov > gate_size * gate_size * innov_var) {
|
||||
time_meas_rejected = time_meas_rejected == 0 ? time_now : time_meas_rejected;
|
||||
|
||||
} else {
|
||||
time_meas_rejected = 0;
|
||||
}
|
||||
|
||||
reinit_filter = time_now - time_meas_rejected > 5_s && time_meas_rejected != 0;
|
||||
|
||||
return time_meas_rejected != 0;
|
||||
return (innov * innov > gate_size * gate_size * innov_var);
|
||||
}
|
||||
|
||||
@@ -44,6 +44,8 @@
|
||||
#include <matrix/math.hpp>
|
||||
|
||||
#include "python/generated/fuse_airspeed.h"
|
||||
#include "python/generated/fuse_beta.h"
|
||||
#include "python/generated/init_wind_using_airspeed.h"
|
||||
|
||||
using namespace time_literals;
|
||||
|
||||
@@ -68,8 +70,7 @@ public:
|
||||
|
||||
bool is_estimate_valid() { return _initialised; }
|
||||
|
||||
bool check_if_meas_is_rejected(uint64_t time_now, float innov, float innov_var, uint8_t gate_size,
|
||||
uint64_t &time_meas_rejected, bool &reinit_filter);
|
||||
bool check_if_meas_is_rejected(float innov, float innov_var, uint8_t gate_size);
|
||||
|
||||
matrix::Vector2f get_wind() { return matrix::Vector2f{_state(INDEX_W_N), _state(INDEX_W_E)}; }
|
||||
|
||||
@@ -130,9 +131,6 @@ private:
|
||||
uint64_t _time_last_airspeed_fuse = 0; ///< timestamp of last airspeed fusion
|
||||
uint64_t _time_last_beta_fuse = 0; ///< timestamp of last sideslip fusion
|
||||
uint64_t _time_last_update = 0; ///< timestamp of last covariance prediction
|
||||
uint64_t _time_rejected_beta = 0; ///< timestamp of when sideslip measurements have consistently started to be rejected
|
||||
uint64_t _time_rejected_tas =
|
||||
0; ///< timestamp of when true airspeed measurements have consistently started to be rejected
|
||||
|
||||
bool _wind_estimator_reset = false; ///< wind estimator was reset in this cycle
|
||||
|
||||
|
||||
@@ -1,7 +1,43 @@
|
||||
import os
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Copyright (c) 2022 PX4 Development Team
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions
|
||||
are met:
|
||||
|
||||
1. Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
2. Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in
|
||||
the documentation and/or other materials provided with the
|
||||
distribution.
|
||||
3. Neither the name PX4 nor the names of its contributors may be
|
||||
used to endorse or promote products derived from this software
|
||||
without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
File: derivation.py
|
||||
Description:
|
||||
Derivation of a wind and airspeed scale (EKF) estimator using SymForce
|
||||
"""
|
||||
|
||||
from symforce import symbolic as sm
|
||||
from symforce import geo
|
||||
from symforce import typing as T
|
||||
from derivation_utils import *
|
||||
|
||||
def fuse_airspeed(
|
||||
v_local: geo.V3,
|
||||
@@ -18,42 +54,65 @@ def fuse_airspeed(
|
||||
innov = airspeed - airspeed_pred
|
||||
|
||||
H = geo.V1(airspeed_pred).jacobian(state)
|
||||
innov_var = (H * P * H.transpose() + R)[0,0]
|
||||
innov_var = (H * P * H.T + R)[0,0]
|
||||
|
||||
K = P * H.transpose() / sm.Max(innov_var, epsilon)
|
||||
K = P * H.T / sm.Max(innov_var, epsilon)
|
||||
|
||||
return (geo.V3(H), K, innov_var, innov)
|
||||
|
||||
from symforce.codegen import Codegen, CppConfig
|
||||
def fuse_beta(
|
||||
v_local: geo.V3,
|
||||
state: geo.V3,
|
||||
P: geo.M33,
|
||||
q_att: geo.V4,
|
||||
R: T.Scalar,
|
||||
epsilon: T.Scalar
|
||||
) -> (geo.V3, geo.V3, T.Scalar, T.Scalar):
|
||||
|
||||
codegen = Codegen.function(
|
||||
fuse_airspeed,
|
||||
output_names=["H", "K", "innov_var", "innov"],
|
||||
config=CppConfig())
|
||||
metadata = codegen.generate_function(
|
||||
output_dir="generated",
|
||||
skip_directory_nesting=True)
|
||||
vel_rel = geo.V3(v_local[0] - state[0], v_local[1] - state[1], v_local[2])
|
||||
relative_wind_body = quat_to_rot(q_att).T * vel_rel
|
||||
|
||||
print("Files generated in {}:\n".format(metadata.output_dir))
|
||||
for f in metadata.generated_files:
|
||||
print(" |- {}".format(os.path.relpath(f, metadata.output_dir)))
|
||||
# Small angle approximation of side slip model
|
||||
# Protect division by zero using epsilon
|
||||
beta_pred = add_epsilon_sign(relative_wind_body[1] / relative_wind_body[0], relative_wind_body[0], epsilon)
|
||||
|
||||
# Replace cstdlib and Eigen functions by PX4 equivalents
|
||||
import fileinput
|
||||
innov = 0.0 - beta_pred
|
||||
|
||||
with fileinput.FileInput(os.path.abspath(metadata.generated_files[0]), inplace=True, backup='.bak') as file:
|
||||
for line in file:
|
||||
line = line.replace("std::max", "math::max")
|
||||
line = line.replace("Eigen", "matrix")
|
||||
line = line.replace("matrix/Dense", "matrix/math.hpp")
|
||||
print(line, end='')
|
||||
H = geo.V1(beta_pred).jacobian(state)
|
||||
innov_var = (H * P * H.T + R)[0,0]
|
||||
|
||||
# Generate python code
|
||||
codegen = Codegen.function(
|
||||
fuse_airspeed,
|
||||
output_names=["H", "K", "innov_var", "innov"],
|
||||
config=PythonConfig())
|
||||
K = P * H.T / sm.Max(innov_var, epsilon)
|
||||
|
||||
metadata = codegen.generate_function(
|
||||
output_dir="generated",
|
||||
skip_directory_nesting=True)
|
||||
return (geo.V3(H), K, innov_var, innov)
|
||||
|
||||
def init_wind_using_airspeed(
|
||||
v_local: geo.V3,
|
||||
heading: T.Scalar,
|
||||
airspeed: T.Scalar,
|
||||
v_var: T.Scalar,
|
||||
heading_var: T.Scalar,
|
||||
sideslip_var: T.Scalar,
|
||||
airspeed_var: T.Scalar,
|
||||
) -> (geo.V2, geo.M22):
|
||||
|
||||
# Initialise wind states assuming zero side slip and horizontal flight
|
||||
wind = geo.V2(v_local[0] - airspeed * sm.cos(heading), v_local[1] - airspeed * sm.sin(heading))
|
||||
# Zero sideslip, propagate the sideslip variance using partial derivatives w.r.t heading
|
||||
J = wind.jacobian([v_local[0], v_local[1], heading, heading, airspeed])
|
||||
|
||||
R = geo.M55()
|
||||
R[0,0] = v_var
|
||||
R[1,1] = v_var
|
||||
R[2,2] = heading_var
|
||||
R[3,3] = sideslip_var
|
||||
R[4,4] = airspeed_var
|
||||
|
||||
P = J * R * J.T
|
||||
|
||||
return (wind, P)
|
||||
|
||||
generate_px4_function(fuse_airspeed, output_names=["H", "K", "innov_var", "innov"])
|
||||
generate_px4_function(fuse_beta, output_names=["H", "K", "innov_var", "innov"])
|
||||
generate_px4_function(init_wind_using_airspeed, output_names=["wind", "P"])
|
||||
|
||||
generate_python_function(fuse_airspeed, output_names=["H", "K", "innov_var", "innov"])
|
||||
|
||||
@@ -0,0 +1,101 @@
|
||||
#!/usr/bin/env python
|
||||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Copyright (c) 2022 PX4 Development Team
|
||||
Redistribution and use in source and binary forms, with or without
|
||||
modification, are permitted provided that the following conditions
|
||||
are met:
|
||||
|
||||
1. Redistributions of source code must retain the above copyright
|
||||
notice, this list of conditions and the following disclaimer.
|
||||
2. Redistributions in binary form must reproduce the above copyright
|
||||
notice, this list of conditions and the following disclaimer in
|
||||
the documentation and/or other materials provided with the
|
||||
distribution.
|
||||
3. Neither the name PX4 nor the names of its contributors may be
|
||||
used to endorse or promote products derived from this software
|
||||
without specific prior written permission.
|
||||
|
||||
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
"AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
File: derivation_utils.py
|
||||
Description:
|
||||
Common functions used for the derivation of most estimators
|
||||
"""
|
||||
|
||||
from symforce import symbolic as sm
|
||||
from symforce import geo
|
||||
from symforce import typing as T
|
||||
|
||||
# q: quaternion describing rotation from frame 1 to frame 2
|
||||
# returns a rotation matrix derived form q which describes the same
|
||||
# rotation
|
||||
def quat_to_rot(q):
|
||||
q0 = q[0]
|
||||
q1 = q[1]
|
||||
q2 = q[2]
|
||||
q3 = q[3]
|
||||
|
||||
Rot = geo.M33([[q0**2 + q1**2 - q2**2 - q3**2, 2*(q1*q2 - q0*q3), 2*(q1*q3 + q0*q2)],
|
||||
[2*(q1*q2 + q0*q3), q0**2 - q1**2 + q2**2 - q3**2, 2*(q2*q3 - q0*q1)],
|
||||
[2*(q1*q3-q0*q2), 2*(q2*q3 + q0*q1), q0**2 - q1**2 - q2**2 + q3**2]])
|
||||
|
||||
return Rot
|
||||
|
||||
def sign_no_zero(x) -> T.Scalar:
|
||||
"""
|
||||
Returns -1 if x is negative, 1 if x is positive, and 1 if x is zero
|
||||
"""
|
||||
return 2 * sm.Min(sm.sign(x), 0) + 1
|
||||
|
||||
def add_epsilon_sign(expr, var, eps):
|
||||
# Avoids a singularity at 0 while keeping the derivative correct
|
||||
return expr.subs(var, var + eps * sign_no_zero(var))
|
||||
|
||||
def generate_px4_function(function_name, output_names):
|
||||
from symforce.codegen import Codegen, CppConfig
|
||||
import os
|
||||
import fileinput
|
||||
|
||||
codegen = Codegen.function(
|
||||
function_name,
|
||||
output_names=output_names,
|
||||
config=CppConfig())
|
||||
metadata = codegen.generate_function(
|
||||
output_dir="generated",
|
||||
skip_directory_nesting=True)
|
||||
|
||||
print("Files generated in {}:\n".format(metadata.output_dir))
|
||||
for f in metadata.generated_files:
|
||||
print(" |- {}".format(os.path.relpath(f, metadata.output_dir)))
|
||||
|
||||
# Replace cstdlib and Eigen functions by PX4 equivalents
|
||||
with fileinput.FileInput(os.path.abspath(metadata.generated_files[0]), inplace=True, backup='.bak') as file:
|
||||
for line in file:
|
||||
line = line.replace("std::max", "math::max")
|
||||
line = line.replace("std::min", "math::min")
|
||||
line = line.replace("Eigen", "matrix")
|
||||
line = line.replace("matrix/Dense", "matrix/math.hpp")
|
||||
print(line, end='')
|
||||
|
||||
def generate_python_function(function_name, output_names):
|
||||
from symforce.codegen import Codegen, PythonConfig
|
||||
codegen = Codegen.function(
|
||||
function_name,
|
||||
output_names=output_names,
|
||||
config=PythonConfig())
|
||||
|
||||
metadata = codegen.generate_function(
|
||||
output_dir="generated",
|
||||
skip_directory_nesting=True)
|
||||
@@ -0,0 +1,102 @@
|
||||
// -----------------------------------------------------------------------------
|
||||
// This file was autogenerated by symforce from template:
|
||||
// backends/cpp/templates/function/FUNCTION.h.jinja
|
||||
// Do NOT modify by hand.
|
||||
// -----------------------------------------------------------------------------
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <matrix/math.hpp>
|
||||
|
||||
namespace sym {
|
||||
|
||||
/**
|
||||
* This function was autogenerated from a symbolic function. Do not modify by hand.
|
||||
*
|
||||
* Symbolic function: fuse_beta
|
||||
*
|
||||
* Args:
|
||||
* v_local: Matrix31
|
||||
* state: Matrix31
|
||||
* P: Matrix33
|
||||
* q_att: Matrix41
|
||||
* R: Scalar
|
||||
* epsilon: Scalar
|
||||
*
|
||||
* Outputs:
|
||||
* H: Matrix13
|
||||
* K: Matrix31
|
||||
* innov_var: Scalar
|
||||
* innov: Scalar
|
||||
*/
|
||||
template <typename Scalar>
|
||||
void FuseBeta(const matrix::Matrix<Scalar, 3, 1>& v_local, const matrix::Matrix<Scalar, 3, 1>& state,
|
||||
const matrix::Matrix<Scalar, 3, 3>& P, const matrix::Matrix<Scalar, 4, 1>& q_att,
|
||||
const Scalar R, const Scalar epsilon, matrix::Matrix<Scalar, 1, 3>* const H = nullptr,
|
||||
matrix::Matrix<Scalar, 3, 1>* const K = nullptr, Scalar* const innov_var = nullptr,
|
||||
Scalar* const innov = nullptr) {
|
||||
// Total ops: 75
|
||||
|
||||
// Input arrays
|
||||
|
||||
// Intermediate terms (23)
|
||||
const Scalar _tmp0 = 2 * v_local(2, 0);
|
||||
const Scalar _tmp1 = std::pow(q_att(1, 0), Scalar(2));
|
||||
const Scalar _tmp2 = std::pow(q_att(2, 0), Scalar(2));
|
||||
const Scalar _tmp3 = std::pow(q_att(0, 0), Scalar(2)) - std::pow(q_att(3, 0), Scalar(2));
|
||||
const Scalar _tmp4 = _tmp1 - _tmp2 + _tmp3;
|
||||
const Scalar _tmp5 = -state(0, 0) + v_local(0, 0);
|
||||
const Scalar _tmp6 = -state(1, 0) + v_local(1, 0);
|
||||
const Scalar _tmp7 = q_att(0, 0) * q_att(3, 0);
|
||||
const Scalar _tmp8 = q_att(1, 0) * q_att(2, 0);
|
||||
const Scalar _tmp9 = 2 * _tmp7 + 2 * _tmp8;
|
||||
const Scalar _tmp10 = _tmp0 * (-q_att(0, 0) * q_att(2, 0) + q_att(1, 0) * q_att(3, 0)) +
|
||||
_tmp4 * _tmp5 + _tmp6 * _tmp9;
|
||||
const Scalar _tmp11 =
|
||||
_tmp10 + epsilon * (2 * math::min<Scalar>(0, (((_tmp10) > 0) - ((_tmp10) < 0))) + 1);
|
||||
const Scalar _tmp12 = Scalar(1.0) / (_tmp11);
|
||||
const Scalar _tmp13 = -2 * _tmp7 + 2 * _tmp8;
|
||||
const Scalar _tmp14 = -_tmp1 + _tmp2 + _tmp3;
|
||||
const Scalar _tmp15 = _tmp0 * (q_att(0, 0) * q_att(1, 0) + q_att(2, 0) * q_att(3, 0)) +
|
||||
_tmp13 * _tmp5 + _tmp14 * _tmp6;
|
||||
const Scalar _tmp16 = _tmp15 / std::pow(_tmp11, Scalar(2));
|
||||
const Scalar _tmp17 = -_tmp12 * _tmp13 + _tmp16 * _tmp4;
|
||||
const Scalar _tmp18 = -_tmp12 * _tmp14 + _tmp16 * _tmp9;
|
||||
const Scalar _tmp19 = P(0, 0) * _tmp17;
|
||||
const Scalar _tmp20 = P(1, 1) * _tmp18;
|
||||
const Scalar _tmp21 =
|
||||
R + _tmp17 * (P(1, 0) * _tmp18 + _tmp19) + _tmp18 * (P(0, 1) * _tmp17 + _tmp20);
|
||||
const Scalar _tmp22 = Scalar(1.0) / (math::max<Scalar>(_tmp21, epsilon));
|
||||
|
||||
// Output terms (4)
|
||||
if (H != nullptr) {
|
||||
matrix::Matrix<Scalar, 1, 3>& _H = (*H);
|
||||
|
||||
_H(0, 0) = _tmp17;
|
||||
_H(0, 1) = _tmp18;
|
||||
_H(0, 2) = 0;
|
||||
}
|
||||
|
||||
if (K != nullptr) {
|
||||
matrix::Matrix<Scalar, 3, 1>& _K = (*K);
|
||||
|
||||
_K(0, 0) = _tmp22 * (P(0, 1) * _tmp18 + _tmp19);
|
||||
_K(1, 0) = _tmp22 * (P(1, 0) * _tmp17 + _tmp20);
|
||||
_K(2, 0) = _tmp22 * (P(2, 0) * _tmp17 + P(2, 1) * _tmp18);
|
||||
}
|
||||
|
||||
if (innov_var != nullptr) {
|
||||
Scalar& _innov_var = (*innov_var);
|
||||
|
||||
_innov_var = _tmp21;
|
||||
}
|
||||
|
||||
if (innov != nullptr) {
|
||||
Scalar& _innov = (*innov);
|
||||
|
||||
_innov = -_tmp12 * _tmp15;
|
||||
}
|
||||
} // NOLINT(readability/fn_size)
|
||||
|
||||
// NOLINTNEXTLINE(readability/fn_size)
|
||||
} // namespace sym
|
||||
@@ -0,0 +1,69 @@
|
||||
// -----------------------------------------------------------------------------
|
||||
// This file was autogenerated by symforce from template:
|
||||
// backends/cpp/templates/function/FUNCTION.h.jinja
|
||||
// Do NOT modify by hand.
|
||||
// -----------------------------------------------------------------------------
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <matrix/math.hpp>
|
||||
|
||||
namespace sym {
|
||||
|
||||
/**
|
||||
* This function was autogenerated from a symbolic function. Do not modify by hand.
|
||||
*
|
||||
* Symbolic function: init_wind_using_airspeed
|
||||
*
|
||||
* Args:
|
||||
* v_local: Matrix31
|
||||
* heading: Scalar
|
||||
* airspeed: Scalar
|
||||
* v_var: Scalar
|
||||
* heading_var: Scalar
|
||||
* sideslip_var: Scalar
|
||||
* airspeed_var: Scalar
|
||||
*
|
||||
* Outputs:
|
||||
* wind: Matrix21
|
||||
* P: Matrix22
|
||||
*/
|
||||
template <typename Scalar>
|
||||
void InitWindUsingAirspeed(const matrix::Matrix<Scalar, 3, 1>& v_local, const Scalar heading,
|
||||
const Scalar airspeed, const Scalar v_var, const Scalar heading_var,
|
||||
const Scalar sideslip_var, const Scalar airspeed_var,
|
||||
matrix::Matrix<Scalar, 2, 1>* const wind = nullptr,
|
||||
matrix::Matrix<Scalar, 2, 2>* const P = nullptr) {
|
||||
// Total ops: 22
|
||||
|
||||
// Input arrays
|
||||
|
||||
// Intermediate terms (7)
|
||||
const Scalar _tmp0 = std::cos(heading);
|
||||
const Scalar _tmp1 = std::sin(heading);
|
||||
const Scalar _tmp2 = std::pow(_tmp1, Scalar(2));
|
||||
const Scalar _tmp3 = std::pow(airspeed, Scalar(2)) * sideslip_var;
|
||||
const Scalar _tmp4 = std::pow(_tmp0, Scalar(2));
|
||||
const Scalar _tmp5 = _tmp0 * _tmp1;
|
||||
const Scalar _tmp6 = -_tmp3 * _tmp5 + _tmp5 * airspeed_var;
|
||||
|
||||
// Output terms (2)
|
||||
if (wind != nullptr) {
|
||||
matrix::Matrix<Scalar, 2, 1>& _wind = (*wind);
|
||||
|
||||
_wind(0, 0) = -_tmp0 * airspeed + v_local(0, 0);
|
||||
_wind(1, 0) = -_tmp1 * airspeed + v_local(1, 0);
|
||||
}
|
||||
|
||||
if (P != nullptr) {
|
||||
matrix::Matrix<Scalar, 2, 2>& _P = (*P);
|
||||
|
||||
_P(0, 0) = _tmp2 * _tmp3 + _tmp4 * airspeed_var + v_var;
|
||||
_P(1, 0) = _tmp6;
|
||||
_P(0, 1) = _tmp6;
|
||||
_P(1, 1) = _tmp2 * airspeed_var + _tmp3 * _tmp4 + v_var;
|
||||
}
|
||||
} // NOLINT(readability/fn_size)
|
||||
|
||||
// NOLINTNEXTLINE(readability/fn_size)
|
||||
} // namespace sym
|
||||
@@ -1,186 +0,0 @@
|
||||
# -*- coding: utf-8 -*-
|
||||
"""
|
||||
Created on Tue Nov 1 19:14:39 2016
|
||||
|
||||
@author: roman
|
||||
"""
|
||||
|
||||
from sympy import *
|
||||
|
||||
# q: quaternion describing rotation from frame 1 to frame 2
|
||||
# returns a rotation matrix derived form q which describes the same
|
||||
# rotation
|
||||
def quat2Rot(q):
|
||||
q0 = q[0]
|
||||
q1 = q[1]
|
||||
q2 = q[2]
|
||||
q3 = q[3]
|
||||
|
||||
Rot = Matrix([[q0**2 + q1**2 - q2**2 - q3**2, 2*(q1*q2 - q0*q3), 2*(q1*q3 + q0*q2)],
|
||||
[2*(q1*q2 + q0*q3), q0**2 - q1**2 + q2**2 - q3**2, 2*(q2*q3 - q0*q1)],
|
||||
[2*(q1*q3-q0*q2), 2*(q2*q3 + q0*q1), q0**2 - q1**2 - q2**2 + q3**2]])
|
||||
|
||||
return Rot
|
||||
|
||||
# take an expression calculated by the cse() method and write the expression
|
||||
# into a text file in C format
|
||||
def write_simplified(P_touple, filename, out_name):
|
||||
subs = P_touple[0]
|
||||
P = Matrix(P_touple[1])
|
||||
fd = open(filename, 'a')
|
||||
|
||||
is_vector = P.shape[0] == 1 or P.shape[1] == 1
|
||||
|
||||
# write sub expressions
|
||||
for index, item in enumerate(subs):
|
||||
fd.write('float ' + str(item[0]) + ' = ' + str(item[1]) + ';\n')
|
||||
|
||||
# write actual matrix values
|
||||
fd.write('\n')
|
||||
|
||||
if not is_vector:
|
||||
iterator = range(0,sqrt(len(P)), 1)
|
||||
for row in iterator:
|
||||
for column in iterator:
|
||||
fd.write(out_name + '(' + str(row) + ',' + str(column) + ') = ' + str(P[row, column]) + ';\n')
|
||||
else:
|
||||
iterator = range(0, len(P), 1)
|
||||
|
||||
for item in iterator:
|
||||
fd.write(out_name + '(' + str(item) + ') = ' + str(P[item]) + ';\n')
|
||||
|
||||
fd.write('\n\n')
|
||||
fd.close()
|
||||
|
||||
########## Symbolic variable definition #######################################
|
||||
|
||||
# model state
|
||||
w_n = Symbol("w_n", real=True) # wind in north direction
|
||||
w_e = Symbol("w_e", real=True) # wind in east direction
|
||||
k_tas = Symbol("k_tas", real=True) # true airspeed scale factor
|
||||
state = Matrix([w_n, w_e, k_tas])
|
||||
|
||||
# process noise
|
||||
q_w = Symbol("q_w", real=True) # process noise for wind states
|
||||
q_k_tas = Symbol("q_k_tas", real=True) # process noise for airspeed scale state
|
||||
|
||||
# airspeed measurement noise
|
||||
r_tas = Symbol("r_tas", real=True)
|
||||
|
||||
# sideslip measurement noise
|
||||
r_beta = Symbol("r_beta", real=True)
|
||||
|
||||
# true airspeed measurement
|
||||
tas_meas = Symbol("tas_meas", real=True)
|
||||
|
||||
# ground velocity variance
|
||||
v_n_var = Symbol("v_n_var", real=True)
|
||||
v_e_var = Symbol("v_e_var", real=True)
|
||||
|
||||
#################### time varying parameters ##################################
|
||||
|
||||
# vehicle velocity
|
||||
v_n = Symbol("v_n", real=True) # north velocity in earth fixed frame
|
||||
v_e = Symbol("v_e", real=True) # east velocity in earth fixed frame
|
||||
v_d = Symbol("v_d", real=True) # down velocity in earth fixed frame
|
||||
|
||||
# unit quaternion describing vehicle attitude, qw is real part
|
||||
qw = Symbol("q_att[0]", real=True)
|
||||
qx = Symbol("q_att[1]", real=True)
|
||||
qy = Symbol("q_att[2]", real=True)
|
||||
qz = Symbol("q_att[3]", real=True)
|
||||
q_att = Matrix([qw, qx, qy, qz])
|
||||
|
||||
# sampling time in seconds
|
||||
dt = Symbol("dt", real=True)
|
||||
|
||||
######################## State and covariance prediction ######################
|
||||
|
||||
# state transition matrix is zero because we are using a stationary
|
||||
# process model. We only need to provide formula for covariance prediction
|
||||
|
||||
# create process noise matrix for covariance prediction
|
||||
state_new = state
|
||||
Q = diag(q_w, q_w, q_k_tas) * dt**2
|
||||
|
||||
# define symbolic covariance matrix
|
||||
p00 = Symbol('_P(0,0)', real=True)
|
||||
p01 = Symbol('_P(0,1)', real=True)
|
||||
p02 = Symbol('_P(0,2)', real=True)
|
||||
p12 = Symbol('_P(1,2)', real=True)
|
||||
p11 = Symbol('_P(1,1)', real=True)
|
||||
p22 = Symbol('_P(2,2)', real=True)
|
||||
P = Matrix([[p00, p01, p02], [p01, p11, p12], [p02, p12, p22]])
|
||||
|
||||
# covariance prediction equation
|
||||
P_next = P + Q
|
||||
|
||||
# simplify the result and write it to a text file in C format
|
||||
PP_simple = cse(P_next, symbols('SPP0:30'))
|
||||
P_pred = Matrix(PP_simple[1])
|
||||
write_simplified(PP_simple, "cov_pred.txt", 'P_next')
|
||||
|
||||
|
||||
############################ Measurement update ###############################
|
||||
|
||||
# airspeed fusion
|
||||
|
||||
tas_pred = Matrix([((v_n - w_n)**2 + (v_e - w_e)**2 + v_d**2)**0.5]) * k_tas
|
||||
# compute true airspeed observation matrix
|
||||
H_tas = tas_pred.jacobian(state)
|
||||
# simplify the result and write it to a text file in C format
|
||||
H_tas_simple = cse(H_tas, symbols('HH0:30'))
|
||||
write_simplified(H_tas_simple, "airspeed_fusion.txt", 'H_tas')
|
||||
K = P * Transpose(H_tas)
|
||||
denom = H_tas * P * Transpose(H_tas) + Matrix([r_tas])
|
||||
denom = 1/denom.values()[0]
|
||||
K = K * denom
|
||||
|
||||
K_simple = cse(K, symbols('KTAS0:30'))
|
||||
write_simplified(K_simple, "airspeed_fusion.txt", "K")
|
||||
|
||||
P_m = P - K*H_tas*P
|
||||
P_m_simple = cse(P_m, symbols('PM0:50'))
|
||||
write_simplified(P_m_simple, "airspeed_fusion.txt", "P_next")
|
||||
|
||||
# sideslip fusion
|
||||
|
||||
# compute relative wind vector in vehicle body frame
|
||||
relative_wind_earth = Matrix([v_n - w_n, v_e - w_e, v_d])
|
||||
R_body_to_earth = quat2Rot(q_att)
|
||||
relative_wind_body = Transpose(R_body_to_earth) * relative_wind_earth
|
||||
# small angle approximation of side slip model
|
||||
beta_pred = relative_wind_body[1] / relative_wind_body[0]
|
||||
# compute side slip observation matrix
|
||||
H_beta = Matrix([beta_pred]).jacobian(state)
|
||||
# simplify the result and write it to a text file in C format
|
||||
H_beta_simple = cse(H_beta, symbols('HB0:30'))
|
||||
write_simplified(H_beta_simple, "beta_fusion.txt", 'H_beta')
|
||||
K = P * Transpose(H_beta)
|
||||
denom = H_beta * P * Transpose(H_beta) + Matrix([r_beta])
|
||||
denom = 1/denom.values()[0]
|
||||
K = K*denom
|
||||
K_simple = cse(K, symbols('KB0:30'))
|
||||
write_simplified(K_simple, "beta_fusion.txt", 'K')
|
||||
|
||||
P_m = P - K*H_beta*P
|
||||
P_m_simple = cse(P_m, symbols('PM0:50'))
|
||||
write_simplified(P_m_simple, "beta_fusion.txt", "P_next")
|
||||
|
||||
# wind covariance initialisation via velocity
|
||||
|
||||
# estimate heading from ground velocity
|
||||
heading_est = atan2(v_n, v_e)
|
||||
|
||||
# calculate wind speed estimate from vehicle ground velocity, heading and
|
||||
# airspeed measurement
|
||||
w_n_est = v_n - tas_meas * cos(heading_est)
|
||||
w_e_est = v_e - tas_meas * sin(heading_est)
|
||||
wind_est = Matrix([w_n_est, w_e_est])
|
||||
|
||||
# calculate estimate of state covariance matrix
|
||||
P_wind = diag(v_n_var, v_e_var, r_tas)
|
||||
|
||||
wind_jac = wind_est.jacobian([v_n, v_e, tas_meas])
|
||||
wind_jac_simple = cse(wind_jac, symbols('L0:30'))
|
||||
write_simplified(wind_jac_simple, "cov_init.txt", "L")
|
||||
@@ -1,6 +1,6 @@
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2018-2021 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2018-2022 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#!/usr/bin/env python3
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -34,6 +34,7 @@
|
||||
|
||||
import math
|
||||
import json
|
||||
import sys
|
||||
import urllib.request
|
||||
|
||||
SAMPLING_RES = 10
|
||||
@@ -47,7 +48,7 @@ def constrain(n, nmin, nmax):
|
||||
|
||||
header = """/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -99,7 +100,8 @@ print('// *INDENT-OFF*')
|
||||
|
||||
# Declination
|
||||
params = urllib.parse.urlencode({'lat1': 0, 'lat2': 0, 'lon1': 0, 'lon2': 0, 'latStepSize': 1, 'lonStepSize': 1, 'magneticComponent': 'd', 'resultFormat': 'json'})
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?%s" % params)
|
||||
key=sys.argv[1] # NOAA key (https://www.ngdc.noaa.gov/geomag/CalcSurvey.shtml)
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params))
|
||||
data = json.loads(f.read())
|
||||
print("// Magnetic declination data in radians * 10^-4")
|
||||
print('// Model: {},'.format(data['model']))
|
||||
@@ -112,7 +114,7 @@ for l in range(SAMPLING_MIN_LON, SAMPLING_MAX_LON+1, SAMPLING_RES):
|
||||
print('')
|
||||
for latitude in range(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+1, SAMPLING_RES):
|
||||
params = urllib.parse.urlencode({'lat1': latitude, 'lat2': latitude, 'lon1': SAMPLING_MIN_LON, 'lon2': SAMPLING_MAX_LON, 'latStepSize': 1, 'lonStepSize': SAMPLING_RES, 'magneticComponent': 'd', 'resultFormat': 'json'})
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?%s" % params)
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params))
|
||||
data = json.loads(f.read())
|
||||
|
||||
print('\t/* LAT: {0:3d} */'.format(latitude) + ' { ', end='')
|
||||
@@ -126,7 +128,7 @@ print("};\n")
|
||||
|
||||
# Inclination
|
||||
params = urllib.parse.urlencode({'lat1': 0, 'lat2': 0, 'lon1': 0, 'lon2': 0, 'latStepSize': 1, 'lonStepSize': 1, 'magneticComponent': 'i', 'resultFormat': 'json'})
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?%s" % params)
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params))
|
||||
data = json.loads(f.read())
|
||||
print("// Magnetic inclination data in radians * 10^-4")
|
||||
print('// Model: {},'.format(data['model']))
|
||||
@@ -139,7 +141,7 @@ for l in range(SAMPLING_MIN_LON, SAMPLING_MAX_LON+1, SAMPLING_RES):
|
||||
print('')
|
||||
for latitude in range(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+1, SAMPLING_RES):
|
||||
params = urllib.parse.urlencode({'lat1': latitude, 'lat2': latitude, 'lon1': SAMPLING_MIN_LON, 'lon2': SAMPLING_MAX_LON, 'latStepSize': 1, 'lonStepSize': SAMPLING_RES, 'magneticComponent': 'i', 'resultFormat': 'json'})
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?%s" % params)
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params))
|
||||
data = json.loads(f.read())
|
||||
|
||||
print('\t/* LAT: {0:3d} */'.format(latitude) + ' { ', end='')
|
||||
@@ -153,7 +155,7 @@ print("};\n")
|
||||
|
||||
# total intensity
|
||||
params = urllib.parse.urlencode({'lat1': 0, 'lat2': 0, 'lon1': 0, 'lon2': 0, 'latStepSize': 1, 'lonStepSize': 1, 'magneticComponent': 'i', 'resultFormat': 'json'})
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?%s" % params)
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params))
|
||||
data = json.loads(f.read())
|
||||
print("// Magnetic strength data in milli-Gauss * 10")
|
||||
print('// Model: {},'.format(data['model']))
|
||||
@@ -166,7 +168,7 @@ for l in range(SAMPLING_MIN_LON, SAMPLING_MAX_LON+1, SAMPLING_RES):
|
||||
print('')
|
||||
for latitude in range(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+1, SAMPLING_RES):
|
||||
params = urllib.parse.urlencode({'lat1': latitude, 'lat2': latitude, 'lon1': SAMPLING_MIN_LON, 'lon2': SAMPLING_MAX_LON, 'latStepSize': 1, 'lonStepSize': SAMPLING_RES, 'magneticComponent': 'f', 'resultFormat': 'json'})
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?%s" % params)
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params))
|
||||
data = json.loads(f.read())
|
||||
|
||||
print('\t/* LAT: {0:3d} */'.format(latitude) + ' { ', end='')
|
||||
|
||||
@@ -1,7 +1,7 @@
|
||||
#!/usr/bin/env python3
|
||||
############################################################################
|
||||
#
|
||||
# Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
|
||||
# Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
|
||||
#
|
||||
# Redistribution and use in source and binary forms, with or without
|
||||
# modification, are permitted provided that the following conditions
|
||||
@@ -33,6 +33,7 @@
|
||||
############################################################################
|
||||
|
||||
import json
|
||||
import sys
|
||||
import urllib.request
|
||||
|
||||
SAMPLING_RES = 5
|
||||
@@ -43,7 +44,7 @@ SAMPLING_MAX_LON = 180
|
||||
|
||||
header = """/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -87,14 +88,15 @@ print('')
|
||||
|
||||
# Declination
|
||||
params = urllib.parse.urlencode({'lat1': 0, 'lat2': 0, 'lon1': 0, 'lon2': 0, 'latStepSize': 1, 'lonStepSize': 1, 'magneticComponent': 'd', 'resultFormat': 'json'})
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?%s" % params)
|
||||
key=sys.argv[1] # NOAA key (https://www.ngdc.noaa.gov/geomag/CalcSurvey.shtml)
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params))
|
||||
data = json.loads(f.read())
|
||||
|
||||
|
||||
print('TEST(GeoLookupTest, declination)\n{')
|
||||
for latitude in range(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+1, SAMPLING_RES):
|
||||
params = urllib.parse.urlencode({'lat1': latitude, 'lat2': latitude, 'lon1': SAMPLING_MIN_LON, 'lon2': SAMPLING_MAX_LON, 'latStepSize': 1, 'lonStepSize': SAMPLING_RES, 'magneticComponent': 'd', 'resultFormat': 'json'})
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?%s" % params)
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params))
|
||||
data = json.loads(f.read())
|
||||
|
||||
for p in data['result']:
|
||||
@@ -112,7 +114,7 @@ print('')
|
||||
print('TEST(GeoLookupTest, inclination)\n{')
|
||||
for latitude in range(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+1, SAMPLING_RES):
|
||||
params = urllib.parse.urlencode({'lat1': latitude, 'lat2': latitude, 'lon1': SAMPLING_MIN_LON, 'lon2': SAMPLING_MAX_LON, 'latStepSize': 1, 'lonStepSize': SAMPLING_RES, 'magneticComponent': 'i', 'resultFormat': 'json'})
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?%s" % params)
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params))
|
||||
data = json.loads(f.read())
|
||||
|
||||
for p in data['result']:
|
||||
@@ -130,7 +132,7 @@ print('')
|
||||
print('TEST(GeoLookupTest, strength)\n{')
|
||||
for latitude in range(SAMPLING_MIN_LAT, SAMPLING_MAX_LAT+1, SAMPLING_RES):
|
||||
params = urllib.parse.urlencode({'lat1': latitude, 'lat2': latitude, 'lon1': SAMPLING_MIN_LON, 'lon2': SAMPLING_MAX_LON, 'latStepSize': 1, 'lonStepSize': SAMPLING_RES, 'magneticComponent': 'f', 'resultFormat': 'json'})
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?%s" % params)
|
||||
f = urllib.request.urlopen("https://www.ngdc.noaa.gov/geomag-web/calculators/calculateIgrfgrid?key=%s&%s" % (key, params))
|
||||
data = json.loads(f.read())
|
||||
|
||||
for p in data['result']:
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014-2021 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2014-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2014-2021 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2014-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
|
||||
@@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2020-2021 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2020-2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@@ -47,80 +47,80 @@ static constexpr int LON_DIM = 37;
|
||||
// Magnetic declination data in radians * 10^-4
|
||||
// Model: WMM-2020,
|
||||
// Version: 0.5.1.11,
|
||||
// Date: 2022.4219,
|
||||
// Date: 2022.8137,
|
||||
static constexpr const int16_t declination_table[19][37] {
|
||||
// LONGITUDE: -180, -170, -160, -150, -140, -130, -120, -110, -100, -90, -80, -70, -60, -50, -40, -30, -20, -10, 0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100, 110, 120, 130, 140, 150, 160, 170, 180,
|
||||
/* LAT: -90 */ { 25990, 24245, 22499, 20754, 19009, 17263, 15518, 13773, 12027, 10282, 8537, 6791, 5046, 3301, 1556, -190, -1935, -3680, -5426, -7171, -8916,-10661,-12407,-14152,-15897,-17643,-19388,-21133,-22879,-24624,-26370,-28115,-29860, 31226, 29481, 27735, 25990, },
|
||||
/* LAT: -80 */ { 22557, 20425, 18484, 16709, 15069, 13530, 12066, 10654, 9279, 7929, 6597, 5278, 3969, 2664, 1357, 38, -1303, -2675, -4084, -5536, -7030, -8566,-10143,-11762,-13426,-15144,-16929,-18801,-20783,-22901,-25175,-27609,-30178, 30014, 27395, 24888, 22557, },
|
||||
/* LAT: -70 */ { 14975, 13577, 12452, 11491, 10623, 9792, 8951, 8064, 7111, 6092, 5022, 3929, 2844, 1788, 766, -244, -1281, -2386, -3586, -4885, -6264, -7694, -9141,-10583,-12009,-13424,-14852,-16337,-17960,-19872,-22389,-26183, 30730, 24152, 19624, 16847, 14975, },
|
||||
/* LAT: -60 */ { 8411, 8167, 7888, 7616, 7364, 7112, 6805, 6373, 5759, 4940, 3940, 2828, 1708, 679, -203, -962, -1691, -2513, -3515, -4710, -6039, -7408, -8729, -9939,-11004,-11904,-12620,-13115,-13287,-12838,-10739, -3518, 4884, 7640, 8415, 8544, 8411, },
|
||||
/* LAT: -50 */ { 5478, 5515, 5460, 5373, 5300, 5264, 5231, 5105, 4762, 4101, 3092, 1820, 478, -703, -1576, -2142, -2540, -2979, -3662, -4673, -5915, -7191, -8332, -9235, -9835,-10076, -9883, -9128, -7621, -5261, -2357, 391, 2500, 3924, 4799, 5273, 5478, },
|
||||
/* LAT: -40 */ { 3949, 4042, 4051, 4008, 3949, 3916, 3922, 3912, 3740, 3207, 2186, 746, -819, -2135, -3001, -3454, -3639, -3700, -3867, -4433, -5407, -6483, -7369, -7910, -8019, -7644, -6756, -5373, -3662, -1959, -498, 723, 1766, 2631, 3287, 3718, 3949, },
|
||||
/* LAT: -30 */ { 2979, 3065, 3097, 3084, 3027, 2949, 2890, 2857, 2731, 2255, 1222, -295, -1903, -3159, -3901, -4249, -4330, -4122, -3689, -3464, -3824, -4571, -5270, -5622, -5499, -4914, -3955, -2749, -1540, -595, 83, 683, 1306, 1909, 2418, 2780, 2979, },
|
||||
/* LAT: -20 */ { 2336, 2383, 2402, 2405, 2364, 2271, 2165, 2089, 1944, 1450, 397, -1090, -2570, -3633, -4169, -4288, -4087, -3532, -2671, -1872, -1592, -1945, -2594, -3065, -3103, -2745, -2111, -1294, -518, -28, 234, 536, 976, 1454, 1876, 2183, 2336, },
|
||||
/* LAT: -10 */ { 1943, 1937, 1917, 1916, 1889, 1806, 1697, 1607, 1423, 874, -185, -1562, -2836, -3668, -3939, -3714, -3141, -2361, -1515, -759, -292, -323, -791, -1298, -1512, -1423, -1110, -611, -114, 127, 176, 336, 707, 1144, 1537, 1824, 1943, },
|
||||
/* LAT: 0 */ { 1730, 1697, 1642, 1635, 1625, 1558, 1454, 1342, 1089, 469, -570, -1796, -2852, -3442, -3444, -2947, -2181, -1399, -746, -209, 205, 318, 41, -376, -632, -688, -590, -328, -38, 51, -9, 79, 420, 862, 1281, 1601, 1730, },
|
||||
/* LAT: 10 */ { 1594, 1602, 1561, 1579, 1606, 1558, 1438, 1253, 878, 161, -859, -1935, -2764, -3106, -2906, -2302, -1526, -814, -298, 84, 410, 560, 399, 77, -158, -266, -289, -209, -104, -146, -285, -259, 42, 496, 977, 1384, 1594, },
|
||||
/* LAT: 20 */ { 1411, 1560, 1622, 1715, 1802, 1783, 1630, 1329, 785, -70, -1113, -2065, -2664, -2777, -2452, -1852, -1141, -491, -30, 281, 540, 687, 597, 354, 154, 36, -56, -120, -200, -390, -627, -686, -452, -5, 536, 1054, 1411, },
|
||||
/* LAT: 30 */ { 1111, 1478, 1738, 1963, 2123, 2135, 1949, 1528, 801, -227, -1345, -2224, -2642, -2583, -2186, -1608, -952, -334, 130, 436, 668, 816, 796, 648, 498, 373, 216, 5, -278, -652, -1021, -1181, -1022, -596, -20, 589, 1111, },
|
||||
/* LAT: 40 */ { 754, 1341, 1835, 2228, 2478, 2522, 2308, 1776, 866, -361, -1601, -2470, -2794, -2644, -2200, -1608, -955, -325, 187, 552, 824, 1023, 1118, 1108, 1031, 883, 614, 204, -335, -941, -1463, -1708, -1592, -1176, -578, 95, 754, },
|
||||
/* LAT: 50 */ { 465, 1212, 1894, 2451, 2818, 2925, 2697, 2044, 904, -593, -2018, -2936, -3233, -3043, -2554, -1908, -1198, -499, 118, 625, 1044, 1401, 1682, 1853, 1872, 1685, 1241, 533, -361, -1264, -1944, -2231, -2107, -1666, -1031, -299, 465, },
|
||||
/* LAT: 60 */ { 271, 1124, 1930, 2625, 3130, 3344, 3131, 2320, 806, -1154, -2874, -3857, -4112, -3852, -3280, -2534, -1707, -866, -56, 696, 1389, 2021, 2565, 2962, 3122, 2937, 2299, 1183, -231, -1552, -2422, -2732, -2568, -2074, -1380, -579, 271, },
|
||||
/* LAT: 70 */ { 39, 975, 1873, 2673, 3288, 3583, 3332, 2198, -39, -2755, -4710, -5537, -5547, -5063, -4293, -3357, -2331, -1264, -188, 873, 1899, 2866, 3735, 4444, 4892, 4926, 4319, 2849, 656, -1453, -2754, -3199, -3040, -2508, -1758, -888, 39, },
|
||||
/* LAT: 80 */ { -657, 266, 1119, 1811, 2196, 2014, 818, -1786, -4993, -7115, -7869, -7741, -7113, -6196, -5104, -3905, -2638, -1331, -5, 1323, 2638, 3921, 5149, 6289, 7286, 8047, 8392, 7952, 6034, 2270, -1332, -3056, -3426, -3101, -2427, -1579, -657, },
|
||||
/* LAT: 90 */ { -29886,-28141,-26395,-24650,-22905,-21159,-19414,-17669,-15923,-14178,-12433,-10688, -8943, -7197, -5452, -3707, -1962, -217, 1528, 3274, 5019, 6764, 8509, 10255, 12000, 13745, 15491, 17236, 18982, 20727, 22473, 24218, 25964, 27709, 29455, 31200,-29886, },
|
||||
/* LAT: -90 */ { 25980, 24235, 22489, 20744, 18999, 17253, 15508, 13763, 12017, 10272, 8527, 6782, 5036, 3291, 1546, -200, -1945, -3690, -5435, -7181, -8926,-10671,-12417,-14162,-15907,-17653,-19398,-21143,-22889,-24634,-26379,-28125,-29870, 31216, 29471, 27726, 25980, },
|
||||
/* LAT: -80 */ { 22546, 20415, 18476, 16702, 15061, 13523, 12060, 10648, 9273, 7923, 6591, 5273, 3964, 2659, 1351, 32, -1309, -2682, -4092, -5544, -7039, -8576,-10154,-11773,-13438,-15156,-16942,-18815,-20798,-22916,-25191,-27625,-30194, 29999, 27381, 24876, 22546, },
|
||||
/* LAT: -70 */ { 14978, 13580, 12453, 11491, 10622, 9790, 8948, 8060, 7108, 6088, 5018, 3925, 2840, 1786, 764, -246, -1283, -2389, -3591, -4892, -6273, -7704, -9152,-10595,-12021,-13438,-14867,-16353,-17977,-19893,-22416,-26218, 30695, 24136, 19622, 16850, 14978, },
|
||||
/* LAT: -60 */ { 8423, 8177, 7895, 7621, 7367, 7113, 6804, 6371, 5756, 4936, 3935, 2824, 1704, 677, -203, -960, -1688, -2512, -3517, -4716, -6048, -7419, -8741, -9952,-11016,-11915,-12630,-13125,-13297,-12848,-10746, -3486, 4925, 7665, 8433, 8558, 8423, },
|
||||
/* LAT: -50 */ { 5487, 5523, 5467, 5377, 5303, 5266, 5231, 5104, 4760, 4096, 3085, 1813, 472, -706, -1574, -2136, -2531, -2972, -3659, -4677, -5925, -7204, -8346, -9247, -9844,-10082, -9886, -9127, -7616, -5254, -2348, 400, 2510, 3934, 4809, 5283, 5487, },
|
||||
/* LAT: -40 */ { 3956, 4049, 4056, 4011, 3951, 3917, 3921, 3910, 3737, 3202, 2178, 735, -828, -2140, -3000, -3448, -3629, -3687, -3858, -4434, -5418, -6498, -7383, -7919, -8024, -7643, -6750, -5365, -3654, -1954, -496, 725, 1769, 2636, 3293, 3724, 3956, },
|
||||
/* LAT: -30 */ { 2984, 3071, 3101, 3086, 3027, 2948, 2888, 2854, 2728, 2249, 1212, -309, -1916, -3167, -3903, -4245, -4321, -4107, -3673, -3458, -3831, -4584, -5281, -5627, -5498, -4908, -3946, -2740, -1535, -594, 82, 682, 1306, 1911, 2422, 2785, 2984, },
|
||||
/* LAT: -20 */ { 2342, 2388, 2405, 2406, 2364, 2269, 2161, 2085, 1939, 1443, 385, -1106, -2584, -3642, -4171, -4283, -4077, -3515, -2652, -1860, -1592, -1952, -2602, -3068, -3101, -2740, -2103, -1288, -515, -29, 231, 532, 974, 1454, 1879, 2188, 2342, },
|
||||
/* LAT: -10 */ { 1948, 1942, 1920, 1917, 1888, 1803, 1692, 1601, 1417, 866, -198, -1576, -2848, -3674, -3937, -3705, -3128, -2345, -1500, -747, -286, -323, -796, -1301, -1511, -1420, -1106, -608, -113, 125, 171, 330, 702, 1143, 1538, 1828, 1948, },
|
||||
/* LAT: 0 */ { 1735, 1702, 1645, 1636, 1624, 1555, 1449, 1334, 1081, 460, -581, -1808, -2861, -3444, -3438, -2936, -2167, -1386, -735, -200, 212, 321, 40, -377, -631, -686, -587, -327, -38, 48, -15, 72, 414, 860, 1282, 1605, 1735, },
|
||||
/* LAT: 10 */ { 1599, 1606, 1564, 1579, 1605, 1555, 1432, 1245, 870, 152, -868, -1944, -2768, -3105, -2898, -2290, -1514, -803, -289, 91, 416, 564, 400, 78, -156, -264, -288, -209, -107, -150, -292, -266, 37, 494, 978, 1387, 1599, },
|
||||
/* LAT: 20 */ { 1413, 1562, 1622, 1714, 1800, 1779, 1624, 1321, 777, -78, -1120, -2070, -2665, -2772, -2443, -1840, -1130, -481, -21, 288, 546, 691, 599, 356, 157, 38, -55, -122, -204, -395, -634, -693, -457, -8, 535, 1055, 1413, },
|
||||
/* LAT: 30 */ { 1109, 1476, 1736, 1960, 2120, 2131, 1943, 1521, 794, -234, -1349, -2224, -2638, -2575, -2175, -1596, -941, -323, 139, 444, 675, 821, 800, 651, 501, 376, 217, 3, -282, -658, -1028, -1187, -1026, -599, -22, 588, 1109, },
|
||||
/* LAT: 40 */ { 749, 1335, 1830, 2223, 2473, 2517, 2302, 1769, 859, -366, -1601, -2466, -2786, -2634, -2188, -1596, -942, -313, 197, 562, 832, 1029, 1122, 1111, 1035, 886, 615, 200, -341, -949, -1470, -1714, -1596, -1179, -581, 91, 749, },
|
||||
/* LAT: 50 */ { 456, 1202, 1883, 2442, 2810, 2918, 2691, 2038, 900, -593, -2012, -2925, -3219, -3028, -2539, -1893, -1183, -485, 131, 637, 1055, 1409, 1689, 1858, 1877, 1688, 1239, 527, -370, -1274, -1951, -2236, -2111, -1670, -1037, -307, 456, },
|
||||
/* LAT: 60 */ { 255, 1106, 1913, 2610, 3117, 3332, 3122, 2315, 808, -1144, -2856, -3836, -4090, -3831, -3260, -2515, -1689, -848, -40, 711, 1403, 2033, 2576, 2970, 3128, 2939, 2295, 1173, -245, -1565, -2431, -2738, -2573, -2080, -1390, -592, 255, },
|
||||
/* LAT: 70 */ { 11, 945, 1842, 2642, 3260, 3558, 3313, 2193, -20, -2713, -4662, -5494, -5509, -5030, -4262, -3330, -2306, -1241, -167, 893, 1918, 2884, 3752, 4458, 4904, 4933, 4318, 2836, 635, -1475, -2771, -3214, -3055, -2526, -1780, -913, 11, },
|
||||
/* LAT: 80 */ { -726, 195, 1047, 1739, 2126, 1954, 793, -1737, -4876, -6994, -7767, -7659, -7045, -6138, -5054, -3860, -2597, -1294, 30, 1357, 2671, 3953, 5181, 6320, 7317, 8079, 8423, 7976, 6029, 2205, -1425, -3142, -3503, -3172, -2496, -1647, -726, },
|
||||
/* LAT: 90 */ { -29738,-27992,-26247,-24501,-22756,-21011,-19265,-17520,-15775,-14030,-12284,-10539, -8794, -7049, -5304, -3558, -1813, -68, 1677, 3422, 5167, 6913, 8658, 10403, 12149, 13894, 15639, 17385, 19130, 20876, 22621, 24367, 26112, 27858, 29603, 31349,-29738, },
|
||||
};
|
||||
|
||||
// Magnetic inclination data in radians * 10^-4
|
||||
// Model: WMM-2020,
|
||||
// Version: 0.5.1.11,
|
||||
// Date: 2022.4219,
|
||||
// Date: 2022.8137,
|
||||
static constexpr const int16_t inclination_table[19][37] {
|
||||
// LONGITUDE: -180, -170, -160, -150, -140, -130, -120, -110, -100, -90, -80, -70, -60, -50, -40, -30, -20, -10, 0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100, 110, 120, 130, 140, 150, 160, 170, 180,
|
||||
/* LAT: -90 */ { -12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572,-12572, },
|
||||
/* LAT: -80 */ { -13657,-13524,-13363,-13183,-12989,-12787,-12583,-12383,-12192,-12015,-11858,-11724,-11614,-11528,-11464,-11423,-11403,-11405,-11433,-11487,-11570,-11685,-11829,-12003,-12201,-12418,-12647,-12880,-13108,-13321,-13507,-13657,-13762,-13813,-13810,-13756,-13657, },
|
||||
/* LAT: -70 */ { -14106,-13787,-13468,-13145,-12813,-12469,-12114,-11756,-11413,-11104,-10851,-10667,-10555,-10502,-10488,-10492,-10499,-10509,-10532,-10588,-10696,-10870,-11116,-11431,-11803,-12221,-12668,-13133,-13599,-14051,-14469,-14814,-15004,-14950,-14720,-14422,-14106, },
|
||||
/* LAT: -60 */ { -13519,-13165,-12827,-12494,-12151,-11779,-11364,-10909,-10441,-10010, -9680, -9503, -9500, -9636, -9840,-10033,-10159,-10203,-10191,-10177,-10224,-10382,-10670,-11078,-11576,-12132,-12718,-13314,-13902,-14464,-14961,-15251,-15075,-14691,-14285,-13892,-13519, },
|
||||
/* LAT: -50 */ { -12496,-12154,-11823,-11501,-11178,-10831,-10432, -9961, -9431, -8909, -8518, -8391, -8591, -9051, -9615,-10127,-10488,-10652,-10623,-10472,-10330,-10334,-10554,-10969,-11511,-12103,-12689,-13228,-13675,-13973,-14081,-14008,-13805,-13521,-13193,-12846,-12496, },
|
||||
/* LAT: -40 */ { -11240,-10892,-10545,-10200, -9860, -9522, -9161, -8735, -8214, -7649, -7222, -7178, -7636, -8459, -9380,-10210,-10870,-11306,-11448,-11282,-10940,-10668,-10659,-10939,-11400,-11905,-12351,-12674,-12833,-12838,-12748,-12611,-12432,-12200,-11914,-11586,-11240, },
|
||||
/* LAT: -30 */ { -9602, -9224, -8845, -8455, -8063, -7687, -7330, -6939, -6426, -5814, -5361, -5442, -6209, -7410, -8661, -9757,-10672,-11383,-11784,-11776,-11406,-10899,-10564,-10563,-10814,-11135,-11392,-11505,-11443,-11268,-11093,-10959,-10813,-10606,-10324, -9979, -9602, },
|
||||
/* LAT: -20 */ { -7371, -6932, -6516, -6088, -5644, -5213, -4822, -4408, -3842, -3156, -2707, -2965, -4074, -5685, -7313, -8683, -9750,-10527,-10967,-11003,-10641,-10027, -9469, -9224, -9272, -9435, -9576, -9594, -9422, -9150, -8956, -8869, -8765, -8557, -8241, -7829, -7371, },
|
||||
/* LAT: -10 */ { -4415, -3881, -3428, -2992, -2535, -2084, -1670, -1215, -587, 117, 480, 55, -1273, -3189, -5164, -6774, -7871, -8506, -8772, -8710, -8302, -7618, -6954, -6608, -6569, -6662, -6779, -6803, -6615, -6319, -6165, -6174, -6134, -5918, -5534, -5007, -4415, },
|
||||
/* LAT: 0 */ { -906, -285, 179, 581, 999, 1415, 1806, 2250, 2836, 3414, 3617, 3122, 1828, -81, -2125, -3776, -4785, -5215, -5274, -5104, -4664, -3948, -3243, -2872, -2812, -2881, -3006, -3080, -2950, -2715, -2660, -2804, -2867, -2680, -2256, -1627, -906, },
|
||||
/* LAT: 10 */ { 2561, 3186, 3618, 3959, 4313, 4680, 5033, 5421, 5873, 6244, 6281, 5793, 4712, 3147, 1457, 82, -724, -972, -881, -645, -234, 404, 1037, 1374, 1437, 1392, 1292, 1200, 1243, 1346, 1270, 1003, 812, 884, 1236, 1838, 2561, },
|
||||
/* LAT: 20 */ { 5416, 5943, 6321, 6616, 6929, 7273, 7616, 7964, 8298, 8499, 8412, 7950, 7116, 6020, 4895, 3987, 3457, 3338, 3488, 3731, 4062, 4527, 4987, 5242, 5298, 5281, 5232, 5175, 5164, 5146, 4972, 4639, 4342, 4252, 4424, 4846, 5416, },
|
||||
/* LAT: 30 */ { 7569, 7941, 8258, 8540, 8849, 9196, 9554, 9896, 10173, 10287, 10143, 9722, 9094, 8383, 7722, 7211, 6920, 6878, 7020, 7231, 7477, 7776, 8064, 8238, 8295, 8308, 8310, 8301, 8278, 8196, 7974, 7622, 7267, 7047, 7031, 7225, 7569, },
|
||||
/* LAT: 40 */ { 9266, 9486, 9742, 10027, 10354, 10715, 11083, 11423, 11675, 11758, 11609, 11249, 10776, 10303, 9907, 9624, 9474, 9470, 9580, 9742, 9917, 10101, 10272, 10397, 10475, 10535, 10590, 10623, 10607, 10497, 10256, 9906, 9539, 9254, 9111, 9123, 9266, },
|
||||
/* LAT: 50 */ { 10802, 10923, 11124, 11394, 11717, 12071, 12426, 12743, 12965, 13025, 12886, 12588, 12224, 11878, 11603, 11416, 11323, 11319, 11386, 11488, 11602, 11718, 11834, 11950, 12068, 12190, 12303, 12376, 12367, 12242, 11997, 11669, 11330, 11045, 10855, 10775, 10802, },
|
||||
/* LAT: 60 */ { 12319, 12392, 12542, 12761, 13031, 13332, 13634, 13901, 14077, 14105, 13969, 13720, 13431, 13160, 12939, 12782, 12691, 12660, 12675, 12723, 12790, 12875, 12981, 13113, 13272, 13448, 13612, 13722, 13728, 13608, 13384, 13105, 12826, 12589, 12419, 12328, 12319, },
|
||||
/* LAT: 70 */ { 13758, 13801, 13896, 14038, 14218, 14422, 14630, 14812, 14916, 14897, 14759, 14558, 14340, 14136, 13962, 13827, 13733, 13678, 13659, 13672, 13714, 13785, 13889, 14025, 14191, 14378, 14562, 14703, 14750, 14678, 14517, 14319, 14124, 13959, 13839, 13771, 13758, },
|
||||
/* LAT: 80 */ { 14998, 15010, 15048, 15108, 15184, 15270, 15349, 15394, 15376, 15297, 15184, 15060, 14937, 14823, 14723, 14641, 14579, 14539, 14520, 14524, 14550, 14599, 14671, 14763, 14875, 15001, 15136, 15269, 15376, 15420, 15382, 15296, 15200, 15116, 15052, 15012, 14998, },
|
||||
/* LAT: 90 */ { 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, 15395, },
|
||||
/* LAT: -90 */ { -12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570,-12570, },
|
||||
/* LAT: -80 */ { -13654,-13520,-13360,-13179,-12986,-12784,-12580,-12380,-12189,-12013,-11856,-11722,-11612,-11526,-11462,-11421,-11401,-11403,-11430,-11485,-11568,-11683,-11828,-12001,-12199,-12416,-12646,-12879,-13107,-13319,-13506,-13656,-13759,-13810,-13807,-13753,-13654, },
|
||||
/* LAT: -70 */ { -14102,-13784,-13464,-13141,-12810,-12466,-12111,-11754,-11411,-11103,-10850,-10667,-10555,-10502,-10488,-10491,-10498,-10507,-10530,-10585,-10694,-10868,-11115,-11430,-11803,-12221,-12669,-13133,-13599,-14052,-14469,-14814,-15002,-14947,-14716,-14418,-14102, },
|
||||
/* LAT: -60 */ { -13516,-13163,-12825,-12492,-12148,-11776,-11361,-10907,-10439,-10009, -9680, -9505, -9502, -9639, -9843,-10035,-10159,-10201,-10187,-10172,-10219,-10379,-10669,-11078,-11577,-12134,-12720,-13316,-13905,-14466,-14963,-15253,-15075,-14690,-14283,-13890,-13516, },
|
||||
/* LAT: -50 */ { -12495,-12153,-11822,-11499,-11176,-10830,-10430, -9959, -9430, -8909, -8520, -8396, -8598, -9059, -9623,-10133,-10491,-10651,-10619,-10465,-10323,-10330,-10552,-10970,-11513,-12106,-12693,-13231,-13677,-13974,-14082,-14009,-13805,-13522,-13193,-12845,-12495, },
|
||||
/* LAT: -40 */ { -11239,-10891,-10543,-10198, -9858, -9520, -9160, -8735, -8214, -7650, -7225, -7186, -7648, -8473, -9394,-10222,-10878,-11310,-11447,-11276,-10932,-10661,-10657,-10941,-11404,-11909,-12354,-12675,-12833,-12838,-12748,-12612,-12433,-12201,-11914,-11586,-11239, },
|
||||
/* LAT: -30 */ { -9602, -9222, -8843, -8452, -8060, -7685, -7329, -6938, -6426, -5815, -5365, -5452, -6226, -7431, -8681, -9775,-10686,-11393,-11788,-11774,-11399,-10891,-10560,-10563,-10816,-11138,-11393,-11504,-11441,-11265,-11092,-10959,-10814,-10608,-10326, -9980, -9602, },
|
||||
/* LAT: -20 */ { -7372, -6930, -6512, -6083, -5639, -5209, -4819, -4407, -3842, -3157, -2712, -2980, -4097, -5713, -7340, -8706, -9768,-10539,-10973,-11003,-10635,-10020, -9463, -9221, -9272, -9434, -9574, -9591, -9417, -9146, -8953, -8869, -8767, -8561, -8244, -7832, -7372, },
|
||||
/* LAT: -10 */ { -4416, -3878, -3423, -2985, -2528, -2078, -1665, -1212, -588, 114, 472, 37, -1301, -3223, -5196, -6799, -7888, -8517, -8777, -8710, -8296, -7609, -6946, -6603, -6565, -6658, -6774, -6797, -6608, -6313, -6161, -6175, -6138, -5924, -5540, -5012, -4416, },
|
||||
/* LAT: 0 */ { -908, -282, 185, 588, 1007, 1423, 1812, 2253, 2835, 3410, 3608, 3104, 1801, -115, -2157, -3800, -4800, -5222, -5277, -5103, -4658, -3939, -3234, -2865, -2805, -2874, -2999, -3071, -2941, -2707, -2655, -2804, -2872, -2688, -2264, -1632, -908, },
|
||||
/* LAT: 10 */ { 2560, 3188, 3624, 3965, 4321, 4688, 5038, 5423, 5872, 6240, 6272, 5778, 4689, 3120, 1430, 61, -736, -977, -882, -644, -229, 412, 1045, 1381, 1444, 1401, 1301, 1210, 1252, 1354, 1275, 1003, 806, 876, 1229, 1832, 2560, },
|
||||
/* LAT: 20 */ { 5415, 5945, 6325, 6621, 6934, 7278, 7620, 7965, 8296, 8494, 8404, 7938, 7099, 6001, 4877, 3972, 3449, 3335, 3488, 3733, 4065, 4533, 4993, 5247, 5305, 5289, 5241, 5184, 5171, 5152, 4975, 4639, 4338, 4247, 4419, 4843, 5415, },
|
||||
/* LAT: 30 */ { 7568, 7942, 8260, 8543, 8852, 9199, 9555, 9895, 10170, 10282, 10136, 9712, 9082, 8371, 7711, 7202, 6914, 6875, 7019, 7232, 7480, 7780, 8069, 8242, 8300, 8314, 8317, 8308, 8284, 8201, 7977, 7622, 7265, 7044, 7028, 7223, 7568, },
|
||||
/* LAT: 40 */ { 9266, 9487, 9743, 10028, 10354, 10715, 11082, 11420, 11672, 11752, 11602, 11241, 10768, 10295, 9900, 9618, 9471, 9469, 9580, 9743, 9919, 10104, 10276, 10401, 10479, 10540, 10596, 10629, 10612, 10501, 10258, 9906, 9538, 9253, 9110, 9123, 9266, },
|
||||
/* LAT: 50 */ { 10802, 10923, 11124, 11393, 11716, 12070, 12424, 12740, 12961, 13019, 12880, 12582, 12218, 11873, 11599, 11413, 11321, 11319, 11386, 11490, 11604, 11720, 11837, 11953, 12071, 12194, 12308, 12380, 12371, 12245, 11998, 11670, 11330, 11045, 10855, 10775, 10802, },
|
||||
/* LAT: 60 */ { 12319, 12392, 12541, 12759, 13029, 13329, 13631, 13896, 14072, 14100, 13964, 13716, 13427, 13157, 12936, 12781, 12690, 12660, 12676, 12724, 12792, 12878, 12984, 13116, 13276, 13452, 13617, 13725, 13730, 13610, 13385, 13106, 12827, 12590, 12420, 12329, 12319, },
|
||||
/* LAT: 70 */ { 13758, 13800, 13894, 14036, 14215, 14418, 14626, 14807, 14911, 14893, 14757, 14556, 14339, 14135, 13962, 13827, 13733, 13679, 13660, 13673, 13715, 13787, 13891, 14028, 14195, 14382, 14566, 14706, 14752, 14679, 14518, 14319, 14125, 13960, 13840, 13771, 13758, },
|
||||
/* LAT: 80 */ { 14996, 15008, 15045, 15104, 15180, 15265, 15343, 15388, 15372, 15295, 15183, 15060, 14937, 14824, 14724, 14642, 14580, 14540, 14521, 14525, 14552, 14601, 14673, 14766, 14877, 15004, 15140, 15272, 15379, 15423, 15384, 15296, 15201, 15116, 15051, 15010, 14996, },
|
||||
/* LAT: 90 */ { 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, 15396, },
|
||||
};
|
||||
|
||||
// Magnetic strength data in milli-Gauss * 10
|
||||
// Model: WMM-2020,
|
||||
// Version: 0.5.1.11,
|
||||
// Date: 2022.4219,
|
||||
// Date: 2022.8137,
|
||||
static constexpr const int16_t strength_table[19][37] {
|
||||
// LONGITUDE: -180, -170, -160, -150, -140, -130, -120, -110, -100, -90, -80, -70, -60, -50, -40, -30, -20, -10, 0, 10, 20, 30, 40, 50, 60, 70, 80, 90, 100, 110, 120, 130, 140, 150, 160, 170, 180,
|
||||
/* LAT: -90 */ { 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, 5452, },
|
||||
/* LAT: -80 */ { 6058, 5995, 5916, 5824, 5721, 5610, 5492, 5370, 5248, 5128, 5014, 4908, 4815, 4735, 4672, 4627, 4602, 4600, 4622, 4668, 4738, 4832, 4946, 5078, 5222, 5371, 5521, 5664, 5795, 5909, 6002, 6071, 6115, 6135, 6130, 6104, 6058, },
|
||||
/* LAT: -70 */ { 6303, 6170, 6020, 5855, 5677, 5485, 5280, 5065, 4846, 4630, 4428, 4245, 4087, 3956, 3852, 3776, 3728, 3716, 3744, 3820, 3948, 4128, 4356, 4624, 4919, 5226, 5529, 5813, 6063, 6267, 6418, 6514, 6556, 6548, 6499, 6415, 6303, },
|
||||
/* LAT: -60 */ { 6188, 5996, 5795, 5586, 5368, 5133, 4877, 4598, 4306, 4016, 3749, 3522, 3342, 3207, 3108, 3035, 2984, 2964, 2990, 3080, 3248, 3500, 3826, 4212, 4634, 5068, 5489, 5873, 6198, 6447, 6610, 6689, 6691, 6628, 6515, 6364, 6188, },
|
||||
/* LAT: -50 */ { 5845, 5615, 5383, 5153, 4921, 4676, 4405, 4102, 3774, 3442, 3140, 2899, 2738, 2646, 2598, 2564, 2530, 2504, 2509, 2581, 2754, 3043, 3439, 3910, 4417, 4922, 5398, 5816, 6156, 6397, 6536, 6577, 6534, 6424, 6263, 6065, 5845, },
|
||||
/* LAT: -40 */ { 5394, 5148, 4904, 4664, 4430, 4193, 3938, 3655, 3341, 3014, 2716, 2493, 2375, 2349, 2368, 2390, 2395, 2383, 2371, 2399, 2529, 2803, 3220, 3733, 4280, 4804, 5272, 5660, 5953, 6140, 6229, 6232, 6162, 6032, 5851, 5633, 5394, },
|
||||
/* LAT: -30 */ { 4879, 4638, 4400, 4165, 3939, 3720, 3502, 3270, 3015, 2740, 2482, 2299, 2228, 2253, 2320, 2391, 2457, 2507, 2530, 2542, 2609, 2806, 3167, 3655, 4186, 4683, 5102, 5419, 5623, 5722, 5749, 5722, 5643, 5511, 5331, 5115, 4879, },
|
||||
/* LAT: -20 */ { 4321, 4109, 3901, 3696, 3500, 3317, 3149, 2985, 2808, 2610, 2419, 2285, 2243, 2286, 2375, 2486, 2614, 2742, 2832, 2868, 2893, 2988, 3226, 3610, 4059, 4486, 4835, 5071, 5176, 5184, 5154, 5107, 5025, 4897, 4731, 4534, 4321, },
|
||||
/* LAT: -10 */ { 3790, 3630, 3477, 3331, 3195, 3075, 2972, 2880, 2783, 2669, 2547, 2447, 2401, 2425, 2510, 2639, 2795, 2954, 3078, 3141, 3156, 3182, 3304, 3555, 3881, 4203, 4468, 4631, 4667, 4615, 4547, 4483, 4395, 4270, 4121, 3958, 3790, },
|
||||
/* LAT: 0 */ { 3412, 3319, 3236, 3163, 3108, 3070, 3044, 3025, 3001, 2954, 2875, 2780, 2699, 2667, 2708, 2811, 2943, 3079, 3194, 3270, 3301, 3323, 3397, 3553, 3762, 3975, 4155, 4262, 4268, 4201, 4113, 4021, 3909, 3777, 3643, 3520, 3412, },
|
||||
/* LAT: 10 */ { 3283, 3252, 3232, 3228, 3253, 3300, 3356, 3410, 3445, 3436, 3367, 3252, 3125, 3030, 3003, 3043, 3124, 3222, 3323, 3408, 3472, 3534, 3621, 3739, 3874, 4012, 4132, 4203, 4205, 4144, 4034, 3891, 3729, 3570, 3435, 3338, 3283, },
|
||||
/* LAT: 20 */ { 3399, 3403, 3429, 3483, 3575, 3697, 3826, 3943, 4025, 4037, 3964, 3822, 3655, 3514, 3438, 3425, 3460, 3532, 3628, 3725, 3816, 3914, 4025, 4136, 4245, 4356, 4458, 4524, 4535, 4477, 4340, 4138, 3911, 3702, 3539, 3438, 3399, },
|
||||
/* LAT: 30 */ { 3723, 3730, 3785, 3885, 4028, 4199, 4375, 4531, 4640, 4667, 4594, 4438, 4249, 4084, 3978, 3931, 3934, 3985, 4071, 4169, 4266, 4372, 4488, 4606, 4725, 4852, 4972, 5059, 5085, 5028, 4872, 4633, 4359, 4104, 3905, 3777, 3723, },
|
||||
/* LAT: 40 */ { 4222, 4221, 4286, 4410, 4578, 4765, 4949, 5105, 5210, 5236, 5168, 5019, 4832, 4657, 4528, 4452, 4426, 4448, 4508, 4587, 4673, 4770, 4885, 5018, 5169, 5331, 5482, 5592, 5631, 5578, 5422, 5185, 4911, 4651, 4441, 4296, 4222, },
|
||||
/* LAT: 50 */ { 4832, 4825, 4881, 4992, 5138, 5298, 5448, 5569, 5642, 5651, 5588, 5461, 5298, 5134, 4996, 4898, 4843, 4831, 4855, 4905, 4974, 5065, 5184, 5333, 5509, 5693, 5859, 5978, 6022, 5978, 5848, 5652, 5427, 5211, 5031, 4902, 4832, },
|
||||
/* LAT: 60 */ { 5392, 5380, 5409, 5472, 5558, 5652, 5739, 5805, 5838, 5829, 5775, 5681, 5560, 5431, 5312, 5216, 5149, 5115, 5113, 5140, 5196, 5282, 5400, 5547, 5714, 5882, 6030, 6134, 6178, 6156, 6074, 5947, 5801, 5658, 5536, 5445, 5392, },
|
||||
/* LAT: 70 */ { 5726, 5706, 5704, 5716, 5738, 5765, 5788, 5803, 5802, 5783, 5743, 5686, 5615, 5539, 5465, 5401, 5353, 5325, 5320, 5340, 5384, 5454, 5545, 5654, 5771, 5886, 5985, 6058, 6097, 6101, 6072, 6018, 5951, 5881, 5816, 5763, 5726, },
|
||||
/* LAT: 80 */ { 5789, 5772, 5758, 5746, 5736, 5726, 5716, 5705, 5690, 5671, 5649, 5624, 5597, 5569, 5545, 5524, 5510, 5505, 5510, 5525, 5551, 5586, 5629, 5676, 5726, 5774, 5817, 5851, 5876, 5889, 5891, 5884, 5870, 5851, 5830, 5809, 5789, },
|
||||
/* LAT: 90 */ { 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, 5681, },
|
||||
/* LAT: -90 */ { 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, 5450, },
|
||||
/* LAT: -80 */ { 6056, 5993, 5914, 5821, 5718, 5607, 5489, 5367, 5244, 5125, 5010, 4905, 4811, 4732, 4669, 4624, 4600, 4598, 4619, 4665, 4736, 4830, 4945, 5077, 5220, 5370, 5520, 5663, 5794, 5908, 6001, 6069, 6114, 6133, 6129, 6102, 6056, },
|
||||
/* LAT: -70 */ { 6301, 6167, 6017, 5852, 5673, 5481, 5276, 5061, 4842, 4627, 4424, 4242, 4084, 3953, 3849, 3773, 3726, 3713, 3742, 3818, 3946, 4127, 4356, 4624, 4919, 5226, 5530, 5814, 6063, 6267, 6418, 6514, 6555, 6547, 6497, 6413, 6301, },
|
||||
/* LAT: -60 */ { 6186, 5994, 5792, 5583, 5364, 5129, 4873, 4594, 4302, 4013, 3746, 3519, 3339, 3205, 3106, 3032, 2982, 2962, 2988, 3079, 3248, 3499, 3827, 4213, 4635, 5070, 5491, 5875, 6199, 6448, 6611, 6690, 6691, 6628, 6514, 6363, 6186, },
|
||||
/* LAT: -50 */ { 5843, 5613, 5381, 5150, 4917, 4672, 4402, 4099, 3770, 3438, 3136, 2897, 2735, 2644, 2596, 2562, 2528, 2501, 2506, 2579, 2753, 3044, 3440, 3912, 4419, 4925, 5400, 5819, 6157, 6399, 6537, 6577, 6534, 6424, 6262, 6064, 5843, },
|
||||
/* LAT: -40 */ { 5393, 5147, 4902, 4662, 4427, 4190, 3935, 3651, 3337, 3011, 2713, 2491, 2374, 2348, 2367, 2388, 2393, 2380, 2367, 2396, 2527, 2804, 3222, 3737, 4284, 4808, 5274, 5662, 5954, 6142, 6230, 6232, 6163, 6032, 5850, 5632, 5393, },
|
||||
/* LAT: -30 */ { 4878, 4637, 4398, 4163, 3937, 3718, 3499, 3268, 3012, 2737, 2479, 2297, 2227, 2252, 2319, 2390, 2455, 2505, 2526, 2539, 2606, 2806, 3170, 3659, 4190, 4687, 5105, 5421, 5624, 5723, 5750, 5723, 5643, 5511, 5331, 5115, 4878, },
|
||||
/* LAT: -20 */ { 4321, 4108, 3899, 3694, 3498, 3315, 3147, 2983, 2806, 2607, 2417, 2283, 2242, 2286, 2375, 2486, 2614, 2742, 2830, 2865, 2890, 2987, 3228, 3613, 4064, 4490, 4838, 5072, 5177, 5185, 5154, 5107, 5025, 4898, 4731, 4534, 4321, },
|
||||
/* LAT: -10 */ { 3790, 3629, 3476, 3329, 3194, 3074, 2970, 2878, 2781, 2666, 2544, 2445, 2400, 2424, 2511, 2640, 2796, 2954, 3077, 3139, 3154, 3181, 3305, 3558, 3884, 4206, 4470, 4632, 4667, 4615, 4547, 4484, 4396, 4271, 4122, 3958, 3790, },
|
||||
/* LAT: 0 */ { 3412, 3319, 3235, 3162, 3107, 3068, 3042, 3023, 2999, 2951, 2872, 2777, 2697, 2666, 2709, 2812, 2944, 3079, 3194, 3269, 3300, 3322, 3397, 3555, 3764, 3978, 4158, 4263, 4269, 4202, 4113, 4021, 3910, 3778, 3644, 3520, 3412, },
|
||||
/* LAT: 10 */ { 3283, 3251, 3231, 3227, 3252, 3299, 3354, 3407, 3442, 3432, 3363, 3249, 3122, 3028, 3002, 3043, 3124, 3223, 3323, 3408, 3472, 3534, 3622, 3741, 3877, 4015, 4135, 4205, 4207, 4145, 4035, 3892, 3730, 3571, 3435, 3339, 3283, },
|
||||
/* LAT: 20 */ { 3399, 3402, 3428, 3482, 3574, 3695, 3823, 3940, 4021, 4033, 3960, 3818, 3651, 3512, 3436, 3424, 3460, 3533, 3629, 3726, 3817, 3916, 4027, 4138, 4247, 4359, 4461, 4527, 4538, 4479, 4342, 4139, 3912, 3702, 3539, 3438, 3399, },
|
||||
/* LAT: 30 */ { 3723, 3729, 3783, 3882, 4025, 4196, 4372, 4528, 4636, 4662, 4589, 4434, 4245, 4081, 3976, 3931, 3934, 3985, 4073, 4171, 4268, 4374, 4491, 4608, 4728, 4855, 4976, 5062, 5088, 5030, 4874, 4634, 4360, 4106, 3906, 3778, 3723, },
|
||||
/* LAT: 40 */ { 4222, 4220, 4284, 4408, 4574, 4762, 4945, 5101, 5206, 5232, 5164, 5015, 4829, 4655, 4527, 4452, 4426, 4449, 4509, 4589, 4675, 4773, 4887, 5021, 5172, 5334, 5485, 5595, 5634, 5580, 5424, 5186, 4912, 4653, 4442, 4296, 4222, },
|
||||
/* LAT: 50 */ { 4832, 4824, 4879, 4989, 5135, 5294, 5444, 5565, 5639, 5648, 5585, 5458, 5296, 5132, 4995, 4898, 4843, 4832, 4857, 4907, 4976, 5067, 5186, 5337, 5512, 5696, 5863, 5980, 6024, 5980, 5849, 5653, 5428, 5213, 5033, 4903, 4832, },
|
||||
/* LAT: 60 */ { 5392, 5379, 5407, 5469, 5554, 5648, 5736, 5802, 5836, 5827, 5773, 5679, 5559, 5431, 5312, 5216, 5150, 5116, 5114, 5142, 5198, 5285, 5403, 5550, 5717, 5885, 6032, 6136, 6179, 6157, 6074, 5948, 5803, 5660, 5538, 5446, 5392, },
|
||||
/* LAT: 70 */ { 5726, 5706, 5702, 5714, 5736, 5762, 5786, 5800, 5800, 5782, 5743, 5686, 5616, 5540, 5466, 5402, 5354, 5326, 5322, 5342, 5387, 5456, 5548, 5656, 5773, 5888, 5987, 6059, 6099, 6102, 6073, 6020, 5953, 5882, 5817, 5764, 5726, },
|
||||
/* LAT: 80 */ { 5789, 5772, 5757, 5745, 5735, 5726, 5716, 5704, 5689, 5671, 5649, 5624, 5597, 5570, 5545, 5525, 5512, 5507, 5511, 5527, 5552, 5588, 5630, 5678, 5728, 5776, 5819, 5853, 5877, 5890, 5892, 5885, 5871, 5852, 5831, 5809, 5789, },
|
||||
/* LAT: 90 */ { 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, 5682, },
|
||||
};
|
||||
|
||||
File diff suppressed because it is too large
Load Diff
@@ -147,10 +147,10 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor
|
||||
*/
|
||||
reporter.armingCheckFailure(required_groups, health_component_t::local_position_estimate,
|
||||
events::ID("check_estimator_hor_vel_not_stable"),
|
||||
events::Log::Error, "Horizontal velocity estimate not stable");
|
||||
events::Log::Error, "Horizontal velocity unstable");
|
||||
|
||||
if (reporter.mavlink_log_pub()) {
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: horizontal velocity estimate not stable");
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: horizontal velocity unstable");
|
||||
}
|
||||
|
||||
} else if (!context.isArmed() && estimator_status.pre_flt_fail_innov_vel_vert) {
|
||||
@@ -158,10 +158,10 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor
|
||||
*/
|
||||
reporter.armingCheckFailure(required_groups, health_component_t::local_position_estimate,
|
||||
events::ID("check_estimator_vert_vel_not_stable"),
|
||||
events::Log::Error, "Vertical velocity estimate not stable");
|
||||
events::Log::Error, "Vertical velocity unstable");
|
||||
|
||||
if (reporter.mavlink_log_pub()) {
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: vertical velocity estimate not stable");
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: vertical velocity unstable");
|
||||
}
|
||||
|
||||
} else if (!context.isArmed() && estimator_status.pre_flt_fail_innov_height) {
|
||||
@@ -194,10 +194,10 @@ void EstimatorChecks::checkEstimatorStatus(const Context &context, Report &repor
|
||||
*/
|
||||
reporter.armingCheckFailure(required_groups_mag, health_component_t::local_position_estimate,
|
||||
events::ID("check_estimator_mag_interference"),
|
||||
events::Log::Warning, "Strong magnetic interference detected");
|
||||
events::Log::Warning, "Strong magnetic interference");
|
||||
|
||||
if (reporter.mavlink_log_pub()) {
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Strong magnetic interference detected");
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "Preflight Fail: Strong magnetic interference");
|
||||
}
|
||||
}
|
||||
|
||||
@@ -625,9 +625,9 @@ void EstimatorChecks::checkEstimatorStatusFlags(const Context &context, Report &
|
||||
* @description
|
||||
* Land and recalibrate the sensors.
|
||||
*/
|
||||
reporter.armingCheckFailure(NavModes::All, health_component_t::local_position_estimate,
|
||||
events::ID("check_estimator_nav_failure"),
|
||||
events::Log::Emergency, "Navigation failure");
|
||||
reporter.healthFailure(NavModes::All, health_component_t::local_position_estimate,
|
||||
events::ID("check_estimator_nav_failure"),
|
||||
events::Log::Emergency, "Navigation failure");
|
||||
|
||||
if (reporter.mavlink_log_pub()) {
|
||||
mavlink_log_critical(reporter.mavlink_log_pub(), "Navigation failure! Land and recalibrate sensors\t");
|
||||
|
||||
@@ -51,7 +51,7 @@ void Ekf::controlBaroHeightFusion()
|
||||
|
||||
if (_baro_buffer && _baro_buffer->pop_first_older_than(_imu_sample_delayed.time_us, &baro_sample)) {
|
||||
|
||||
const float measurement = baro_sample.hgt;
|
||||
const float measurement = compensateBaroForDynamicPressure(baro_sample.hgt);
|
||||
const float measurement_var = sq(_params.baro_noise);
|
||||
|
||||
const float innov_gate = fmaxf(_params.baro_innov_gate, 1.f);
|
||||
@@ -60,10 +60,10 @@ void Ekf::controlBaroHeightFusion()
|
||||
|
||||
if (measurement_valid) {
|
||||
if (_baro_counter == 0) {
|
||||
_baro_lpf.reset(baro_sample.hgt);
|
||||
_baro_lpf.reset(measurement);
|
||||
|
||||
} else {
|
||||
_baro_lpf.update(baro_sample.hgt);
|
||||
_baro_lpf.update(measurement);
|
||||
}
|
||||
|
||||
if (_baro_counter <= _obs_buffer_length) {
|
||||
|
||||
@@ -83,8 +83,7 @@ void Ekf::fuseDrag(const dragSample &drag_sample)
|
||||
// predicted specific forces
|
||||
// calculate relative wind velocity in earth frame and rotate into body frame
|
||||
const Vector3f rel_wind_earth(vn - vwn, ve - vwe, vd);
|
||||
const Dcmf earth_to_body = quatToInverseRotMat(_state.quat_nominal);
|
||||
const Vector3f rel_wind_body = earth_to_body * rel_wind_earth;
|
||||
const Vector3f rel_wind_body = _state.quat_nominal.rotateVectorInverse(rel_wind_earth);
|
||||
|
||||
// perform sequential fusion of XY specific forces
|
||||
for (uint8_t axis_index = 0; axis_index < 2; axis_index++) {
|
||||
|
||||
+10
-16
@@ -519,7 +519,6 @@ private:
|
||||
bool _mag_bias_observable{false}; ///< true when there is enough rotation to make magnetometer bias errors observable
|
||||
bool _yaw_angle_observable{false}; ///< true when there is enough horizontal acceleration to make yaw observable
|
||||
uint64_t _time_yaw_started{0}; ///< last system time in usec that a yaw rotation manoeuvre was detected
|
||||
uint8_t _num_bad_flight_yaw_events{0}; ///< number of times a bad heading has been detected in flight and required a yaw reset
|
||||
uint64_t _mag_use_not_inhibit_us{0}; ///< last system time in usec before magnetometer use was inhibited
|
||||
float _last_static_yaw{NAN}; ///< last yaw angle recorded when on ground motion checks were passing (rad)
|
||||
|
||||
@@ -696,20 +695,20 @@ private:
|
||||
// fuse single velocity and position measurement
|
||||
bool fuseVelPosHeight(const float innov, const float innov_var, const int obs_index);
|
||||
|
||||
void resetVelocityTo(const Vector3f &vel);
|
||||
void resetHorizontalVelocityTo(const Vector2f &new_horz_vel);
|
||||
void resetVerticalVelocityTo(float new_vert_vel, float new_vert_vel_var = NAN);
|
||||
void resetVelocityTo(const Vector3f &vel, const Vector3f &new_vel_var);
|
||||
|
||||
void resetHorizontalVelocityTo(const Vector2f &new_horz_vel, const Vector2f &new_horz_vel_var);
|
||||
void resetHorizontalVelocityTo(const Vector2f &new_horz_vel, float vel_var) { resetHorizontalVelocityTo(new_horz_vel, Vector2f(vel_var, vel_var)); }
|
||||
|
||||
void resetVelocityToGps(const gpsSample &gps_sample);
|
||||
void resetHorizontalVelocityToOpticalFlow(const flowSample &flow_sample);
|
||||
void resetVelocityToVision();
|
||||
void resetHorizontalVelocityToZero();
|
||||
|
||||
void resetHorizontalPositionToGps(const gpsSample &gps_sample);
|
||||
void resetVerticalVelocityTo(float new_vert_vel, float new_vert_vel_var);
|
||||
void resetHorizontalPositionToVision();
|
||||
void resetHorizontalPositionToOpticalFlow();
|
||||
void resetHorizontalPositionToLastKnown();
|
||||
void resetHorizontalPositionTo(const Vector2f &new_horz_pos);
|
||||
|
||||
void resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f &new_horz_pos_var);
|
||||
void resetHorizontalPositionTo(const Vector2f &new_horz_pos, const float pos_var = NAN) { resetHorizontalPositionTo(new_horz_pos, Vector2f(pos_var, pos_var)); }
|
||||
|
||||
bool isHeightResetRequired() const;
|
||||
|
||||
@@ -776,10 +775,6 @@ private:
|
||||
// return true if successful
|
||||
bool resetYawToEv();
|
||||
|
||||
// Do a forced re-alignment of the yaw angle to align with the horizontal velocity vector from the GPS.
|
||||
// It is used to align the yaw angle after launch or takeoff for fixed wing vehicle.
|
||||
bool realignYawGPS(const Vector3f &mag);
|
||||
|
||||
// Return the magnetic declination in radians to be used by the alignment and fusion processing
|
||||
float getMagDeclination();
|
||||
|
||||
@@ -864,7 +859,7 @@ private:
|
||||
// and a scalar innovation value
|
||||
void fuse(const Vector24f &K, float innovation);
|
||||
|
||||
float compensateBaroForDynamicPressure(float baro_alt_uncompensated) const override;
|
||||
float compensateBaroForDynamicPressure(float baro_alt_uncompensated) const;
|
||||
|
||||
// calculate the earth rotation vector from a given latitude
|
||||
Vector3f calcEarthRateNED(float lat_rad) const;
|
||||
@@ -899,7 +894,7 @@ private:
|
||||
|
||||
void runOnGroundYawReset();
|
||||
bool canResetMagHeading() const;
|
||||
void runInAirYawReset(const Vector3f &mag);
|
||||
void runInAirYawReset();
|
||||
|
||||
void selectMagAuto();
|
||||
void check3DMagFusionSuitability();
|
||||
@@ -1030,7 +1025,6 @@ private:
|
||||
void startAirspeedFusion();
|
||||
void stopAirspeedFusion();
|
||||
|
||||
void startGpsFusion(const gpsSample &gps_sample);
|
||||
void stopGpsFusion();
|
||||
void stopGpsPosFusion();
|
||||
void stopGpsVelFusion();
|
||||
|
||||
@@ -44,51 +44,11 @@
|
||||
#include <mathlib/mathlib.h>
|
||||
#include <cstdlib>
|
||||
|
||||
void Ekf::resetVelocityToGps(const gpsSample &gps_sample)
|
||||
{
|
||||
_information_events.flags.reset_vel_to_gps = true;
|
||||
ECL_INFO("reset velocity to GPS");
|
||||
resetVelocityTo(gps_sample.vel);
|
||||
P.uncorrelateCovarianceSetVariance<3>(4, sq(gps_sample.sacc));
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalVelocityToOpticalFlow(const flowSample &flow_sample)
|
||||
{
|
||||
_information_events.flags.reset_vel_to_flow = true;
|
||||
ECL_INFO("reset velocity to flow");
|
||||
// constrain height above ground to be above minimum possible
|
||||
const float heightAboveGndEst = fmaxf((_terrain_vpos - _state.pos(2)), _params.rng_gnd_clearance);
|
||||
|
||||
// calculate absolute distance from focal point to centre of frame assuming a flat earth
|
||||
const float range = heightAboveGndEst / _range_sensor.getCosTilt();
|
||||
|
||||
if ((range - _params.rng_gnd_clearance) > 0.3f) {
|
||||
// we should have reliable OF measurements so
|
||||
// calculate X and Y body relative velocities from OF measurements
|
||||
Vector3f vel_optflow_body;
|
||||
vel_optflow_body(0) = - range * _flow_compensated_XY_rad(1) / flow_sample.dt;
|
||||
vel_optflow_body(1) = range * _flow_compensated_XY_rad(0) / flow_sample.dt;
|
||||
vel_optflow_body(2) = 0.0f;
|
||||
|
||||
// rotate from body to earth frame
|
||||
const Vector3f vel_optflow_earth = _R_to_earth * vel_optflow_body;
|
||||
|
||||
resetHorizontalVelocityTo(Vector2f(vel_optflow_earth));
|
||||
|
||||
} else {
|
||||
resetHorizontalVelocityTo(Vector2f{0.f, 0.f});
|
||||
}
|
||||
|
||||
// reset the horizontal velocity variance using the optical flow noise variance
|
||||
P.uncorrelateCovarianceSetVariance<2>(4, sq(range) * calcOptFlowMeasVar(flow_sample));
|
||||
}
|
||||
|
||||
void Ekf::resetVelocityToVision()
|
||||
{
|
||||
_information_events.flags.reset_vel_to_vision = true;
|
||||
ECL_INFO("reset to vision velocity");
|
||||
resetVelocityTo(getVisionVelocityInEkfFrame());
|
||||
P.uncorrelateCovarianceSetVariance<3>(4, getVisionVelocityVarianceInEkfFrame());
|
||||
resetVelocityTo(getVisionVelocityInEkfFrame(), getVisionVelocityVarianceInEkfFrame());
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalVelocityToZero()
|
||||
@@ -96,21 +56,28 @@ void Ekf::resetHorizontalVelocityToZero()
|
||||
_information_events.flags.reset_vel_to_zero = true;
|
||||
ECL_INFO("reset velocity to zero");
|
||||
// Used when falling back to non-aiding mode of operation
|
||||
resetHorizontalVelocityTo(Vector2f{0.f, 0.f});
|
||||
P.uncorrelateCovarianceSetVariance<2>(4, 25.0f);
|
||||
resetHorizontalVelocityTo(Vector2f{0.f, 0.f}, 25.f);
|
||||
}
|
||||
|
||||
void Ekf::resetVelocityTo(const Vector3f &new_vel)
|
||||
void Ekf::resetVelocityTo(const Vector3f &new_vel, const Vector3f &new_vel_var)
|
||||
{
|
||||
resetHorizontalVelocityTo(Vector2f(new_vel));
|
||||
resetVerticalVelocityTo(new_vel(2));
|
||||
resetHorizontalVelocityTo(Vector2f(new_vel), Vector2f(new_vel_var(0), new_vel_var(1)));
|
||||
resetVerticalVelocityTo(new_vel(2), new_vel_var(2));
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalVelocityTo(const Vector2f &new_horz_vel)
|
||||
void Ekf::resetHorizontalVelocityTo(const Vector2f &new_horz_vel, const Vector2f &new_horz_vel_var)
|
||||
{
|
||||
const Vector2f delta_horz_vel = new_horz_vel - Vector2f(_state.vel);
|
||||
_state.vel.xy() = new_horz_vel;
|
||||
|
||||
if (PX4_ISFINITE(new_horz_vel_var(0))) {
|
||||
P.uncorrelateCovarianceSetVariance<1>(4, math::max(sq(0.01f), new_horz_vel_var(0)));
|
||||
}
|
||||
|
||||
if (PX4_ISFINITE(new_horz_vel_var(1))) {
|
||||
P.uncorrelateCovarianceSetVariance<1>(5, math::max(sq(0.01f), new_horz_vel_var(1)));
|
||||
}
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index].vel.xy() += delta_horz_vel;
|
||||
}
|
||||
@@ -148,14 +115,6 @@ void Ekf::resetVerticalVelocityTo(float new_vert_vel, float new_vert_vel_var)
|
||||
_time_last_ver_vel_fuse = _imu_sample_delayed.time_us;
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalPositionToGps(const gpsSample &gps_sample)
|
||||
{
|
||||
_information_events.flags.reset_pos_to_gps = true;
|
||||
ECL_INFO("reset position to GPS");
|
||||
resetHorizontalPositionTo(gps_sample.pos);
|
||||
P.uncorrelateCovarianceSetVariance<2>(7, sq(gps_sample.hacc));
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalPositionToVision()
|
||||
{
|
||||
_information_events.flags.reset_pos_to_vision = true;
|
||||
@@ -166,45 +125,33 @@ void Ekf::resetHorizontalPositionToVision()
|
||||
_ev_pos = _R_ev_to_ekf * _ev_sample_delayed.pos;
|
||||
}
|
||||
|
||||
resetHorizontalPositionTo(Vector2f(_ev_pos));
|
||||
P.uncorrelateCovarianceSetVariance<2>(7, _ev_sample_delayed.posVar.slice<2, 1>(0, 0));
|
||||
resetHorizontalPositionTo(Vector2f(_ev_pos), _ev_sample_delayed.posVar.slice<2, 1>(0, 0));
|
||||
|
||||
// let the next odometry update know that the previous value of states cannot be used to calculate the change in position
|
||||
_hpos_prev_available = false;
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalPositionToOpticalFlow()
|
||||
{
|
||||
_information_events.flags.reset_pos_to_last_known = true;
|
||||
|
||||
if (!_control_status.flags.in_air) {
|
||||
ECL_INFO("reset horizontal position to (0, 0)");
|
||||
// we are likely starting OF for the first time so reset the horizontal position
|
||||
resetHorizontalPositionTo(Vector2f(0.f, 0.f));
|
||||
|
||||
} else {
|
||||
ECL_INFO("reset horizontal position to last known");
|
||||
resetHorizontalPositionTo(_last_known_pos.xy());
|
||||
}
|
||||
|
||||
// estimate is relative to initial position in this mode, so we start with zero error.
|
||||
P.uncorrelateCovarianceSetVariance<2>(7, 0.0f);
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalPositionToLastKnown()
|
||||
{
|
||||
_information_events.flags.reset_pos_to_last_known = true;
|
||||
ECL_INFO("reset position to last known position");
|
||||
// Used when falling back to non-aiding mode of operation
|
||||
resetHorizontalPositionTo(_last_known_pos.xy());
|
||||
P.uncorrelateCovarianceSetVariance<2>(7, sq(_params.pos_noaid_noise));
|
||||
resetHorizontalPositionTo(_last_known_pos.xy(), sq(_params.pos_noaid_noise));
|
||||
}
|
||||
|
||||
void Ekf::resetHorizontalPositionTo(const Vector2f &new_horz_pos)
|
||||
void Ekf::resetHorizontalPositionTo(const Vector2f &new_horz_pos, const Vector2f &new_horz_pos_var)
|
||||
{
|
||||
const Vector2f delta_horz_pos{new_horz_pos - Vector2f{_state.pos}};
|
||||
_state.pos.xy() = new_horz_pos;
|
||||
|
||||
if (PX4_ISFINITE(new_horz_pos_var(0))) {
|
||||
P.uncorrelateCovarianceSetVariance<1>(7, math::max(sq(0.01f), new_horz_pos_var(0)));
|
||||
}
|
||||
|
||||
if (PX4_ISFINITE(new_horz_pos_var(1))) {
|
||||
P.uncorrelateCovarianceSetVariance<1>(8, math::max(sq(0.01f), new_horz_pos_var(1)));
|
||||
}
|
||||
|
||||
for (uint8_t index = 0; index < _output_buffer.get_length(); index++) {
|
||||
_output_buffer[index].pos.xy() += delta_horz_pos;
|
||||
}
|
||||
@@ -298,117 +245,6 @@ void Ekf::alignOutputFilter()
|
||||
_output_new = _output_buffer.get_newest();
|
||||
}
|
||||
|
||||
// Do a forced re-alignment of the yaw angle to align with the horizontal velocity vector from the GPS.
|
||||
// It is used to align the yaw angle after launch or takeoff for fixed wing vehicle only.
|
||||
bool Ekf::realignYawGPS(const Vector3f &mag)
|
||||
{
|
||||
const float gpsSpeed = sqrtf(sq(_gps_sample_delayed.vel(0)) + sq(_gps_sample_delayed.vel(1)));
|
||||
|
||||
// Need at least 5 m/s of GPS horizontal speed and
|
||||
// ratio of velocity error to velocity < 0.15 for a reliable alignment
|
||||
const bool gps_yaw_alignment_possible = (gpsSpeed > 5.0f) && (_gps_sample_delayed.sacc < (0.15f * gpsSpeed));
|
||||
|
||||
if (!gps_yaw_alignment_possible) {
|
||||
// attempt a normal alignment using the magnetometer
|
||||
return resetMagHeading();
|
||||
}
|
||||
|
||||
// check for excessive horizontal GPS velocity innovations
|
||||
const float gps_vel_test_ratio = fmaxf(_aid_src_gnss_vel.test_ratio[0], _aid_src_gnss_vel.test_ratio[1]);
|
||||
const bool badVelInnov = (gps_vel_test_ratio > 1.0f) && _control_status.flags.gps;
|
||||
|
||||
// calculate GPS course over ground angle
|
||||
const float gpsCOG = atan2f(_gps_sample_delayed.vel(1), _gps_sample_delayed.vel(0));
|
||||
|
||||
// calculate course yaw angle
|
||||
const float ekfCOG = atan2f(_state.vel(1), _state.vel(0));
|
||||
|
||||
// Check the EKF and GPS course over ground for consistency
|
||||
const float courseYawError = wrap_pi(gpsCOG - ekfCOG);
|
||||
|
||||
// If the angles disagree and horizontal GPS velocity innovations are large or no previous yaw alignment, we declare the magnetic yaw as bad
|
||||
const bool badYawErr = fabsf(courseYawError) > 0.5f;
|
||||
const bool badMagYaw = (badYawErr && badVelInnov);
|
||||
|
||||
if (badMagYaw) {
|
||||
_num_bad_flight_yaw_events++;
|
||||
}
|
||||
|
||||
// correct yaw angle using GPS ground course if compass yaw bad or yaw is previously not aligned
|
||||
if (badMagYaw || !_control_status.flags.yaw_align) {
|
||||
_warning_events.flags.bad_yaw_using_gps_course = true;
|
||||
ECL_WARN("bad yaw, using GPS course");
|
||||
|
||||
// declare the magnetometer as failed if a bad yaw has occurred more than once
|
||||
if (_control_status.flags.mag_aligned_in_flight && (_num_bad_flight_yaw_events >= 2)
|
||||
&& !_control_status.flags.mag_fault) {
|
||||
_warning_events.flags.stopping_mag_use = true;
|
||||
ECL_WARN("stopping mag use");
|
||||
_control_status.flags.mag_fault = true;
|
||||
}
|
||||
|
||||
// calculate new yaw estimate
|
||||
float yaw_new;
|
||||
|
||||
if (!_control_status.flags.mag_aligned_in_flight) {
|
||||
// This is our first flight alignment so we can assume that the recent change in velocity has occurred due to a
|
||||
// forward direction takeoff or launch and therefore the inertial and GPS ground course discrepancy is due to yaw error
|
||||
const float current_yaw = getEulerYaw(_R_to_earth);
|
||||
yaw_new = current_yaw + courseYawError;
|
||||
_control_status.flags.mag_aligned_in_flight = true;
|
||||
|
||||
} else if (_control_status.flags.wind) {
|
||||
// we have previously aligned yaw in-flight and have wind estimates so set the yaw such that the vehicle nose is
|
||||
// aligned with the wind relative GPS velocity vector
|
||||
yaw_new = atan2f((_gps_sample_delayed.vel(1) - _state.wind_vel(1)),
|
||||
(_gps_sample_delayed.vel(0) - _state.wind_vel(0)));
|
||||
|
||||
} else {
|
||||
// we don't have wind estimates, so align yaw to the GPS velocity vector
|
||||
yaw_new = atan2f(_gps_sample_delayed.vel(1), _gps_sample_delayed.vel(0));
|
||||
|
||||
}
|
||||
|
||||
// use the combined EKF and GPS speed variance to calculate a rough estimate of the yaw error after alignment
|
||||
const float SpdErrorVariance = sq(_gps_sample_delayed.sacc) + P(4, 4) + P(5, 5);
|
||||
const float sineYawError = math::constrain(sqrtf(SpdErrorVariance) / gpsSpeed, 0.0f, 1.0f);
|
||||
const float yaw_variance_new = sq(asinf(sineYawError));
|
||||
|
||||
// Apply updated yaw and yaw variance to states and covariances
|
||||
resetQuatStateYaw(yaw_new, yaw_variance_new);
|
||||
|
||||
// Use the last magnetometer measurements to reset the field states
|
||||
_state.mag_B.zero();
|
||||
_state.mag_I = _R_to_earth * mag;
|
||||
|
||||
resetMagCov();
|
||||
|
||||
// record the start time for the magnetic field alignment
|
||||
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
|
||||
|
||||
// If heading was bad, then we also need to reset the velocity and position states
|
||||
if (badMagYaw) {
|
||||
resetVelocityToGps(_gps_sample_delayed);
|
||||
resetHorizontalPositionToGps(_gps_sample_delayed);
|
||||
}
|
||||
|
||||
return true;
|
||||
|
||||
} else {
|
||||
// align mag states only
|
||||
|
||||
// calculate initial earth magnetic field states
|
||||
_state.mag_I = _R_to_earth * mag;
|
||||
|
||||
resetMagCov();
|
||||
|
||||
// record the start time for the magnetic field alignment
|
||||
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
|
||||
|
||||
return true;
|
||||
}
|
||||
}
|
||||
|
||||
// Reset heading and magnetic field states
|
||||
bool Ekf::resetMagHeading()
|
||||
{
|
||||
@@ -511,31 +347,36 @@ void Ekf::constrainStates()
|
||||
|
||||
float Ekf::compensateBaroForDynamicPressure(const float baro_alt_uncompensated) const
|
||||
{
|
||||
// calculate static pressure error = Pmeas - Ptruth
|
||||
// model position error sensitivity as a body fixed ellipse with a different scale in the positive and
|
||||
// negative X and Y directions. Used to correct baro data for positional errors
|
||||
const matrix::Dcmf R_to_body(_output_new.quat_nominal.inversed());
|
||||
if (_control_status.flags.wind && local_position_is_valid()) {
|
||||
// calculate static pressure error = Pmeas - Ptruth
|
||||
// model position error sensitivity as a body fixed ellipse with a different scale in the positive and
|
||||
// negative X and Y directions. Used to correct baro data for positional errors
|
||||
|
||||
// Calculate airspeed in body frame
|
||||
const Vector3f velocity_earth = _output_new.vel - _vel_imu_rel_body_ned;
|
||||
// Calculate airspeed in body frame
|
||||
const Vector3f vel_imu_rel_body_ned = _R_to_earth * (_ang_rate_delayed_raw % _params.imu_pos_body);
|
||||
const Vector3f velocity_earth = _state.vel - vel_imu_rel_body_ned;
|
||||
|
||||
const Vector3f wind_velocity_earth(_state.wind_vel(0), _state.wind_vel(1), 0.0f);
|
||||
const Vector3f wind_velocity_earth(_state.wind_vel(0), _state.wind_vel(1), 0.0f);
|
||||
|
||||
const Vector3f airspeed_earth = velocity_earth - wind_velocity_earth;
|
||||
const Vector3f airspeed_earth = velocity_earth - wind_velocity_earth;
|
||||
|
||||
const Vector3f airspeed_body = R_to_body * airspeed_earth;
|
||||
const Vector3f airspeed_body = _state.quat_nominal.rotateVectorInverse(airspeed_earth);
|
||||
|
||||
const Vector3f K_pstatic_coef(airspeed_body(0) >= 0.0f ? _params.static_pressure_coef_xp :
|
||||
_params.static_pressure_coef_xn,
|
||||
airspeed_body(1) >= 0.0f ? _params.static_pressure_coef_yp : _params.static_pressure_coef_yn,
|
||||
_params.static_pressure_coef_z);
|
||||
const Vector3f K_pstatic_coef(
|
||||
airspeed_body(0) >= 0.f ? _params.static_pressure_coef_xp : _params.static_pressure_coef_xn,
|
||||
airspeed_body(1) >= 0.f ? _params.static_pressure_coef_yp : _params.static_pressure_coef_yn,
|
||||
_params.static_pressure_coef_z);
|
||||
|
||||
const Vector3f airspeed_squared = matrix::min(airspeed_body.emult(airspeed_body), sq(_params.max_correction_airspeed));
|
||||
const Vector3f airspeed_squared = matrix::min(airspeed_body.emult(airspeed_body), sq(_params.max_correction_airspeed));
|
||||
|
||||
const float pstatic_err = 0.5f * _air_density * (airspeed_squared.dot(K_pstatic_coef));
|
||||
const float pstatic_err = 0.5f * _air_density * (airspeed_squared.dot(K_pstatic_coef));
|
||||
|
||||
// correct baro measurement using pressure error estimate and assuming sea level gravity
|
||||
return baro_alt_uncompensated + pstatic_err / (_air_density * CONSTANTS_ONE_G);
|
||||
// correct baro measurement using pressure error estimate and assuming sea level gravity
|
||||
return baro_alt_uncompensated + pstatic_err / (_air_density * CONSTANTS_ONE_G);
|
||||
}
|
||||
|
||||
// otherwise return the uncorrected baro measurement
|
||||
return baro_alt_uncompensated;
|
||||
}
|
||||
|
||||
// calculate the earth rotation vector
|
||||
@@ -1462,22 +1303,6 @@ void Ekf::stopAirspeedFusion()
|
||||
_control_status.flags.fuse_aspd = false;
|
||||
}
|
||||
|
||||
void Ekf::startGpsFusion(const gpsSample &gps_sample)
|
||||
{
|
||||
if (!_control_status.flags.gps) {
|
||||
resetHorizontalPositionToGps(gps_sample);
|
||||
|
||||
// when already using another velocity source velocity reset is not necessary
|
||||
if (!_control_status.flags.opt_flow && !_control_status.flags.ev_vel) {
|
||||
resetVelocityToGps(gps_sample);
|
||||
}
|
||||
|
||||
_information_events.flags.starting_gps_fusion = true;
|
||||
ECL_INFO("starting GPS fusion");
|
||||
_control_status.flags.gps = true;
|
||||
}
|
||||
}
|
||||
|
||||
void Ekf::stopGpsFusion()
|
||||
{
|
||||
if (_control_status.flags.gps) {
|
||||
|
||||
@@ -221,7 +221,7 @@ void EstimatorInterface::setBaroData(const baroSample &baro_sample)
|
||||
|
||||
baroSample baro_sample_new;
|
||||
baro_sample_new.time_us = time_us;
|
||||
baro_sample_new.hgt = compensateBaroForDynamicPressure(baro_sample.hgt);
|
||||
baro_sample_new.hgt = baro_sample.hgt;
|
||||
|
||||
_baro_buffer->push(baro_sample_new);
|
||||
_time_last_baro_buffer_push = _newest_high_rate_imu_sample.time_us;
|
||||
|
||||
@@ -396,8 +396,6 @@ protected:
|
||||
// this is the previous status of the filter control modes - used to detect mode transitions
|
||||
filter_control_status_u _control_status_prev{};
|
||||
|
||||
virtual float compensateBaroForDynamicPressure(const float baro_alt_uncompensated) const = 0;
|
||||
|
||||
// these are used to record single frame events for external monitoring and should NOT be used for
|
||||
// state logic becasue they will be cleared externally after being read.
|
||||
warning_event_status_u _warning_events{};
|
||||
|
||||
@@ -59,10 +59,11 @@ void Ekf::controlGpsFusion()
|
||||
controlGpsYawFusion(gps_sample, gps_checks_passing, gps_checks_failing);
|
||||
|
||||
// GNSS velocity
|
||||
const float vel_obs_var = sq(math::max(gps_sample.sacc, _params.gps_vel_noise));
|
||||
const float vel_var = sq(math::max(gps_sample.sacc, _params.gps_vel_noise));
|
||||
const Vector3f vel_obs_var(vel_var, vel_var, vel_var * sq(1.5f));
|
||||
updateVelocityAidSrcStatus(gps_sample.time_us,
|
||||
gps_sample.vel, // observation
|
||||
Vector3f(vel_obs_var, vel_obs_var, vel_obs_var * sq(1.5f)), // observation variance
|
||||
vel_obs_var, // observation variance
|
||||
math::max(_params.gps_vel_innov_gate, 1.f), // innovation gate
|
||||
_aid_src_gnss_vel);
|
||||
_aid_src_gnss_vel.fusion_enabled = (_params.gnss_ctrl & GnssCtrl::VEL);
|
||||
@@ -79,10 +80,11 @@ void Ekf::controlGpsFusion()
|
||||
}
|
||||
}
|
||||
|
||||
const float pos_obs_var = sq(pos_noise);
|
||||
const float pos_var = sq(pos_noise);
|
||||
const Vector2f pos_obs_var(pos_var, pos_var);
|
||||
updateHorizontalPositionAidSrcStatus(gps_sample.time_us,
|
||||
gps_sample.pos, // observation
|
||||
Vector2f(pos_obs_var, pos_obs_var), // observation variance
|
||||
pos_obs_var, // observation variance
|
||||
math::max(_params.gps_pos_innov_gate, 1.f), // innovation gate
|
||||
_aid_src_gnss_pos);
|
||||
_aid_src_gnss_pos.fusion_enabled = (_params.gnss_ctrl & GnssCtrl::HPOS);
|
||||
@@ -127,20 +129,13 @@ void Ekf::controlGpsFusion()
|
||||
if (resetYawToEKFGSF()) {
|
||||
ECL_WARN("GPS emergency yaw reset");
|
||||
}
|
||||
|
||||
} else {
|
||||
// use GPS velocity data to check and correct yaw angle if a FW vehicle
|
||||
if (_control_status.flags.fixed_wing && _control_status.flags.in_air) {
|
||||
// if flying a fixed wing aircraft, do a complete reset that includes yaw
|
||||
_mag_yaw_reset_req = true;
|
||||
}
|
||||
|
||||
_warning_events.flags.gps_fusion_timout = true;
|
||||
ECL_WARN("GPS fusion timeout - resetting");
|
||||
}
|
||||
|
||||
resetVelocityToGps(gps_sample);
|
||||
resetHorizontalPositionToGps(gps_sample);
|
||||
ECL_WARN("GPS fusion timeout, resetting velocity and position");
|
||||
_information_events.flags.reset_vel_to_gps = true;
|
||||
_information_events.flags.reset_pos_to_gps = true;
|
||||
resetVelocityTo(gps_sample.vel, vel_obs_var);
|
||||
resetHorizontalPositionTo(gps_sample.pos, pos_obs_var);
|
||||
}
|
||||
|
||||
} else {
|
||||
@@ -174,7 +169,20 @@ void Ekf::controlGpsFusion()
|
||||
_inhibit_ev_yaw_use = true;
|
||||
|
||||
} else {
|
||||
startGpsFusion(gps_sample);
|
||||
ECL_INFO("starting GPS fusion");
|
||||
_information_events.flags.starting_gps_fusion = true;
|
||||
|
||||
// reset position
|
||||
_information_events.flags.reset_pos_to_gps = true;
|
||||
resetHorizontalPositionTo(gps_sample.pos, pos_obs_var);
|
||||
|
||||
// when already using another velocity source velocity reset is not necessary
|
||||
if (!isHorizontalAidingActive()) {
|
||||
_information_events.flags.reset_vel_to_gps = true;
|
||||
resetVelocityTo(gps_sample.vel, vel_obs_var);
|
||||
}
|
||||
|
||||
_control_status.flags.gps = true;
|
||||
}
|
||||
|
||||
} else if (gps_checks_passing && !_control_status.flags.yaw_align && (_params.mag_fusion_type == MagFuseType::NONE)) {
|
||||
@@ -182,8 +190,12 @@ void Ekf::controlGpsFusion()
|
||||
if (resetYawToEKFGSF()) {
|
||||
_information_events.flags.yaw_aligned_to_imu_gps = true;
|
||||
ECL_INFO("Yaw aligned using IMU and GPS");
|
||||
resetVelocityToGps(gps_sample);
|
||||
resetHorizontalPositionToGps(gps_sample);
|
||||
|
||||
ECL_INFO("reset velocity and position to GPS");
|
||||
_information_events.flags.reset_vel_to_gps = true;
|
||||
_information_events.flags.reset_pos_to_gps = true;
|
||||
resetVelocityTo(gps_sample.vel, vel_obs_var);
|
||||
resetHorizontalPositionTo(gps_sample.pos, pos_obs_var);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@@ -80,9 +80,8 @@ void Ekf::controlMagFusion()
|
||||
|
||||
// compute magnetometer innovations (for estimator_aid_src_mag logging)
|
||||
// rotate magnetometer earth field state into body frame
|
||||
const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal);
|
||||
const Vector3f mag_I_rot = R_to_body * _state.mag_I;
|
||||
const Vector3f mag_innov = mag_I_rot - mag_observation;
|
||||
const Vector3f mag_I_body = _state.quat_nominal.rotateVectorInverse(_state.mag_I);
|
||||
const Vector3f mag_innov = mag_I_body - mag_observation;
|
||||
|
||||
resetEstimatorAidStatus(_aid_src_mag);
|
||||
_aid_src_mag.timestamp_sample = mag_sample.time_us;
|
||||
@@ -95,7 +94,6 @@ void Ekf::controlMagFusion()
|
||||
// re-initialised next time we achieve flight altitude
|
||||
if (!_control_status.flags.in_air) {
|
||||
_control_status.flags.mag_aligned_in_flight = false;
|
||||
_num_bad_flight_yaw_events = 0;
|
||||
}
|
||||
|
||||
if (_params.mag_fusion_type >= MagFuseType::NONE
|
||||
@@ -142,7 +140,7 @@ void Ekf::controlMagFusion()
|
||||
|
||||
if (_control_status.flags.in_air) {
|
||||
checkHaglYawResetReq();
|
||||
runInAirYawReset(mag_sample.mag);
|
||||
runInAirYawReset();
|
||||
|
||||
} else {
|
||||
runOnGroundYawReset();
|
||||
@@ -198,13 +196,43 @@ bool Ekf::canResetMagHeading() const
|
||||
return !_control_status.flags.mag_field_disturbed && (_params.mag_fusion_type != MagFuseType::NONE);
|
||||
}
|
||||
|
||||
void Ekf::runInAirYawReset(const Vector3f &mag_sample)
|
||||
void Ekf::runInAirYawReset()
|
||||
{
|
||||
if (_mag_yaw_reset_req && !_is_yaw_fusion_inhibited) {
|
||||
bool has_realigned_yaw = false;
|
||||
|
||||
if (_control_status.flags.gps && _control_status.flags.fixed_wing) {
|
||||
has_realigned_yaw = realignYawGPS(mag_sample);
|
||||
// use yaw estimator if available
|
||||
if (_control_status.flags.gps && isYawEmergencyEstimateAvailable() &&
|
||||
(_mag_counter != 0) && isNewestSampleRecent(_time_last_mag_buffer_push, 500'000) // mag LPF available
|
||||
) {
|
||||
|
||||
resetQuatStateYaw(_yawEstimator.getYaw(), _yawEstimator.getYawVar());
|
||||
|
||||
_information_events.flags.yaw_aligned_to_imu_gps = true;
|
||||
_ekfgsf_yaw_reset_time = _imu_sample_delayed.time_us;
|
||||
|
||||
// if world magnetic model (inclination, declination, strength) available then use it to reset mag states
|
||||
if (PX4_ISFINITE(_mag_inclination_gps) && PX4_ISFINITE(_mag_declination_gps) && PX4_ISFINITE(_mag_strength_gps)) {
|
||||
// use predicted earth field to reset states
|
||||
const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps, _mag_declination_gps)) * Vector3f(_mag_strength_gps, 0, 0);
|
||||
_state.mag_I = mag_earth_pred;
|
||||
|
||||
const Dcmf R_to_body = quatToInverseRotMat(_state.quat_nominal);
|
||||
_state.mag_B = _mag_lpf.getState() - (R_to_body * mag_earth_pred);
|
||||
|
||||
} else {
|
||||
// Use the last magnetometer measurements to reset the field states
|
||||
// calculate initial earth magnetic field states
|
||||
_state.mag_I = _R_to_earth * _mag_lpf.getState();
|
||||
_state.mag_B.zero();
|
||||
}
|
||||
|
||||
ECL_DEBUG("resetting mag I: [%.3f, %.3f, %.3f], B: [%.3f, %.3f, %.3f]",
|
||||
(double)_state.mag_I(0), (double)_state.mag_I(1), (double)_state.mag_I(2),
|
||||
(double)_state.mag_B(0), (double)_state.mag_B(1), (double)_state.mag_B(2)
|
||||
);
|
||||
|
||||
resetMagCov();
|
||||
}
|
||||
|
||||
if (!has_realigned_yaw && canResetMagHeading()) {
|
||||
@@ -216,6 +244,9 @@ void Ekf::runInAirYawReset(const Vector3f &mag_sample)
|
||||
_control_status.flags.yaw_align = true;
|
||||
_control_status.flags.mag_aligned_in_flight = true;
|
||||
|
||||
// record the time for the magnetic field alignment event
|
||||
_flt_mag_align_start_time = _imu_sample_delayed.time_us;
|
||||
|
||||
// Handle the special case where we have not been constraining yaw drift or learning yaw bias due
|
||||
// to assumed invalid mag field associated with indoor operation with a downwards looking flow sensor.
|
||||
if (_mag_inhibit_yaw_reset_req) {
|
||||
|
||||
@@ -47,6 +47,7 @@
|
||||
#include "python/ekf_derivation/generated/compute_mag_z_innov_var_and_h.h"
|
||||
#include "python/ekf_derivation/generated/compute_yaw_321_innov_var_and_h.h"
|
||||
#include "python/ekf_derivation/generated/compute_yaw_312_innov_var_and_h.h"
|
||||
#include "python/ekf_derivation/generated/compute_mag_declination_innov_innov_var_and_h.h"
|
||||
|
||||
#include <mathlib/mathlib.h>
|
||||
|
||||
@@ -333,63 +334,24 @@ bool Ekf::fuseYaw(const float innovation, const float variance, estimator_aid_so
|
||||
|
||||
bool Ekf::fuseDeclination(float decl_sigma)
|
||||
{
|
||||
// assign intermediate state variables
|
||||
const float magN = _state.mag_I(0);
|
||||
const float magE = _state.mag_I(1);
|
||||
|
||||
// minimum North field strength before calculation becomes badly conditioned (T)
|
||||
constexpr float N_field_min = 0.001f;
|
||||
|
||||
// observation variance (rad**2)
|
||||
const float R_DECL = sq(decl_sigma);
|
||||
|
||||
// Calculate intermediate variables
|
||||
if (fabsf(magN) < sq(N_field_min)) {
|
||||
// calculation is badly conditioned close to +-90 deg declination
|
||||
return false;
|
||||
}
|
||||
Vector24f H;
|
||||
float innovation;
|
||||
float innovation_variance;
|
||||
|
||||
const float HK0 = ecl::powf(magN, -2);
|
||||
const float HK1 = HK0*ecl::powf(magE, 2) + 1.0F;
|
||||
const float HK2 = 1.0F/HK1;
|
||||
const float HK3 = 1.0F/magN;
|
||||
const float HK4 = HK2*HK3;
|
||||
const float HK5 = HK3*magE;
|
||||
const float HK6 = HK5*P(16,17) - P(17,17);
|
||||
const float HK7 = ecl::powf(HK1, -2);
|
||||
const float HK8 = HK5*P(16,16) - P(16,17);
|
||||
const float innovation_variance = -HK0*HK6*HK7 + HK7*HK8*magE/ecl::powf(magN, 3) + R_DECL;
|
||||
float HK9;
|
||||
sym::ComputeMagDeclinationInnovInnovVarAndH(getStateAtFusionHorizonAsVector(), P, getMagDeclination(), R_DECL, FLT_EPSILON, &innovation, &innovation_variance, &H);
|
||||
|
||||
if (innovation_variance > R_DECL) {
|
||||
HK9 = HK4/innovation_variance;
|
||||
} else {
|
||||
if (innovation_variance < R_DECL) {
|
||||
// variance calculation is badly conditioned
|
||||
return false;
|
||||
}
|
||||
|
||||
// Calculate the observation Jacobian
|
||||
// Note only 2 terms are non-zero which can be used in matrix operations for calculation of Kalman gains and covariance update to significantly reduce cost
|
||||
// Note Hfusion indices do not match state indices
|
||||
SparseVector24f<16,17> Hfusion;
|
||||
Hfusion.at<16>() = -HK0*HK2*magE;
|
||||
Hfusion.at<17>() = HK4;
|
||||
SparseVector24f<16,17> Hfusion(H);
|
||||
|
||||
// Calculate the Kalman gains
|
||||
Vector24f Kfusion;
|
||||
|
||||
for (unsigned row = 0; row <= 15; row++) {
|
||||
Kfusion(row) = -HK9*(HK5*P(row,16) - P(row,17));
|
||||
}
|
||||
|
||||
Kfusion(16) = -HK8*HK9;
|
||||
Kfusion(17) = -HK6*HK9;
|
||||
|
||||
for (unsigned row = 18; row <= 23; row++) {
|
||||
Kfusion(row) = -HK9*(HK5*P(16,row) - P(17,row));
|
||||
}
|
||||
|
||||
const float innovation = math::constrain(atan2f(magE, magN) - getMagDeclination(), -0.5f, 0.5f);
|
||||
Vector24f Kfusion = P * Hfusion / innovation_variance;
|
||||
|
||||
const bool is_fused = measurementUpdate(Kfusion, Hfusion, innovation);
|
||||
|
||||
|
||||
@@ -77,11 +77,12 @@ void Ekf::controlOpticalFlowFusion()
|
||||
_delta_time_of = _imu_sample_delayed.delta_ang_dt;
|
||||
|
||||
is_delta_time_good = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (is_quality_good && !is_delta_time_good) {
|
||||
ECL_DEBUG("Optical flow: bad delta time: OF dt %.6f s (min: %.3f, max: %.3f), IMU dt %.6f s",
|
||||
(double)_flow_sample_delayed.dt, (double)delta_time_min, (double)delta_time_max, (double)_imu_sample_delayed.delta_ang_dt);
|
||||
(double)_flow_sample_delayed.dt, (double)delta_time_min, (double)delta_time_max,
|
||||
(double)_imu_sample_delayed.delta_ang_dt);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -166,12 +167,25 @@ void Ekf::controlOpticalFlowFusion()
|
||||
|
||||
// if we are not using GPS or external vision aiding, then the velocity and position states and covariances need to be set
|
||||
if (!isHorizontalAidingActive()) {
|
||||
resetHorizontalVelocityToOpticalFlow(_flow_sample_delayed);
|
||||
resetHorizontalPositionToOpticalFlow();
|
||||
ECL_INFO("reset velocity to flow");
|
||||
_information_events.flags.reset_vel_to_flow = true;
|
||||
resetHorizontalVelocityTo(_flow_vel_ne, calcOptFlowMeasVar(_flow_sample_delayed));
|
||||
|
||||
// reset position, estimate is relative to initial position in this mode, so we start with zero error
|
||||
if (!_control_status.flags.in_air) {
|
||||
ECL_INFO("reset position to zero");
|
||||
resetHorizontalPositionTo(Vector2f(0.f, 0.f), 0.f);
|
||||
_last_known_pos.xy() = _state.pos.xy();
|
||||
|
||||
} else {
|
||||
_information_events.flags.reset_pos_to_last_known = true;
|
||||
ECL_INFO("reset position to last known position");
|
||||
resetHorizontalPositionTo(_last_known_pos.xy(), 0.f);
|
||||
}
|
||||
}
|
||||
|
||||
_control_status.flags.opt_flow = true;
|
||||
_aid_src_optical_flow.time_last_fuse = _imu_sample_delayed.time_us;
|
||||
_control_status.flags.opt_flow = true;
|
||||
|
||||
return;
|
||||
}
|
||||
@@ -190,11 +204,19 @@ void Ekf::controlOpticalFlowFusion()
|
||||
}
|
||||
|
||||
// handle the case when we have optical flow, are reliant on it, but have not been using it for an extended period
|
||||
if (isTimedOut(_aid_src_optical_flow.time_last_fuse, _params.reset_timeout_max)
|
||||
if (isTimedOut(_aid_src_optical_flow.time_last_fuse, _params.no_aid_timeout_max)
|
||||
&& !isOtherSourceOfHorizontalAidingThan(_control_status.flags.opt_flow)) {
|
||||
|
||||
resetHorizontalVelocityToOpticalFlow(_flow_sample_delayed);
|
||||
resetHorizontalPositionToOpticalFlow();
|
||||
ECL_INFO("reset velocity to flow");
|
||||
_information_events.flags.reset_vel_to_flow = true;
|
||||
resetHorizontalVelocityTo(_flow_vel_ne, calcOptFlowMeasVar(_flow_sample_delayed));
|
||||
|
||||
// reset position, estimate is relative to initial position in this mode, so we start with zero error
|
||||
ECL_INFO("reset position to last known");
|
||||
_information_events.flags.reset_pos_to_last_known = true;
|
||||
resetHorizontalPositionTo(_last_known_pos.xy(), 0.f);
|
||||
|
||||
_aid_src_optical_flow.time_last_fuse = _imu_sample_delayed.time_us;
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -321,6 +321,22 @@ def compute_yaw_312_innov_var_and_h_alternate(
|
||||
|
||||
return (innov_var, H.T)
|
||||
|
||||
def compute_mag_declination_innov_innov_var_and_h(
|
||||
state: VState,
|
||||
P: MState,
|
||||
meas: sf.Scalar,
|
||||
R: sf.Scalar,
|
||||
epsilon: sf.Scalar
|
||||
) -> (sf.Scalar, VState):
|
||||
|
||||
meas_pred = sf.atan2(state[State.iy], state[State.ix], epsilon=epsilon)
|
||||
innov = meas_pred - meas
|
||||
|
||||
H = sf.V1(meas_pred).jacobian(state)
|
||||
innov_var = (H * P * H.T + R)[0,0]
|
||||
|
||||
return (innov, innov_var, H.T)
|
||||
|
||||
print("Derive EKF2 equations...")
|
||||
generate_px4_function(compute_airspeed_innov_and_innov_var, output_names=["innov", "innov_var"])
|
||||
generate_px4_function(compute_airspeed_h_and_k, output_names=["H", "K"])
|
||||
@@ -335,3 +351,4 @@ generate_px4_function(compute_yaw_321_innov_var_and_h, output_names=["innov_var"
|
||||
generate_px4_function(compute_yaw_321_innov_var_and_h_alternate, output_names=["innov_var", "H"])
|
||||
generate_px4_function(compute_yaw_312_innov_var_and_h, output_names=["innov_var", "H"])
|
||||
generate_px4_function(compute_yaw_312_innov_var_and_h_alternate, output_names=["innov_var", "H"])
|
||||
generate_px4_function(compute_mag_declination_innov_innov_var_and_h, output_names=["innov", "innov_var", "H"])
|
||||
|
||||
+74
@@ -0,0 +1,74 @@
|
||||
// -----------------------------------------------------------------------------
|
||||
// This file was autogenerated by symforce from template:
|
||||
// backends/cpp/templates/function/FUNCTION.h.jinja
|
||||
// Do NOT modify by hand.
|
||||
// -----------------------------------------------------------------------------
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <matrix/math.hpp>
|
||||
|
||||
namespace sym {
|
||||
|
||||
/**
|
||||
* This function was autogenerated from a symbolic function. Do not modify by hand.
|
||||
*
|
||||
* Symbolic function: compute_mag_declination_innov_innov_var_and_h
|
||||
*
|
||||
* Args:
|
||||
* state: Matrix24_1
|
||||
* P: Matrix24_24
|
||||
* meas: Scalar
|
||||
* R: Scalar
|
||||
* epsilon: Scalar
|
||||
*
|
||||
* Outputs:
|
||||
* innov: Scalar
|
||||
* innov_var: Scalar
|
||||
* H: Matrix24_1
|
||||
*/
|
||||
template <typename Scalar>
|
||||
void ComputeMagDeclinationInnovInnovVarAndH(const matrix::Matrix<Scalar, 24, 1>& state,
|
||||
const matrix::Matrix<Scalar, 24, 24>& P,
|
||||
const Scalar meas, const Scalar R, const Scalar epsilon,
|
||||
Scalar* const innov = nullptr,
|
||||
Scalar* const innov_var = nullptr,
|
||||
matrix::Matrix<Scalar, 24, 1>* const H = nullptr) {
|
||||
// Total ops: 23
|
||||
|
||||
// Input arrays
|
||||
|
||||
// Intermediate terms (4)
|
||||
const Scalar _tmp0 =
|
||||
epsilon * ((((state(16, 0)) > 0) - ((state(16, 0)) < 0)) + Scalar(0.5)) + state(16, 0);
|
||||
const Scalar _tmp1 =
|
||||
Scalar(1.0) / (std::pow(_tmp0, Scalar(2)) + std::pow(state(17, 0), Scalar(2)));
|
||||
const Scalar _tmp2 = _tmp1 * state(17, 0);
|
||||
const Scalar _tmp3 = _tmp0 * _tmp1;
|
||||
|
||||
// Output terms (3)
|
||||
if (innov != nullptr) {
|
||||
Scalar& _innov = (*innov);
|
||||
|
||||
_innov = -meas + std::atan2(state(17, 0), _tmp0);
|
||||
}
|
||||
|
||||
if (innov_var != nullptr) {
|
||||
Scalar& _innov_var = (*innov_var);
|
||||
|
||||
_innov_var = R - _tmp2 * (-P(16, 16) * _tmp2 + P(17, 16) * _tmp3) +
|
||||
_tmp3 * (-P(16, 17) * _tmp2 + P(17, 17) * _tmp3);
|
||||
}
|
||||
|
||||
if (H != nullptr) {
|
||||
matrix::Matrix<Scalar, 24, 1>& _H = (*H);
|
||||
|
||||
_H.setZero();
|
||||
|
||||
_H(16, 0) = -_tmp2;
|
||||
_H(17, 0) = _tmp3;
|
||||
}
|
||||
} // NOLINT(readability/fn_size)
|
||||
|
||||
// NOLINTNEXTLINE(readability/fn_size)
|
||||
} // namespace sym
|
||||
-227
@@ -1,227 +0,0 @@
|
||||
#include <math.h>
|
||||
#include <stdio.h>
|
||||
#include <cstdlib>
|
||||
#include "../../../../../matrix/matrix/math.hpp"
|
||||
|
||||
typedef matrix::Vector<float, 24> Vector24f;
|
||||
typedef matrix::SquareMatrix<float, 24> SquareMatrix24f;
|
||||
|
||||
float sq(float in) {
|
||||
return in * in;
|
||||
}
|
||||
|
||||
int main()
|
||||
{
|
||||
// Compare calculation of observation Jacobians and Kalman gains for sympy and matlab generated equations
|
||||
|
||||
float Hfusion[24] = {};
|
||||
Vector24f H_DECL;
|
||||
Vector24f Kfusion;
|
||||
float decl_innov_var;
|
||||
|
||||
const float R_DECL = sq(0.3f);
|
||||
|
||||
const float _gps_yaw_offset = 1.5f;
|
||||
|
||||
// quaternion inputs must be normalised
|
||||
float q0 = 2.0f * ((float)rand() - 0.5f);
|
||||
float q1 = 2.0f * ((float)rand() - 0.5f);
|
||||
float q2 = 2.0f * ((float)rand() - 0.5f);
|
||||
float q3 = 2.0f * ((float)rand() - 0.5f);
|
||||
const float length = sqrtf(sq(q0) + sq(q1) + sq(q2) + sq(q3));
|
||||
q0 /= length;
|
||||
q1 /= length;
|
||||
q2 /= length;
|
||||
q3 /= length;
|
||||
|
||||
const float magN = 0.04f;
|
||||
const float magE = -0.03f;
|
||||
|
||||
const float h_field_min = 1e-3f;
|
||||
|
||||
// create a symmetrical positive dfinite matrix with off diagonals between -1 and 1 and diagonals between 0 and 1
|
||||
SquareMatrix24f P;
|
||||
for (int col=0; col<=23; col++) {
|
||||
for (int row=0; row<=col; row++) {
|
||||
if (row == col) {
|
||||
P(row,col) = (float)rand();
|
||||
} else {
|
||||
P(col,row) = P(row,col) = 2.0f * ((float)rand() - 0.5f);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// First calculate observationjacobians and Kalman gains using sympy generated equations
|
||||
|
||||
// Calculate intermediate variables
|
||||
const float magN_sq = sq(magN);
|
||||
if (magN_sq < sq(h_field_min)) {
|
||||
printf("bad numerical conditioning\n");
|
||||
return 0;
|
||||
}
|
||||
const float HK0 = 1.0F / magN_sq;
|
||||
const float HK1 = HK0*sq(magE) + 1.0F;
|
||||
const float HK2 = 1.0F/HK1;
|
||||
const float HK3 = 1.0F/magN;
|
||||
const float HK4 = HK2*HK3;
|
||||
const float HK5 = HK3*magE;
|
||||
const float HK6 = HK5*P(16,17) - P(17,17);
|
||||
const float HK7 = 1.0F/sq(HK1);
|
||||
const float HK8 = HK5*P(16,16) - P(16,17);
|
||||
const float innovation_variance = -HK0*HK6*HK7 + HK7*HK8*magE/(magN * magN_sq) + R_DECL;
|
||||
float HK9;
|
||||
if (innovation_variance > R_DECL) {
|
||||
HK9 = HK4/innovation_variance;
|
||||
} else {
|
||||
printf("bad numerical conditioning\n");
|
||||
}
|
||||
|
||||
// Calculate the observation Jacobian
|
||||
// Note only 2 terms are non-zero which can be used in matrix operations for calculation of Kalman gains and covariance update to significantly reduce cost
|
||||
Hfusion[16] = -HK0*HK2*magE;
|
||||
Hfusion[17] = HK4;
|
||||
|
||||
// Calculate the Kalman gains
|
||||
for (unsigned row = 0; row <= 15; row++) {
|
||||
Kfusion(row) = -HK9*(HK5*P(row,16) - P(row,17));
|
||||
}
|
||||
|
||||
Kfusion(16) = -HK8*HK9;
|
||||
Kfusion(17) = -HK6*HK9;
|
||||
|
||||
for (unsigned row = 18; row <= 23; row++) {
|
||||
Kfusion(row) = -HK9*(HK5*P(16,row) - P(17,row));
|
||||
}
|
||||
|
||||
// save output and repeat calculation using legacy matlab generated code
|
||||
float Hfusion_sympy[24];
|
||||
Vector24f Kfusion_sympy;
|
||||
for (int row=0; row<24; row++) {
|
||||
Hfusion_sympy[row] = Hfusion[row];
|
||||
Kfusion_sympy(row) = Kfusion(row);
|
||||
}
|
||||
|
||||
// repeat calculation using matlab generated equations
|
||||
// Calculate intermediate variables
|
||||
float t2 = magE*magE;
|
||||
float t3 = magN*magN;
|
||||
float t4 = t2+t3;
|
||||
// if the horizontal magnetic field is too small, this calculation will be badly conditioned
|
||||
if (t4 < h_field_min*h_field_min) {
|
||||
printf("bad numerical conditioning\n");
|
||||
return 0;
|
||||
}
|
||||
float t5 = P(16,16)*t2;
|
||||
float t6 = P(17,17)*t3;
|
||||
float t7 = t2*t2;
|
||||
float t8 = R_DECL*t7;
|
||||
float t9 = t3*t3;
|
||||
float t10 = R_DECL*t9;
|
||||
float t11 = R_DECL*t2*t3*2.0f;
|
||||
float t14 = P(16,17)*magE*magN;
|
||||
float t15 = P(17,16)*magE*magN;
|
||||
float t12 = t5+t6+t8+t10+t11-t14-t15;
|
||||
float t13;
|
||||
if (fabsf(t12) > 1e-6f) {
|
||||
t13 = 1.0f / t12;
|
||||
} else {
|
||||
printf("bad numerical conditioning\n");
|
||||
return 0;
|
||||
}
|
||||
float t18 = magE*magE;
|
||||
float t19 = magN*magN;
|
||||
float t20 = t18+t19;
|
||||
float t21;
|
||||
if (fabsf(t20) > 1e-6f) {
|
||||
t21 = 1.0f/t20;
|
||||
} else {
|
||||
printf("bad numerical conditioning\n");
|
||||
return 0;
|
||||
}
|
||||
|
||||
// Calculate the observation Jacobian
|
||||
// Note only 2 terms are non-zero which can be used in matrix operations for calculation of Kalman gains and covariance update to significantly reduce cost
|
||||
memset(&H_DECL, 0, sizeof(H_DECL));
|
||||
H_DECL(16) = -magE*t21;
|
||||
H_DECL(17) = magN*t21;
|
||||
|
||||
// Calculate the Kalman gains
|
||||
Kfusion(0) = -t4*t13*(P(0,16)*magE-P(0,17)*magN);
|
||||
Kfusion(1) = -t4*t13*(P(1,16)*magE-P(1,17)*magN);
|
||||
Kfusion(2) = -t4*t13*(P(2,16)*magE-P(2,17)*magN);
|
||||
Kfusion(3) = -t4*t13*(P(3,16)*magE-P(3,17)*magN);
|
||||
Kfusion(4) = -t4*t13*(P(4,16)*magE-P(4,17)*magN);
|
||||
Kfusion(5) = -t4*t13*(P(5,16)*magE-P(5,17)*magN);
|
||||
Kfusion(6) = -t4*t13*(P(6,16)*magE-P(6,17)*magN);
|
||||
Kfusion(7) = -t4*t13*(P(7,16)*magE-P(7,17)*magN);
|
||||
Kfusion(8) = -t4*t13*(P(8,16)*magE-P(8,17)*magN);
|
||||
Kfusion(9) = -t4*t13*(P(9,16)*magE-P(9,17)*magN);
|
||||
Kfusion(10) = -t4*t13*(P(10,16)*magE-P(10,17)*magN);
|
||||
Kfusion(11) = -t4*t13*(P(11,16)*magE-P(11,17)*magN);
|
||||
Kfusion(12) = -t4*t13*(P(12,16)*magE-P(12,17)*magN);
|
||||
Kfusion(13) = -t4*t13*(P(13,16)*magE-P(13,17)*magN);
|
||||
Kfusion(14) = -t4*t13*(P(14,16)*magE-P(14,17)*magN);
|
||||
Kfusion(15) = -t4*t13*(P(15,16)*magE-P(15,17)*magN);
|
||||
Kfusion(16) = -t4*t13*(P(16,16)*magE-P(16,17)*magN);
|
||||
Kfusion(17) = -t4*t13*(P(17,16)*magE-P(17,17)*magN);
|
||||
Kfusion(18) = -t4*t13*(P(18,16)*magE-P(18,17)*magN);
|
||||
Kfusion(19) = -t4*t13*(P(19,16)*magE-P(19,17)*magN);
|
||||
Kfusion(20) = -t4*t13*(P(20,16)*magE-P(20,17)*magN);
|
||||
Kfusion(21) = -t4*t13*(P(21,16)*magE-P(21,17)*magN);
|
||||
Kfusion(22) = -t4*t13*(P(22,16)*magE-P(22,17)*magN);
|
||||
Kfusion(23) = -t4*t13*(P(23,16)*magE-P(23,17)*magN);
|
||||
|
||||
// find largest observation variance difference as a fraction of the matlab value
|
||||
float max_diff_fraction = 0.0f;
|
||||
int max_row;
|
||||
float max_old, max_new;
|
||||
for (int row=0; row<24; row++) {
|
||||
float diff_fraction;
|
||||
if (H_DECL(row) != 0.0f) {
|
||||
diff_fraction = fabsf(Hfusion_sympy[row] - H_DECL(row)) / fabsf(H_DECL(row));
|
||||
} else if (Hfusion_sympy[row] != 0.0f) {
|
||||
diff_fraction = fabsf(Hfusion_sympy[row] - H_DECL(row)) / fabsf(Hfusion_sympy[row]);
|
||||
} else {
|
||||
diff_fraction = 0.0f;
|
||||
}
|
||||
if (diff_fraction > max_diff_fraction) {
|
||||
max_diff_fraction = diff_fraction;
|
||||
max_row = row;
|
||||
max_old = H_DECL(row);
|
||||
max_new = Hfusion_sympy[row];
|
||||
}
|
||||
}
|
||||
|
||||
if (max_diff_fraction > 1e-5f) {
|
||||
printf("Fail: Mag Declination Hfusion max diff fraction = %e , old = %e , new = %e , location index = %i\n",max_diff_fraction, max_old, max_new, max_row);
|
||||
} else {
|
||||
printf("Pass: Mag Declination Hfusion max diff fraction = %e\n",max_diff_fraction);
|
||||
}
|
||||
|
||||
// find largest Kalman gain difference as a fraction of the matlab value
|
||||
max_diff_fraction = 0.0f;
|
||||
for (int row=0; row<4; row++) {
|
||||
float diff_fraction;
|
||||
if (Kfusion(row) != 0.0f) {
|
||||
diff_fraction = fabsf(Kfusion_sympy(row) - Kfusion(row)) / fabsf(Kfusion(row));
|
||||
} else if (Kfusion_sympy(row) != 0.0f) {
|
||||
diff_fraction = fabsf(Kfusion_sympy(row) - Kfusion(row)) / fabsf(Kfusion_sympy(row));
|
||||
} else {
|
||||
diff_fraction = 0.0f;
|
||||
}
|
||||
if (diff_fraction > max_diff_fraction) {
|
||||
max_diff_fraction = diff_fraction;
|
||||
max_row = row;
|
||||
max_old = Kfusion(row);
|
||||
max_new = Kfusion_sympy(row);
|
||||
}
|
||||
}
|
||||
|
||||
if (max_diff_fraction > 1e-5f) {
|
||||
printf("Fail: Mag Declination Kfusion max diff fraction = %e , old = %e , new = %e , location index = %i\n",max_diff_fraction, max_old, max_new, max_row);
|
||||
} else {
|
||||
printf("Pass: Mag Declination Kfusion max diff fraction = %e\n",max_diff_fraction);
|
||||
}
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -1,51 +0,0 @@
|
||||
// Sub Expressions
|
||||
const float HK0 = 1.0F/((magN)*(magN));
|
||||
const float HK1 = HK0*(magE)*(magE) + 1;
|
||||
const float HK2 = 1.0F/(HK1);
|
||||
const float HK3 = 1.0F/(magN);
|
||||
const float HK4 = HK2*HK3;
|
||||
const float HK5 = HK3*magE;
|
||||
const float HK6 = HK5*P(16,17) - P(17,17);
|
||||
const float HK7 = 1.0F/((HK1)*(HK1));
|
||||
const float HK8 = HK5*P(16,16) - P(16,17);
|
||||
const float HK9 = HK4/(-HK0*HK6*HK7 + HK7*HK8*magE/ecl::powf(magN, 3) + R_DECL);
|
||||
|
||||
|
||||
// Observation Jacobians
|
||||
Hfusion.at<16>() = -HK0*HK2*magE;
|
||||
Hfusion.at<17>() = HK4;
|
||||
|
||||
|
||||
// Kalman gains
|
||||
Kfusion(0) = -HK9*(HK5*P(0,16) - P(0,17));
|
||||
Kfusion(1) = -HK9*(HK5*P(1,16) - P(1,17));
|
||||
Kfusion(2) = -HK9*(HK5*P(2,16) - P(2,17));
|
||||
Kfusion(3) = -HK9*(HK5*P(3,16) - P(3,17));
|
||||
Kfusion(4) = -HK9*(HK5*P(4,16) - P(4,17));
|
||||
Kfusion(5) = -HK9*(HK5*P(5,16) - P(5,17));
|
||||
Kfusion(6) = -HK9*(HK5*P(6,16) - P(6,17));
|
||||
Kfusion(7) = -HK9*(HK5*P(7,16) - P(7,17));
|
||||
Kfusion(8) = -HK9*(HK5*P(8,16) - P(8,17));
|
||||
Kfusion(9) = -HK9*(HK5*P(9,16) - P(9,17));
|
||||
Kfusion(10) = -HK9*(HK5*P(10,16) - P(10,17));
|
||||
Kfusion(11) = -HK9*(HK5*P(11,16) - P(11,17));
|
||||
Kfusion(12) = -HK9*(HK5*P(12,16) - P(12,17));
|
||||
Kfusion(13) = -HK9*(HK5*P(13,16) - P(13,17));
|
||||
Kfusion(14) = -HK9*(HK5*P(14,16) - P(14,17));
|
||||
Kfusion(15) = -HK9*(HK5*P(15,16) - P(15,17));
|
||||
Kfusion(16) = -HK8*HK9;
|
||||
Kfusion(17) = -HK6*HK9;
|
||||
Kfusion(18) = -HK9*(HK5*P(16,18) - P(17,18));
|
||||
Kfusion(19) = -HK9*(HK5*P(16,19) - P(17,19));
|
||||
Kfusion(20) = -HK9*(HK5*P(16,20) - P(17,20));
|
||||
Kfusion(21) = -HK9*(HK5*P(16,21) - P(17,21));
|
||||
Kfusion(22) = -HK9*(HK5*P(16,22) - P(17,22));
|
||||
Kfusion(23) = -HK9*(HK5*P(16,23) - P(17,23));
|
||||
|
||||
|
||||
// Predicted observation
|
||||
|
||||
|
||||
// Innovation variance
|
||||
|
||||
|
||||
@@ -50,6 +50,7 @@ px4_add_unit_gtest(SRC test_EKF_height_fusion.cpp LINKLIBS ecl_EKF ecl_sensor_si
|
||||
px4_add_unit_gtest(SRC test_EKF_imuSampling.cpp LINKLIBS ecl_EKF ecl_sensor_sim)
|
||||
px4_add_unit_gtest(SRC test_EKF_initialization.cpp LINKLIBS ecl_EKF ecl_sensor_sim)
|
||||
px4_add_unit_gtest(SRC test_EKF_mag_3d_fusion_generated.cpp LINKLIBS ecl_EKF ecl_test_helper)
|
||||
px4_add_unit_gtest(SRC test_EKF_mag_declination_generated.cpp LINKLIBS ecl_EKF ecl_test_helper)
|
||||
px4_add_unit_gtest(SRC test_EKF_measurementSampling.cpp LINKLIBS ecl_EKF ecl_sensor_sim)
|
||||
px4_add_unit_gtest(SRC test_EKF_ringbuffer.cpp LINKLIBS ecl_EKF ecl_sensor_sim)
|
||||
px4_add_unit_gtest(SRC test_EKF_sideslip_fusion_generated.cpp LINKLIBS ecl_EKF ecl_test_helper)
|
||||
|
||||
@@ -63,329 +63,329 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
||||
6090000,1,-0.0095,-0.011,-0.022,0.0053,0.0052,-0.011,0.0021,0.00027,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,1.4e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.5e-07,0.00038,0.00038,0.00016,0.23,0.23,7,0.1,0.1,0.33,1.8e-08,1.8e-08,5.3e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6190000,1,-0.0095,-0.011,-0.022,0.0056,0.0072,-0.005,0.0027,0.00092,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,-1.1e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-07,0.00041,0.00041,0.00016,0.27,0.27,4.9,0.13,0.13,0.32,1.8e-08,1.8e-08,5e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6290000,1,-0.0095,-0.011,-0.022,0.0071,0.0075,-0.012,0.0033,0.0016,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,-1.9e-07,0.19,9.3e-10,0.4,0,0,0,0,0,1.6e-07,0.00043,0.00043,0.00016,0.31,0.31,3.2,0.17,0.17,0.3,1.8e-08,1.8e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6390000,0.71,0.0014,-0.014,0.71,0.0048,0.0076,-0.05,0.0025,0.0017,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,4e-07,0.21,0.002,0.44,0,0,0,0,0,0.00076,0.00034,0.00034,0.00085,0.22,0.22,2.3,0.13,0.13,0.29,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6490000,0.71,0.0014,-0.014,0.71,0.0043,0.0083,-0.052,0.0029,0.0025,-3.7e+02,-1.6e-05,-5.6e-05,4.1e-07,0,0,-8.7e-08,0.21,0.002,0.44,0,0,0,0,0,0.00051,0.00034,0.00034,0.00056,0.22,0.22,1.5,0.16,0.16,0.26,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6590000,0.71,0.0015,-0.014,0.71,0.0036,0.0085,-0.099,0.0034,0.0033,-3.7e+02,-1.6e-05,-5.6e-05,3.6e-07,0,0,1.7e-06,0.21,0.002,0.44,0,0,0,0,0,0.00039,0.00034,0.00034,0.00043,0.23,0.23,1.1,0.19,0.19,0.23,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6690000,0.7,0.0015,-0.014,0.71,0.0037,0.0095,-0.076,0.0037,0.0042,-3.7e+02,-1.6e-05,-5.6e-05,3e-07,0,0,-1.5e-06,0.21,0.002,0.44,0,0,0,0,0,0.00031,0.00034,0.00034,0.00035,0.24,0.24,0.78,0.23,0.23,0.21,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6790000,0.71,0.0015,-0.014,0.71,0.0021,0.0095,-0.11,0.004,0.0052,-3.7e+02,-1.6e-05,-5.6e-05,3.3e-07,0,0,8.5e-07,0.21,0.002,0.44,0,0,0,0,0,0.00027,0.00034,0.00034,0.0003,0.25,0.25,0.6,0.28,0.28,0.2,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6890000,0.71,0.0015,-0.014,0.71,-0.00021,0.01,-0.12,0.0041,0.0062,-3.7e+02,-1.6e-05,-5.6e-05,3.4e-07,0,0,3.4e-07,0.21,0.002,0.44,0,0,0,0,0,0.00024,0.00035,0.00035,0.00026,0.26,0.26,0.46,0.33,0.33,0.18,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6990000,0.7,0.0016,-0.014,0.71,-0.00055,0.011,-0.12,0.004,0.0072,-3.7e+02,-1.6e-05,-5.6e-05,1.6e-07,0,0,-2.7e-06,0.21,0.002,0.44,0,0,0,0,0,0.00021,0.00035,0.00035,0.00023,0.28,0.28,0.36,0.38,0.38,0.16,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
7090000,0.7,0.0016,-0.014,0.71,-0.0014,0.011,-0.13,0.0039,0.0083,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-08,0,0,-6.3e-06,0.21,0.002,0.44,0,0,0,0,0,0.0002,0.00036,0.00036,0.00022,0.3,0.3,0.29,0.44,0.44,0.16,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
7190000,0.7,0.0016,-0.014,0.71,-0.0034,0.011,-0.15,0.0037,0.0093,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-07,0,0,-4.1e-06,0.21,0.002,0.44,0,0,0,0,0,0.00018,0.00036,0.00036,0.0002,0.32,0.32,0.24,0.51,0.51,0.15,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
7290000,0.7,0.0016,-0.014,0.71,-0.0052,0.011,-0.15,0.0033,0.01,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,0,0,-1.1e-05,0.21,0.002,0.44,0,0,0,0,0,0.00017,0.00037,0.00037,0.00018,0.34,0.34,0.2,0.58,0.58,0.14,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7390000,0.7,0.0017,-0.014,0.71,-0.0056,0.012,-0.16,0.0027,0.011,-3.7e+02,-1.6e-05,-5.6e-05,-1.3e-07,0,0,-1.2e-05,0.21,0.002,0.44,0,0,0,0,0,0.00016,0.00038,0.00038,0.00017,0.37,0.37,0.18,0.66,0.66,0.13,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7490000,0.7,0.0017,-0.014,0.71,-0.0076,0.013,-0.16,0.002,0.013,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,0,0,-2e-05,0.21,0.002,0.44,0,0,0,0,0,0.00015,0.00039,0.00039,0.00016,0.4,0.4,0.15,0.76,0.76,0.12,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7590000,0.7,0.0017,-0.014,0.71,-0.0098,0.014,-0.17,0.0011,0.014,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-08,0,0,-2.9e-05,0.21,0.002,0.44,0,0,0,0,0,0.00014,0.00039,0.00039,0.00015,0.43,0.43,0.14,0.85,0.85,0.12,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7690000,0.7,0.0018,-0.014,0.71,-0.012,0.015,-0.16,2.3e-05,0.015,-3.7e+02,-1.6e-05,-5.6e-05,-4.5e-08,0,0,-4.9e-05,0.21,0.002,0.44,0,0,0,0,0,0.00014,0.0004,0.0004,0.00015,0.47,0.47,0.13,0.96,0.96,0.11,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7790000,0.7,0.0019,-0.014,0.71,-0.014,0.016,-0.16,-0.0013,0.017,-3.7e+02,-1.6e-05,-5.6e-05,-3.7e-07,0,0,-6.9e-05,0.21,0.002,0.44,0,0,0,0,0,0.00013,0.00041,0.00041,0.00014,0.51,0.51,0.12,1.1,1.1,0.11,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
|
||||
7890000,0.7,0.0019,-0.014,0.71,-0.017,0.018,-0.16,-0.0028,0.018,-3.7e+02,-1.6e-05,-5.6e-05,-2.7e-07,0,0,-9.5e-05,0.21,0.002,0.44,0,0,0,0,0,0.00013,0.00042,0.00042,0.00014,0.55,0.55,0.11,1.2,1.2,0.1,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
|
||||
7990000,0.7,0.0019,-0.014,0.71,-0.019,0.019,-0.16,-0.0046,0.02,-3.7e+02,-1.6e-05,-5.6e-05,-1.6e-07,0,0,-0.00011,0.21,0.002,0.44,0,0,0,0,0,0.00012,0.00043,0.00043,0.00013,0.6,0.59,0.1,1.3,1.3,0.099,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
|
||||
8090000,0.7,0.0019,-0.014,0.71,-0.021,0.02,-0.17,-0.0066,0.022,-3.7e+02,-1.6e-05,-5.6e-05,6.1e-08,0,0,-0.00011,0.21,0.002,0.44,0,0,0,0,0,0.00012,0.00045,0.00045,0.00013,0.65,0.65,0.1,1.5,1.5,0.097,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
|
||||
8190000,0.7,0.0019,-0.014,0.71,-0.024,0.021,-0.18,-0.0088,0.023,-3.7e+02,-1.6e-05,-5.6e-05,-2.1e-07,0,0,-0.00013,0.21,0.002,0.44,0,0,0,0,0,0.00012,0.00046,0.00046,0.00012,0.69,0.69,0.099,1.7,1.7,0.094,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
|
||||
8290000,0.7,0.002,-0.014,0.71,-0.026,0.022,-0.17,-0.011,0.025,-3.7e+02,-1.6e-05,-5.6e-05,-4e-07,0,0,-0.00017,0.21,0.002,0.44,0,0,0,0,0,0.00011,0.00047,0.00047,0.00012,0.75,0.75,0.097,1.9,1.9,0.091,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0
|
||||
8390000,0.7,0.002,-0.014,0.71,-0.029,0.023,-0.17,-0.014,0.028,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,0,0,-0.00021,0.21,0.002,0.44,0,0,0,0,0,0.00011,0.00048,0.00048,0.00012,0.81,0.81,0.097,2.1,2.1,0.091,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0
|
||||
8490000,0.7,0.002,-0.014,0.71,-0.031,0.025,-0.17,-0.017,0.029,-3.7e+02,-1.6e-05,-5.6e-05,-3e-07,0,0,-0.00025,0.21,0.002,0.44,0,0,0,0,0,0.00011,0.00049,0.00049,0.00012,0.87,0.87,0.096,2.3,2.3,0.089,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0
|
||||
8590000,0.7,0.002,-0.014,0.71,-0.034,0.027,-0.17,-0.021,0.032,-3.7e+02,-1.6e-05,-5.6e-05,-6.2e-07,0,0,-0.00029,0.21,0.002,0.44,0,0,0,0,0,0.00011,0.00051,0.00051,0.00011,0.94,0.94,0.095,2.5,2.5,0.088,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
|
||||
8690000,0.7,0.0021,-0.014,0.71,-0.037,0.028,-0.16,-0.024,0.033,-3.7e+02,-1.6e-05,-5.6e-05,-2.5e-07,0,0,-0.00034,0.21,0.002,0.44,0,0,0,0,0,0.00011,0.00052,0.00052,0.00011,0.99,0.99,0.096,2.7,2.7,0.088,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
|
||||
8790000,0.7,0.0021,-0.014,0.71,-0.04,0.03,-0.15,-0.028,0.036,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,0,0,-0.00041,0.21,0.002,0.44,0,0,0,0,0,0.0001,0.00054,0.00054,0.00011,1.1,1.1,0.095,3,3,0.087,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,3.1e-06,0,0,0,0,0,0,0,0
|
||||
8890000,0.7,0.0021,-0.014,0.71,-0.043,0.03,-0.15,-0.032,0.038,-3.7e+02,-1.6e-05,-5.6e-05,-6.2e-07,0,0,-0.00045,0.21,0.002,0.44,0,0,0,0,0,0.0001,0.00055,0.00055,0.00011,1.1,1.1,0.095,3.3,3.3,0.086,1.3e-08,1.3e-08,4.5e-09,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0
|
||||
8990000,0.7,0.0021,-0.014,0.71,-0.045,0.031,-0.14,-0.036,0.04,-3.7e+02,-1.6e-05,-5.6e-05,-9.6e-07,0,0,-0.0005,0.21,0.002,0.44,0,0,0,0,0,0.0001,0.00056,0.00056,0.00011,1.2,1.2,0.096,3.6,3.6,0.087,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0
|
||||
9090000,0.7,0.0022,-0.014,0.71,-0.048,0.031,-0.14,-0.04,0.042,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-06,0,0,-0.00053,0.21,0.002,0.44,0,0,0,0,0,0.0001,0.00057,0.00057,0.00011,1.3,1.3,0.095,3.9,3.9,0.086,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0
|
||||
9190000,0.7,0.0022,-0.014,0.71,-0.05,0.032,-0.14,-0.045,0.045,-3.7e+02,-1.6e-05,-5.6e-05,-5.2e-07,0,0,-0.00057,0.21,0.002,0.44,0,0,0,0,0,9.9e-05,0.00059,0.00059,0.0001,1.4,1.4,0.094,4.3,4.3,0.085,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.7e-06,0,0,0,0,0,0,0,0
|
||||
9290000,0.7,0.0022,-0.014,0.71,-0.051,0.033,-0.14,-0.048,0.046,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,0,0,-0.00061,0.21,0.002,0.44,0,0,0,0,0,9.9e-05,0.0006,0.0006,0.0001,1.4,1.4,0.093,4.5,4.5,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0
|
||||
9390000,0.7,0.0022,-0.014,0.71,-0.053,0.035,-0.14,-0.054,0.049,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-07,0,0,-0.00064,0.21,0.002,0.44,0,0,0,0,0,9.8e-05,0.00062,0.00061,0.0001,1.5,1.5,0.093,5,5,0.086,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0
|
||||
9490000,0.7,0.0022,-0.014,0.71,-0.054,0.035,-0.13,-0.057,0.05,-3.7e+02,-1.6e-05,-5.6e-05,1.3e-08,0,0,-0.00068,0.21,0.002,0.44,0,0,0,0,0,9.8e-05,0.00062,0.00062,0.0001,1.6,1.6,0.091,5.2,5.2,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.3e-06,0,0,0,0,0,0,0,0
|
||||
9590000,0.7,0.0022,-0.014,0.71,-0.058,0.036,-0.13,-0.062,0.053,-3.7e+02,-1.6e-05,-5.6e-05,1.4e-07,0,0,-0.00072,0.21,0.002,0.44,0,0,0,0,0,9.7e-05,0.00064,0.00064,0.0001,1.7,1.7,0.089,5.8,5.8,0.085,1.3e-08,1.3e-08,4.2e-09,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0
|
||||
9690000,0.7,0.0022,-0.014,0.71,-0.058,0.037,-0.12,-0.065,0.053,-3.7e+02,-1.6e-05,-5.6e-05,-4.4e-07,0,0,-0.00077,0.21,0.002,0.44,0,0,0,0,0,9.7e-05,0.00064,0.00064,0.0001,1.7,1.7,0.089,6,6,0.086,1.3e-08,1.3e-08,4.2e-09,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0
|
||||
9790000,0.7,0.0022,-0.014,0.71,-0.06,0.039,-0.11,-0.071,0.056,-3.7e+02,-1.6e-05,-5.6e-05,-9.9e-08,0,0,-0.00082,0.21,0.002,0.44,0,0,0,0,0,9.7e-05,0.00066,0.00066,0.0001,1.8,1.8,0.087,6.6,6.6,0.085,1.3e-08,1.3e-08,4.1e-09,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0
|
||||
9890000,0.7,0.0022,-0.014,0.71,-0.06,0.039,-0.11,-0.073,0.056,-3.7e+02,-1.6e-05,-5.6e-05,-1.8e-07,0,0,-0.00085,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00066,0.00066,9.9e-05,1.8,1.8,0.084,6.8,6.8,0.085,1.2e-08,1.2e-08,4.1e-09,4e-06,4e-06,1.8e-06,0,0,0,0,0,0,0,0
|
||||
9990000,0.7,0.0023,-0.014,0.71,-0.063,0.04,-0.1,-0.079,0.06,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,0,0,-0.00088,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00068,0.00068,9.9e-05,2,2,0.083,7.4,7.4,0.086,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0
|
||||
10090000,0.7,0.0023,-0.014,0.71,-0.061,0.039,-0.097,-0.079,0.059,-3.7e+02,-1.5e-05,-5.6e-05,-3.7e-07,0,0,-0.00091,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00067,0.00067,9.8e-05,2,2,0.08,7.5,7.5,0.085,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0
|
||||
10190000,0.7,0.0023,-0.014,0.71,-0.064,0.042,-0.096,-0.086,0.063,-3.7e+02,-1.5e-05,-5.6e-05,-1.2e-06,0,0,-0.00092,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00069,0.00069,9.8e-05,2.1,2.1,0.078,8.3,8.3,0.084,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
|
||||
10290000,0.7,0.0022,-0.014,0.71,-0.062,0.04,-0.084,-0.085,0.061,-3.7e+02,-1.5e-05,-5.6e-05,-1.7e-06,0,0,-0.00098,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00068,0.00068,9.8e-05,2.1,2.1,0.076,8.3,8.3,0.085,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
|
||||
10390000,0.7,0.0022,-0.014,0.71,0.0091,-0.019,0.0085,0.00085,-0.0017,-3.7e+02,-1.5e-05,-5.6e-05,-1.7e-06,-6.6e-10,4.8e-10,-0.001,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.0007,0.0007,9.7e-05,0.25,0.25,0.25,0.25,0.25,0.075,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0
|
||||
10490000,0.7,0.0023,-0.014,0.71,0.0074,-0.017,0.014,0.0017,-0.0036,-3.7e+02,-1.5e-05,-5.6e-05,-2.2e-06,-1.7e-08,1.3e-08,-0.001,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00073,0.00073,9.7e-05,0.26,0.26,0.25,0.26,0.26,0.071,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
|
||||
10590000,0.7,0.0024,-0.014,0.71,0.0069,-0.0065,0.018,0.0018,-0.00081,-3.7e+02,-1.5e-05,-5.6e-05,-2.2e-06,-2.7e-06,4.7e-07,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00073,0.00073,9.7e-05,0.14,0.14,0.17,0.13,0.13,0.067,1.2e-08,1.2e-08,3.7e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
|
||||
10690000,0.7,0.0024,-0.014,0.71,0.0044,-0.0059,0.02,0.0024,-0.0015,-3.7e+02,-1.5e-05,-5.6e-05,-2.4e-06,-2.7e-06,4.9e-07,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00076,0.00076,9.7e-05,0.15,0.15,0.16,0.14,0.14,0.069,1.2e-08,1.2e-08,3.7e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
10790000,0.7,0.0024,-0.014,0.71,0.004,-0.0032,0.018,0.0026,-0.00073,-3.7e+02,-1.5e-05,-5.5e-05,-2.4e-06,-4.3e-06,2.2e-06,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00074,0.00073,9.7e-05,0.11,0.11,0.12,0.091,0.091,0.066,1.1e-08,1.1e-08,3.6e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
10890000,0.7,0.0024,-0.014,0.71,0.0023,-0.0019,0.014,0.0029,-0.00094,-3.7e+02,-1.5e-05,-5.5e-05,-2.5e-06,-4.3e-06,2.2e-06,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00076,0.00076,9.6e-05,0.13,0.13,0.12,0.098,0.098,0.067,1.1e-08,1.1e-08,3.5e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
10990000,0.7,0.0023,-0.014,0.71,0.0052,0.0032,0.01,0.0046,-0.0022,-3.7e+02,-1.4e-05,-5.5e-05,-2e-06,-8.4e-06,9e-06,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.0007,0.00069,9.7e-05,0.1,0.1,0.093,0.073,0.073,0.065,1.1e-08,1.1e-08,3.5e-09,3.9e-06,3.9e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11090000,0.7,0.0023,-0.014,0.71,0.0035,0.0056,0.014,0.0051,-0.0018,-3.7e+02,-1.4e-05,-5.5e-05,-1.5e-06,-8.5e-06,9e-06,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00072,0.00072,9.6e-05,0.13,0.13,0.087,0.08,0.08,0.067,1.1e-08,1.1e-08,3.4e-09,3.9e-06,3.9e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11190000,0.7,0.0022,-0.014,0.71,0.0087,0.0081,0.0049,0.0066,-0.0028,-3.7e+02,-1.3e-05,-5.5e-05,-2e-06,-9.6e-06,1.6e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00062,0.00062,9.6e-05,0.1,0.1,0.071,0.063,0.063,0.064,9.4e-09,9.5e-09,3.4e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11290000,0.7,0.0023,-0.014,0.71,0.0082,0.011,0.0045,0.0075,-0.0018,-3.7e+02,-1.3e-05,-5.5e-05,-2.7e-06,-9.6e-06,1.6e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00064,0.00064,9.6e-05,0.13,0.13,0.067,0.071,0.071,0.067,9.4e-09,9.5e-09,3.3e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11390000,0.7,0.0023,-0.014,0.71,0.0037,0.009,-0.00033,0.0054,-0.002,-3.7e+02,-1.4e-05,-5.5e-05,-3.2e-06,-5.4e-06,1.2e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00054,0.00054,9.6e-05,0.1,0.1,0.056,0.058,0.058,0.064,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11490000,0.7,0.0023,-0.014,0.71,0.00095,0.012,0.00039,0.0056,-0.00092,-3.7e+02,-1.4e-05,-5.5e-05,-4.2e-06,-5.5e-06,1.2e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00056,0.00056,9.6e-05,0.13,0.13,0.052,0.066,0.066,0.064,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11590000,0.7,0.0022,-0.014,0.71,-0.0029,0.01,-0.005,0.0044,-0.0014,-3.7e+02,-1.4e-05,-5.6e-05,-4.4e-06,-1.2e-06,1.1e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00046,0.00046,9.6e-05,0.1,0.1,0.045,0.054,0.054,0.063,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11690000,0.7,0.0022,-0.014,0.71,-0.006,0.013,-0.0091,0.0039,-0.00027,-3.7e+02,-1.4e-05,-5.6e-05,-4.7e-06,-1.1e-06,1.1e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00047,0.00047,9.6e-05,0.12,0.12,0.042,0.063,0.063,0.063,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,9.9e-07,0,0,0,0,0,0,0,0
|
||||
11790000,0.7,0.0022,-0.014,0.71,-0.011,0.013,-0.011,0.0017,0.00056,-3.7e+02,-1.4e-05,-5.6e-05,-4.8e-06,-1.6e-08,9.8e-06,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00039,0.00039,9.6e-05,0.096,0.096,0.037,0.052,0.052,0.061,6.6e-09,6.6e-09,3e-09,3.7e-06,3.7e-06,9.9e-07,0,0,0,0,0,0,0,0
|
||||
11890000,0.7,0.0022,-0.014,0.71,-0.013,0.014,-0.012,0.00052,0.0019,-3.7e+02,-1.4e-05,-5.6e-05,-5.3e-06,-9.2e-08,9.9e-06,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.0004,0.0004,9.6e-05,0.12,0.12,0.035,0.061,0.061,0.061,6.6e-09,6.6e-09,2.9e-09,3.7e-06,3.7e-06,9.9e-07,0,0,0,0,0,0,0,0
|
||||
11990000,0.7,0.0022,-0.014,0.71,-0.014,0.014,-0.017,-0.0004,0.0023,-3.7e+02,-1.4e-05,-5.6e-05,-5.1e-06,1.4e-06,1e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.7e-05,0.00034,0.00034,9.6e-05,0.09,0.09,0.032,0.051,0.051,0.059,5.9e-09,5.9e-09,2.9e-09,3.7e-06,3.7e-06,9.8e-07,0,0,0,0,0,0,0,0
|
||||
12090000,0.7,0.0022,-0.014,0.71,-0.016,0.016,-0.022,-0.0019,0.0038,-3.7e+02,-1.4e-05,-5.6e-05,-4.7e-06,1.6e-06,1e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.7e-05,0.00035,0.00035,9.6e-05,0.11,0.11,0.03,0.06,0.06,0.059,5.9e-09,5.9e-09,2.8e-09,3.7e-06,3.7e-06,9.8e-07,0,0,0,0,0,0,0,0
|
||||
12190000,0.7,0.0018,-0.014,0.71,-0.0089,0.013,-0.017,0.0014,0.0019,-3.7e+02,-1.3e-05,-5.7e-05,-4.5e-06,4.2e-06,1.6e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.0003,0.0003,9.5e-05,0.085,0.085,0.028,0.051,0.051,0.057,5.4e-09,5.4e-09,2.8e-09,3.7e-06,3.7e-06,9.7e-07,0,0,0,0,0,0,0,0
|
||||
12290000,0.7,0.0018,-0.014,0.71,-0.012,0.015,-0.017,0.00035,0.0033,-3.7e+02,-1.3e-05,-5.7e-05,-4.3e-06,3.9e-06,1.6e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.7e-05,0.00031,0.00031,9.6e-05,0.1,0.1,0.027,0.059,0.059,0.058,5.4e-09,5.4e-09,2.7e-09,3.7e-06,3.7e-06,9.7e-07,0,0,0,0,0,0,0,0
|
||||
12390000,0.7,0.0015,-0.014,0.71,-0.0059,0.011,-0.015,0.0029,0.0017,-3.7e+02,-1.3e-05,-5.8e-05,-4.6e-06,5.6e-06,1.9e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.7e-05,0.00027,0.00027,9.5e-05,0.079,0.079,0.026,0.05,0.05,0.056,5e-09,5e-09,2.6e-09,3.6e-06,3.6e-06,9.6e-07,0,0,0,0,0,0,0,0
|
||||
12490000,0.7,0.0015,-0.014,0.71,-0.0072,0.013,-0.018,0.0023,0.0029,-3.7e+02,-1.3e-05,-5.8e-05,-5.1e-06,5.6e-06,1.9e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00028,0.00028,9.5e-05,0.092,0.092,0.025,0.059,0.059,0.056,5e-09,5e-09,2.6e-09,3.6e-06,3.6e-06,9.6e-07,0,0,0,0,0,0,0,0
|
||||
12590000,0.7,0.0016,-0.014,0.71,-0.015,0.011,-0.024,-0.0028,0.0015,-3.7e+02,-1.3e-05,-5.8e-05,-5e-06,7e-06,1.7e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.7e-05,0.00025,0.00025,9.5e-05,0.073,0.073,0.025,0.05,0.05,0.055,4.7e-09,4.7e-09,2.5e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0
|
||||
12690000,0.7,0.0016,-0.014,0.71,-0.015,0.012,-0.027,-0.0043,0.0026,-3.7e+02,-1.3e-05,-5.8e-05,-5.2e-06,7.3e-06,1.7e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.7e-05,0.00026,0.00026,9.5e-05,0.085,0.085,0.025,0.058,0.058,0.054,4.7e-09,4.7e-09,2.5e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0
|
||||
12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0092,-0.03,-0.0077,0.0013,-3.7e+02,-1.4e-05,-5.8e-05,-5e-06,7.7e-06,1.6e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00023,0.00023,9.5e-05,0.068,0.068,0.024,0.049,0.049,0.053,4.4e-09,4.4e-09,2.4e-09,3.6e-06,3.6e-06,9.2e-07,0,0,0,0,0,0,0,0
|
||||
12890000,0.7,0.0016,-0.013,0.71,-0.021,0.0091,-0.029,-0.0097,0.0022,-3.7e+02,-1.4e-05,-5.8e-05,-4.8e-06,7e-06,1.7e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.7e-05,0.00024,0.00024,9.5e-05,0.079,0.079,0.025,0.058,0.058,0.053,4.4e-09,4.4e-09,2.4e-09,3.6e-06,3.6e-06,9.2e-07,0,0,0,0,0,0,0,0
|
||||
12990000,0.7,0.0012,-0.014,0.71,-0.0088,0.0066,-0.03,-0.0011,0.0012,-3.7e+02,-1.3e-05,-5.9e-05,-4.2e-06,7e-06,1.8e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00022,9.5e-05,0.064,0.064,0.025,0.049,0.049,0.052,4.2e-09,4.2e-09,2.3e-09,3.6e-06,3.6e-06,9e-07,0,0,0,0,0,0,0,0
|
||||
13090000,0.7,0.0012,-0.014,0.71,-0.0096,0.0068,-0.03,-0.002,0.0018,-3.7e+02,-1.3e-05,-5.9e-05,-4.7e-06,6.6e-06,1.9e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00023,0.00023,9.5e-05,0.073,0.073,0.025,0.057,0.057,0.052,4.2e-09,4.2e-09,2.3e-09,3.6e-06,3.6e-06,8.9e-07,0,0,0,0,0,0,0,0
|
||||
13190000,0.7,0.00099,-0.014,0.71,-0.00038,0.0062,-0.027,0.0044,0.0012,-3.7e+02,-1.2e-05,-5.9e-05,-4.6e-06,5.2e-06,2e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.06,0.06,0.025,0.049,0.049,0.05,4e-09,4e-09,2.2e-09,3.6e-06,3.6e-06,8.7e-07,0,0,0,0,0,0,0,0
|
||||
13290000,0.7,0.001,-0.014,0.71,-0.00066,0.007,-0.023,0.0043,0.0018,-3.7e+02,-1.2e-05,-5.9e-05,-4.1e-06,3.9e-06,2.1e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00022,9.4e-05,0.068,0.068,0.026,0.057,0.057,0.051,4e-09,4e-09,2.2e-09,3.6e-06,3.6e-06,8.6e-07,0,0,0,0,0,0,0,0
|
||||
13390000,0.7,0.00085,-0.014,0.71,0.00025,0.006,-0.02,0.0033,0.0011,-3.7e+02,-1.2e-05,-5.9e-05,-3.5e-06,2.2e-06,2.1e-05,-0.0011,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.056,0.056,0.026,0.049,0.049,0.05,3.8e-09,3.8e-09,2.1e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0
|
||||
13490000,0.7,0.00087,-0.014,0.71,-0.00026,0.0059,-0.018,0.0033,0.0017,-3.7e+02,-1.2e-05,-5.9e-05,-3.1e-06,1.4e-06,2.2e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00021,9.4e-05,0.064,0.064,0.027,0.057,0.057,0.05,3.8e-09,3.8e-09,2.1e-09,3.6e-06,3.6e-06,8.2e-07,0,0,0,0,0,0,0,0
|
||||
13590000,0.7,0.00081,-0.014,0.71,7.2e-05,0.0061,-0.02,0.0024,0.001,-3.7e+02,-1.2e-05,-5.9e-05,-3.4e-06,1.1e-06,2e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.4e-05,0.053,0.053,0.027,0.049,0.049,0.05,3.6e-09,3.6e-09,2e-09,3.6e-06,3.6e-06,7.9e-07,0,0,0,0,0,0,0,0
|
||||
13690000,0.7,0.00079,-0.014,0.71,0.00075,0.0078,-0.024,0.0024,0.0017,-3.7e+02,-1.2e-05,-5.9e-05,-2.7e-06,1.4e-06,2e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.061,0.061,0.028,0.056,0.056,0.05,3.6e-09,3.6e-09,2e-09,3.6e-06,3.6e-06,7.8e-07,0,0,0,0,0,0,0,0
|
||||
13790000,0.7,0.00067,-0.014,0.71,0.0014,0.0036,-0.026,0.0035,-0.00062,-3.7e+02,-1.1e-05,-6e-05,-2.7e-06,-7.1e-07,1.9e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.3e-05,0.051,0.051,0.028,0.048,0.048,0.049,3.4e-09,3.4e-09,1.9e-09,3.6e-06,3.6e-06,7.4e-07,0,0,0,0,0,0,0,0
|
||||
13890000,0.7,0.00063,-0.014,0.71,0.0019,0.0035,-0.03,0.0036,-0.00029,-3.7e+02,-1.1e-05,-6e-05,-2.3e-06,-4e-07,1.8e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.3e-05,0.058,0.058,0.029,0.056,0.056,0.05,3.4e-09,3.4e-09,1.9e-09,3.6e-06,3.6e-06,7.4e-07,0,0,0,0,0,0,0,0
|
||||
13990000,0.7,0.00056,-0.014,0.71,0.0022,0.001,-0.029,0.0045,-0.002,-3.7e+02,-1.1e-05,-6e-05,-2.2e-06,-3e-06,1.7e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.049,0.049,0.029,0.048,0.048,0.05,3.2e-09,3.2e-09,1.8e-09,3.6e-06,3.6e-06,7e-07,0,0,0,0,0,0,0,0
|
||||
14090000,0.7,0.00054,-0.014,0.71,0.0023,0.0012,-0.03,0.0047,-0.0019,-3.7e+02,-1.1e-05,-6e-05,-1.5e-06,-2.9e-06,1.7e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.055,0.055,0.03,0.056,0.056,0.05,3.2e-09,3.2e-09,1.8e-09,3.6e-06,3.6e-06,6.9e-07,0,0,0,0,0,0,0,0
|
||||
14190000,0.7,0.00044,-0.014,0.71,0.0057,0.00062,-0.032,0.0068,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-1.1e-06,-2.7e-06,1.4e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.047,0.047,0.03,0.048,0.048,0.05,3.1e-09,3.1e-09,1.8e-09,3.6e-06,3.6e-06,6.5e-07,0,0,0,0,0,0,0,0
|
||||
14290000,0.7,0.00045,-0.014,0.71,0.0065,0.0014,-0.031,0.0074,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-8.2e-07,-3.3e-06,1.5e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.053,0.053,0.031,0.055,0.055,0.051,3.1e-09,3.1e-09,1.7e-09,3.6e-06,3.6e-06,6.4e-07,0,0,0,0,0,0,0,0
|
||||
14390000,0.7,0.00036,-0.014,0.71,0.0083,0.0023,-0.033,0.0087,-0.0013,-3.7e+02,-1.1e-05,-6e-05,-1.5e-07,-3.4e-06,1.2e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.5e-05,0.00019,0.00019,9.2e-05,0.045,0.045,0.03,0.048,0.048,0.05,2.9e-09,2.9e-09,1.7e-09,3.6e-06,3.6e-06,6e-07,0,0,0,0,0,0,0,0
|
||||
14490000,0.7,0.00034,-0.013,0.71,0.0083,0.0035,-0.036,0.0095,-0.001,-3.7e+02,-1e-05,-6e-05,8e-08,-2.8e-06,1.2e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.2e-05,0.051,0.051,0.031,0.055,0.055,0.051,2.9e-09,2.9e-09,1.6e-09,3.6e-06,3.6e-06,5.8e-07,0,0,0,0,0,0,0,0
|
||||
14590000,0.7,0.00033,-0.013,0.71,0.0049,0.0019,-0.036,0.006,-0.0025,-3.7e+02,-1.1e-05,-6.1e-05,1.4e-07,-6.5e-06,1.6e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.2e-05,0.044,0.044,0.03,0.047,0.047,0.05,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.5e-07,0,0,0,0,0,0,0,0
|
||||
14690000,0.7,0.00029,-0.013,0.71,0.0062,-0.0011,-0.033,0.0066,-0.0024,-3.7e+02,-1.1e-05,-6.1e-05,6.2e-07,-7.6e-06,1.7e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.2e-05,0.049,0.049,0.031,0.054,0.054,0.051,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.3e-07,0,0,0,0,0,0,0,0
|
||||
14790000,0.7,0.00031,-0.013,0.71,0.003,-0.0026,-0.029,0.0037,-0.0034,-3.7e+02,-1.1e-05,-6.1e-05,7.8e-07,-1.1e-05,2.2e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.1e-05,0.043,0.043,0.03,0.047,0.047,0.05,2.6e-09,2.6e-09,1.5e-09,3.6e-06,3.6e-06,5e-07,0,0,0,0,0,0,0,0
|
||||
14890000,0.7,0.00031,-0.013,0.71,0.0046,-0.0017,-0.032,0.0041,-0.0036,-3.7e+02,-1.1e-05,-6.1e-05,1.1e-06,-1.1e-05,2.2e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.1e-05,0.048,0.048,0.03,0.054,0.054,0.052,2.6e-09,2.6e-09,1.5e-09,3.6e-06,3.6e-06,4.9e-07,0,0,0,0,0,0,0,0
|
||||
14990000,0.7,0.0003,-0.013,0.71,0.0034,-0.0019,-0.028,0.0031,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,1e-06,-1.2e-05,2.4e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.042,0.042,0.029,0.047,0.047,0.051,2.4e-09,2.4e-09,1.5e-09,3.5e-06,3.5e-06,4.5e-07,0,0,0,0,0,0,0,0
|
||||
15090000,0.7,0.00023,-0.013,0.71,0.0038,-0.0021,-0.031,0.0035,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.1e-06,-1.1e-05,2.4e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.047,0.047,0.03,0.054,0.054,0.052,2.4e-09,2.4e-09,1.4e-09,3.5e-06,3.5e-06,4.4e-07,0,0,0,0,0,0,0,0
|
||||
15190000,0.7,0.00024,-0.013,0.71,0.0032,-0.00083,-0.029,0.0028,-0.0024,-3.7e+02,-1.2e-05,-6.1e-05,1e-06,-1.1e-05,2.5e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.041,0.041,0.029,0.047,0.047,0.051,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4.1e-07,0,0,0,0,0,0,0,0
|
||||
15290000,0.7,0.0002,-0.013,0.71,0.0038,-0.00068,-0.026,0.0031,-0.0025,-3.7e+02,-1.2e-05,-6.1e-05,1.4e-06,-1.2e-05,2.6e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9e-05,0.046,0.046,0.029,0.054,0.054,0.052,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4e-07,0,0,0,0,0,0,0,0
|
||||
15390000,0.7,0.00021,-0.013,0.71,0.003,-0.00033,-0.024,0.00054,-0.002,-3.7e+02,-1.2e-05,-6.1e-05,2e-06,-1.3e-05,2.8e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.3e-05,0.00018,0.00018,9e-05,0.04,0.04,0.028,0.047,0.047,0.051,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.7e-07,0,0,0,0,0,0,0,0
|
||||
15490000,0.7,0.00023,-0.013,0.71,0.0043,-0.00071,-0.024,0.00091,-0.0021,-3.7e+02,-1.2e-05,-6.1e-05,1.7e-06,-1.2e-05,2.8e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9e-05,0.045,0.045,0.028,0.053,0.053,0.052,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.6e-07,0,0,0,0,0,0,0,0
|
||||
15590000,0.7,0.00024,-0.013,0.71,0.0024,-0.0007,-0.023,-0.0013,-0.0017,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.2e-05,3e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,9e-05,0.039,0.039,0.027,0.046,0.046,0.051,1.9e-09,1.9e-09,1.3e-09,3.5e-06,3.5e-06,3.3e-07,0,0,0,0,0,0,0,0
|
||||
15690000,0.7,0.00025,-0.013,0.71,0.0027,-0.00088,-0.023,-0.0011,-0.0018,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.3e-05,3e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00018,8.9e-05,0.044,0.044,0.027,0.053,0.053,0.052,1.9e-09,1.9e-09,1.2e-09,3.5e-06,3.5e-06,3.2e-07,0,0,0,0,0,0,0,0
|
||||
15790000,0.7,0.00021,-0.013,0.71,0.0032,-0.0025,-0.025,-0.00098,-0.0028,-3.7e+02,-1.2e-05,-6.1e-05,1.6e-06,-1.5e-05,3.1e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,8.9e-05,0.039,0.039,0.026,0.046,0.046,0.051,1.8e-09,1.8e-09,1.2e-09,3.4e-06,3.4e-06,3e-07,0,0,0,0,0,0,0,0
|
||||
15890000,0.7,0.00016,-0.013,0.71,0.0041,-0.003,-0.024,-0.00058,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.7e-06,-1.5e-05,3.1e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,8.9e-05,0.044,0.044,0.026,0.053,0.053,0.052,1.8e-09,1.8e-09,1.2e-09,3.4e-06,3.4e-06,2.9e-07,0,0,0,0,0,0,0,0
|
||||
15990000,0.7,0.0001,-0.013,0.71,0.004,-0.0039,-0.019,-0.00066,-0.0039,-3.7e+02,-1.2e-05,-6.1e-05,2.1e-06,-1.8e-05,3.3e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.9e-05,0.038,0.038,0.025,0.046,0.046,0.051,1.7e-09,1.7e-09,1.2e-09,3.4e-06,3.4e-06,2.7e-07,0,0,0,0,0,0,0,0
|
||||
16090000,0.71,0.0001,-0.013,0.71,0.0058,-0.0042,-0.016,-0.00019,-0.0043,-3.7e+02,-1.2e-05,-6.1e-05,2.7e-06,-1.9e-05,3.3e-05,-0.0012,0.21,0.002,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,8.8e-05,0.043,0.043,0.025,0.053,0.053,0.051,1.7e-09,1.7e-09,1.1e-09,3.4e-06,3.4e-06,2.6e-07,0,0,0,0,0,0,0,0
|
||||
16190000,0.71,0.00013,-0.013,0.71,0.0057,-0.0034,-0.014,-0.0004,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,2.8e-06,-1.8e-05,3.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.8e-05,0.038,0.038,0.024,0.046,0.046,0.051,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.4e-07,0,0,0,0,0,0,0,0
|
||||
16290000,0.71,0.00014,-0.013,0.71,0.0074,-0.0042,-0.016,0.00026,-0.0039,-3.7e+02,-1.2e-05,-6.1e-05,3.4e-06,-1.7e-05,3.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.8e-05,0.042,0.042,0.024,0.053,0.053,0.051,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.3e-07,0,0,0,0,0,0,0,0
|
||||
16390000,0.71,0.00013,-0.013,0.71,0.0063,-0.0044,-0.015,-6.7e-05,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,3.3e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.8e-05,0.037,0.037,0.023,0.046,0.046,0.05,1.4e-09,1.4e-09,1.1e-09,3.3e-06,3.4e-06,2.2e-07,0,0,0,0,0,0,0,0
|
||||
16490000,0.71,0.00015,-0.013,0.71,0.0055,-0.004,-0.018,0.00049,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,3.4e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.7e-05,0.042,0.042,0.023,0.052,0.052,0.051,1.4e-09,1.4e-09,1e-09,3.3e-06,3.4e-06,2.1e-07,0,0,0,0,0,0,0,0
|
||||
16590000,0.71,0.00041,-0.013,0.71,0.0019,-0.0012,-0.018,-0.0025,-7.8e-05,-3.7e+02,-1.3e-05,-6e-05,3.5e-06,-9e-06,4.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,9e-05,0.00016,0.00016,8.7e-05,0.037,0.037,0.022,0.046,0.046,0.05,1.3e-09,1.3e-09,1e-09,3.3e-06,3.3e-06,1.9e-07,0,0,0,0,0,0,0,0
|
||||
16690000,0.71,0.0004,-0.013,0.71,0.0021,-0.00073,-0.015,-0.0023,-0.00018,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-9.6e-06,4.7e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.9e-05,0.00017,0.00016,8.7e-05,0.041,0.041,0.022,0.052,0.052,0.05,1.3e-09,1.3e-09,9.9e-10,3.3e-06,3.3e-06,1.9e-07,0,0,0,0,0,0,0,0
|
||||
16790000,0.71,0.00055,-0.013,0.71,-0.0013,0.0015,-0.014,-0.0047,0.0025,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-3.9e-06,5.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.7e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.2e-09,1.2e-09,9.7e-10,3.3e-06,3.3e-06,1.8e-07,0,0,0,0,0,0,0,0
|
||||
16890000,0.71,0.00056,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0048,0.0027,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-4.3e-06,5.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.6e-05,0.041,0.041,0.021,0.052,0.052,0.05,1.2e-09,1.2e-09,9.5e-10,3.3e-06,3.3e-06,1.7e-07,0,0,0,0,0,0,0,0
|
||||
16990000,0.71,0.0005,-0.013,0.71,-0.0016,0.00033,-0.01,-0.0052,0.00086,-3.7e+02,-1.3e-05,-6e-05,2.9e-06,-8.4e-06,5.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.9e-05,0.00015,0.00015,8.6e-05,0.036,0.036,0.02,0.046,0.046,0.049,1.1e-09,1.1e-09,9.2e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0
|
||||
17090000,0.71,0.00047,-0.013,0.71,-0.00076,0.0013,-0.01,-0.0053,0.00091,-3.7e+02,-1.3e-05,-6e-05,3e-06,-8.3e-06,5.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.8e-05,0.00016,0.00016,8.6e-05,0.04,0.04,0.019,0.052,0.052,0.049,1.1e-09,1.1e-09,9e-10,3.3e-06,3.3e-06,1.5e-07,0,0,0,0,0,0,0,0
|
||||
17190000,0.71,0.00045,-0.013,0.71,-0.00031,0.0013,-0.011,-0.0057,-0.00054,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.6e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.5e-10,9.6e-10,8.9e-10,3.2e-06,3.2e-06,1.4e-07,0,0,0,0,0,0,0,0
|
||||
17290000,0.71,0.00043,-0.013,0.71,0.0018,0.0023,-0.0067,-0.0056,-0.00038,-3.7e+02,-1.4e-05,-6e-05,3e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.5e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.5e-10,9.6e-10,8.7e-10,3.2e-06,3.2e-06,1.4e-07,0,0,0,0,0,0,0,0
|
||||
17390000,0.71,0.0004,-0.013,0.71,0.0024,0.0015,-0.0048,-0.0047,-0.0016,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00014,8.5e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.7e-10,8.7e-10,8.5e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
|
||||
17490000,0.71,0.00039,-0.013,0.71,0.003,0.001,-0.0031,-0.0044,-0.0015,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.7e-05,0.00015,0.00015,8.5e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.7e-10,8.7e-10,8.3e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
|
||||
17590000,0.71,0.0003,-0.013,0.71,0.0042,-0.00014,0.0024,-0.0037,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.4e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.5e-05,0.034,0.034,0.017,0.046,0.046,0.048,7.9e-10,7.9e-10,8.1e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0
|
||||
17690000,0.71,0.00027,-0.012,0.71,0.0051,0.00056,0.0018,-0.0032,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.6e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.038,0.038,0.017,0.052,0.052,0.048,7.9e-10,7.9e-10,7.9e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
|
||||
17790000,0.71,0.00018,-0.013,0.71,0.0077,0.00029,0.00048,-0.0021,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.9e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.033,0.033,0.016,0.045,0.045,0.048,7.1e-10,7.1e-10,7.8e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
|
||||
17890000,0.71,0.00019,-0.013,0.71,0.0092,-0.00047,0.00058,-0.0012,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.9e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.4e-05,0.037,0.037,0.016,0.052,0.052,0.048,7.1e-10,7.1e-10,7.6e-10,3.2e-06,3.2e-06,1e-07,0,0,0,0,0,0,0,0
|
||||
17990000,0.71,0.00013,-0.013,0.71,0.011,-0.0022,0.0018,-0.00053,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.4e-05,0.032,0.032,0.015,0.045,0.045,0.047,6.4e-10,6.4e-10,7.5e-10,3.1e-06,3.1e-06,9.8e-08,0,0,0,0,0,0,0,0
|
||||
18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0024,0.0042,0.00061,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.3e-05,0.036,0.036,0.015,0.051,0.051,0.047,6.4e-10,6.4e-10,7.3e-10,3.1e-06,3.1e-06,9.5e-08,0,0,0,0,0,0,0,0
|
||||
18190000,0.71,0.00011,-0.013,0.71,0.012,-0.0013,0.0055,0.0015,-0.0017,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.3e-05,0.032,0.032,0.015,0.045,0.045,0.046,5.8e-10,5.8e-10,7.2e-10,3.1e-06,3.1e-06,9e-08,0,0,0,0,0,0,0,0
|
||||
18290000,0.71,4.8e-05,-0.012,0.71,0.012,-0.0019,0.0067,0.0027,-0.0018,-3.7e+02,-1.3e-05,-6.1e-05,4.1e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-10,5.8e-10,7e-10,3.1e-06,3.1e-06,8.7e-08,0,0,0,0,0,0,0,0
|
||||
18390000,0.71,6.4e-05,-0.013,0.71,0.014,-0.0002,0.0078,0.0032,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.031,0.031,0.014,0.045,0.045,0.045,5.3e-10,5.3e-10,6.9e-10,3.1e-06,3.1e-06,8.3e-08,0,0,0,0,0,0,0,0
|
||||
18490000,0.71,7.9e-05,-0.012,0.71,0.014,0.00021,0.0075,0.0047,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.5e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.2e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.3e-10,5.3e-10,6.7e-10,3.1e-06,3.1e-06,8e-08,0,0,0,0,0,0,0,0
|
||||
18590000,0.71,8.4e-05,-0.012,0.71,0.013,0.00045,0.0056,0.0035,-0.0012,-3.7e+02,-1.4e-05,-6.1e-05,4.9e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.8e-10,4.8e-10,6.6e-10,3.1e-06,3.1e-06,7.6e-08,0,0,0,0,0,0,0,0
|
||||
18690000,0.71,5.3e-05,-0.012,0.71,0.014,-0.00024,0.0038,0.0049,-0.0011,-3.7e+02,-1.4e-05,-6.1e-05,4.8e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00013,0.00012,8.2e-05,0.034,0.034,0.013,0.051,0.051,0.045,4.8e-10,4.8e-10,6.5e-10,3.1e-06,3.1e-06,7.4e-08,0,0,0,0,0,0,0,0
|
||||
18790000,0.71,8.4e-05,-0.012,0.71,0.012,6.5e-05,0.0034,0.0038,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,4.6e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.4e-10,4.4e-10,6.3e-10,3.1e-06,3.1e-06,7.1e-08,0,0,0,0,0,0,0,0
|
||||
18890000,0.71,0.00011,-0.012,0.71,0.013,0.00056,0.004,0.005,-0.00085,-3.7e+02,-1.4e-05,-6.1e-05,5e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.4e-10,4.4e-10,6.2e-10,3.1e-06,3.1e-06,6.9e-08,0,0,0,0,0,0,0,0
|
||||
18990000,0.71,9.4e-05,-0.012,0.71,0.014,0.0015,0.0027,0.0063,-0.0007,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.029,0.029,0.012,0.045,0.045,0.044,4e-10,4e-10,6.1e-10,3e-06,3e-06,6.6e-08,0,0,0,0,0,0,0,0
|
||||
19090000,0.71,7.8e-05,-0.012,0.71,0.015,0.0021,0.0057,0.0078,-0.0005,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.032,0.032,0.012,0.051,0.051,0.044,4e-10,4e-10,6e-10,3e-06,3e-06,6.4e-08,0,0,0,0,0,0,0,0
|
||||
19190000,0.71,8.1e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0086,-0.00045,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00011,8.1e-05,0.028,0.028,0.012,0.045,0.045,0.043,3.6e-10,3.6e-10,5.9e-10,3e-06,3e-06,6.1e-08,0,0,0,0,0,0,0,0
|
||||
19290000,0.71,0.0001,-0.012,0.71,0.015,0.0013,0.0085,0.01,-0.00027,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00012,8e-05,0.031,0.031,0.012,0.05,0.05,0.043,3.6e-10,3.6e-10,5.7e-10,3e-06,3e-06,5.9e-08,0,0,0,0,0,0,0,0
|
||||
19390000,0.71,0.00012,-0.012,0.71,0.013,0.00039,0.012,0.008,-0.00028,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.028,0.028,0.011,0.045,0.045,0.043,3.3e-10,3.3e-10,5.6e-10,3e-06,3e-06,5.7e-08,0,0,0,0,0,0,0,0
|
||||
19490000,0.71,0.00014,-0.012,0.71,0.012,-0.00032,0.0087,0.0092,-0.00028,-3.7e+02,-1.4e-05,-6.1e-05,5.6e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-10,3.3e-10,5.5e-10,3e-06,3e-06,5.5e-08,0,0,0,0,0,0,0,0
|
||||
19590000,0.71,0.00019,-0.012,0.71,0.0097,-0.0013,0.008,0.0075,-0.0003,-3.7e+02,-1.4e-05,-6.1e-05,5.9e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-10,3e-10,5.4e-10,3e-06,3e-06,5.3e-08,0,0,0,0,0,0,0,0
|
||||
19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0035,0.0095,0.0085,-0.00055,-3.7e+02,-1.4e-05,-6.1e-05,5.7e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-10,3e-10,5.3e-10,3e-06,3e-06,5.2e-08,0,0,0,0,0,0,0,0
|
||||
19790000,0.71,0.00026,-0.012,0.71,0.0078,-0.0044,0.0099,0.0068,-0.00044,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,5.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19890000,0.71,0.0002,-0.012,0.71,0.0065,-0.0047,0.011,0.0076,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,6.2e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-10,2.7e-10,5.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19990000,0.71,0.00019,-0.012,0.71,0.0041,-0.0053,0.014,0.0062,-0.00076,-3.7e+02,-1.4e-05,-6.1e-05,6.7e-06,-1.7e-05,7.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-10,2.5e-10,5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20090000,0.71,0.00018,-0.012,0.71,0.0039,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-1.4e-05,-6.1e-05,7.1e-06,-1.7e-05,7.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.028,0.028,0.01,0.05,0.05,0.042,2.5e-10,2.5e-10,4.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20190000,0.71,0.00029,-0.012,0.71,0.0015,-0.008,0.016,0.0042,-0.0011,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.6e-05,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.9e-05,0.025,0.025,0.0099,0.044,0.044,0.041,2.3e-10,2.3e-10,4.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20290000,0.71,0.00025,-0.012,0.71,0.00038,-0.0096,0.014,0.0043,-0.002,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-1.6e-05,7.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.8e-05,0.027,0.027,0.0098,0.049,0.049,0.041,2.3e-10,2.3e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20390000,0.71,0.00027,-0.012,0.71,-0.0021,-0.01,0.016,0.0024,-0.0015,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-1.4e-05,7.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.8e-05,0.024,0.024,0.0096,0.044,0.044,0.041,2.1e-10,2.1e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20490000,0.71,0.00032,-0.012,0.71,-0.0025,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.4e-05,7.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.027,0.027,0.0095,0.049,0.049,0.04,2.1e-10,2.1e-10,4.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20590000,0.71,0.00034,-0.012,0.71,-0.0022,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-1.4e-05,-6e-05,7.1e-06,-1.3e-05,7.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.024,0.024,0.0093,0.044,0.044,0.04,2e-10,2e-10,4.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20690000,0.71,0.00037,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.3e-05,7.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.026,0.026,0.0093,0.049,0.049,0.04,2e-10,2e-10,4.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20790000,0.71,0.0004,-0.012,0.71,-0.0033,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.1e-05,7.7e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.7e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20890000,0.71,0.00038,-0.012,0.71,-0.0038,-0.014,0.014,0.001,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-1.1e-05,7.7e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,0.0001,0.0001,7.7e-05,0.025,0.025,0.009,0.049,0.049,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.014,0.0027,-0.0031,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-8.6e-06,7.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.7e-05,0.023,0.023,0.0088,0.043,0.043,0.039,1.7e-10,1.7e-10,4.2e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21090000,0.71,0.00039,-0.012,0.71,-0.0041,-0.017,0.015,0.0023,-0.0046,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-8.7e-06,7.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,9.9e-05,9.9e-05,7.7e-05,0.025,0.025,0.0088,0.048,0.048,0.039,1.7e-10,1.7e-10,4.1e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21190000,0.71,0.00042,-0.012,0.71,-0.0033,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.6e-06,-6.3e-06,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,9.7e-05,9.7e-05,7.7e-05,0.022,0.022,0.0086,0.043,0.043,0.039,1.5e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21290000,0.71,0.00046,-0.012,0.71,-0.0039,-0.018,0.016,0.0034,-0.0054,-3.7e+02,-1.4e-05,-6e-05,7.9e-06,-6.2e-06,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.6e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.6e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21390000,0.71,0.00051,-0.012,0.71,-0.0047,-0.017,0.016,0.0029,-0.0034,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-2.6e-06,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.9e-05,9.6e-05,9.6e-05,7.6e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-10,1.4e-10,3.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21490000,0.71,0.00052,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-2.6e-06,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.8e-05,9.7e-05,9.6e-05,7.6e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-10,1.4e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21590000,0.71,0.00054,-0.012,0.71,-0.0058,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,8.2e-07,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-10,1.3e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21690000,0.71,0.00055,-0.012,0.71,-0.0057,-0.016,0.017,0.0013,-0.0048,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,8e-07,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.023,0.023,0.0083,0.048,0.048,0.038,1.3e-10,1.3e-10,3.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21790000,0.71,0.00057,-0.012,0.71,-0.0063,-0.011,0.015,9e-05,-0.00074,-3.7e+02,-1.4e-05,-5.9e-05,7.6e-06,6e-06,7.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.8e-05,9.4e-05,9.4e-05,7.5e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21890000,0.71,0.00057,-0.012,0.71,-0.0063,-0.012,0.016,-0.00054,-0.0019,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,5.9e-06,7.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.7e-05,9.4e-05,9.4e-05,7.5e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21990000,0.71,0.00062,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,1e-05,7.7e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.7e-05,9.3e-05,9.3e-05,7.5e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-10,1.2e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22090000,0.71,0.00063,-0.012,0.71,-0.0071,-0.0082,0.015,-0.0021,0.00064,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1e-05,7.7e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.7e-05,9.4e-05,9.3e-05,7.5e-05,0.022,0.022,0.0081,0.047,0.047,0.037,1.2e-10,1.2e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22190000,0.71,0.00061,-0.012,0.71,-0.0069,-0.0073,0.015,-0.0018,0.00059,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.7e-05,9.2e-05,9.2e-05,7.5e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-10,1.1e-10,3.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22290000,0.71,0.00065,-0.012,0.71,-0.0082,-0.0081,0.015,-0.0025,-0.00018,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.7e-05,9.3e-05,9.2e-05,7.4e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-10,1.1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22390000,0.71,0.00062,-0.012,0.71,-0.0088,-0.0075,0.017,-0.0022,-0.00017,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.2e-05,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.7e-05,9.1e-05,9.1e-05,7.4e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-10,1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22490000,0.71,0.00063,-0.012,0.71,-0.0095,-0.0075,0.018,-0.0031,-0.00094,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.2e-05,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.6e-05,9.2e-05,9.2e-05,7.4e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-10,1e-10,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22590000,0.71,0.00061,-0.012,0.71,-0.0092,-0.007,0.017,-0.0034,0.00014,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.3e-05,7.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.6e-05,9.1e-05,9e-05,7.4e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-11,9.7e-11,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22690000,0.71,0.00064,-0.012,0.71,-0.01,-0.0067,0.018,-0.0043,-0.00054,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.3e-05,7.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.6e-05,9.1e-05,9.1e-05,7.4e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-11,9.7e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22790000,0.71,0.00063,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00043,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.4e-05,7.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.4e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-11,9.2e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22890000,0.71,0.00064,-0.012,0.71,-0.012,-0.0051,0.021,-0.0066,-0.00097,-3.7e+02,-1.4e-05,-5.9e-05,6.9e-06,1.4e-05,7.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-11,9.2e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22990000,0.71,0.00062,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00086,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.6e-05,8.9e-05,8.9e-05,7.3e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-11,8.7e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23090000,0.71,0.00059,-0.012,0.71,-0.013,-0.0056,0.022,-0.0086,-0.0014,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.5e-05,9e-05,9e-05,7.3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-11,8.7e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23190000,0.71,0.00065,-0.012,0.71,-0.014,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.9e-05,7.3e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-11,8.2e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23290000,0.71,0.00059,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.9e-05,7.3e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-11,8.2e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23390000,0.71,0.00068,-0.012,0.71,-0.016,-0.008,0.021,-0.016,-0.0018,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,1.5e-05,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.5e-05,8.8e-05,8.8e-05,7.3e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.8e-05,7.3e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0076,-0.044,-0.017,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,1.8e-05,7.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.4e-05,8.8e-05,8.7e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,1.8e-05,7.3e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.4e-05,8.8e-05,8.8e-05,7.2e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23790000,0.71,0.005,0.00066,0.71,-0.089,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2e-05,6.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.005,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2e-05,6.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23990000,0.71,0.00097,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2.2e-05,6.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.6e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-11,6.7e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24090000,0.71,0.0023,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.2e-05,6.4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.8e-11,6.8e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.4e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.4e-05,8.6e-05,8.6e-05,7.1e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-11,6.4e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2.4e-05,5.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.3e-05,8.6e-05,8.6e-05,7.1e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.5e-11,6.5e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24390000,0.71,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.1e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24490000,0.71,0.0047,-0.0017,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.1e-05,5.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.3e-05,8.6e-05,8.5e-05,7.1e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.068,-0.56,-0.081,-0.045,-3.7e+02,-1.3e-05,-5.9e-05,6.4e-06,2e-05,4.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-11,5.9e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-1.3e-05,-5.9e-05,6.5e-06,2e-05,4.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-11,5.9e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24790000,0.71,0.0049,0.0015,0.71,-0.2,-0.095,-0.73,-0.1,-0.063,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.4e-05,4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.3e-05,8.4e-05,8.4e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-11,5.7e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-1.3e-05,-5.9e-05,6.2e-06,2.4e-05,4e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.2e-05,8.4e-05,8.4e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-11,5.7e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-1.3e-05,-5.9e-05,6e-06,3.4e-05,2.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.3e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.5e-11,5.5e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.86,-0.15,-0.093,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3.4e-05,2.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.2e-05,8.4e-05,8.3e-05,7e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.5e-11,5.5e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3e-05,1.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.2e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-11,5.3e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3e-05,1.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.3e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-11,5.3e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-1.2e-05,-5.9e-05,5.9e-06,3.3e-05,3.5e-06,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.2e-05,8.2e-05,8.2e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,3.2e-05,3.7e-06,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.2e-05,8.2e-05,8.2e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,2.9e-05,-5.8e-06,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.2e-05,8.1e-05,8.1e-05,7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-11,4.9e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,2.9e-05,-5.5e-06,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.1e-05,8.1e-05,8.1e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-11,4.9e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,3.8e-05,-3.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3.7e-05,-3.1e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.1e-05,8.1e-05,8e-05,6.9e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-1.1e-05,-5.9e-05,6.1e-06,3.3e-05,-4.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-1.1e-05,-5.9e-05,5.9e-06,3.4e-05,-4.7e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-11,4.6e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-1.1e-05,-5.9e-05,6e-06,4.5e-05,-8.6e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7e-05,7.9e-05,7.9e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-11,4.4e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-1.1e-05,-5.9e-05,5.9e-06,4.6e-05,-8.5e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7e-05,7.9e-05,7.9e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-11,4.5e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-1e-05,-5.9e-05,5.9e-06,3.3e-05,-9.9e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7e-05,7.8e-05,7.8e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-1e-05,-5.9e-05,5.8e-06,3.3e-05,-9.8e-05,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7e-05,7.9e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-9.5e-06,-5.9e-05,5.5e-06,4.3e-05,-0.00013,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7e-05,7.8e-05,7.7e-05,6.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-9.5e-06,-5.9e-05,5.6e-06,4.2e-05,-0.00013,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7e-05,7.8e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-9e-06,-6e-05,5.4e-06,2e-05,-0.00016,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.8e-05,0.015,0.014,0.008,0.039,0.039,0.035,4.1e-11,4.1e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-9e-06,-6e-05,5.4e-06,2e-05,-0.00016,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.9e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4.1e-11,4.1e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-7.9e-06,-6e-05,5.4e-06,2.9e-05,-0.00021,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7e-05,7.6e-05,7.6e-05,6.9e-05,0.015,0.014,0.008,0.039,0.039,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-7.9e-06,-6e-05,5.3e-06,2.9e-05,-0.00021,-0.0013,0.21,0.002,0.44,0,0,0,0,0,7e-05,7.7e-05,7.6e-05,6.8e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-7.8e-06,-5.9e-05,5.4e-06,3.9e-05,-0.0002,-0.0013,0.21,0.002,0.44,0,0,0,0,0,6.9e-05,7.6e-05,7.6e-05,6.8e-05,0.016,0.015,0.0081,0.045,0.045,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-7.8e-06,-5.9e-05,5.4e-06,3.9e-05,-0.0002,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.8e-05,0.017,0.016,0.0081,0.05,0.049,0.035,4e-11,4e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27390000,0.71,0.037,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-7.2e-06,-5.9e-05,5.5e-06,5.9e-05,-0.00021,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.7e-05,0.017,0.016,0.0081,0.052,0.052,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27490000,0.71,0.031,0.063,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-7.2e-06,-5.9e-05,5.4e-06,5.8e-05,-0.00021,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-7.5e-06,-5.9e-05,5.5e-06,5.7e-05,-0.0002,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.017,0.0082,0.06,0.059,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-7.5e-06,-5.9e-05,5.4e-06,5.6e-05,-0.00019,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.7e-05,6.7e-05,0.019,0.018,0.0083,0.065,0.065,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-7.6e-06,-5.8e-05,5.3e-06,5.8e-05,-0.00018,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.019,0.018,0.0082,0.068,0.067,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-7.6e-06,-5.8e-05,5.2e-06,5.6e-05,-0.00018,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.019,0.0083,0.074,0.073,0.035,3.9e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-8e-06,-5.8e-05,5.3e-06,5.1e-05,-0.00016,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.019,0.0083,0.076,0.076,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-8e-06,-5.8e-05,5.1e-06,5e-05,-0.00016,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0084,0.083,0.082,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-8.2e-06,-5.8e-05,5.1e-06,4.7e-05,-0.00014,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.09,-4.4,-2.4,-3.7e+02,-8.2e-06,-5.8e-05,4.9e-06,4.5e-05,-0.00014,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0086,0.092,0.092,0.036,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-8.2e-06,-5.8e-05,4.8e-06,4.3e-05,-0.00013,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.7e-05,6.5e-05,0.022,0.021,0.0087,0.1,0.099,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28490000,0.71,0.0026,0.0045,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,4e-05,-0.00012,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.023,0.022,0.0088,0.11,0.11,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28590000,0.71,0.00084,0.001,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,3.6e-05,-0.00012,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.023,0.0089,0.12,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28690000,0.71,0.00014,8.4e-05,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-8.2e-06,-5.8e-05,4.6e-06,3.2e-05,-0.0001,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.025,0.025,0.009,0.13,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28790000,0.71,-0.00015,-0.00016,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-8.9e-06,-5.8e-05,4.6e-06,1.2e-06,-0.00018,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28890000,0.71,-0.00017,5.4e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-8.9e-06,-5.8e-05,4.6e-06,-3.1e-06,-0.00016,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.8e-05,6.5e-05,0.025,0.025,0.009,0.14,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28990000,0.71,2.3e-05,0.0005,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-9.8e-06,-5.8e-05,4.5e-06,-2.4e-05,-0.00025,-0.0012,0.21,0.002,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.8e-05,6.4e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.7e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29090000,0.71,0.00018,0.0009,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-9.8e-06,-5.8e-05,4.4e-06,-2.9e-05,-0.00023,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-11,3.7e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29190000,0.71,0.0004,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-1e-05,-5.8e-05,4.4e-06,-4.9e-05,-0.00027,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29290000,0.71,0.00075,0.0022,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-1e-05,-5.8e-05,4.3e-06,-5.4e-05,-0.00025,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.026,0.0091,0.16,0.16,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29390000,0.71,0.0013,0.0037,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-1.1e-05,-5.8e-05,4.1e-06,-7e-05,-0.00029,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.009,0.16,0.16,0.036,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-1.1e-05,-5.8e-05,4.1e-06,-7.4e-05,-0.00028,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-1.1e-05,-5.7e-05,4e-06,-9.8e-05,-0.00028,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.009,0.17,0.16,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-1.1e-05,-5.7e-05,3.9e-06,-0.0001,-0.00027,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.93,-8.5,-4.1,-3.7e+02,-1.2e-05,-5.7e-05,3.9e-06,-0.00012,-0.00029,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.3e-05,0.025,0.025,0.0091,0.18,0.17,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29890000,0.71,0.0029,0.0074,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-1.2e-05,-5.7e-05,3.7e-06,-0.00013,-0.00026,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29990000,0.71,0.003,0.0076,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-1.2e-05,-5.7e-05,3.6e-06,-0.00015,-0.00026,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.19,0.18,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30090000,0.71,0.003,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00015,-0.00024,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.026,0.0091,0.2,0.2,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30190000,0.71,0.0031,0.0074,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00017,-0.00025,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.2,0.19,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30290000,0.71,0.003,0.0072,0.71,-2,-1,0.86,-9.6,-4.6,-3.7e+02,-1.2e-05,-5.7e-05,3.4e-06,-0.00017,-0.00024,-0.0011,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.21,0.21,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30390000,0.71,0.003,0.0071,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00018,-0.00023,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.21,0.2,0.036,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30490000,0.71,0.0029,0.0068,0.71,-2,-1,0.83,-10,-4.8,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00019,-0.00022,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.22,0.22,0.037,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30590000,0.71,0.0028,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00019,-0.00022,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.4e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.3e-11,3.2e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.0002,-0.00021,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.23,0.23,0.037,3.3e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30790000,0.71,0.0026,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00021,-0.0002,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30890000,0.71,0.0025,0.0055,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00021,-0.00019,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.24,0.24,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30990000,0.71,0.0024,0.005,0.71,-1.8,-0.96,0.76,-11,-5.3,-3.7e+02,-1.3e-05,-5.7e-05,3.1e-06,-0.00022,-0.00018,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31090000,0.71,0.0022,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-1.3e-05,-5.7e-05,3e-06,-0.00023,-0.00017,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.25,0.24,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31190000,0.71,0.0022,0.0043,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00024,-0.00014,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.1e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31290000,0.71,0.002,0.0038,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00024,-0.00013,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.1e-05,0.026,0.027,0.0089,0.26,0.25,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31390000,0.71,0.0018,0.0033,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00025,-0.00011,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31490000,0.71,0.0016,0.0027,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00026,-0.0001,-0.001,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.027,0.0088,0.26,0.26,0.037,3.1e-11,3.1e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31590000,0.71,0.0016,0.0023,0.71,-1.7,-0.91,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-8.4e-05,-0.00099,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31690000,0.71,0.0013,0.0017,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-7.2e-05,-0.00099,0.21,0.002,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31790000,0.71,0.0011,0.0011,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00028,-5.4e-05,-0.00098,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31890000,0.71,0.00087,0.00037,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00029,-4.1e-05,-0.00098,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31990000,0.71,0.00074,-8.3e-05,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.0003,-2.2e-05,-0.00097,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32090000,0.71,0.00045,-0.0008,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.0003,-6.8e-06,-0.00096,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32190000,0.71,0.00024,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00031,1.4e-05,-0.00096,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-11,2.9e-11,9.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32290000,0.71,6.6e-06,-0.0023,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00032,3e-05,-0.00095,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.3,0.3,0.037,3e-11,2.9e-11,9.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32390000,0.71,-0.00018,-0.0029,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00032,3.9e-05,-0.00095,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-11,2.9e-11,9.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32490000,0.71,-0.0003,-0.0032,0.71,-1.4,-0.82,0.72,-14,-6.6,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00033,5e-05,-0.00094,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-11,2.9e-11,9.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32590000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,5.8e-05,-0.00094,0.21,0.002,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0084,0.31,0.31,0.036,2.9e-11,2.9e-11,9.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32690000,0.71,-0.00034,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,6.3e-05,-0.00094,0.21,0.002,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.5e-05,5.9e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32790000,0.71,-0.0003,-0.0034,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00034,7.2e-05,-0.00094,0.21,0.002,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0084,0.32,0.31,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32890000,0.71,-0.00021,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00034,8.3e-05,-0.00093,0.21,0.002,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.9e-11,2.9e-11,9.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32990000,0.71,-7.6e-05,-0.0033,0.71,-1.3,-0.77,0.7,-15,-7,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00035,9.6e-05,-0.00093,0.21,0.002,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.32,0.32,0.036,2.8e-11,2.8e-11,9.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33090000,0.71,-0.00011,-0.0033,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.0001,-0.00093,0.21,0.002,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-11,2.8e-11,9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.00011,-0.00092,0.21,0.002,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.33,0.33,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33290000,0.65,0.015,-0.0015,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00036,0.00011,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.9e-05,8e-05,7.4e-05,6.1e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33390000,0.55,0.013,-0.0017,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,7.9e-05,7.5e-05,6.5e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-11,2.8e-11,8.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33490000,0.41,0.0069,0.00072,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5e-05,7.8e-05,7.7e-05,7e-05,0.026,0.026,0.0081,0.36,0.35,0.036,2.8e-11,2.8e-11,8.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33590000,0.25,0.00098,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.002,0.44,0,0,0,0,0,4.7e-05,7.6e-05,7.8e-05,7.3e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33690000,0.087,-0.0023,-0.0049,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.002,0.44,0,0,0,0,0,4.5e-05,7.5e-05,8e-05,7.6e-05,0.028,0.028,0.0076,0.36,0.36,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33790000,-0.082,-0.0038,-0.0067,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.002,0.44,0,0,0,0,0,4.4e-05,7.2e-05,8e-05,7.6e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-11,2.7e-11,8.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33890000,-0.25,-0.0049,-0.0074,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.002,0.44,0,0,0,0,0,4.6e-05,7.2e-05,8.1e-05,7.5e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-11,2.8e-11,8.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33990000,-0.39,-0.0031,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.002,0.44,0,0,0,0,0,4.8e-05,6.9e-05,7.8e-05,7.2e-05,0.031,0.032,0.007,0.37,0.37,0.035,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34090000,-0.5,-0.0021,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.6e-06,-0.00036,0.00012,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.1e-05,6.9e-05,7.8e-05,6.9e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34190000,-0.57,-0.0014,-0.011,0.82,-0.92,-0.54,0.74,-16,-7.8,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.4e-05,6.5e-05,7.3e-05,6.7e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34290000,-0.61,-0.0023,-0.0086,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,6.5e-05,7.3e-05,6.5e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34390000,-0.64,-0.0025,-0.0061,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00043,0.00019,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,6e-05,6.7e-05,6.4e-05,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-11,2.7e-11,8.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34490000,-0.65,-0.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00043,0.00019,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,6.1e-05,6.7e-05,6.3e-05,0.049,0.05,0.0064,0.4,0.4,0.035,2.7e-11,2.7e-11,8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00027,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-11,2.7e-11,8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.37,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00027,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-11,2.7e-11,7.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34790000,-0.67,-0.0021,-0.0018,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00064,0.00038,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34890000,-0.68,-0.0021,-0.0017,0.74,-0.7,-0.32,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00064,0.00038,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.059,0.061,0.0062,0.42,0.42,0.034,2.6e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34990000,-0.68,-0.0085,-0.0045,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.058,0.058,0.0068,0.42,0.42,0.034,2.6e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35090000,-0.68,-0.0085,-0.0045,0.73,0.43,0.31,-0.19,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.063,0.063,0.0068,0.43,0.43,0.034,2.7e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35190000,-0.68,-0.0085,-0.0045,0.73,0.45,0.34,-0.18,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.068,0.068,0.0067,0.44,0.44,0.034,2.7e-11,2.7e-11,7.6e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35290000,-0.68,-0.0086,-0.0046,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.073,0.074,0.0066,0.46,0.45,0.033,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35390000,-0.68,-0.0086,-0.0046,0.73,0.5,0.41,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.079,0.08,0.0066,0.47,0.47,0.034,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35490000,-0.68,-0.0087,-0.0046,0.73,0.52,0.44,-0.18,-17,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.085,0.087,0.0065,0.49,0.49,0.034,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35590000,-0.68,-0.0056,-0.0046,0.73,0.41,0.36,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00077,0.00052,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6.1e-05,0.068,0.069,0.0062,0.48,0.48,0.033,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35690000,-0.68,-0.0057,-0.0045,0.73,0.43,0.38,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00077,0.00052,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6e-05,0.073,0.075,0.0061,0.49,0.49,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35790000,-0.68,-0.0034,-0.0044,0.73,0.35,0.32,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3e-06,-0.00079,0.00053,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.061,0.062,0.0059,0.49,0.48,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35890000,-0.68,-0.0034,-0.0045,0.73,0.37,0.35,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,3.1e-06,-0.00079,0.00053,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.066,0.068,0.0059,0.5,0.5,0.033,2.7e-11,2.7e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35990000,-0.68,-0.0016,-0.0044,0.73,0.3,0.29,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.3e-06,-0.00087,0.00059,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.8e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36090000,-0.68,-0.0016,-0.0044,0.73,0.31,0.31,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00087,0.0006,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-11,2.8e-11,7.1e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36190000,-0.68,-0.00015,-0.0043,0.73,0.26,0.27,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00097,0.00068,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-11,2.8e-11,7.1e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36290000,-0.68,-0.00021,-0.0042,0.73,0.27,0.28,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.7e-06,-0.00097,0.00068,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.06,0.062,0.0056,0.52,0.52,0.032,2.7e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36390000,-0.68,0.00084,-0.0041,0.73,0.22,0.24,-0.21,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.9e-06,-0.0011,0.00077,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36490000,-0.68,0.00079,-0.0042,0.73,0.23,0.26,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.1e-06,-0.0011,0.00077,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.059,0.061,0.0055,0.53,0.52,0.032,2.8e-11,2.8e-11,6.9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36590000,-0.68,0.0016,-0.004,0.73,0.19,0.22,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.3e-06,-0.0012,0.00086,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,6e-05,0.053,0.054,0.0055,0.52,0.52,0.031,2.8e-11,2.8e-11,6.9e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36690000,-0.68,0.0016,-0.004,0.74,0.19,0.23,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.4e-06,-0.0012,0.00086,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,5.9e-05,0.058,0.06,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36790000,-0.68,0.0022,-0.0039,0.74,0.16,0.2,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.5e-06,-0.0013,0.00095,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,5.9e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36890000,-0.68,0.0022,-0.0039,0.74,0.16,0.21,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.6e-06,-0.0013,0.00095,-0.00092,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,5.9e-05,0.057,0.059,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36990000,-0.68,0.0026,-0.0037,0.74,0.13,0.18,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.8e-06,-0.0015,0.001,-0.00093,0.21,0.002,0.44,0,0,0,0,0,5.6e-05,1.9e-05,2e-05,5.9e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37090000,-0.68,0.0026,-0.0037,0.74,0.13,0.19,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5e-06,-0.0015,0.001,-0.00093,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,2e-05,2.1e-05,5.9e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37190000,-0.68,0.0029,-0.0036,0.74,0.11,0.16,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.2e-06,-0.0016,0.0011,-0.00093,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.9e-05,2e-05,5.9e-05,0.05,0.052,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.6e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37290000,-0.68,0.0029,-0.0036,0.74,0.11,0.17,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.4e-06,-0.0016,0.0011,-0.00093,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.9e-05,2e-05,5.9e-05,0.055,0.057,0.0059,0.56,0.56,0.031,2.8e-11,2.9e-11,6.6e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37390000,-0.68,0.0032,-0.0034,0.74,0.088,0.14,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.5e-06,-0.0017,0.0011,-0.00093,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.05,0.051,0.0059,0.56,0.56,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37490000,-0.68,0.0032,-0.0034,0.74,0.087,0.15,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.6e-06,-0.0017,0.0011,-0.00093,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37590000,-0.68,0.0033,-0.0033,0.74,0.069,0.12,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.8e-06,-0.0017,0.0012,-0.00093,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.049,0.05,0.0061,0.57,0.57,0.031,2.9e-11,2.9e-11,6.4e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37690000,-0.68,0.0033,-0.0034,0.74,0.066,0.13,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.9e-06,-0.0017,0.0012,-0.00093,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-11,2.9e-11,6.4e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37790000,-0.68,0.0034,-0.0033,0.74,0.052,0.11,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.1e-06,-0.0018,0.0012,-0.00094,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.048,0.048,0.0063,0.58,0.58,0.03,2.9e-11,2.9e-11,6.4e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37890000,-0.68,0.0034,-0.0033,0.74,0.05,0.11,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.3e-06,-0.0018,0.0012,-0.00094,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.052,0.053,0.0064,0.59,0.59,0.03,2.9e-11,2.9e-11,6.3e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37990000,-0.68,0.0034,-0.0033,0.74,0.037,0.097,-0.15,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.5e-06,-0.0019,0.0013,-0.00095,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.047,0.047,0.0065,0.59,0.59,0.031,2.9e-11,2.9e-11,6.3e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38090000,-0.68,0.0034,-0.0033,0.74,0.034,0.1,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.6e-06,-0.0019,0.0013,-0.00095,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38190000,-0.68,0.0034,-0.0032,0.74,0.022,0.085,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.8e-06,-0.002,0.0013,-0.00096,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38290000,-0.68,0.0034,-0.0032,0.74,0.019,0.086,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.9e-06,-0.002,0.0013,-0.00096,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.049,0.05,0.0068,0.61,0.61,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38390000,-0.68,0.0034,-0.0031,0.74,0.012,0.074,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.1e-06,-0.002,0.0013,-0.00097,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38490000,-0.68,0.0034,-0.0031,0.74,0.0091,0.076,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.2e-06,-0.002,0.0013,-0.00097,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.8e-05,0.048,0.048,0.007,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38590000,-0.68,0.0034,-0.003,0.74,0.0051,0.065,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.4e-06,-0.002,0.0013,-0.00098,0.21,0.002,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.8e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38690000,-0.68,0.0033,-0.003,0.74,0.0012,0.065,-0.097,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.5e-06,-0.0021,0.0013,-0.00098,0.21,0.002,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38790000,-0.68,0.0033,-0.003,0.74,-0.0034,0.054,-0.089,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.7e-06,-0.0021,0.0013,-0.00098,0.21,0.002,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38890000,-0.67,0.0031,-0.003,0.74,-0.013,0.043,0.41,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.8e-06,-0.0021,0.0013,-0.00099,0.21,0.002,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.045,0.045,0.0075,0.64,0.64,0.032,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
6390000,0.71,0.0014,-0.014,0.71,0.0048,0.0076,-0.05,0.0025,0.0017,-3.7e+02,-1.6e-05,-5.6e-05,4.3e-07,0,0,4e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00076,0.00034,0.00034,0.00085,0.22,0.22,2.3,0.13,0.13,0.29,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6490000,0.71,0.0014,-0.014,0.71,0.0043,0.0083,-0.052,0.0029,0.0025,-3.7e+02,-1.6e-05,-5.6e-05,4.1e-07,0,0,-8.7e-08,0.21,0.0021,0.44,0,0,0,0,0,0.00051,0.00034,0.00034,0.00056,0.22,0.22,1.5,0.16,0.16,0.26,1.4e-08,1.5e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6590000,0.71,0.0015,-0.014,0.71,0.0036,0.0085,-0.099,0.0034,0.0033,-3.7e+02,-1.6e-05,-5.6e-05,3.6e-07,0,0,1.7e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00039,0.00034,0.00034,0.00043,0.23,0.23,1.1,0.19,0.19,0.23,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6690000,0.7,0.0015,-0.014,0.71,0.0037,0.0095,-0.076,0.0037,0.0042,-3.7e+02,-1.6e-05,-5.6e-05,3e-07,0,0,-1.5e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00031,0.00034,0.00034,0.00035,0.24,0.24,0.78,0.23,0.23,0.21,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6790000,0.71,0.0015,-0.014,0.71,0.0021,0.0095,-0.11,0.004,0.0052,-3.7e+02,-1.6e-05,-5.6e-05,3.3e-07,0,0,8.5e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00027,0.00034,0.00034,0.0003,0.25,0.25,0.6,0.28,0.28,0.2,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6890000,0.71,0.0015,-0.014,0.71,-0.00021,0.01,-0.12,0.0041,0.0062,-3.7e+02,-1.6e-05,-5.6e-05,3.4e-07,0,0,3.4e-07,0.21,0.0021,0.44,0,0,0,0,0,0.00024,0.00035,0.00035,0.00026,0.26,0.26,0.46,0.33,0.33,0.18,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
6990000,0.7,0.0016,-0.014,0.71,-0.00055,0.011,-0.12,0.004,0.0072,-3.7e+02,-1.6e-05,-5.6e-05,1.6e-07,0,0,-2.7e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00021,0.00035,0.00035,0.00023,0.28,0.28,0.36,0.38,0.38,0.16,1.4e-08,1.4e-08,4.8e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
7090000,0.7,0.0016,-0.014,0.71,-0.0014,0.011,-0.13,0.0039,0.0083,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-08,0,0,-6.3e-06,0.21,0.0021,0.44,0,0,0,0,0,0.0002,0.00036,0.00036,0.00022,0.3,0.3,0.29,0.44,0.44,0.16,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
7190000,0.7,0.0016,-0.014,0.71,-0.0034,0.011,-0.15,0.0037,0.0093,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-07,0,0,-4.1e-06,0.21,0.0021,0.44,0,0,0,0,0,0.00018,0.00036,0.00036,0.0002,0.32,0.32,0.24,0.51,0.51,0.15,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,4e-06,0,0,0,0,0,0,0,0
|
||||
7290000,0.7,0.0016,-0.014,0.71,-0.0052,0.011,-0.15,0.0033,0.01,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,0,0,-1.1e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00017,0.00037,0.00037,0.00018,0.34,0.34,0.2,0.58,0.58,0.14,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7390000,0.7,0.0017,-0.014,0.71,-0.0056,0.012,-0.16,0.0027,0.011,-3.7e+02,-1.6e-05,-5.6e-05,-1.3e-07,0,0,-1.2e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00016,0.00038,0.00038,0.00017,0.37,0.37,0.18,0.66,0.66,0.13,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7490000,0.7,0.0017,-0.014,0.71,-0.0076,0.013,-0.16,0.002,0.013,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,0,0,-2e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00015,0.00039,0.00039,0.00016,0.4,0.4,0.15,0.76,0.76,0.12,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7590000,0.7,0.0017,-0.014,0.71,-0.0098,0.014,-0.17,0.0011,0.014,-3.7e+02,-1.6e-05,-5.6e-05,-1.4e-08,0,0,-2.9e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.00039,0.00039,0.00015,0.43,0.43,0.14,0.85,0.85,0.12,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7690000,0.7,0.0018,-0.014,0.71,-0.012,0.015,-0.16,2.3e-05,0.015,-3.7e+02,-1.6e-05,-5.6e-05,-4.5e-08,0,0,-4.9e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00014,0.0004,0.0004,0.00015,0.47,0.47,0.13,0.96,0.96,0.11,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.9e-06,0,0,0,0,0,0,0,0
|
||||
7790000,0.7,0.0019,-0.014,0.71,-0.014,0.016,-0.16,-0.0013,0.017,-3.7e+02,-1.6e-05,-5.6e-05,-3.7e-07,0,0,-6.9e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00041,0.00041,0.00014,0.51,0.51,0.12,1.1,1.1,0.11,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
|
||||
7890000,0.7,0.0019,-0.014,0.71,-0.017,0.018,-0.16,-0.0028,0.018,-3.7e+02,-1.6e-05,-5.6e-05,-2.7e-07,0,0,-9.5e-05,0.21,0.0021,0.44,0,0,0,0,0,0.00013,0.00042,0.00042,0.00014,0.55,0.55,0.11,1.2,1.2,0.1,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
|
||||
7990000,0.7,0.0019,-0.014,0.71,-0.019,0.019,-0.16,-0.0046,0.02,-3.7e+02,-1.6e-05,-5.6e-05,-1.6e-07,0,0,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00043,0.00043,0.00013,0.6,0.59,0.1,1.3,1.3,0.099,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.8e-06,0,0,0,0,0,0,0,0
|
||||
8090000,0.7,0.0019,-0.014,0.71,-0.021,0.02,-0.17,-0.0066,0.022,-3.7e+02,-1.6e-05,-5.6e-05,6.1e-08,0,0,-0.00011,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00045,0.00045,0.00013,0.65,0.65,0.1,1.5,1.5,0.097,1.4e-08,1.4e-08,4.7e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
|
||||
8190000,0.7,0.0019,-0.014,0.71,-0.024,0.021,-0.18,-0.0088,0.023,-3.7e+02,-1.6e-05,-5.6e-05,-2.1e-07,0,0,-0.00013,0.21,0.0021,0.44,0,0,0,0,0,0.00012,0.00046,0.00046,0.00012,0.69,0.69,0.099,1.7,1.7,0.094,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.7e-06,0,0,0,0,0,0,0,0
|
||||
8290000,0.7,0.002,-0.014,0.71,-0.026,0.022,-0.17,-0.011,0.025,-3.7e+02,-1.6e-05,-5.6e-05,-4e-07,0,0,-0.00017,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00047,0.00047,0.00012,0.75,0.75,0.097,1.9,1.9,0.091,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.6e-06,0,0,0,0,0,0,0,0
|
||||
8390000,0.7,0.002,-0.014,0.71,-0.029,0.023,-0.17,-0.014,0.028,-3.7e+02,-1.6e-05,-5.6e-05,-1.5e-07,0,0,-0.00021,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00048,0.00048,0.00012,0.81,0.81,0.097,2.1,2.1,0.091,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.5e-06,0,0,0,0,0,0,0,0
|
||||
8490000,0.7,0.002,-0.014,0.71,-0.031,0.025,-0.17,-0.017,0.029,-3.7e+02,-1.6e-05,-5.6e-05,-3e-07,0,0,-0.00025,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00049,0.00049,0.00012,0.87,0.87,0.096,2.3,2.3,0.089,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.4e-06,0,0,0,0,0,0,0,0
|
||||
8590000,0.7,0.002,-0.014,0.71,-0.034,0.027,-0.17,-0.021,0.032,-3.7e+02,-1.6e-05,-5.6e-05,-6.2e-07,0,0,-0.00029,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00051,0.00051,0.00011,0.94,0.94,0.095,2.5,2.5,0.088,1.4e-08,1.4e-08,4.6e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
|
||||
8690000,0.7,0.0021,-0.014,0.71,-0.037,0.028,-0.16,-0.024,0.033,-3.7e+02,-1.6e-05,-5.6e-05,-2.5e-07,0,0,-0.00034,0.21,0.0021,0.44,0,0,0,0,0,0.00011,0.00052,0.00052,0.00011,0.99,0.99,0.096,2.7,2.7,0.088,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,3.3e-06,0,0,0,0,0,0,0,0
|
||||
8790000,0.7,0.0021,-0.014,0.71,-0.04,0.03,-0.15,-0.028,0.036,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,0,0,-0.00041,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00054,0.00054,0.00011,1.1,1.1,0.095,3,3,0.087,1.4e-08,1.4e-08,4.5e-09,4e-06,4e-06,3.1e-06,0,0,0,0,0,0,0,0
|
||||
8890000,0.7,0.0021,-0.014,0.71,-0.043,0.03,-0.15,-0.032,0.038,-3.7e+02,-1.6e-05,-5.6e-05,-6.2e-07,0,0,-0.00045,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00055,0.00055,0.00011,1.1,1.1,0.095,3.3,3.3,0.086,1.3e-08,1.3e-08,4.5e-09,4e-06,4e-06,3e-06,0,0,0,0,0,0,0,0
|
||||
8990000,0.7,0.0021,-0.014,0.71,-0.045,0.031,-0.14,-0.036,0.04,-3.7e+02,-1.6e-05,-5.6e-05,-9.6e-07,0,0,-0.0005,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00056,0.00056,0.00011,1.2,1.2,0.096,3.6,3.6,0.087,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.9e-06,0,0,0,0,0,0,0,0
|
||||
9090000,0.7,0.0022,-0.014,0.71,-0.048,0.031,-0.14,-0.04,0.042,-3.7e+02,-1.6e-05,-5.6e-05,-1.2e-06,0,0,-0.00053,0.21,0.0021,0.44,0,0,0,0,0,0.0001,0.00057,0.00057,0.00011,1.3,1.3,0.095,3.9,3.9,0.086,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.8e-06,0,0,0,0,0,0,0,0
|
||||
9190000,0.7,0.0022,-0.014,0.71,-0.05,0.032,-0.14,-0.045,0.045,-3.7e+02,-1.6e-05,-5.6e-05,-5.2e-07,0,0,-0.00057,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.00059,0.00059,0.0001,1.4,1.4,0.094,4.3,4.3,0.085,1.3e-08,1.3e-08,4.4e-09,4e-06,4e-06,2.7e-06,0,0,0,0,0,0,0,0
|
||||
9290000,0.7,0.0022,-0.014,0.71,-0.051,0.033,-0.14,-0.048,0.046,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,0,0,-0.00061,0.21,0.0021,0.44,0,0,0,0,0,9.9e-05,0.0006,0.0006,0.0001,1.4,1.4,0.093,4.5,4.5,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.5e-06,0,0,0,0,0,0,0,0
|
||||
9390000,0.7,0.0022,-0.014,0.71,-0.053,0.035,-0.14,-0.054,0.049,-3.7e+02,-1.6e-05,-5.6e-05,-5.1e-07,0,0,-0.00064,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00062,0.00061,0.0001,1.5,1.5,0.093,5,5,0.086,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.4e-06,0,0,0,0,0,0,0,0
|
||||
9490000,0.7,0.0022,-0.014,0.71,-0.054,0.035,-0.13,-0.057,0.05,-3.7e+02,-1.6e-05,-5.6e-05,1.3e-08,0,0,-0.00068,0.21,0.0021,0.44,0,0,0,0,0,9.8e-05,0.00062,0.00062,0.0001,1.6,1.6,0.091,5.2,5.2,0.085,1.3e-08,1.3e-08,4.3e-09,4e-06,4e-06,2.3e-06,0,0,0,0,0,0,0,0
|
||||
9590000,0.7,0.0022,-0.014,0.71,-0.058,0.036,-0.13,-0.062,0.053,-3.7e+02,-1.6e-05,-5.6e-05,1.4e-07,0,0,-0.00072,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00064,0.00064,0.0001,1.7,1.7,0.089,5.8,5.8,0.085,1.3e-08,1.3e-08,4.2e-09,4e-06,4e-06,2.1e-06,0,0,0,0,0,0,0,0
|
||||
9690000,0.7,0.0022,-0.014,0.71,-0.058,0.037,-0.12,-0.065,0.053,-3.7e+02,-1.6e-05,-5.6e-05,-4.4e-07,0,0,-0.00077,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00064,0.00064,0.0001,1.7,1.7,0.089,6,6,0.086,1.3e-08,1.3e-08,4.2e-09,4e-06,4e-06,2e-06,0,0,0,0,0,0,0,0
|
||||
9790000,0.7,0.0022,-0.014,0.71,-0.06,0.039,-0.11,-0.071,0.056,-3.7e+02,-1.6e-05,-5.6e-05,-9.9e-08,0,0,-0.00082,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00066,0.00066,0.0001,1.8,1.8,0.087,6.6,6.6,0.085,1.3e-08,1.3e-08,4.1e-09,4e-06,4e-06,1.9e-06,0,0,0,0,0,0,0,0
|
||||
9890000,0.7,0.0022,-0.014,0.71,-0.06,0.039,-0.11,-0.073,0.056,-3.7e+02,-1.6e-05,-5.6e-05,-1.8e-07,0,0,-0.00085,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00066,0.00066,9.9e-05,1.8,1.8,0.084,6.8,6.8,0.085,1.2e-08,1.2e-08,4.1e-09,4e-06,4e-06,1.8e-06,0,0,0,0,0,0,0,0
|
||||
9990000,0.7,0.0023,-0.014,0.71,-0.063,0.04,-0.1,-0.079,0.06,-3.7e+02,-1.6e-05,-5.6e-05,-4.7e-07,0,0,-0.00088,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00068,0.00068,9.9e-05,2,2,0.083,7.4,7.4,0.086,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.7e-06,0,0,0,0,0,0,0,0
|
||||
10090000,0.7,0.0023,-0.014,0.71,-0.061,0.039,-0.097,-0.079,0.059,-3.7e+02,-1.5e-05,-5.6e-05,-3.7e-07,0,0,-0.00091,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00067,0.00067,9.8e-05,2,2,0.08,7.5,7.5,0.085,1.2e-08,1.2e-08,4e-09,4e-06,4e-06,1.6e-06,0,0,0,0,0,0,0,0
|
||||
10190000,0.7,0.0023,-0.014,0.71,-0.064,0.042,-0.096,-0.086,0.063,-3.7e+02,-1.5e-05,-5.6e-05,-1.2e-06,0,0,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00069,0.00069,9.8e-05,2.1,2.1,0.078,8.3,8.3,0.084,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
|
||||
10290000,0.7,0.0022,-0.014,0.71,-0.062,0.04,-0.084,-0.085,0.061,-3.7e+02,-1.5e-05,-5.6e-05,-1.7e-06,0,0,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00068,0.00068,9.8e-05,2.1,2.1,0.076,8.3,8.3,0.085,1.2e-08,1.2e-08,3.9e-09,4e-06,4e-06,1.4e-06,0,0,0,0,0,0,0,0
|
||||
10390000,0.7,0.0022,-0.014,0.71,0.0091,-0.019,0.0096,0.00085,-0.0017,-3.7e+02,-1.5e-05,-5.6e-05,-1.7e-06,-6.6e-10,4.8e-10,-0.001,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0007,0.0007,9.7e-05,0.25,0.25,0.56,0.25,0.25,0.078,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.3e-06,0,0,0,0,0,0,0,0
|
||||
10490000,0.7,0.0023,-0.014,0.71,0.0074,-0.017,0.023,0.0017,-0.0036,-3.7e+02,-1.5e-05,-5.6e-05,-2.2e-06,-1.7e-08,1.2e-08,-0.001,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00073,0.00073,9.7e-05,0.26,0.26,0.55,0.26,0.26,0.08,1.2e-08,1.2e-08,3.8e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
|
||||
10590000,0.7,0.0024,-0.014,0.71,0.0069,-0.0065,0.026,0.0018,-0.00081,-3.7e+02,-1.5e-05,-5.6e-05,-2.2e-06,-2.7e-06,4.5e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00073,0.00073,9.7e-05,0.14,0.14,0.27,0.13,0.13,0.073,1.2e-08,1.2e-08,3.7e-09,4e-06,4e-06,1.2e-06,0,0,0,0,0,0,0,0
|
||||
10690000,0.7,0.0024,-0.014,0.71,0.0044,-0.0059,0.03,0.0024,-0.0015,-3.7e+02,-1.5e-05,-5.6e-05,-2.4e-06,-2.7e-06,4.7e-07,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00076,0.00076,9.7e-05,0.15,0.15,0.26,0.14,0.14,0.078,1.2e-08,1.2e-08,3.7e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
10790000,0.7,0.0024,-0.014,0.71,0.004,-0.0032,0.024,0.0026,-0.00073,-3.7e+02,-1.5e-05,-5.5e-05,-2.4e-06,-4.3e-06,2.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00074,0.00073,9.7e-05,0.11,0.11,0.17,0.091,0.091,0.072,1.1e-08,1.1e-08,3.6e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
10890000,0.7,0.0024,-0.014,0.71,0.0023,-0.0019,0.02,0.0029,-0.00095,-3.7e+02,-1.5e-05,-5.5e-05,-2.5e-06,-4.3e-06,2.1e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00076,0.00076,9.6e-05,0.13,0.13,0.16,0.098,0.098,0.075,1.1e-08,1.1e-08,3.5e-09,4e-06,4e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
10990000,0.7,0.0023,-0.014,0.71,0.0052,0.0032,0.014,0.0046,-0.0022,-3.7e+02,-1.4e-05,-5.5e-05,-2e-06,-8.3e-06,8.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0007,0.00069,9.7e-05,0.1,0.1,0.12,0.073,0.073,0.071,1.1e-08,1.1e-08,3.5e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
11090000,0.7,0.0023,-0.014,0.71,0.0035,0.0056,0.019,0.0051,-0.0018,-3.7e+02,-1.4e-05,-5.5e-05,-1.5e-06,-8.3e-06,8.9e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00072,0.00072,9.6e-05,0.13,0.13,0.11,0.08,0.08,0.074,1.1e-08,1.1e-08,3.4e-09,3.9e-06,3.9e-06,1.1e-06,0,0,0,0,0,0,0,0
|
||||
11190000,0.7,0.0022,-0.014,0.71,0.0087,0.0081,0.0077,0.0066,-0.0028,-3.7e+02,-1.3e-05,-5.5e-05,-2e-06,-9.5e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00062,0.00062,9.6e-05,0.1,0.1,0.084,0.063,0.063,0.069,9.4e-09,9.5e-09,3.4e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11290000,0.7,0.0023,-0.014,0.71,0.0082,0.011,0.0074,0.0075,-0.0018,-3.7e+02,-1.3e-05,-5.5e-05,-2.7e-06,-9.5e-06,1.5e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00064,0.00064,9.6e-05,0.13,0.13,0.078,0.071,0.071,0.072,9.4e-09,9.5e-09,3.3e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11390000,0.7,0.0023,-0.014,0.71,0.0037,0.009,0.0017,0.0054,-0.002,-3.7e+02,-1.4e-05,-5.5e-05,-3.2e-06,-5.3e-06,1.2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00054,0.00054,9.6e-05,0.1,0.1,0.063,0.058,0.058,0.068,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11490000,0.7,0.0023,-0.014,0.71,0.00095,0.012,0.0025,0.0056,-0.00092,-3.7e+02,-1.4e-05,-5.5e-05,-4.2e-06,-5.3e-06,1.2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00056,0.00056,9.6e-05,0.13,0.13,0.058,0.066,0.066,0.069,8.4e-09,8.4e-09,3.2e-09,3.8e-06,3.8e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11590000,0.7,0.0022,-0.014,0.71,-0.0029,0.01,-0.0034,0.0044,-0.0014,-3.7e+02,-1.4e-05,-5.6e-05,-4.4e-06,-1e-06,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00046,0.00046,9.6e-05,0.1,0.1,0.049,0.054,0.054,0.066,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11690000,0.7,0.0022,-0.014,0.71,-0.006,0.013,-0.008,0.0039,-0.00027,-3.7e+02,-1.4e-05,-5.6e-05,-4.7e-06,-9.5e-07,1.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00047,0.00047,9.6e-05,0.12,0.12,0.046,0.063,0.063,0.066,7.4e-09,7.4e-09,3.1e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11790000,0.7,0.0022,-0.014,0.71,-0.011,0.013,-0.0098,0.0017,0.00056,-3.7e+02,-1.4e-05,-5.6e-05,-4.8e-06,1.4e-07,9.7e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00039,0.00039,9.6e-05,0.096,0.096,0.039,0.052,0.052,0.063,6.6e-09,6.6e-09,3e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11890000,0.7,0.0022,-0.014,0.71,-0.013,0.014,-0.011,0.00052,0.0019,-3.7e+02,-1.4e-05,-5.6e-05,-5.3e-06,8.2e-08,9.7e-06,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0004,0.0004,9.6e-05,0.12,0.12,0.037,0.061,0.061,0.063,6.6e-09,6.6e-09,2.9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
11990000,0.7,0.0022,-0.014,0.71,-0.014,0.014,-0.016,-0.0004,0.0023,-3.7e+02,-1.4e-05,-5.6e-05,-5.1e-06,1.5e-06,1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00034,0.00034,9.6e-05,0.09,0.09,0.033,0.051,0.051,0.061,5.9e-09,5.9e-09,2.9e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
12090000,0.7,0.0022,-0.014,0.71,-0.016,0.016,-0.022,-0.0019,0.0038,-3.7e+02,-1.4e-05,-5.6e-05,-4.7e-06,1.7e-06,1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00035,0.00035,9.6e-05,0.11,0.11,0.031,0.06,0.06,0.061,5.9e-09,5.9e-09,2.8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
12190000,0.7,0.0018,-0.014,0.71,-0.0089,0.013,-0.017,0.0014,0.0019,-3.7e+02,-1.3e-05,-5.7e-05,-4.5e-06,4.4e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0003,0.0003,9.5e-05,0.085,0.085,0.028,0.051,0.051,0.059,5.4e-09,5.4e-09,2.8e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
12290000,0.7,0.0018,-0.014,0.71,-0.012,0.015,-0.016,0.00035,0.0033,-3.7e+02,-1.3e-05,-5.7e-05,-4.3e-06,4.1e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00031,0.00031,9.6e-05,0.1,0.1,0.028,0.059,0.059,0.059,5.4e-09,5.4e-09,2.7e-09,3.7e-06,3.7e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
12390000,0.7,0.0015,-0.014,0.71,-0.0059,0.011,-0.015,0.0029,0.0017,-3.7e+02,-1.3e-05,-5.8e-05,-4.6e-06,5.9e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00027,0.00027,9.5e-05,0.079,0.079,0.026,0.05,0.05,0.057,5e-09,5e-09,2.6e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
12490000,0.7,0.0015,-0.014,0.71,-0.0072,0.013,-0.018,0.0023,0.0029,-3.7e+02,-1.3e-05,-5.8e-05,-5.1e-06,5.9e-06,1.9e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00028,0.00028,9.5e-05,0.092,0.092,0.026,0.059,0.059,0.057,5e-09,5e-09,2.6e-09,3.6e-06,3.6e-06,1e-06,0,0,0,0,0,0,0,0
|
||||
12590000,0.7,0.0016,-0.014,0.71,-0.015,0.011,-0.023,-0.0028,0.0015,-3.7e+02,-1.3e-05,-5.8e-05,-5e-06,7.3e-06,1.7e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00025,0.00025,9.5e-05,0.073,0.073,0.025,0.05,0.05,0.055,4.7e-09,4.7e-09,2.5e-09,3.6e-06,3.6e-06,9.8e-07,0,0,0,0,0,0,0,0
|
||||
12690000,0.7,0.0016,-0.014,0.71,-0.015,0.012,-0.027,-0.0043,0.0026,-3.7e+02,-1.3e-05,-5.8e-05,-5.2e-06,7.5e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00026,0.00026,9.5e-05,0.085,0.085,0.025,0.058,0.058,0.055,4.7e-09,4.7e-09,2.5e-09,3.6e-06,3.6e-06,9.8e-07,0,0,0,0,0,0,0,0
|
||||
12790000,0.7,0.0016,-0.013,0.71,-0.02,0.0092,-0.03,-0.0077,0.0013,-3.7e+02,-1.4e-05,-5.8e-05,-5e-06,8e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00023,0.00023,9.5e-05,0.068,0.068,0.024,0.049,0.049,0.053,4.4e-09,4.4e-09,2.4e-09,3.6e-06,3.6e-06,9.7e-07,0,0,0,0,0,0,0,0
|
||||
12890000,0.7,0.0016,-0.013,0.71,-0.021,0.0091,-0.03,-0.0097,0.0022,-3.7e+02,-1.4e-05,-5.8e-05,-4.8e-06,7.4e-06,1.6e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.7e-05,0.00024,0.00024,9.5e-05,0.079,0.079,0.025,0.058,0.058,0.054,4.4e-09,4.4e-09,2.4e-09,3.6e-06,3.6e-06,9.6e-07,0,0,0,0,0,0,0,0
|
||||
12990000,0.7,0.0012,-0.014,0.71,-0.0088,0.0066,-0.03,-0.0011,0.0012,-3.7e+02,-1.3e-05,-5.9e-05,-4.2e-06,7.3e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00022,9.5e-05,0.064,0.064,0.025,0.049,0.049,0.052,4.2e-09,4.2e-09,2.3e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0
|
||||
13090000,0.7,0.0012,-0.014,0.71,-0.0096,0.0068,-0.03,-0.002,0.0018,-3.7e+02,-1.3e-05,-5.9e-05,-4.7e-06,6.9e-06,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00023,0.00023,9.5e-05,0.073,0.073,0.025,0.057,0.057,0.052,4.2e-09,4.2e-09,2.3e-09,3.6e-06,3.6e-06,9.4e-07,0,0,0,0,0,0,0,0
|
||||
13190000,0.7,0.00099,-0.014,0.71,-0.00038,0.0062,-0.027,0.0044,0.0012,-3.7e+02,-1.2e-05,-5.9e-05,-4.6e-06,5.6e-06,2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.06,0.06,0.025,0.049,0.049,0.051,4e-09,4e-09,2.2e-09,3.6e-06,3.6e-06,9.1e-07,0,0,0,0,0,0,0,0
|
||||
13290000,0.7,0.001,-0.014,0.71,-0.00066,0.007,-0.024,0.0043,0.0018,-3.7e+02,-1.2e-05,-5.9e-05,-4.1e-06,4.3e-06,2.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00022,9.4e-05,0.068,0.069,0.027,0.057,0.057,0.051,4e-09,4e-09,2.2e-09,3.6e-06,3.6e-06,9.1e-07,0,0,0,0,0,0,0,0
|
||||
13390000,0.7,0.00085,-0.014,0.71,0.00026,0.006,-0.02,0.0033,0.0011,-3.7e+02,-1.2e-05,-5.9e-05,-3.6e-06,2.6e-06,2.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.056,0.056,0.026,0.049,0.049,0.05,3.8e-09,3.8e-09,2.1e-09,3.6e-06,3.6e-06,8.8e-07,0,0,0,0,0,0,0,0
|
||||
13490000,0.7,0.00087,-0.014,0.71,-0.00025,0.0059,-0.019,0.0033,0.0017,-3.7e+02,-1.2e-05,-5.9e-05,-3.1e-06,1.8e-06,2.1e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00022,0.00021,9.4e-05,0.064,0.064,0.028,0.057,0.057,0.05,3.8e-09,3.8e-09,2.1e-09,3.6e-06,3.6e-06,8.7e-07,0,0,0,0,0,0,0,0
|
||||
13590000,0.7,0.00081,-0.014,0.71,7.7e-05,0.0061,-0.021,0.0024,0.001,-3.7e+02,-1.2e-05,-5.9e-05,-3.4e-06,1.5e-06,2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.4e-05,0.053,0.053,0.028,0.049,0.049,0.05,3.6e-09,3.6e-09,2e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0
|
||||
13690000,0.7,0.00079,-0.014,0.71,0.00075,0.0078,-0.025,0.0024,0.0017,-3.7e+02,-1.1e-05,-5.9e-05,-2.7e-06,1.8e-06,2e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.4e-05,0.061,0.061,0.029,0.056,0.056,0.05,3.6e-09,3.6e-09,2e-09,3.6e-06,3.6e-06,8.3e-07,0,0,0,0,0,0,0,0
|
||||
13790000,0.7,0.00067,-0.014,0.71,0.0014,0.0036,-0.027,0.0035,-0.00062,-3.7e+02,-1.1e-05,-6e-05,-2.7e-06,-3.4e-07,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.0002,0.0002,9.3e-05,0.051,0.051,0.029,0.048,0.048,0.049,3.4e-09,3.4e-09,1.9e-09,3.6e-06,3.6e-06,7.9e-07,0,0,0,0,0,0,0,0
|
||||
13890000,0.7,0.00063,-0.014,0.71,0.0019,0.0035,-0.031,0.0036,-0.00029,-3.7e+02,-1.1e-05,-6e-05,-2.3e-06,-3.5e-08,1.8e-05,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,9.6e-05,0.00021,0.00021,9.3e-05,0.058,0.058,0.03,0.056,0.056,0.05,3.4e-09,3.4e-09,1.9e-09,3.6e-06,3.6e-06,7.8e-07,0,0,0,0,0,0,0,0
|
||||
13990000,0.7,0.00056,-0.014,0.71,0.0022,0.001,-0.03,0.0045,-0.002,-3.7e+02,-1.1e-05,-6e-05,-2.2e-06,-2.7e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.049,0.049,0.03,0.048,0.048,0.05,3.2e-09,3.2e-09,1.8e-09,3.6e-06,3.6e-06,7.4e-07,0,0,0,0,0,0,0,0
|
||||
14090000,0.7,0.00054,-0.014,0.71,0.0023,0.0012,-0.031,0.0047,-0.0019,-3.7e+02,-1.1e-05,-6e-05,-1.5e-06,-2.6e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.055,0.055,0.031,0.056,0.056,0.05,3.2e-09,3.2e-09,1.8e-09,3.6e-06,3.6e-06,7.3e-07,0,0,0,0,0,0,0,0
|
||||
14190000,0.7,0.00044,-0.014,0.71,0.0057,0.00062,-0.033,0.0068,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-1.1e-06,-2.4e-06,1.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.047,0.047,0.031,0.048,0.048,0.05,3.1e-09,3.1e-09,1.8e-09,3.6e-06,3.6e-06,6.9e-07,0,0,0,0,0,0,0,0
|
||||
14290000,0.7,0.00045,-0.014,0.71,0.0065,0.0014,-0.032,0.0074,-0.0016,-3.7e+02,-1.1e-05,-6e-05,-8.2e-07,-3e-06,1.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.0002,0.0002,9.3e-05,0.053,0.053,0.032,0.055,0.055,0.051,3.1e-09,3.1e-09,1.7e-09,3.6e-06,3.6e-06,6.7e-07,0,0,0,0,0,0,0,0
|
||||
14390000,0.7,0.00036,-0.014,0.71,0.0083,0.0023,-0.034,0.0087,-0.0013,-3.7e+02,-1.1e-05,-6e-05,-1.5e-07,-3.1e-06,1.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.5e-05,0.00019,0.00019,9.2e-05,0.045,0.045,0.031,0.048,0.048,0.05,2.9e-09,2.9e-09,1.7e-09,3.6e-06,3.6e-06,6.3e-07,0,0,0,0,0,0,0,0
|
||||
14490000,0.7,0.00034,-0.013,0.71,0.0083,0.0035,-0.037,0.0095,-0.001,-3.7e+02,-1e-05,-6e-05,7.6e-08,-2.6e-06,1.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.2e-05,0.051,0.051,0.032,0.055,0.055,0.051,2.9e-09,2.9e-09,1.6e-09,3.6e-06,3.6e-06,6.2e-07,0,0,0,0,0,0,0,0
|
||||
14590000,0.7,0.00033,-0.013,0.71,0.0049,0.0019,-0.038,0.006,-0.0025,-3.7e+02,-1.1e-05,-6.1e-05,1.4e-07,-6.3e-06,1.6e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.2e-05,0.044,0.044,0.031,0.047,0.047,0.051,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.8e-07,0,0,0,0,0,0,0,0
|
||||
14690000,0.7,0.00029,-0.013,0.71,0.0062,-0.0011,-0.034,0.0066,-0.0024,-3.7e+02,-1.1e-05,-6.1e-05,6.2e-07,-7.4e-06,1.7e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.2e-05,0.049,0.049,0.032,0.054,0.054,0.051,2.7e-09,2.7e-09,1.6e-09,3.6e-06,3.6e-06,5.6e-07,0,0,0,0,0,0,0,0
|
||||
14790000,0.7,0.00031,-0.013,0.71,0.003,-0.0026,-0.03,0.0037,-0.0034,-3.7e+02,-1.1e-05,-6.1e-05,7.8e-07,-1.1e-05,2.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.00019,0.00019,9.1e-05,0.043,0.043,0.031,0.047,0.047,0.051,2.6e-09,2.6e-09,1.5e-09,3.6e-06,3.6e-06,5.3e-07,0,0,0,0,0,0,0,0
|
||||
14890000,0.7,0.00031,-0.013,0.71,0.0046,-0.0017,-0.033,0.0041,-0.0036,-3.7e+02,-1.1e-05,-6.1e-05,1.1e-06,-1.1e-05,2.2e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.4e-05,0.0002,0.0002,9.1e-05,0.048,0.048,0.031,0.054,0.054,0.052,2.6e-09,2.6e-09,1.5e-09,3.6e-06,3.6e-06,5.1e-07,0,0,0,0,0,0,0,0
|
||||
14990000,0.7,0.0003,-0.013,0.71,0.0034,-0.0019,-0.029,0.0031,-0.0029,-3.7e+02,-1.2e-05,-6.1e-05,1e-06,-1.2e-05,2.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.042,0.042,0.03,0.047,0.047,0.051,2.4e-09,2.4e-09,1.5e-09,3.5e-06,3.5e-06,4.8e-07,0,0,0,0,0,0,0,0
|
||||
15090000,0.7,0.00023,-0.013,0.71,0.0038,-0.0021,-0.032,0.0035,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.1e-06,-1.1e-05,2.4e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.047,0.047,0.031,0.054,0.054,0.052,2.4e-09,2.4e-09,1.4e-09,3.5e-06,3.5e-06,4.6e-07,0,0,0,0,0,0,0,0
|
||||
15190000,0.7,0.00025,-0.013,0.71,0.0032,-0.00083,-0.029,0.0028,-0.0024,-3.7e+02,-1.2e-05,-6.1e-05,1e-06,-1.1e-05,2.5e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9.1e-05,0.041,0.041,0.03,0.047,0.047,0.052,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4.3e-07,0,0,0,0,0,0,0,0
|
||||
15290000,0.7,0.0002,-0.013,0.71,0.0038,-0.00068,-0.027,0.0031,-0.0025,-3.7e+02,-1.2e-05,-6.1e-05,1.4e-06,-1.2e-05,2.6e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00019,0.00019,9e-05,0.046,0.046,0.03,0.054,0.054,0.052,2.3e-09,2.3e-09,1.4e-09,3.5e-06,3.5e-06,4.2e-07,0,0,0,0,0,0,0,0
|
||||
15390000,0.7,0.00021,-0.013,0.71,0.003,-0.00032,-0.025,0.00054,-0.002,-3.7e+02,-1.2e-05,-6.1e-05,2e-06,-1.3e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.3e-05,0.00018,0.00018,9e-05,0.04,0.04,0.029,0.047,0.047,0.051,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.9e-07,0,0,0,0,0,0,0,0
|
||||
15490000,0.7,0.00023,-0.013,0.71,0.0043,-0.00071,-0.025,0.00091,-0.0021,-3.7e+02,-1.2e-05,-6.1e-05,1.7e-06,-1.2e-05,2.8e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00019,9e-05,0.045,0.045,0.029,0.053,0.053,0.053,2.1e-09,2.1e-09,1.3e-09,3.5e-06,3.5e-06,3.7e-07,0,0,0,0,0,0,0,0
|
||||
15590000,0.7,0.00024,-0.013,0.71,0.0024,-0.0007,-0.023,-0.0013,-0.0017,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.2e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,9e-05,0.039,0.039,0.028,0.046,0.046,0.052,1.9e-09,1.9e-09,1.3e-09,3.5e-06,3.5e-06,3.5e-07,0,0,0,0,0,0,0,0
|
||||
15690000,0.7,0.00025,-0.013,0.71,0.0027,-0.00088,-0.024,-0.0011,-0.0018,-3.7e+02,-1.2e-05,-6.1e-05,1.5e-06,-1.2e-05,3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00019,0.00018,8.9e-05,0.044,0.044,0.028,0.053,0.053,0.052,1.9e-09,1.9e-09,1.2e-09,3.5e-06,3.5e-06,3.3e-07,0,0,0,0,0,0,0,0
|
||||
15790000,0.7,0.00021,-0.013,0.71,0.0032,-0.0025,-0.026,-0.00098,-0.0028,-3.7e+02,-1.2e-05,-6.1e-05,1.6e-06,-1.5e-05,3.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.2e-05,0.00018,0.00018,8.9e-05,0.039,0.039,0.027,0.046,0.046,0.051,1.8e-09,1.8e-09,1.2e-09,3.4e-06,3.4e-06,3.1e-07,0,0,0,0,0,0,0,0
|
||||
15890000,0.7,0.00016,-0.013,0.71,0.0042,-0.003,-0.024,-0.00058,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,1.7e-06,-1.5e-05,3.1e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,8.9e-05,0.044,0.044,0.027,0.053,0.053,0.052,1.8e-09,1.8e-09,1.2e-09,3.4e-06,3.4e-06,3e-07,0,0,0,0,0,0,0,0
|
||||
15990000,0.7,0.0001,-0.013,0.71,0.004,-0.0039,-0.02,-0.00066,-0.0039,-3.7e+02,-1.2e-05,-6.1e-05,2.1e-06,-1.8e-05,3.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.9e-05,0.038,0.038,0.026,0.046,0.046,0.051,1.7e-09,1.7e-09,1.2e-09,3.4e-06,3.4e-06,2.8e-07,0,0,0,0,0,0,0,0
|
||||
16090000,0.71,0.0001,-0.013,0.71,0.0058,-0.0042,-0.016,-0.00019,-0.0043,-3.7e+02,-1.2e-05,-6.1e-05,2.7e-06,-1.9e-05,3.3e-05,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00018,0.00018,8.8e-05,0.043,0.043,0.025,0.053,0.053,0.052,1.7e-09,1.7e-09,1.1e-09,3.4e-06,3.4e-06,2.7e-07,0,0,0,0,0,0,0,0
|
||||
16190000,0.71,0.00013,-0.013,0.71,0.0057,-0.0034,-0.015,-0.0004,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,2.8e-06,-1.8e-05,3.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9.1e-05,0.00017,0.00017,8.8e-05,0.038,0.038,0.025,0.046,0.046,0.051,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.5e-07,0,0,0,0,0,0,0,0
|
||||
16290000,0.71,0.00014,-0.013,0.71,0.0074,-0.0042,-0.016,0.00026,-0.0039,-3.7e+02,-1.2e-05,-6.1e-05,3.4e-06,-1.7e-05,3.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.8e-05,0.042,0.042,0.024,0.053,0.053,0.052,1.5e-09,1.5e-09,1.1e-09,3.4e-06,3.4e-06,2.4e-07,0,0,0,0,0,0,0,0
|
||||
16390000,0.71,0.00013,-0.013,0.71,0.0063,-0.0044,-0.015,-6.7e-05,-0.0031,-3.7e+02,-1.2e-05,-6.1e-05,3.3e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.8e-05,0.037,0.037,0.023,0.046,0.046,0.051,1.4e-09,1.4e-09,1.1e-09,3.3e-06,3.4e-06,2.2e-07,0,0,0,0,0,0,0,0
|
||||
16490000,0.71,0.00015,-0.013,0.71,0.0055,-0.004,-0.018,0.00049,-0.0035,-3.7e+02,-1.2e-05,-6.1e-05,3.4e-06,-1.6e-05,3.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00017,0.00017,8.7e-05,0.042,0.042,0.023,0.052,0.052,0.052,1.4e-09,1.4e-09,1e-09,3.3e-06,3.4e-06,2.1e-07,0,0,0,0,0,0,0,0
|
||||
16590000,0.71,0.00041,-0.013,0.71,0.0019,-0.0012,-0.018,-0.0025,-7.8e-05,-3.7e+02,-1.3e-05,-6e-05,3.5e-06,-9e-06,4.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,9e-05,0.00016,0.00016,8.7e-05,0.037,0.037,0.022,0.046,0.046,0.051,1.3e-09,1.3e-09,1e-09,3.3e-06,3.3e-06,2e-07,0,0,0,0,0,0,0,0
|
||||
16690000,0.71,0.0004,-0.013,0.71,0.0021,-0.00073,-0.015,-0.0023,-0.00018,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-9.6e-06,4.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00017,0.00016,8.7e-05,0.041,0.041,0.022,0.052,0.052,0.051,1.3e-09,1.3e-09,9.9e-10,3.3e-06,3.3e-06,1.9e-07,0,0,0,0,0,0,0,0
|
||||
16790000,0.71,0.00055,-0.013,0.71,-0.0013,0.0015,-0.014,-0.0047,0.0025,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-3.9e-06,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.7e-05,0.036,0.036,0.021,0.046,0.046,0.05,1.2e-09,1.2e-09,9.7e-10,3.3e-06,3.3e-06,1.8e-07,0,0,0,0,0,0,0,0
|
||||
16890000,0.71,0.00056,-0.013,0.71,-0.0016,0.0023,-0.011,-0.0048,0.0027,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-4.3e-06,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00016,0.00016,8.6e-05,0.041,0.041,0.021,0.052,0.052,0.051,1.2e-09,1.2e-09,9.5e-10,3.3e-06,3.3e-06,1.7e-07,0,0,0,0,0,0,0,0
|
||||
16990000,0.71,0.0005,-0.013,0.71,-0.0016,0.00033,-0.011,-0.0052,0.00086,-3.7e+02,-1.3e-05,-6e-05,2.9e-06,-8.4e-06,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.9e-05,0.00015,0.00015,8.6e-05,0.036,0.036,0.02,0.046,0.046,0.05,1.1e-09,1.1e-09,9.2e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0
|
||||
17090000,0.71,0.00047,-0.013,0.71,-0.00076,0.0013,-0.01,-0.0053,0.00091,-3.7e+02,-1.3e-05,-6e-05,3e-06,-8.3e-06,5.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00016,0.00016,8.6e-05,0.04,0.04,0.02,0.052,0.052,0.05,1.1e-09,1.1e-09,9e-10,3.3e-06,3.3e-06,1.6e-07,0,0,0,0,0,0,0,0
|
||||
17190000,0.71,0.00046,-0.013,0.71,-0.00031,0.0013,-0.011,-0.0057,-0.00054,-3.7e+02,-1.3e-05,-6e-05,3.2e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.6e-05,0.035,0.035,0.019,0.046,0.046,0.049,9.5e-10,9.6e-10,8.9e-10,3.2e-06,3.2e-06,1.5e-07,0,0,0,0,0,0,0,0
|
||||
17290000,0.71,0.00043,-0.013,0.71,0.0018,0.0023,-0.0067,-0.0056,-0.00038,-3.7e+02,-1.4e-05,-6e-05,3e-06,-1.2e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00015,8.5e-05,0.039,0.039,0.019,0.052,0.052,0.049,9.5e-10,9.6e-10,8.7e-10,3.2e-06,3.2e-06,1.4e-07,0,0,0,0,0,0,0,0
|
||||
17390000,0.71,0.0004,-0.013,0.71,0.0024,0.0015,-0.0047,-0.0047,-0.0016,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.8e-05,0.00015,0.00014,8.5e-05,0.034,0.034,0.018,0.046,0.046,0.048,8.7e-10,8.7e-10,8.5e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
|
||||
17490000,0.71,0.00039,-0.013,0.71,0.003,0.001,-0.003,-0.0044,-0.0015,-3.7e+02,-1.3e-05,-6e-05,3.3e-06,-1.6e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00015,0.00015,8.5e-05,0.038,0.038,0.018,0.052,0.052,0.049,8.7e-10,8.7e-10,8.3e-10,3.2e-06,3.2e-06,1.3e-07,0,0,0,0,0,0,0,0
|
||||
17590000,0.71,0.0003,-0.013,0.71,0.0042,-0.00014,0.0025,-0.0037,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.4e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.5e-05,0.034,0.034,0.017,0.046,0.046,0.048,7.9e-10,7.9e-10,8.1e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0
|
||||
17690000,0.71,0.00027,-0.012,0.71,0.0051,0.00056,0.0019,-0.0032,-0.0026,-3.7e+02,-1.4e-05,-6.1e-05,3.6e-06,-1.9e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.038,0.038,0.017,0.052,0.052,0.048,7.9e-10,7.9e-10,7.9e-10,3.2e-06,3.2e-06,1.2e-07,0,0,0,0,0,0,0,0
|
||||
17790000,0.71,0.00018,-0.013,0.71,0.0077,0.00029,0.00056,-0.0021,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.9e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.7e-05,0.00014,0.00014,8.4e-05,0.033,0.033,0.016,0.045,0.045,0.048,7.1e-10,7.1e-10,7.8e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
|
||||
17890000,0.71,0.00019,-0.013,0.71,0.0092,-0.00047,0.00065,-0.0012,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.9e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.4e-05,0.037,0.037,0.016,0.052,0.052,0.048,7.1e-10,7.1e-10,7.6e-10,3.2e-06,3.2e-06,1.1e-07,0,0,0,0,0,0,0,0
|
||||
17990000,0.71,0.00014,-0.013,0.71,0.011,-0.0022,0.0019,-0.00053,-0.0019,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.4e-05,0.032,0.032,0.016,0.045,0.045,0.047,6.4e-10,6.4e-10,7.5e-10,3.1e-06,3.1e-06,1e-07,0,0,0,0,0,0,0,0
|
||||
18090000,0.71,0.00014,-0.013,0.71,0.012,-0.0024,0.0043,0.00061,-0.0022,-3.7e+02,-1.3e-05,-6.1e-05,4e-06,-1.8e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00014,0.00014,8.3e-05,0.036,0.036,0.016,0.051,0.051,0.047,6.4e-10,6.4e-10,7.3e-10,3.1e-06,3.1e-06,9.7e-08,0,0,0,0,0,0,0,0
|
||||
18190000,0.71,0.00011,-0.013,0.71,0.012,-0.0013,0.0056,0.0015,-0.0017,-3.7e+02,-1.3e-05,-6.1e-05,4.2e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.6e-05,0.00013,0.00013,8.3e-05,0.032,0.032,0.015,0.045,0.045,0.047,5.8e-10,5.8e-10,7.2e-10,3.1e-06,3.1e-06,9.2e-08,0,0,0,0,0,0,0,0
|
||||
18290000,0.71,4.9e-05,-0.012,0.71,0.012,-0.0019,0.0068,0.0027,-0.0018,-3.7e+02,-1.3e-05,-6.1e-05,4.1e-06,-1.7e-05,5.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.035,0.035,0.015,0.051,0.051,0.046,5.8e-10,5.8e-10,7e-10,3.1e-06,3.1e-06,8.9e-08,0,0,0,0,0,0,0,0
|
||||
18390000,0.71,6.5e-05,-0.013,0.71,0.014,-0.0002,0.0079,0.0032,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.4e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.3e-05,0.031,0.031,0.014,0.045,0.045,0.046,5.3e-10,5.3e-10,6.9e-10,3.1e-06,3.1e-06,8.4e-08,0,0,0,0,0,0,0,0
|
||||
18490000,0.71,8e-05,-0.012,0.71,0.014,0.00021,0.0076,0.0047,-0.0014,-3.7e+02,-1.3e-05,-6.1e-05,4.5e-06,-1.7e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00013,0.00013,8.2e-05,0.034,0.034,0.014,0.051,0.051,0.046,5.3e-10,5.3e-10,6.7e-10,3.1e-06,3.1e-06,8.2e-08,0,0,0,0,0,0,0,0
|
||||
18590000,0.71,8.5e-05,-0.012,0.71,0.013,0.00045,0.0057,0.0035,-0.0012,-3.7e+02,-1.4e-05,-6.1e-05,4.9e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.5e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.014,0.045,0.045,0.045,4.8e-10,4.8e-10,6.6e-10,3.1e-06,3.1e-06,7.8e-08,0,0,0,0,0,0,0,0
|
||||
18690000,0.71,5.4e-05,-0.012,0.71,0.014,-0.00024,0.0038,0.0049,-0.0011,-3.7e+02,-1.4e-05,-6.1e-05,4.8e-06,-1.7e-05,5.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00013,0.00012,8.2e-05,0.034,0.034,0.013,0.051,0.051,0.045,4.8e-10,4.8e-10,6.5e-10,3.1e-06,3.1e-06,7.5e-08,0,0,0,0,0,0,0,0
|
||||
18790000,0.71,8.4e-05,-0.012,0.71,0.012,6.5e-05,0.0035,0.0038,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,4.6e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.2e-05,0.03,0.03,0.013,0.045,0.045,0.045,4.4e-10,4.4e-10,6.3e-10,3.1e-06,3.1e-06,7.2e-08,0,0,0,0,0,0,0,0
|
||||
18890000,0.71,0.00011,-0.012,0.71,0.013,0.00056,0.0041,0.005,-0.00085,-3.7e+02,-1.4e-05,-6.1e-05,5e-06,-1.7e-05,6.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.033,0.033,0.013,0.051,0.051,0.045,4.4e-10,4.4e-10,6.2e-10,3.1e-06,3.1e-06,7e-08,0,0,0,0,0,0,0,0
|
||||
18990000,0.71,9.4e-05,-0.012,0.71,0.014,0.0015,0.0028,0.0063,-0.0007,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.029,0.029,0.012,0.045,0.045,0.044,4e-10,4e-10,6.1e-10,3e-06,3e-06,6.6e-08,0,0,0,0,0,0,0,0
|
||||
19090000,0.71,7.9e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0078,-0.0005,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.2e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.4e-05,0.00012,0.00012,8.1e-05,0.032,0.032,0.012,0.051,0.051,0.044,4e-10,4e-10,6e-10,3e-06,3e-06,6.5e-08,0,0,0,0,0,0,0,0
|
||||
19190000,0.71,8.1e-05,-0.012,0.71,0.015,0.0021,0.0058,0.0086,-0.00045,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00011,8.1e-05,0.028,0.028,0.012,0.045,0.045,0.044,3.6e-10,3.6e-10,5.9e-10,3e-06,3e-06,6.2e-08,0,0,0,0,0,0,0,0
|
||||
19290000,0.71,0.0001,-0.012,0.71,0.015,0.0013,0.0086,0.01,-0.00027,-3.7e+02,-1.4e-05,-6.1e-05,5.2e-06,-1.7e-05,6.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00012,0.00012,8e-05,0.031,0.031,0.012,0.05,0.05,0.044,3.6e-10,3.6e-10,5.7e-10,3e-06,3e-06,6e-08,0,0,0,0,0,0,0,0
|
||||
19390000,0.71,0.00012,-0.012,0.71,0.013,0.00039,0.012,0.008,-0.00028,-3.7e+02,-1.4e-05,-6.1e-05,5.3e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.028,0.028,0.012,0.045,0.045,0.043,3.3e-10,3.3e-10,5.6e-10,3e-06,3e-06,5.8e-08,0,0,0,0,0,0,0,0
|
||||
19490000,0.71,0.00014,-0.012,0.71,0.012,-0.00033,0.0088,0.0092,-0.00028,-3.7e+02,-1.4e-05,-6.1e-05,5.6e-06,-1.8e-05,6.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.3e-05,0.00011,0.00011,8e-05,0.03,0.03,0.011,0.05,0.05,0.043,3.3e-10,3.3e-10,5.5e-10,3e-06,3e-06,5.6e-08,0,0,0,0,0,0,0,0
|
||||
19590000,0.71,0.00019,-0.012,0.71,0.0097,-0.0013,0.0081,0.0075,-0.0003,-3.7e+02,-1.4e-05,-6.1e-05,5.9e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.027,0.027,0.011,0.044,0.044,0.042,3e-10,3e-10,5.4e-10,3e-06,3e-06,5.4e-08,0,0,0,0,0,0,0,0
|
||||
19690000,0.71,0.00019,-0.012,0.71,0.01,-0.0035,0.0096,0.0085,-0.00055,-3.7e+02,-1.4e-05,-6.1e-05,5.7e-06,-1.8e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,8e-05,0.029,0.029,0.011,0.05,0.05,0.042,3e-10,3e-10,5.3e-10,3e-06,3e-06,5.2e-08,0,0,0,0,0,0,0,0
|
||||
19790000,0.71,0.00026,-0.012,0.71,0.0078,-0.0044,0.01,0.0068,-0.00044,-3.7e+02,-1.4e-05,-6.1e-05,5.8e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.011,0.044,0.044,0.042,2.7e-10,2.7e-10,5.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19890000,0.71,0.0002,-0.012,0.71,0.0065,-0.0047,0.011,0.0076,-0.00091,-3.7e+02,-1.4e-05,-6.1e-05,6.2e-06,-1.8e-05,7.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.2e-05,0.00011,0.00011,7.9e-05,0.029,0.029,0.011,0.05,0.05,0.042,2.7e-10,2.7e-10,5.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19990000,0.71,0.00019,-0.012,0.71,0.0041,-0.0053,0.014,0.0062,-0.00076,-3.7e+02,-1.4e-05,-6.1e-05,6.7e-06,-1.7e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.026,0.026,0.01,0.044,0.044,0.041,2.5e-10,2.5e-10,5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20090000,0.71,0.00018,-0.012,0.71,0.0039,-0.0073,0.014,0.0065,-0.0014,-3.7e+02,-1.4e-05,-6.1e-05,7.1e-06,-1.7e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.9e-05,0.028,0.028,0.01,0.05,0.05,0.042,2.5e-10,2.5e-10,4.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20190000,0.71,0.00029,-0.012,0.71,0.0015,-0.008,0.017,0.0042,-0.0011,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.6e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.9e-05,0.025,0.025,0.01,0.044,0.044,0.041,2.3e-10,2.3e-10,4.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20290000,0.71,0.00025,-0.012,0.71,0.00038,-0.0096,0.015,0.0043,-0.002,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-1.6e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.00011,0.00011,7.8e-05,0.027,0.027,0.0099,0.049,0.049,0.041,2.3e-10,2.3e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20390000,0.71,0.00027,-0.012,0.71,-0.0021,-0.01,0.017,0.0024,-0.0015,-3.7e+02,-1.4e-05,-6e-05,7.4e-06,-1.4e-05,7.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8.1e-05,0.0001,0.0001,7.8e-05,0.024,0.024,0.0097,0.044,0.044,0.041,2.1e-10,2.1e-10,4.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20490000,0.71,0.00032,-0.012,0.71,-0.0025,-0.011,0.016,0.0022,-0.0026,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.4e-05,7.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.027,0.027,0.0096,0.049,0.049,0.041,2.1e-10,2.1e-10,4.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20590000,0.71,0.00034,-0.012,0.71,-0.0022,-0.011,0.013,0.0019,-0.0021,-3.7e+02,-1.4e-05,-6e-05,7.1e-06,-1.3e-05,7.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.024,0.024,0.0094,0.044,0.044,0.04,2e-10,2e-10,4.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20690000,0.71,0.00037,-0.012,0.71,-0.0022,-0.012,0.015,0.0016,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.2e-06,-1.3e-05,7.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.8e-05,0.026,0.026,0.0093,0.049,0.049,0.04,2e-10,2e-10,4.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20790000,0.71,0.0004,-0.012,0.71,-0.0033,-0.011,0.015,0.0014,-0.0025,-3.7e+02,-1.4e-05,-6e-05,7.3e-06,-1.1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,8e-05,0.0001,0.0001,7.7e-05,0.023,0.023,0.0091,0.043,0.043,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20890000,0.71,0.00038,-0.012,0.71,-0.0037,-0.014,0.014,0.001,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-1.1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,0.0001,0.0001,7.7e-05,0.025,0.025,0.0091,0.049,0.049,0.04,1.8e-10,1.8e-10,4.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20990000,0.71,0.00039,-0.012,0.71,-0.004,-0.014,0.015,0.0027,-0.0031,-3.7e+02,-1.4e-05,-6e-05,7.5e-06,-8.7e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.7e-05,0.023,0.023,0.0089,0.043,0.043,0.039,1.7e-10,1.7e-10,4.2e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21090000,0.71,0.00039,-0.012,0.71,-0.0041,-0.017,0.015,0.0023,-0.0047,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-8.7e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.9e-05,9.9e-05,7.7e-05,0.025,0.025,0.0089,0.048,0.048,0.039,1.7e-10,1.7e-10,4.1e-10,2.9e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21190000,0.71,0.00042,-0.012,0.71,-0.0033,-0.016,0.014,0.0037,-0.0038,-3.7e+02,-1.4e-05,-6e-05,7.6e-06,-6.3e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.7e-05,9.7e-05,7.7e-05,0.022,0.022,0.0087,0.043,0.043,0.039,1.5e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21290000,0.71,0.00046,-0.012,0.71,-0.0039,-0.018,0.016,0.0034,-0.0054,-3.7e+02,-1.4e-05,-6e-05,7.9e-06,-6.3e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.8e-05,9.8e-05,7.6e-05,0.024,0.024,0.0086,0.048,0.048,0.039,1.6e-10,1.6e-10,4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21390000,0.71,0.00051,-0.012,0.71,-0.0047,-0.017,0.016,0.0029,-0.0034,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,-2.6e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.9e-05,9.6e-05,9.6e-05,7.6e-05,0.022,0.022,0.0085,0.043,0.043,0.039,1.4e-10,1.4e-10,3.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21490000,0.71,0.00052,-0.012,0.71,-0.0053,-0.018,0.015,0.0023,-0.0052,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,-2.6e-06,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.7e-05,9.6e-05,7.6e-05,0.023,0.023,0.0085,0.048,0.048,0.038,1.4e-10,1.4e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21590000,0.71,0.00054,-0.012,0.71,-0.0058,-0.015,0.015,0.0019,-0.0032,-3.7e+02,-1.4e-05,-6e-05,7.7e-06,8e-07,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.021,0.021,0.0083,0.043,0.043,0.038,1.3e-10,1.3e-10,3.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21690000,0.71,0.00055,-0.012,0.71,-0.0057,-0.016,0.017,0.0013,-0.0048,-3.7e+02,-1.4e-05,-6e-05,7.8e-06,7.8e-07,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.5e-05,9.5e-05,7.6e-05,0.023,0.023,0.0084,0.048,0.048,0.038,1.3e-10,1.3e-10,3.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21790000,0.71,0.00057,-0.012,0.71,-0.0063,-0.011,0.015,9e-05,-0.00075,-3.7e+02,-1.4e-05,-5.9e-05,7.6e-06,6e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.8e-05,9.4e-05,9.4e-05,7.5e-05,0.021,0.021,0.0082,0.042,0.042,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21890000,0.71,0.00057,-0.012,0.71,-0.0063,-0.012,0.016,-0.00054,-0.0019,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,5.9e-06,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.4e-05,9.4e-05,7.5e-05,0.022,0.022,0.0082,0.047,0.047,0.038,1.3e-10,1.3e-10,3.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21990000,0.71,0.00062,-0.012,0.71,-0.0068,-0.0091,0.016,-0.0015,0.0015,-3.7e+02,-1.4e-05,-5.9e-05,7.5e-06,1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.3e-05,9.3e-05,7.5e-05,0.02,0.02,0.0081,0.042,0.042,0.038,1.2e-10,1.2e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22090000,0.71,0.00064,-0.012,0.71,-0.0071,-0.0082,0.015,-0.0021,0.00064,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1e-05,7.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.4e-05,9.3e-05,7.5e-05,0.022,0.022,0.0081,0.047,0.047,0.038,1.2e-10,1.2e-10,3.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22190000,0.71,0.00061,-0.012,0.71,-0.0069,-0.0073,0.015,-0.0018,0.00059,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.2e-05,9.2e-05,7.5e-05,0.02,0.02,0.008,0.042,0.042,0.037,1.1e-10,1.1e-10,3.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22290000,0.71,0.00065,-0.012,0.71,-0.0082,-0.0081,0.015,-0.0025,-0.00018,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.1e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.3e-05,9.2e-05,7.4e-05,0.021,0.021,0.008,0.047,0.047,0.037,1.1e-10,1.1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22390000,0.71,0.00062,-0.012,0.71,-0.0088,-0.0075,0.017,-0.0022,-0.00017,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.2e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.7e-05,9.1e-05,9.1e-05,7.4e-05,0.019,0.019,0.0079,0.042,0.042,0.037,1e-10,1e-10,3.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22490000,0.71,0.00063,-0.012,0.71,-0.0095,-0.0075,0.018,-0.0031,-0.00094,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.2e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.2e-05,9.2e-05,7.4e-05,0.021,0.021,0.0079,0.047,0.047,0.037,1e-10,1e-10,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22590000,0.71,0.00061,-0.012,0.71,-0.0092,-0.007,0.017,-0.0034,0.00014,-3.7e+02,-1.4e-05,-5.9e-05,7.3e-06,1.3e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.1e-05,9e-05,7.4e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.7e-11,9.7e-11,3.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22690000,0.71,0.00064,-0.012,0.71,-0.01,-0.0067,0.018,-0.0043,-0.00054,-3.7e+02,-1.4e-05,-5.9e-05,7.4e-06,1.3e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9.1e-05,9.1e-05,7.4e-05,0.02,0.02,0.0079,0.046,0.046,0.037,9.7e-11,9.7e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22790000,0.71,0.00063,-0.012,0.71,-0.011,-0.0055,0.019,-0.0055,-0.00043,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.4e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.4e-05,0.019,0.019,0.0078,0.042,0.042,0.036,9.2e-11,9.2e-11,3.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22890000,0.71,0.00064,-0.012,0.71,-0.012,-0.0051,0.021,-0.0066,-0.00097,-3.7e+02,-1.4e-05,-5.9e-05,6.9e-06,1.4e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,9e-05,9e-05,7.3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,9.2e-11,9.2e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22990000,0.71,0.00062,-0.012,0.71,-0.012,-0.0056,0.022,-0.0074,-0.00086,-3.7e+02,-1.4e-05,-5.9e-05,7e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.6e-05,8.9e-05,8.9e-05,7.3e-05,0.018,0.018,0.0078,0.041,0.041,0.036,8.7e-11,8.7e-11,3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23090000,0.71,0.00059,-0.012,0.71,-0.013,-0.0056,0.022,-0.0086,-0.0014,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.4e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,9e-05,9e-05,7.3e-05,0.02,0.02,0.0078,0.046,0.046,0.036,8.7e-11,8.7e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23190000,0.71,0.00065,-0.012,0.71,-0.014,-0.0066,0.024,-0.012,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.9e-05,7.3e-05,0.018,0.018,0.0077,0.041,0.041,0.036,8.2e-11,8.2e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23290000,0.71,0.00059,-0.012,0.71,-0.015,-0.0078,0.024,-0.013,-0.002,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.9e-05,7.3e-05,0.019,0.019,0.0078,0.046,0.046,0.036,8.2e-11,8.2e-11,2.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23390000,0.71,0.00068,-0.012,0.71,-0.016,-0.008,0.022,-0.016,-0.0018,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,1.5e-05,7.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.8e-05,8.8e-05,7.3e-05,0.018,0.018,0.0077,0.041,0.041,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23490000,0.71,0.0031,-0.0096,0.71,-0.023,-0.0089,-0.012,-0.018,-0.0026,-3.7e+02,-1.4e-05,-5.9e-05,6.7e-06,1.5e-05,7.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.5e-05,8.9e-05,8.8e-05,7.3e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.8e-11,7.8e-11,2.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23590000,0.71,0.0083,-0.0018,0.71,-0.034,-0.0076,-0.044,-0.017,-0.0013,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,1.8e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.8e-05,8.7e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23690000,0.71,0.0079,0.004,0.71,-0.065,-0.016,-0.094,-0.021,-0.0024,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,1.8e-05,7.3e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.8e-05,8.8e-05,7.2e-05,0.019,0.019,0.0078,0.045,0.045,0.036,7.4e-11,7.4e-11,2.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23790000,0.71,0.005,0.00066,0.71,-0.089,-0.027,-0.15,-0.021,-0.0017,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23890000,0.71,0.0024,-0.0054,0.71,-0.11,-0.036,-0.2,-0.03,-0.005,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2e-05,6.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.019,0.019,0.0078,0.045,0.045,0.035,7.1e-11,7.1e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23990000,0.71,0.00097,-0.01,0.71,-0.11,-0.04,-0.25,-0.034,-0.0082,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2.2e-05,6.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.6e-05,7.2e-05,0.017,0.017,0.0077,0.041,0.041,0.035,6.7e-11,6.7e-11,2.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24090000,0.71,0.0023,-0.0088,0.71,-0.11,-0.04,-0.3,-0.045,-0.012,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.2e-05,6.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.7e-05,8.7e-05,7.2e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.8e-11,6.8e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24190000,0.71,0.0033,-0.0065,0.71,-0.11,-0.041,-0.35,-0.046,-0.014,-3.7e+02,-1.4e-05,-5.9e-05,6.6e-06,2.4e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.4e-05,8.6e-05,8.6e-05,7.1e-05,0.017,0.017,0.0077,0.04,0.04,0.035,6.4e-11,6.4e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24290000,0.71,0.0038,-0.0057,0.71,-0.12,-0.045,-0.41,-0.058,-0.018,-3.7e+02,-1.4e-05,-5.9e-05,6.5e-06,2.4e-05,5.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.6e-05,8.6e-05,7.1e-05,0.018,0.018,0.0078,0.045,0.045,0.036,6.5e-11,6.5e-11,2.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24390000,0.71,0.0039,-0.0059,0.71,-0.13,-0.052,-0.46,-0.064,-0.03,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.1e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.017,0.017,0.0078,0.04,0.04,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24490000,0.71,0.0047,-0.0017,0.71,-0.14,-0.057,-0.51,-0.077,-0.035,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.1e-05,5.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.6e-05,8.5e-05,7.1e-05,0.018,0.018,0.0078,0.045,0.045,0.035,6.2e-11,6.2e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24590000,0.71,0.0052,0.0019,0.71,-0.16,-0.068,-0.56,-0.081,-0.045,-3.7e+02,-1.3e-05,-5.9e-05,6.4e-06,2e-05,4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.017,0.017,0.0078,0.04,0.04,0.035,5.9e-11,5.9e-11,2.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24690000,0.71,0.0052,0.0028,0.71,-0.18,-0.082,-0.64,-0.098,-0.052,-3.7e+02,-1.3e-05,-5.9e-05,6.5e-06,2e-05,4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.5e-05,8.5e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.9e-11,5.9e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24790000,0.71,0.0049,0.0015,0.71,-0.2,-0.095,-0.72,-0.1,-0.063,-3.7e+02,-1.3e-05,-5.9e-05,6.3e-06,2.4e-05,3.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.3e-05,8.4e-05,8.4e-05,7.1e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.7e-11,5.7e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24890000,0.71,0.0067,0.0031,0.71,-0.22,-0.11,-0.75,-0.13,-0.073,-3.7e+02,-1.3e-05,-5.9e-05,6.2e-06,2.4e-05,4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.4e-05,8.4e-05,7.1e-05,0.018,0.018,0.0078,0.044,0.044,0.035,5.7e-11,5.7e-11,2.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24990000,0.71,0.0085,0.0047,0.71,-0.24,-0.11,-0.81,-0.13,-0.081,-3.7e+02,-1.3e-05,-5.9e-05,6e-06,3.4e-05,2.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.3e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.5e-11,5.5e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25090000,0.71,0.0088,0.0041,0.71,-0.27,-0.12,-0.85,-0.15,-0.093,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3.4e-05,2.4e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.4e-05,8.3e-05,7e-05,0.018,0.018,0.0079,0.044,0.044,0.035,5.5e-11,5.5e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25190000,0.71,0.0082,0.0027,0.71,-0.29,-0.14,-0.91,-0.17,-0.12,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3e-05,1.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.2e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.2e-11,5.3e-11,2.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25290000,0.71,0.01,0.0095,0.71,-0.32,-0.15,-0.96,-0.2,-0.13,-3.7e+02,-1.3e-05,-5.9e-05,5.9e-06,3e-05,1.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.3e-05,8.3e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.3e-11,5.3e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25390000,0.71,0.011,0.016,0.71,-0.35,-0.17,-1,-0.22,-0.15,-3.7e+02,-1.2e-05,-5.9e-05,5.9e-06,3.3e-05,3.5e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.2e-05,8.2e-05,7e-05,0.016,0.016,0.0078,0.04,0.04,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25490000,0.71,0.012,0.017,0.71,-0.4,-0.19,-1.1,-0.25,-0.17,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,3.2e-05,3.6e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.2e-05,8.2e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,5.1e-11,5.1e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25590000,0.71,0.011,0.015,0.71,-0.44,-0.22,-1.1,-0.28,-0.21,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,2.9e-05,-5.8e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.2e-05,8.1e-05,8.1e-05,7e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.9e-11,4.9e-11,2.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25690000,0.71,0.015,0.022,0.71,-0.49,-0.24,-1.2,-0.33,-0.23,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,2.9e-05,-5.5e-06,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8.1e-05,8.1e-05,7e-05,0.017,0.017,0.0079,0.044,0.044,0.035,4.9e-11,4.9e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25790000,0.71,0.017,0.028,0.71,-0.53,-0.27,-1.2,-0.34,-0.26,-3.7e+02,-1.2e-05,-5.9e-05,6e-06,3.8e-05,-3.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.016,0.016,0.0079,0.04,0.04,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25890000,0.71,0.017,0.028,0.71,-0.6,-0.3,-1.3,-0.4,-0.29,-3.7e+02,-1.2e-05,-5.9e-05,6.1e-06,3.7e-05,-3.1e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8.1e-05,8e-05,6.9e-05,0.017,0.017,0.008,0.044,0.044,0.035,4.7e-11,4.7e-11,2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25990000,0.71,0.016,0.025,0.71,-0.66,-0.33,-1.3,-0.44,-0.34,-3.7e+02,-1.1e-05,-5.9e-05,6.1e-06,3.3e-05,-4.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26090000,0.7,0.021,0.035,0.71,-0.72,-0.36,-1.3,-0.51,-0.38,-3.7e+02,-1.1e-05,-5.9e-05,5.9e-06,3.4e-05,-4.7e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7.1e-05,8e-05,8e-05,6.9e-05,0.017,0.016,0.008,0.043,0.043,0.035,4.6e-11,4.6e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26190000,0.7,0.023,0.045,0.71,-0.78,-0.39,-1.3,-0.53,-0.42,-3.7e+02,-1.1e-05,-5.9e-05,6e-06,4.5e-05,-8.6e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.9e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.4e-11,4.4e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26290000,0.7,0.024,0.047,0.71,-0.87,-0.44,-1.3,-0.62,-0.46,-3.7e+02,-1.1e-05,-5.9e-05,5.9e-06,4.6e-05,-8.5e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.9e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.5e-11,4.5e-11,1.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26390000,0.7,0.023,0.043,0.71,-0.95,-0.49,-1.3,-0.68,-0.55,-3.7e+02,-1e-05,-5.9e-05,5.9e-06,3.3e-05,-9.9e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.8e-05,6.9e-05,0.015,0.015,0.0079,0.039,0.039,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26490000,0.7,0.031,0.059,0.71,-1,-0.53,-1.3,-0.78,-0.6,-3.7e+02,-1e-05,-5.9e-05,5.8e-06,3.3e-05,-9.8e-05,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.9e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.3e-11,4.3e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26590000,0.7,0.037,0.075,0.71,-1.1,-0.59,-1.3,-0.82,-0.67,-3.7e+02,-9.5e-06,-5.9e-05,5.5e-06,4.3e-05,-0.00013,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.7e-05,6.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26690000,0.7,0.038,0.078,0.71,-1.3,-0.65,-1.3,-0.94,-0.73,-3.7e+02,-9.5e-06,-5.9e-05,5.6e-06,4.2e-05,-0.00013,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.8e-05,7.8e-05,6.9e-05,0.016,0.016,0.008,0.043,0.043,0.035,4.2e-11,4.2e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26790000,0.7,0.036,0.072,0.71,-1.4,-0.73,-1.3,-1,-0.85,-3.7e+02,-9e-06,-6e-05,5.4e-06,2e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.8e-05,0.015,0.014,0.008,0.039,0.039,0.035,4.1e-11,4.1e-11,1.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26890000,0.7,0.045,0.094,0.7,-1.5,-0.79,-1.3,-1.2,-0.93,-3.7e+02,-9e-06,-6e-05,5.5e-06,2e-05,-0.00016,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.7e-05,6.9e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4.1e-11,4.1e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26990000,0.7,0.051,0.12,0.7,-1.7,-0.87,-1.3,-1.2,-1,-3.7e+02,-7.9e-06,-6e-05,5.4e-06,2.9e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.6e-05,7.6e-05,6.9e-05,0.015,0.014,0.008,0.039,0.039,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27090000,0.7,0.052,0.12,0.7,-1.9,-0.96,-1.3,-1.4,-1.1,-3.7e+02,-7.9e-06,-6e-05,5.3e-06,2.9e-05,-0.00021,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,7e-05,7.7e-05,7.6e-05,6.8e-05,0.016,0.015,0.0081,0.043,0.043,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27190000,0.71,0.048,0.11,0.7,-2.1,-1,-1.2,-1.6,-1.2,-3.7e+02,-7.8e-06,-5.9e-05,5.4e-06,3.9e-05,-0.0002,-0.0013,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.6e-05,7.6e-05,6.8e-05,0.016,0.015,0.0081,0.045,0.045,0.035,4e-11,4e-11,1.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27290000,0.71,0.043,0.094,0.7,-2.2,-1.1,-1.2,-1.8,-1.3,-3.7e+02,-7.8e-06,-5.9e-05,5.4e-06,3.9e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.8e-05,0.017,0.016,0.0081,0.05,0.049,0.035,4e-11,4e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27390000,0.71,0.037,0.078,0.7,-2.3,-1.1,-1.2,-2,-1.4,-3.7e+02,-7.2e-06,-5.9e-05,5.5e-06,5.9e-05,-0.00021,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.9e-05,7.7e-05,7.6e-05,6.7e-05,0.017,0.016,0.0081,0.052,0.052,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27490000,0.71,0.031,0.063,0.7,-2.4,-1.2,-1.2,-2.3,-1.5,-3.7e+02,-7.2e-06,-5.9e-05,5.4e-06,5.8e-05,-0.00021,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.018,0.0082,0.057,0.057,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27590000,0.71,0.026,0.05,0.7,-2.5,-1.2,-1.2,-2.5,-1.6,-3.7e+02,-7.5e-06,-5.9e-05,5.5e-06,5.7e-05,-0.0002,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.6e-05,6.7e-05,0.018,0.017,0.0082,0.06,0.059,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27690000,0.71,0.025,0.048,0.7,-2.5,-1.2,-1.2,-2.8,-1.7,-3.7e+02,-7.5e-06,-5.9e-05,5.4e-06,5.6e-05,-0.00019,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.8e-05,7.7e-05,7.7e-05,6.7e-05,0.019,0.018,0.0083,0.065,0.065,0.035,3.9e-11,3.9e-11,1.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27790000,0.71,0.026,0.05,0.7,-2.6,-1.2,-1.2,-3,-1.8,-3.7e+02,-7.6e-06,-5.8e-05,5.3e-06,5.8e-05,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.019,0.018,0.0082,0.068,0.067,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27890000,0.71,0.025,0.048,0.7,-2.6,-1.2,-1.2,-3.3,-2,-3.7e+02,-7.6e-06,-5.8e-05,5.2e-06,5.6e-05,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.019,0.0083,0.074,0.073,0.035,3.9e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27990000,0.71,0.024,0.045,0.7,-2.7,-1.2,-1.2,-3.6,-2.1,-3.7e+02,-8e-06,-5.8e-05,5.3e-06,5.1e-05,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.019,0.0083,0.076,0.076,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28090000,0.71,0.03,0.058,0.7,-2.7,-1.3,-1.2,-3.9,-2.2,-3.7e+02,-8e-06,-5.8e-05,5.1e-06,5e-05,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0084,0.083,0.082,0.035,3.8e-11,3.8e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28190000,0.71,0.035,0.071,0.7,-2.8,-1.3,-0.95,-4.2,-2.3,-3.7e+02,-8.2e-06,-5.8e-05,5.1e-06,4.7e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.02,0.02,0.0084,0.085,0.085,0.035,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28290000,0.71,0.028,0.054,0.7,-2.8,-1.3,-0.09,-4.4,-2.4,-3.7e+02,-8.2e-06,-5.8e-05,4.9e-06,4.5e-05,-0.00014,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.7e-05,7.7e-05,7.6e-05,6.6e-05,0.021,0.02,0.0086,0.092,0.092,0.036,3.8e-11,3.7e-11,1.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28390000,0.71,0.011,0.023,0.7,-2.8,-1.3,0.77,-4.7,-2.6,-3.7e+02,-8.2e-06,-5.8e-05,4.8e-06,4.3e-05,-0.00013,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.7e-05,7.7e-05,6.5e-05,0.022,0.021,0.0087,0.1,0.099,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28490000,0.71,0.0026,0.0045,0.7,-2.7,-1.3,1.1,-5,-2.7,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,4e-05,-0.00012,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.023,0.022,0.0088,0.11,0.11,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28590000,0.71,0.00085,0.001,0.7,-2.6,-1.3,0.96,-5.3,-2.8,-3.7e+02,-8.2e-06,-5.8e-05,4.7e-06,3.7e-05,-0.00012,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.023,0.0089,0.12,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28690000,0.71,0.00014,8.3e-05,0.7,-2.6,-1.2,0.96,-5.5,-2.9,-3.7e+02,-8.2e-06,-5.8e-05,4.6e-06,3.2e-05,-0.0001,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.6e-05,7.8e-05,7.7e-05,6.5e-05,0.025,0.025,0.009,0.13,0.12,0.036,3.8e-11,3.8e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28790000,0.71,-0.00015,-0.00017,0.71,-2.5,-1.2,0.97,-5.8,-3,-3.7e+02,-8.9e-06,-5.8e-05,4.6e-06,1.3e-06,-0.00018,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.7e-05,6.5e-05,0.024,0.024,0.0089,0.13,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28890000,0.71,-0.00017,5.3e-05,0.71,-2.5,-1.2,0.96,-6.1,-3.2,-3.7e+02,-8.9e-06,-5.8e-05,4.6e-06,-3e-06,-0.00016,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.8e-05,6.5e-05,0.025,0.025,0.009,0.14,0.13,0.036,3.7e-11,3.7e-11,1.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28990000,0.71,2.5e-05,0.0005,0.71,-2.4,-1.2,0.95,-6.4,-3.3,-3.7e+02,-9.8e-06,-5.8e-05,4.5e-06,-2.4e-05,-0.00025,-0.0012,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.8e-05,7.8e-05,6.4e-05,0.024,0.024,0.009,0.14,0.14,0.036,3.7e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29090000,0.71,0.00018,0.0009,0.71,-2.4,-1.2,0.94,-6.7,-3.4,-3.7e+02,-9.8e-06,-5.8e-05,4.4e-06,-2.9e-05,-0.00023,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.025,0.009,0.15,0.15,0.036,3.7e-11,3.7e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29190000,0.71,0.0004,0.0013,0.71,-2.3,-1.1,0.93,-7,-3.5,-3.7e+02,-1e-05,-5.8e-05,4.4e-06,-4.9e-05,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.024,0.009,0.15,0.15,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29290000,0.71,0.00075,0.0022,0.71,-2.3,-1.1,0.96,-7.2,-3.6,-3.7e+02,-1e-05,-5.8e-05,4.3e-06,-5.4e-05,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.025,0.026,0.0091,0.16,0.16,0.036,3.6e-11,3.6e-11,1.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29390000,0.71,0.0013,0.0037,0.71,-2.3,-1.1,0.97,-7.5,-3.7,-3.7e+02,-1.1e-05,-5.8e-05,4.1e-06,-7e-05,-0.00029,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.009,0.16,0.16,0.036,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29490000,0.71,0.0018,0.0048,0.71,-2.2,-1.1,0.97,-7.7,-3.8,-3.7e+02,-1.1e-05,-5.7e-05,4.1e-06,-7.4e-05,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.5e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.17,0.17,0.037,3.6e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29590000,0.71,0.0022,0.0059,0.71,-2.2,-1.1,0.96,-8,-3.9,-3.7e+02,-1.1e-05,-5.7e-05,4e-06,-9.8e-05,-0.00028,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.4e-05,0.024,0.025,0.009,0.17,0.16,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29690000,0.71,0.0025,0.0066,0.71,-2.2,-1.1,0.95,-8.2,-4,-3.7e+02,-1.1e-05,-5.7e-05,3.9e-06,-0.0001,-0.00027,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.4e-05,0.026,0.026,0.0091,0.18,0.18,0.036,3.5e-11,3.5e-11,1.3e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29790000,0.71,0.0028,0.0071,0.71,-2.1,-1.1,0.93,-8.5,-4.1,-3.7e+02,-1.2e-05,-5.7e-05,3.9e-06,-0.00012,-0.00029,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,7.9e-05,7.8e-05,6.3e-05,0.025,0.025,0.0091,0.18,0.17,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29890000,0.71,0.0029,0.0074,0.71,-2.1,-1.1,0.92,-8.7,-4.2,-3.7e+02,-1.2e-05,-5.7e-05,3.7e-06,-0.00013,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.026,0.0091,0.19,0.19,0.037,3.5e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29990000,0.71,0.003,0.0076,0.71,-2.1,-1.1,0.9,-9,-4.3,-3.7e+02,-1.2e-05,-5.7e-05,3.6e-06,-0.00015,-0.00026,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.19,0.18,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30090000,0.71,0.003,0.0075,0.71,-2.1,-1,0.89,-9.2,-4.4,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00015,-0.00024,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.026,0.0091,0.2,0.2,0.036,3.4e-11,3.4e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30190000,0.71,0.0031,0.0074,0.71,-2,-1,0.88,-9.4,-4.5,-3.7e+02,-1.2e-05,-5.7e-05,3.5e-06,-0.00017,-0.00025,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.2,0.19,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30290000,0.71,0.003,0.0072,0.71,-2,-1,0.86,-9.6,-4.6,-3.7e+02,-1.2e-05,-5.7e-05,3.4e-06,-0.00017,-0.00024,-0.0011,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.21,0.21,0.037,3.4e-11,3.3e-11,1.2e-10,2.8e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30390000,0.71,0.003,0.0071,0.71,-2,-1,0.85,-9.9,-4.7,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00018,-0.00023,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.025,0.025,0.009,0.21,0.2,0.036,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30490000,0.71,0.0029,0.0068,0.71,-2,-1,0.83,-10,-4.8,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00019,-0.00022,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.8e-05,6.3e-05,0.026,0.027,0.0091,0.22,0.22,0.037,3.3e-11,3.3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30590000,0.71,0.0028,0.0065,0.71,-1.9,-1,0.79,-10,-4.9,-3.7e+02,-1.3e-05,-5.7e-05,3.4e-06,-0.00019,-0.00022,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.4e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.21,0.21,0.037,3.3e-11,3.2e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30690000,0.71,0.0027,0.0062,0.71,-1.9,-0.99,0.79,-11,-5,-3.7e+02,-1.3e-05,-5.7e-05,3.3e-06,-0.0002,-0.00021,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.23,0.23,0.037,3.3e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30790000,0.71,0.0026,0.0059,0.71,-1.9,-0.98,0.78,-11,-5.1,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00021,-0.0002,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.009,0.22,0.22,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30890000,0.71,0.0025,0.0055,0.71,-1.9,-0.97,0.76,-11,-5.2,-3.7e+02,-1.3e-05,-5.7e-05,3.2e-06,-0.00021,-0.00019,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.24,0.24,0.037,3.2e-11,3.2e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30990000,0.71,0.0024,0.005,0.71,-1.8,-0.96,0.76,-11,-5.3,-3.7e+02,-1.3e-05,-5.7e-05,3.1e-06,-0.00022,-0.00018,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8e-05,7.7e-05,6.2e-05,0.025,0.025,0.0089,0.23,0.23,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31090000,0.71,0.0022,0.0045,0.71,-1.8,-0.96,0.74,-11,-5.4,-3.7e+02,-1.3e-05,-5.7e-05,3e-06,-0.00023,-0.00017,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.2e-05,0.026,0.027,0.009,0.25,0.24,0.037,3.2e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31190000,0.71,0.0022,0.0043,0.71,-1.8,-0.95,0.73,-12,-5.5,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00024,-0.00014,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.1e-05,0.025,0.025,0.0089,0.24,0.24,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31290000,0.71,0.002,0.0038,0.71,-1.8,-0.94,0.73,-12,-5.6,-3.7e+02,-1.4e-05,-5.7e-05,3e-06,-0.00024,-0.00013,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.7e-05,6.1e-05,0.026,0.027,0.0089,0.26,0.25,0.037,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31390000,0.71,0.0018,0.0033,0.71,-1.8,-0.93,0.73,-12,-5.7,-3.7e+02,-1.4e-05,-5.7e-05,2.9e-06,-0.00025,-0.00011,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0088,0.25,0.25,0.036,3.1e-11,3.1e-11,1.1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31490000,0.71,0.0016,0.0027,0.71,-1.7,-0.92,0.72,-12,-5.8,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00026,-0.0001,-0.001,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.027,0.0088,0.26,0.26,0.037,3.1e-11,3.1e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31590000,0.71,0.0016,0.0023,0.71,-1.7,-0.91,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-8.3e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.26,0.26,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31690000,0.71,0.0013,0.0017,0.71,-1.7,-0.9,0.72,-12,-5.9,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00027,-7.1e-05,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,6.3e-05,8.1e-05,7.6e-05,6.1e-05,0.026,0.026,0.0088,0.27,0.27,0.037,3.1e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31790000,0.71,0.0011,0.0011,0.71,-1.7,-0.89,0.72,-13,-6,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00028,-5.3e-05,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6.1e-05,0.025,0.025,0.0087,0.27,0.27,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31890000,0.71,0.00087,0.00038,0.71,-1.6,-0.88,0.72,-13,-6.1,-3.7e+02,-1.4e-05,-5.7e-05,2.8e-06,-0.00029,-4e-05,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.28,0.28,0.037,3e-11,3e-11,1e-10,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31990000,0.71,0.00074,-8.2e-05,0.71,-1.6,-0.87,0.71,-13,-6.2,-3.7e+02,-1.4e-05,-5.7e-05,2.7e-06,-0.0003,-2.1e-05,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.025,0.025,0.0086,0.28,0.28,0.036,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32090000,0.71,0.00045,-0.0008,0.71,-1.6,-0.86,0.72,-13,-6.3,-3.7e+02,-1.4e-05,-5.7e-05,2.6e-06,-0.0003,-6.3e-06,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.6e-05,6e-05,0.026,0.026,0.0087,0.29,0.29,0.037,3e-11,3e-11,9.9e-11,2.7e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32190000,0.71,0.00024,-0.0016,0.71,-1.5,-0.85,0.72,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00031,1.4e-05,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0086,0.29,0.29,0.036,2.9e-11,2.9e-11,9.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32290000,0.71,9.8e-06,-0.0023,0.71,-1.5,-0.84,0.71,-13,-6.4,-3.7e+02,-1.4e-05,-5.7e-05,2.4e-06,-0.00032,3e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.3,0.3,0.037,3e-11,2.9e-11,9.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32390000,0.71,-0.00017,-0.0029,0.71,-1.5,-0.83,0.71,-14,-6.5,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00032,3.9e-05,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0085,0.3,0.3,0.037,2.9e-11,2.9e-11,9.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32490000,0.71,-0.00029,-0.0032,0.71,-1.4,-0.81,0.72,-14,-6.6,-3.7e+02,-1.4e-05,-5.7e-05,2.5e-06,-0.00033,5.1e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.026,0.026,0.0086,0.31,0.31,0.037,2.9e-11,2.9e-11,9.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32590000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.8,0.71,-14,-6.7,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,5.8e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,6e-05,0.025,0.025,0.0084,0.31,0.31,0.036,2.9e-11,2.9e-11,9.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32690000,0.71,-0.00033,-0.0035,0.71,-1.4,-0.79,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00033,6.4e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.2e-05,8.1e-05,7.5e-05,5.9e-05,0.026,0.026,0.0085,0.32,0.32,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32790000,0.71,-0.00029,-0.0034,0.71,-1.4,-0.78,0.71,-14,-6.8,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00034,7.3e-05,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0084,0.32,0.31,0.036,2.9e-11,2.9e-11,9.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32890000,0.71,-0.0002,-0.0034,0.71,-1.3,-0.77,0.71,-14,-6.9,-3.7e+02,-1.5e-05,-5.7e-05,2.2e-06,-0.00034,8.4e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.33,0.33,0.036,2.9e-11,2.9e-11,9.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32990000,0.71,-7.3e-05,-0.0033,0.71,-1.3,-0.77,0.7,-15,-7,-3.7e+02,-1.5e-05,-5.7e-05,2.3e-06,-0.00035,9.7e-05,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.32,0.32,0.036,2.8e-11,2.8e-11,9.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33090000,0.71,-0.00011,-0.0033,0.71,-1.3,-0.76,0.69,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.0001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.026,0.026,0.0084,0.34,0.34,0.036,2.8e-11,2.8e-11,9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33190000,0.7,0.0033,-0.0024,0.71,-1.3,-0.75,0.64,-15,-7.1,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00035,0.00011,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,6.1e-05,8.1e-05,7.4e-05,5.9e-05,0.025,0.025,0.0083,0.33,0.33,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33290000,0.65,0.015,-0.0015,0.76,-1.3,-0.73,0.62,-15,-7.2,-3.7e+02,-1.5e-05,-5.7e-05,2.4e-06,-0.00036,0.00011,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.9e-05,8e-05,7.4e-05,6.1e-05,0.026,0.026,0.0083,0.35,0.35,0.036,2.8e-11,2.8e-11,8.9e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33390000,0.55,0.013,-0.0017,0.84,-1.3,-0.72,0.81,-15,-7.3,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,7.9e-05,7.5e-05,6.5e-05,0.024,0.024,0.0083,0.34,0.34,0.036,2.8e-11,2.8e-11,8.8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33490000,0.41,0.0069,0.00072,0.91,-1.2,-0.71,0.83,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5e-05,7.8e-05,7.7e-05,7e-05,0.026,0.026,0.0081,0.36,0.35,0.036,2.8e-11,2.8e-11,8.7e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33590000,0.25,0.00099,-0.0018,0.97,-1.2,-0.71,0.79,-15,-7.4,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.7e-05,7.6e-05,7.8e-05,7.3e-05,0.025,0.025,0.0078,0.35,0.35,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33690000,0.087,-0.0023,-0.0049,1,-1.2,-0.71,0.8,-15,-7.5,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.5e-05,7.5e-05,8e-05,7.6e-05,0.028,0.028,0.0076,0.36,0.36,0.036,2.8e-11,2.8e-11,8.6e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33790000,-0.082,-0.0038,-0.0067,1,-1.1,-0.69,0.78,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.4e-05,7.2e-05,8e-05,7.6e-05,0.028,0.028,0.0074,0.36,0.36,0.036,2.7e-11,2.7e-11,8.5e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33890000,-0.25,-0.0049,-0.0074,0.97,-1,-0.67,0.77,-16,-7.6,-3.7e+02,-1.5e-05,-5.7e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.6e-05,7.2e-05,8.1e-05,7.5e-05,0.031,0.032,0.0072,0.37,0.37,0.036,2.7e-11,2.8e-11,8.4e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33990000,-0.39,-0.0031,-0.011,0.92,-0.98,-0.63,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.5e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,4.8e-05,6.9e-05,7.8e-05,7.2e-05,0.032,0.032,0.007,0.37,0.37,0.035,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34090000,-0.5,-0.0021,-0.013,0.87,-0.93,-0.58,0.74,-16,-7.7,-3.7e+02,-1.5e-05,-5.6e-05,2.6e-06,-0.00036,0.00012,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.1e-05,6.9e-05,7.8e-05,6.9e-05,0.036,0.037,0.0069,0.38,0.38,0.036,2.7e-11,2.7e-11,8.3e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34190000,-0.57,-0.0014,-0.011,0.82,-0.92,-0.54,0.74,-16,-7.8,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,6.5e-05,7.3e-05,6.7e-05,0.036,0.037,0.0067,0.38,0.38,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34290000,-0.61,-0.0023,-0.0086,0.79,-0.87,-0.49,0.74,-16,-7.9,-3.7e+02,-1.5e-05,-5.7e-05,2.6e-06,-0.00039,0.00014,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,6.5e-05,7.3e-05,6.5e-05,0.042,0.043,0.0066,0.39,0.39,0.035,2.7e-11,2.7e-11,8.2e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34390000,-0.64,-0.0025,-0.0061,0.77,-0.85,-0.46,0.73,-16,-7.9,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00044,0.00019,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,6e-05,6.7e-05,6.4e-05,0.042,0.043,0.0065,0.39,0.39,0.035,2.7e-11,2.7e-11,8.1e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34490000,-0.65,-0.0034,-0.0039,0.76,-0.8,-0.42,0.73,-16,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00043,0.00019,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,6.1e-05,6.7e-05,6.3e-05,0.049,0.05,0.0064,0.4,0.4,0.035,2.7e-11,2.7e-11,8e-11,2.7e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34590000,-0.66,-0.0028,-0.0028,0.75,-0.8,-0.4,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00027,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.047,0.048,0.0063,0.4,0.4,0.034,2.6e-11,2.7e-11,8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34690000,-0.67,-0.0032,-0.002,0.74,-0.75,-0.37,0.73,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00053,0.00027,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.5e-05,6.1e-05,6.2e-05,0.054,0.056,0.0063,0.41,0.41,0.034,2.7e-11,2.7e-11,7.9e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34790000,-0.67,-0.0021,-0.0018,0.74,-0.75,-0.36,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00064,0.00038,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.051,0.053,0.0062,0.41,0.41,0.034,2.6e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34890000,-0.68,-0.0021,-0.0017,0.74,-0.7,-0.32,0.72,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00064,0.00038,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,5.1e-05,5.5e-05,6.2e-05,0.059,0.061,0.0062,0.42,0.42,0.034,2.6e-11,2.7e-11,7.8e-11,2.6e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34990000,-0.68,-0.0085,-0.0045,0.73,0.31,0.29,-0.13,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.058,0.058,0.0068,0.42,0.42,0.034,2.6e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35090000,-0.68,-0.0085,-0.0045,0.73,0.43,0.31,-0.19,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.063,0.063,0.0068,0.43,0.43,0.034,2.7e-11,2.7e-11,7.7e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35190000,-0.68,-0.0085,-0.0045,0.73,0.45,0.34,-0.18,-17,-8.2,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.068,0.068,0.0067,0.44,0.44,0.034,2.7e-11,2.7e-11,7.6e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35290000,-0.68,-0.0086,-0.0046,0.73,0.48,0.37,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.8e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.073,0.074,0.0066,0.46,0.45,0.033,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35390000,-0.68,-0.0086,-0.0046,0.73,0.5,0.41,-0.18,-17,-8.1,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.079,0.08,0.0066,0.47,0.47,0.034,2.7e-11,2.7e-11,7.5e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35490000,-0.68,-0.0087,-0.0046,0.73,0.52,0.44,-0.18,-17,-8,-3.7e+02,-1.6e-05,-5.7e-05,2.7e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,4.6e-05,5e-05,6.1e-05,0.085,0.087,0.0065,0.49,0.49,0.034,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35590000,-0.68,-0.0056,-0.0045,0.73,0.41,0.36,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6.1e-05,0.068,0.069,0.0062,0.48,0.48,0.033,2.7e-11,2.7e-11,7.4e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35690000,-0.68,-0.0057,-0.0045,0.73,0.43,0.38,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,2.9e-06,-0.00077,0.00052,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.7e-05,3.9e-05,4.2e-05,6e-05,0.073,0.075,0.0061,0.49,0.49,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35790000,-0.68,-0.0034,-0.0044,0.73,0.35,0.32,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3e-06,-0.00079,0.00053,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.061,0.062,0.0059,0.49,0.48,0.033,2.7e-11,2.7e-11,7.3e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35890000,-0.68,-0.0034,-0.0045,0.73,0.37,0.35,-0.19,-17,-8.1,-3.7e+02,-1.7e-05,-5.7e-05,3.1e-06,-0.00079,0.00053,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3.4e-05,3.6e-05,6e-05,0.066,0.068,0.0059,0.5,0.5,0.033,2.7e-11,2.7e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
35990000,-0.68,-0.0016,-0.0044,0.73,0.3,0.29,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.3e-06,-0.00087,0.0006,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.057,0.058,0.0057,0.49,0.49,0.033,2.7e-11,2.8e-11,7.2e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36090000,-0.68,-0.0016,-0.0044,0.73,0.31,0.31,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00087,0.0006,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,3e-05,3.1e-05,6e-05,0.062,0.064,0.0057,0.51,0.51,0.032,2.7e-11,2.8e-11,7.1e-11,2.5e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36190000,-0.68,-0.00014,-0.0043,0.73,0.26,0.27,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.5e-06,-0.00097,0.00068,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.055,0.056,0.0055,0.5,0.5,0.032,2.7e-11,2.8e-11,7.1e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36290000,-0.68,-0.00021,-0.0042,0.73,0.27,0.28,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.7e-06,-0.00097,0.00068,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.6e-05,2.8e-05,6e-05,0.06,0.062,0.0056,0.52,0.52,0.032,2.7e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36390000,-0.68,0.00084,-0.0041,0.73,0.22,0.24,-0.21,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,3.9e-06,-0.0011,0.00077,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.053,0.055,0.0055,0.51,0.51,0.032,2.8e-11,2.8e-11,7e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36490000,-0.68,0.00079,-0.0041,0.73,0.23,0.26,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.1e-06,-0.0011,0.00077,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.4e-05,2.5e-05,6e-05,0.059,0.061,0.0055,0.53,0.52,0.032,2.8e-11,2.8e-11,6.9e-11,2.4e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36590000,-0.68,0.0016,-0.004,0.73,0.19,0.22,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.3e-06,-0.0012,0.00086,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,6e-05,0.053,0.054,0.0055,0.52,0.52,0.031,2.8e-11,2.8e-11,6.9e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36690000,-0.68,0.0016,-0.004,0.74,0.19,0.23,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.4e-06,-0.0012,0.00086,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.2e-05,2.3e-05,5.9e-05,0.058,0.06,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.3e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36790000,-0.68,0.0022,-0.0039,0.74,0.16,0.2,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.5e-06,-0.0013,0.00095,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,5.9e-05,0.052,0.053,0.0055,0.53,0.53,0.031,2.8e-11,2.8e-11,6.8e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36890000,-0.68,0.0022,-0.0039,0.74,0.16,0.21,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.6e-06,-0.0013,0.00095,-0.00092,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,2.1e-05,2.2e-05,5.9e-05,0.057,0.059,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
36990000,-0.68,0.0026,-0.0037,0.74,0.13,0.18,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,4.8e-06,-0.0015,0.001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.6e-05,1.9e-05,2e-05,5.9e-05,0.051,0.052,0.0056,0.54,0.54,0.031,2.8e-11,2.8e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37090000,-0.68,0.0026,-0.0037,0.74,0.13,0.19,-0.2,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5e-06,-0.0015,0.001,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,2e-05,2.1e-05,5.9e-05,0.056,0.058,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.7e-11,2.2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37190000,-0.68,0.0029,-0.0036,0.74,0.11,0.16,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.2e-06,-0.0016,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.9e-05,2e-05,5.9e-05,0.05,0.052,0.0057,0.55,0.55,0.031,2.8e-11,2.9e-11,6.6e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37290000,-0.68,0.0029,-0.0036,0.74,0.11,0.17,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.4e-06,-0.0016,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.9e-05,2e-05,5.9e-05,0.055,0.057,0.0059,0.56,0.56,0.031,2.8e-11,2.9e-11,6.6e-11,2.1e-06,1.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37390000,-0.68,0.0032,-0.0034,0.74,0.088,0.14,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.5e-06,-0.0017,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.05,0.051,0.0059,0.56,0.56,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37490000,-0.68,0.0032,-0.0034,0.74,0.087,0.15,-0.19,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.6e-06,-0.0017,0.0011,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.054,0.055,0.006,0.57,0.57,0.031,2.9e-11,2.9e-11,6.5e-11,2e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37590000,-0.68,0.0033,-0.0033,0.74,0.069,0.12,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.8e-06,-0.0017,0.0012,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.049,0.05,0.0061,0.57,0.57,0.031,2.9e-11,2.9e-11,6.4e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37690000,-0.68,0.0033,-0.0034,0.74,0.066,0.13,-0.18,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,5.9e-06,-0.0017,0.0012,-0.00093,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.053,0.054,0.0062,0.58,0.58,0.031,2.9e-11,2.9e-11,6.4e-11,1.9e-06,1.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37790000,-0.68,0.0034,-0.0033,0.74,0.052,0.11,-0.17,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.1e-06,-0.0018,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.048,0.048,0.0063,0.58,0.58,0.03,2.9e-11,2.9e-11,6.4e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37890000,-0.68,0.0034,-0.0033,0.74,0.05,0.11,-0.16,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.3e-06,-0.0018,0.0012,-0.00094,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.9e-05,5.9e-05,0.052,0.053,0.0064,0.59,0.59,0.03,2.9e-11,2.9e-11,6.3e-11,1.8e-06,1.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
37990000,-0.68,0.0034,-0.0033,0.74,0.037,0.097,-0.15,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.5e-06,-0.0019,0.0013,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.047,0.047,0.0065,0.59,0.59,0.031,2.9e-11,2.9e-11,6.3e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38090000,-0.68,0.0034,-0.0033,0.74,0.034,0.1,-0.14,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.6e-06,-0.0019,0.0013,-0.00095,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.05,0.051,0.0066,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.7e-06,1.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38190000,-0.68,0.0034,-0.0032,0.74,0.022,0.085,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.8e-06,-0.002,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.045,0.046,0.0067,0.6,0.6,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38290000,-0.68,0.0034,-0.0032,0.74,0.019,0.086,-0.13,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,6.9e-06,-0.002,0.0013,-0.00096,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.9e-05,0.049,0.05,0.0068,0.61,0.61,0.031,2.9e-11,3e-11,6.2e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38390000,-0.68,0.0034,-0.0031,0.74,0.012,0.074,-0.12,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.1e-06,-0.002,0.0013,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.7e-05,1.8e-05,5.9e-05,0.044,0.045,0.0069,0.61,0.61,0.031,2.9e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38490000,-0.68,0.0034,-0.0031,0.74,0.0091,0.076,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.2e-06,-0.002,0.0013,-0.00097,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.8e-05,0.048,0.048,0.007,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.6e-06,1.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38590000,-0.68,0.0034,-0.003,0.74,0.0051,0.065,-0.11,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.4e-06,-0.002,0.0013,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.5e-05,1.8e-05,1.8e-05,5.8e-05,0.043,0.044,0.0071,0.62,0.62,0.031,3e-11,3e-11,6.1e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38690000,-0.68,0.0033,-0.003,0.74,0.0012,0.065,-0.097,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.5e-06,-0.0021,0.0013,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.046,0.047,0.0072,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.5e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38790000,-0.68,0.0033,-0.003,0.74,-0.0034,0.054,-0.089,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.7e-06,-0.0021,0.0013,-0.00098,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.042,0.042,0.0073,0.63,0.63,0.031,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
38890000,-0.67,0.0031,-0.003,0.74,-0.013,0.043,0.41,-17,-8.2,-3.7e+02,-1.7e-05,-5.7e-05,7.8e-06,-0.0021,0.0013,-0.00099,0.21,0.0021,0.44,0,0,0,0,0,5.4e-05,1.8e-05,1.9e-05,5.8e-05,0.045,0.045,0.0075,0.64,0.64,0.032,3e-11,3e-11,6e-11,1.4e-06,1.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
|
||||
|
@@ -65,7 +65,7 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
||||
6290000,0.98,-0.0068,-0.013,0.18,0.004,0.021,0.19,0.0035,0.0084,0.051,-1.9e-05,-5.5e-05,7.4e-07,0,0,-0.0019,0.2,-6.1e-09,0.43,0,0,0,0,0,5e-06,0.00044,0.00044,0.00015,0.31,0.31,0.039,0.17,0.17,0.07,1.8e-08,1.8e-08,4.8e-09,4e-06,4e-06,3.9e-07,0,0,0,0,0,0,0,0
|
||||
6390000,0.98,-0.0068,-0.013,0.18,0.0046,0.018,0.19,0.0024,0.0066,0.064,-1.8e-05,-5.6e-05,7.2e-07,0,0,-0.0019,0.2,-6.1e-09,0.43,0,0,0,0,0,4.9e-06,0.00036,0.00036,0.00015,0.24,0.24,0.038,0.13,0.13,0.07,1.5e-08,1.5e-08,4.6e-09,4e-06,4e-06,3.6e-07,0,0,0,0,0,0,0,0
|
||||
6490000,0.98,-0.0068,-0.013,0.18,0.0024,0.017,0.19,0.0027,0.0083,0.08,-1.8e-05,-5.6e-05,7.2e-07,0,0,-0.0019,0.2,-6.1e-09,0.43,0,0,0,0,0,4.8e-06,0.00038,0.00038,0.00015,0.28,0.28,0.036,0.16,0.16,0.069,1.5e-08,1.5e-08,4.4e-09,4e-06,4e-06,3.4e-07,0,0,0,0,0,0,0,0
|
||||
6590000,0.98,-0.0067,-0.013,0.19,0.00045,0.015,0.19,0.0017,0.0063,0.088,-1.7e-05,-5.6e-05,7.1e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,5.4e-05,0.0003,0.0003,0.0015,0.2,0.2,0.035,0.12,0.12,0.068,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,3.2e-07,0,0,0,0,0,0,0,0
|
||||
6590000,0.98,-0.0067,-0.013,0.19,0.00045,0.015,0.19,0.0017,0.0063,0.088,-1.7e-05,-5.6e-05,7.1e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,5.5e-05,0.0003,0.0003,0.0015,0.2,0.2,0.035,0.12,0.12,0.068,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,3.2e-07,0,0,0,0,0,0,0,0
|
||||
6690000,0.98,-0.0066,-0.013,0.19,-0.0022,0.017,0.19,0.0016,0.0079,0.097,-1.7e-05,-5.6e-05,6.9e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,3.5e-05,0.0003,0.0003,0.00097,0.21,0.21,0.033,0.15,0.15,0.067,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,3e-07,0,0,0,0,0,0,0,0
|
||||
6790000,0.98,-0.0066,-0.013,0.19,-0.00042,0.019,0.19,0.0014,0.0096,0.11,-1.7e-05,-5.6e-05,6.8e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,2.7e-05,0.0003,0.0003,0.00074,0.21,0.21,0.032,0.18,0.18,0.067,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2.8e-07,0,0,0,0,0,0,0,0
|
||||
6890000,0.98,-0.0064,-0.013,0.19,-0.00086,0.019,0.19,0.0013,0.011,0.12,-1.7e-05,-5.6e-05,6.8e-07,0,0,-0.0019,0.2,0.002,0.43,0,0,0,0,0,2.1e-05,0.0003,0.0003,0.00058,0.22,0.22,0.031,0.22,0.22,0.066,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2.6e-07,0,0,0,0,0,0,0,0
|
||||
@@ -74,15 +74,15 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
||||
7190000,0.98,-0.0062,-0.013,0.19,-0.0022,0.027,0.18,0.00066,0.018,0.13,-1.7e-05,-5.6e-05,6.7e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,1.3e-05,0.00031,0.00031,0.00036,0.27,0.27,0.028,0.36,0.36,0.064,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2.2e-07,0,0,0,0,0,0,0,0
|
||||
7290000,0.98,-0.0062,-0.013,0.19,-0.0013,0.031,0.18,0.00039,0.021,0.14,-1.7e-05,-5.6e-05,7e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,1.2e-05,0.00031,0.00031,0.00032,0.29,0.29,0.027,0.42,0.42,0.063,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2.1e-07,0,0,0,0,0,0,0,0
|
||||
7390000,0.98,-0.0061,-0.013,0.19,-0.003,0.034,0.17,0.00015,0.024,0.15,-1.7e-05,-5.6e-05,7.2e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,1.1e-05,0.00032,0.00032,0.00029,0.32,0.32,0.026,0.48,0.48,0.063,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,2e-07,0,0,0,0,0,0,0,0
|
||||
7490000,0.98,-0.0061,-0.013,0.19,-0.00063,0.036,0.17,-3e-05,0.028,0.15,-1.7e-05,-5.6e-05,8.3e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,9.6e-06,0.00033,0.00032,0.00026,0.35,0.35,0.026,0.56,0.56,0.062,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.8e-07,0,0,0,0,0,0,0,0
|
||||
7590000,0.98,-0.0062,-0.013,0.19,0.00044,0.039,0.17,-7.3e-05,0.031,0.16,-1.7e-05,-5.6e-05,8.6e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00033,0.00033,0.00024,0.38,0.38,0.025,0.64,0.64,0.061,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.7e-07,0,0,0,0,0,0,0,0
|
||||
7690000,0.98,-0.0062,-0.013,0.19,0.00019,0.043,0.17,-7.7e-05,0.035,0.17,-1.7e-05,-5.6e-05,8.5e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00034,0.00034,0.00022,0.41,0.41,0.024,0.73,0.73,0.061,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0
|
||||
7790000,0.98,-0.0061,-0.013,0.19,0.0019,0.045,0.16,-4.7e-05,0.039,0.16,-1.7e-05,-5.6e-05,8e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,7.7e-06,0.00034,0.00034,0.00021,0.45,0.45,0.023,0.83,0.83,0.06,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0
|
||||
7890000,0.98,-0.0061,-0.013,0.19,0.0006,0.049,0.15,-7.1e-05,0.044,0.16,-1.7e-05,-5.6e-05,7.7e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,0.00035,0.00035,0.0002,0.49,0.49,0.022,0.95,0.95,0.059,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.5e-07,0,0,0,0,0,0,0,0
|
||||
7990000,0.98,-0.006,-0.013,0.19,0.00096,0.052,0.15,-3.6e-05,0.048,0.16,-1.7e-05,-5.7e-05,8e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,0.00036,0.00036,0.00018,0.53,0.53,0.022,1.1,1.1,0.058,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0
|
||||
7490000,0.98,-0.0061,-0.013,0.19,-0.00063,0.036,0.17,-3.1e-05,0.028,0.15,-1.7e-05,-5.6e-05,8.3e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,9.6e-06,0.00033,0.00032,0.00026,0.35,0.35,0.026,0.56,0.56,0.062,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.8e-07,0,0,0,0,0,0,0,0
|
||||
7590000,0.98,-0.0062,-0.013,0.19,0.00044,0.039,0.17,-7.4e-05,0.031,0.16,-1.7e-05,-5.6e-05,8.6e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,8.8e-06,0.00033,0.00033,0.00024,0.38,0.38,0.025,0.64,0.64,0.061,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.7e-07,0,0,0,0,0,0,0,0
|
||||
7690000,0.98,-0.0062,-0.013,0.19,0.00019,0.043,0.17,-7.8e-05,0.035,0.17,-1.7e-05,-5.6e-05,8.5e-07,0,0,-0.0018,0.2,0.002,0.43,0,0,0,0,0,8.2e-06,0.00034,0.00034,0.00022,0.41,0.41,0.024,0.73,0.73,0.061,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0
|
||||
7790000,0.98,-0.0061,-0.013,0.19,0.0019,0.045,0.16,-4.8e-05,0.039,0.16,-1.7e-05,-5.6e-05,8e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,7.7e-06,0.00034,0.00034,0.00021,0.45,0.45,0.023,0.83,0.83,0.06,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.6e-07,0,0,0,0,0,0,0,0
|
||||
7890000,0.98,-0.0061,-0.013,0.19,0.0006,0.049,0.15,-7.2e-05,0.044,0.16,-1.7e-05,-5.6e-05,7.7e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,7.2e-06,0.00035,0.00035,0.0002,0.49,0.49,0.022,0.95,0.95,0.059,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.5e-07,0,0,0,0,0,0,0,0
|
||||
7990000,0.98,-0.006,-0.013,0.19,0.00096,0.052,0.15,-3.8e-05,0.048,0.16,-1.7e-05,-5.7e-05,8e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,6.8e-06,0.00036,0.00036,0.00018,0.53,0.53,0.022,1.1,1.1,0.058,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.4e-07,0,0,0,0,0,0,0,0
|
||||
8090000,0.98,-0.0059,-0.013,0.19,0.0025,0.056,0.15,0.00011,0.053,0.16,-1.7e-05,-5.7e-05,6e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,6.4e-06,0.00037,0.00037,0.00018,0.59,0.59,0.021,1.2,1.2,0.058,1.2e-08,1.2e-08,4.3e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0
|
||||
8190000,0.98,-0.0059,-0.013,0.19,0.0032,0.061,0.15,0.00034,0.058,0.17,-1.7e-05,-5.7e-05,4.4e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,6.1e-06,0.00037,0.00037,0.00017,0.63,0.63,0.02,1.4,1.4,0.057,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0
|
||||
8290000,0.98,-0.0059,-0.013,0.19,0.0055,0.065,0.14,0.00071,0.064,0.17,-1.7e-05,-5.7e-05,4e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,5.8e-06,0.00038,0.00038,0.00016,0.69,0.69,0.02,1.5,1.5,0.057,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0
|
||||
8190000,0.98,-0.0059,-0.013,0.19,0.0032,0.061,0.15,0.00033,0.058,0.17,-1.7e-05,-5.7e-05,4.4e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,6.1e-06,0.00037,0.00037,0.00017,0.63,0.63,0.02,1.4,1.4,0.057,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,1.3e-07,0,0,0,0,0,0,0,0
|
||||
8290000,0.98,-0.0059,-0.013,0.19,0.0055,0.065,0.14,0.0007,0.064,0.17,-1.7e-05,-5.7e-05,4e-07,0,0,-0.0017,0.2,0.002,0.43,0,0,0,0,0,5.8e-06,0.00038,0.00038,0.00016,0.69,0.69,0.02,1.5,1.5,0.057,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,1.2e-07,0,0,0,0,0,0,0,0
|
||||
8390000,0.98,-0.0059,-0.013,0.19,0.0034,0.067,0.14,0.0011,0.071,0.17,-1.7e-05,-5.7e-05,3.6e-07,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,5.6e-06,0.00039,0.00039,0.00015,0.75,0.75,0.019,1.7,1.7,0.057,1.2e-08,1.2e-08,4.2e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0
|
||||
8490000,0.98,-0.0058,-0.013,0.19,0.0033,0.071,0.13,0.0014,0.076,0.16,-1.7e-05,-5.7e-05,5.1e-07,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,5.4e-06,0.0004,0.0004,0.00015,0.81,0.81,0.019,1.9,1.9,0.056,1.1e-08,1.1e-08,4.2e-09,4e-06,4e-06,1.1e-07,0,0,0,0,0,0,0,0
|
||||
8590000,0.98,-0.0057,-0.013,0.19,0.0044,0.074,0.13,0.0017,0.083,0.17,-1.7e-05,-5.7e-05,4.3e-07,0,0,-0.0016,0.2,0.002,0.43,0,0,0,0,0,5.2e-06,0.00041,0.00041,0.00014,0.87,0.88,0.018,2.2,2.2,0.055,1.1e-08,1.1e-08,4.2e-09,4e-06,4e-06,1e-07,0,0,0,0,0,0,0,0
|
||||
@@ -97,221 +97,221 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
||||
9490000,0.98,-0.0056,-0.013,0.19,0.011,0.092,0.097,0.0071,0.14,0.16,-1.6e-05,-5.7e-05,1.3e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.3e-06,0.00047,0.00047,0.00011,1.5,1.5,0.014,5,5,0.051,1e-08,1e-08,4e-09,4e-06,4e-06,6.9e-08,0,0,0,0,0,0,0,0
|
||||
9590000,0.98,-0.0057,-0.013,0.19,0.011,0.093,0.093,0.0079,0.14,0.15,-1.6e-05,-5.7e-05,7.3e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00048,0.00048,0.00011,1.6,1.6,0.014,5.5,5.5,0.05,1e-08,1e-08,3.9e-09,4e-06,4e-06,6.7e-08,0,0,0,0,0,0,0,0
|
||||
9690000,0.98,-0.0057,-0.013,0.19,0.011,0.092,0.092,0.0085,0.14,0.15,-1.6e-05,-5.7e-05,5.9e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.2e-06,0.00047,0.00047,0.00011,1.6,1.6,0.014,5.7,5.7,0.05,1e-08,1e-08,3.9e-09,4e-06,4e-06,6.4e-08,0,0,0,0,0,0,0,0
|
||||
9790000,0.98,-0.0057,-0.013,0.19,0.012,0.095,0.087,0.0094,0.15,0.15,-1.6e-05,-5.7e-05,3.6e-08,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00049,0.00049,0.00011,1.7,1.7,0.014,6.4,6.4,0.049,1e-08,1e-08,3.9e-09,4e-06,4e-06,6.2e-08,0,0,0,0,0,0,0,0
|
||||
9790000,0.98,-0.0057,-0.013,0.19,0.012,0.095,0.087,0.0093,0.15,0.15,-1.6e-05,-5.7e-05,3.6e-08,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00049,0.00049,0.00011,1.7,1.7,0.014,6.4,6.4,0.049,1e-08,1e-08,3.9e-09,4e-06,4e-06,6.2e-08,0,0,0,0,0,0,0,0
|
||||
9890000,0.98,-0.0058,-0.012,0.19,0.014,0.091,0.084,0.0098,0.15,0.14,-1.6e-05,-5.7e-05,1.7e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00048,0.00048,0.00011,1.7,1.7,0.013,6.6,6.6,0.049,9.9e-09,9.9e-09,3.8e-09,4e-06,4e-06,5.9e-08,0,0,0,0,0,0,0,0
|
||||
9990000,0.98,-0.0058,-0.013,0.19,0.016,0.093,0.082,0.011,0.16,0.14,-1.6e-05,-5.7e-05,-2.7e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4.1e-06,0.00049,0.00049,0.00011,1.8,1.8,0.013,7.2,7.2,0.049,9.9e-09,9.9e-09,3.8e-09,4e-06,4e-06,5.7e-08,0,0,0,0,0,0,0,0
|
||||
10090000,0.98,-0.0058,-0.013,0.19,0.014,0.087,0.079,0.011,0.16,0.14,-1.6e-05,-5.8e-05,-8.1e-07,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00047,0.00047,0.00011,1.8,1.8,0.013,7.4,7.4,0.048,9.6e-09,9.6e-09,3.7e-09,4e-06,4e-06,5.5e-08,0,0,0,0,0,0,0,0
|
||||
10190000,0.98,-0.0058,-0.013,0.19,0.012,0.089,0.077,0.012,0.16,0.13,-1.6e-05,-5.8e-05,-1.4e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00049,0.00049,0.00011,1.9,1.9,0.012,8.1,8.1,0.048,9.6e-09,9.6e-09,3.7e-09,4e-06,4e-06,5.3e-08,0,0,0,0,0,0,0,0
|
||||
10290000,0.98,-0.0059,-0.012,0.19,0.012,0.084,0.073,0.012,0.16,0.13,-1.5e-05,-5.8e-05,-1.2e-06,0,0,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00047,0.00047,0.00011,1.9,1.9,0.012,8.2,8.2,0.048,9.3e-09,9.3e-09,3.7e-09,4e-06,4e-06,5.1e-08,0,0,0,0,0,0,0,0
|
||||
10390000,0.98,-0.0059,-0.012,0.19,0.007,0.0043,-0.0039,0.00075,0.00011,0.13,-1.5e-05,-5.8e-05,-9.6e-07,1.5e-09,-1.1e-09,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00048,0.00048,0.00011,0.25,0.25,0.25,0.25,0.25,0.046,9.3e-09,9.3e-09,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10490000,0.98,-0.0058,-0.012,0.19,0.0082,0.0058,-0.0048,0.0015,0.00058,0.12,-1.5e-05,-5.8e-05,-1.4e-06,6.1e-09,-4.5e-09,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.0005,0.0005,0.00011,0.26,0.26,0.25,0.26,0.26,0.048,9.3e-09,9.3e-09,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10590000,0.98,-0.0058,-0.012,0.19,-0.0014,0.0037,-0.0033,-0.0012,-0.0055,0.11,-1.5e-05,-5.8e-05,-1e-06,3.1e-06,-1.8e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0005,0.0005,0.0001,0.13,0.13,0.17,0.13,0.13,0.049,9.2e-09,9.2e-09,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10690000,0.98,-0.0057,-0.012,0.19,-0.00039,0.004,-0.0071,-0.0013,-0.0051,0.11,-1.5e-05,-5.8e-05,-1.2e-06,3.1e-06,-2e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00052,0.00052,0.0001,0.14,0.14,0.16,0.14,0.14,0.054,9.2e-09,9.2e-09,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10790000,0.98,-0.0058,-0.012,0.19,0.0014,0.00059,-0.0093,-0.00079,-0.0047,0.1,-1.5e-05,-5.8e-05,-1.2e-06,4.7e-06,3.8e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00051,0.00051,0.0001,0.1,0.1,0.12,0.091,0.091,0.054,9e-09,9e-09,3.4e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10890000,0.98,-0.0058,-0.012,0.19,0.0014,0.0032,-0.018,-0.00064,-0.0046,0.091,-1.5e-05,-5.8e-05,-5.4e-07,4.8e-06,3.7e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00053,0.00053,0.0001,0.12,0.12,0.12,0.098,0.098,0.058,9e-09,9e-09,3.4e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10990000,0.98,-0.0058,-0.013,0.19,0.00095,0.0094,-0.012,-0.00047,-0.0032,0.092,-1.5e-05,-5.8e-05,-7e-07,5.5e-06,5.1e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0005,0.0005,0.0001,0.091,0.091,0.092,0.073,0.073,0.058,8.7e-09,8.7e-09,3.3e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11090000,0.98,-0.0059,-0.012,0.19,0.0018,0.014,-0.013,-0.00037,-0.0021,0.087,-1.5e-05,-5.8e-05,-1.3e-06,5.5e-06,5e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00052,0.00052,0.0001,0.11,0.11,0.086,0.079,0.079,0.061,8.7e-09,8.7e-09,3.3e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11190000,0.98,-0.0062,-0.013,0.19,0.0035,0.014,-0.0065,0.001,-0.002,0.089,-1.4e-05,-5.8e-05,-1.6e-06,4.3e-06,1.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00047,0.00047,0.0001,0.09,0.09,0.07,0.063,0.063,0.06,8.1e-09,8.1e-09,3.2e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11290000,0.98,-0.0061,-0.013,0.19,0.0035,0.014,-0.0089,0.0013,-0.00055,0.082,-1.4e-05,-5.8e-05,-1.8e-06,4.4e-06,1.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00048,0.00048,0.0001,0.11,0.11,0.066,0.07,0.07,0.063,8.1e-09,8.1e-09,3.2e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11390000,0.98,-0.0062,-0.012,0.19,0.002,0.013,-0.016,0.00084,-0.0011,0.071,-1.4e-05,-5.8e-05,-1.7e-06,8.7e-06,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00043,0.00043,0.0001,0.091,0.091,0.055,0.057,0.057,0.061,7.5e-09,7.5e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11490000,0.98,-0.0062,-0.012,0.19,0.001,0.013,-0.013,0.00093,0.00026,0.071,-1.4e-05,-5.8e-05,-1.6e-06,8.7e-06,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00044,0.00044,0.0001,0.11,0.11,0.05,0.065,0.065,0.062,7.5e-09,7.5e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11590000,0.98,-0.0064,-0.012,0.19,0.0029,0.011,-0.013,0.0008,-0.0005,0.067,-1.3e-05,-5.9e-05,-1.6e-06,1.2e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00038,0.00038,0.0001,0.091,0.091,0.043,0.054,0.054,0.061,6.9e-09,6.9e-09,3e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11690000,0.98,-0.0064,-0.012,0.19,0.0033,0.014,-0.013,0.0011,0.00073,0.061,-1.3e-05,-5.9e-05,-1.4e-06,1.2e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00039,0.00039,0.0001,0.11,0.11,0.04,0.062,0.062,0.062,6.9e-09,6.9e-09,3e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11790000,0.98,-0.0067,-0.012,0.19,0.0021,0.0092,-0.01,0.00067,-0.0018,0.062,-1.3e-05,-5.9e-05,-7.6e-07,1.6e-05,3.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00034,0.00034,0.0001,0.088,0.088,0.034,0.052,0.052,0.059,6.4e-09,6.4e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11890000,0.98,-0.0068,-0.012,0.19,0.0047,0.01,-0.013,0.00096,-0.00089,0.059,-1.3e-05,-5.9e-05,-8.8e-07,1.6e-05,3.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00035,0.00035,0.0001,0.11,0.11,0.032,0.06,0.06,0.06,6.4e-09,6.4e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11990000,0.98,-0.0069,-0.012,0.19,0.0077,0.011,-0.013,0.0021,-0.0018,0.054,-1.2e-05,-5.9e-05,-6.7e-07,1.6e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0003,0.0003,0.0001,0.085,0.085,0.028,0.051,0.051,0.058,5.9e-09,5.9e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12090000,0.98,-0.0069,-0.012,0.19,0.0092,0.011,-0.0093,0.0029,-0.00079,0.057,-1.2e-05,-5.9e-05,-6.8e-07,1.5e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00031,0.00031,0.0001,0.1,0.1,0.026,0.059,0.059,0.058,5.9e-09,5.9e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12190000,0.98,-0.0067,-0.012,0.19,0.0075,0.01,-0.0086,0.0018,0.00035,0.057,-1.3e-05,-5.9e-05,-9.1e-07,1.8e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00027,0.00027,0.0001,0.08,0.08,0.023,0.05,0.05,0.056,5.5e-09,5.5e-09,2.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12290000,0.98,-0.0068,-0.012,0.19,0.0051,0.0095,-0.0094,0.0024,0.0014,0.056,-1.3e-05,-5.9e-05,-1.1e-06,1.8e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00028,0.00028,0.0001,0.095,0.095,0.021,0.059,0.059,0.056,5.5e-09,5.5e-09,2.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12390000,0.98,-0.0069,-0.012,0.19,0.0038,0.0065,-0.0096,0.0017,0.00047,0.049,-1.2e-05,-6e-05,-1.1e-06,2e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00025,0.00025,0.0001,0.076,0.076,0.019,0.05,0.05,0.054,5.2e-09,5.2e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12490000,0.98,-0.0069,-0.012,0.19,0.0037,0.0075,-0.0044,0.0021,0.0012,0.049,-1.2e-05,-6e-05,-1.2e-06,2e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00026,0.00026,0.0001,0.089,0.089,0.018,0.058,0.058,0.054,5.2e-09,5.2e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12590000,0.98,-0.0071,-0.012,0.19,0.0075,0.0011,-0.0015,0.0033,-0.0013,0.05,-1.2e-05,-6e-05,-1.2e-06,2e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00023,0.00023,0.0001,0.071,0.071,0.016,0.049,0.049,0.053,4.9e-09,4.9e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12690000,0.98,-0.007,-0.012,0.19,0.008,-0.0011,-0.00092,0.004,-0.0013,0.051,-1.2e-05,-6e-05,-1.2e-06,1.9e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00024,0.00024,0.0001,0.082,0.082,0.015,0.058,0.058,0.052,4.9e-09,4.9e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12790000,0.98,-0.0073,-0.012,0.19,0.0096,-0.0042,0.0019,0.0041,-0.0044,0.052,-1.1e-05,-6e-05,-3.8e-07,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00022,0.00022,0.0001,0.067,0.067,0.014,0.049,0.049,0.05,4.6e-09,4.6e-09,2.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12890000,0.98,-0.0073,-0.012,0.19,0.0097,-0.0051,0.0038,0.0051,-0.0049,0.054,-1.1e-05,-6e-05,1.5e-07,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00023,0.00023,0.0001,0.077,0.077,0.013,0.057,0.057,0.05,4.6e-09,4.6e-09,2.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12990000,0.98,-0.0072,-0.012,0.19,0.0077,-0.003,0.0053,0.0036,-0.0036,0.055,-1.1e-05,-6e-05,6.3e-07,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.063,0.063,0.012,0.049,0.049,0.049,4.4e-09,4.4e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13090000,0.98,-0.0073,-0.012,0.19,0.0085,-0.0029,0.004,0.0044,-0.0038,0.053,-1.1e-05,-6e-05,1.3e-06,2e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00022,0.00022,0.0001,0.072,0.072,0.011,0.057,0.057,0.048,4.4e-09,4.4e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13190000,0.98,-0.0073,-0.012,0.19,0.0036,-0.0045,0.0045,0.00096,-0.0045,0.054,-1.1e-05,-6e-05,1.7e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.059,0.059,0.011,0.049,0.049,0.047,4.2e-09,4.2e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13290000,0.98,-0.0073,-0.012,0.19,0.0031,-0.0054,0.0028,0.0013,-0.005,0.053,-1.1e-05,-6e-05,1.7e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.067,0.067,0.01,0.057,0.057,0.047,4.2e-09,4.2e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13390000,0.98,-0.0072,-0.012,0.19,0.0023,-0.0034,0.0037,0.00085,-0.0037,0.053,-1.2e-05,-6e-05,1.5e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.056,0.056,0.0096,0.049,0.049,0.045,4e-09,4e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13490000,0.98,-0.0072,-0.012,0.19,0.0027,-0.0016,0.0042,0.0011,-0.0039,0.049,-1.2e-05,-6e-05,1.7e-06,2.2e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.064,0.064,0.0092,0.056,0.056,0.045,4e-09,4e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13590000,0.98,-0.0072,-0.012,0.19,0.0072,-0.0018,0.0067,0.004,-0.0032,0.048,-1.1e-05,-6e-05,1.5e-06,2.3e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.053,0.053,0.0088,0.048,0.048,0.044,3.8e-09,3.8e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13690000,0.98,-0.0071,-0.012,0.19,0.0071,-0.0032,0.0077,0.0047,-0.0034,0.05,-1.1e-05,-6e-05,1.9e-06,2.3e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.06,0.06,0.0085,0.056,0.056,0.043,3.8e-09,3.8e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13790000,0.98,-0.0071,-0.012,0.19,0.014,0.00098,0.0087,0.0083,-0.00094,0.05,-1.2e-05,-5.9e-05,1.7e-06,2.6e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.051,0.051,0.0081,0.048,0.048,0.042,3.6e-09,3.6e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13890000,0.98,-0.007,-0.012,0.19,0.015,0.0017,0.011,0.0097,-0.00079,0.052,-1.2e-05,-5.9e-05,2.2e-06,2.6e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.057,0.057,0.008,0.056,0.056,0.042,3.6e-09,3.6e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0019,0.01,0.0073,-0.0023,0.051,-1.1e-05,-6e-05,2.6e-06,2.4e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.048,0.048,0.0077,0.048,0.048,0.041,3.4e-09,3.5e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14090000,0.98,-0.0071,-0.012,0.19,0.012,-0.0024,0.012,0.0088,-0.0023,0.048,-1.1e-05,-6e-05,1.6e-06,2.5e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.055,0.055,0.0076,0.055,0.055,0.04,3.4e-09,3.5e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14190000,0.98,-0.007,-0.011,0.19,0.0095,-0.0011,0.013,0.008,-0.0017,0.049,-1.2e-05,-6e-05,1.2e-06,2.6e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-09,3.3e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14290000,0.98,-0.007,-0.011,0.19,0.011,-0.0011,0.012,0.0089,-0.0019,0.053,-1.2e-05,-6e-05,1.2e-06,2.5e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.053,0.053,0.0073,0.055,0.055,0.039,3.3e-09,3.3e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14390000,0.98,-0.0071,-0.011,0.19,0.011,-0.0041,0.014,0.0084,-0.0031,0.058,-1.1e-05,-6e-05,1.5e-06,2.4e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,0.0001,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-09,3.1e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14490000,0.98,-0.0072,-0.011,0.19,0.0096,-0.0038,0.019,0.0094,-0.0035,0.061,-1.1e-05,-6e-05,1e-06,2.3e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-09,3.1e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14590000,0.98,-0.0072,-0.011,0.19,0.0074,-0.0039,0.018,0.0058,-0.0041,0.057,-1.2e-05,-6e-05,9.4e-07,2.1e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,0.0001,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-09,2.9e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14690000,0.98,-0.0072,-0.011,0.19,0.0065,-0.0038,0.018,0.0065,-0.0045,0.058,-1.2e-05,-6e-05,1.1e-06,2.1e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-09,2.9e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14790000,0.98,-0.0071,-0.011,0.19,0.0083,0.0031,0.019,0.0052,0.00085,0.061,-1.2e-05,-6e-05,1.7e-06,2.2e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.043,0.043,0.007,0.047,0.047,0.037,2.7e-09,2.7e-09,1.6e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14890000,0.98,-0.0071,-0.011,0.19,0.0069,0.00083,0.024,0.0059,0.0011,0.062,-1.2e-05,-6e-05,2.1e-06,2.2e-05,4.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.048,0.048,0.007,0.054,0.054,0.037,2.7e-09,2.7e-09,1.5e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14990000,0.98,-0.0072,-0.011,0.19,0.0057,-0.00084,0.027,0.0047,-0.00061,0.065,-1.2e-05,-6.1e-05,2.3e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.042,0.042,0.007,0.047,0.047,0.036,2.6e-09,2.6e-09,1.5e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15090000,0.98,-0.0072,-0.011,0.19,0.0056,0.00033,0.032,0.0052,-0.00068,0.068,-1.2e-05,-6.1e-05,2.3e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00019,0.00019,9.8e-05,0.047,0.047,0.007,0.054,0.054,0.036,2.6e-09,2.6e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15190000,0.98,-0.0073,-0.011,0.19,0.0038,-0.00078,0.033,0.0041,-0.00066,0.07,-1.2e-05,-6.1e-05,2.1e-06,2e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.8e-05,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-09,2.4e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15290000,0.98,-0.0074,-0.011,0.19,0.0043,-0.0018,0.033,0.0046,-0.00076,0.068,-1.2e-05,-6.1e-05,2.5e-06,2.3e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00019,0.00019,9.7e-05,0.046,0.046,0.0071,0.054,0.054,0.035,2.4e-09,2.4e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15390000,0.98,-0.0075,-0.011,0.19,0.0046,0.00057,0.033,0.0037,-0.00053,0.069,-1.2e-05,-6.1e-05,2.5e-06,2.4e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.7e-05,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-09,2.2e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15490000,0.98,-0.0075,-0.011,0.19,0.0039,-0.0019,0.034,0.0041,-0.00056,0.07,-1.2e-05,-6.1e-05,2.5e-06,2.4e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00019,0.00019,9.7e-05,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-09,2.2e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15590000,0.98,-0.0077,-0.011,0.19,0.0076,-0.0058,0.034,0.0061,-0.0046,0.069,-1.1e-05,-6.1e-05,2.7e-06,2.8e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-09,2.1e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15690000,0.98,-0.0077,-0.011,0.19,0.0093,-0.0088,0.035,0.007,-0.0053,0.071,-1.1e-05,-6.1e-05,3.1e-06,2.8e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-09,2.1e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15790000,0.98,-0.0077,-0.011,0.19,0.0058,-0.0081,0.036,0.0054,-0.0041,0.073,-1.2e-05,-6.1e-05,3.6e-06,2.7e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00017,9.5e-05,0.039,0.039,0.0073,0.046,0.046,0.034,1.9e-09,1.9e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15890000,0.98,-0.0077,-0.011,0.19,0.0046,-0.0065,0.037,0.0059,-0.0049,0.074,-1.2e-05,-6.1e-05,3.2e-06,3e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00018,9.5e-05,0.044,0.044,0.0074,0.053,0.053,0.034,1.9e-09,1.9e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15990000,0.98,-0.0075,-0.011,0.19,0.0027,-0.0051,0.034,0.0047,-0.0038,0.073,-1.2e-05,-6.1e-05,3.2e-06,3.2e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.5e-05,0.039,0.039,0.0075,0.046,0.046,0.034,1.7e-09,1.7e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16090000,0.98,-0.0075,-0.011,0.19,0.002,-0.0063,0.033,0.0049,-0.0043,0.074,-1.2e-05,-6.1e-05,3e-06,3.4e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00018,9.4e-05,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-09,1.7e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16190000,0.98,-0.0074,-0.011,0.19,-0.0018,-0.004,0.032,0.0026,-0.0032,0.071,-1.2e-05,-6.1e-05,2.7e-06,3.5e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.4e-05,0.038,0.038,0.0076,0.046,0.046,0.034,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16290000,0.98,-0.0075,-0.011,0.19,-0.0016,-0.0054,0.032,0.0024,-0.0037,0.074,-1.2e-05,-6.1e-05,2.8e-06,3.6e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00017,0.00017,9.3e-05,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16390000,0.98,-0.0074,-0.011,0.19,0.00094,-0.0048,0.033,0.0035,-0.0028,0.074,-1.2e-05,-6.1e-05,3.1e-06,4.2e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.3e-05,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-09,1.5e-09,1.1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16490000,0.98,-0.0075,-0.011,0.19,0.0029,-0.0063,0.036,0.0037,-0.0034,0.079,-1.2e-05,-6.1e-05,3e-06,4.1e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00017,0.00017,9.3e-05,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-09,1.5e-09,1.1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16590000,0.98,-0.0075,-0.011,0.19,0.007,-0.0065,0.04,0.0033,-0.0027,0.08,-1.2e-05,-6.1e-05,3e-06,4.3e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.2e-05,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-09,1.3e-09,1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16690000,0.98,-0.0076,-0.011,0.19,0.0084,-0.011,0.04,0.004,-0.0035,0.081,-1.2e-05,-6.1e-05,3.2e-06,4.4e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.1e-05,0.042,0.042,0.008,0.052,0.052,0.034,1.3e-09,1.3e-09,1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16790000,0.98,-0.0074,-0.011,0.19,0.0093,-0.0099,0.039,0.0032,-0.0025,0.081,-1.3e-05,-6.1e-05,3.3e-06,4.6e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00015,9.1e-05,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-09,1.2e-09,9.9e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16890000,0.98,-0.0074,-0.011,0.19,0.0083,-0.01,0.041,0.0041,-0.0035,0.081,-1.3e-05,-6.1e-05,3.7e-06,4.9e-05,2.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00016,0.00016,9.1e-05,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-09,1.2e-09,9.7e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16990000,0.98,-0.0074,-0.011,0.19,0.0081,-0.0097,0.041,0.0039,-0.0026,0.08,-1.3e-05,-6.1e-05,3.8e-06,5.5e-05,2.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,9e-05,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-09,1.1e-09,9.5e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17090000,0.98,-0.0075,-0.011,0.19,0.0097,-0.012,0.041,0.0049,-0.0038,0.08,-1.3e-05,-6.1e-05,3.7e-06,5.8e-05,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.04,0.04,0.0083,0.052,0.052,0.034,1.1e-09,1.1e-09,9.3e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17190000,0.98,-0.0076,-0.011,0.19,0.0085,-0.018,0.043,0.0032,-0.0073,0.084,-1.3e-05,-6.1e-05,3.2e-06,5.7e-05,1.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-10,9.9e-10,9.1e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17290000,0.98,-0.0076,-0.011,0.19,0.0095,-0.018,0.043,0.0042,-0.0091,0.084,-1.3e-05,-6.1e-05,2.9e-06,6e-05,1.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-10,9.9e-10,8.9e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17390000,0.98,-0.0075,-0.011,0.19,0.0062,-0.018,0.042,0.0056,-0.0057,0.084,-1.3e-05,-6e-05,3.2e-06,6.8e-05,1.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.8e-05,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-10,8.9e-10,8.7e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17490000,0.98,-0.0075,-0.011,0.19,0.0043,-0.018,0.042,0.0061,-0.0075,0.087,-1.3e-05,-6e-05,3.1e-06,6.9e-05,1.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00015,0.00014,8.8e-05,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-10,8.9e-10,8.5e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17590000,0.98,-0.0074,-0.011,0.19,0.00053,-0.014,0.041,0.0023,-0.0056,0.085,-1.4e-05,-6.1e-05,3.1e-06,6.9e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-10,8.1e-10,8.3e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17690000,0.98,-0.0075,-0.011,0.19,-0.00043,-0.015,0.043,0.0024,-0.0071,0.088,-1.4e-05,-6.1e-05,3.1e-06,7e-05,1.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.038,0.038,0.0085,0.052,0.052,0.034,8.1e-10,8.1e-10,8.2e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17790000,0.98,-0.0074,-0.011,0.19,0.0023,-0.013,0.043,0.0034,-0.006,0.093,-1.4e-05,-6e-05,3.1e-06,7.4e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00013,0.00013,8.7e-05,0.034,0.034,0.0085,0.046,0.046,0.034,7.3e-10,7.3e-10,8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17890000,0.98,-0.0074,-0.011,0.19,0.0044,-0.015,0.043,0.0038,-0.0074,0.098,-1.4e-05,-6e-05,3.3e-06,7.4e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00014,0.00014,8.6e-05,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-10,7.3e-10,7.8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17990000,0.98,-0.0071,-0.011,0.19,0.0038,-0.0086,0.043,0.003,-0.0017,0.099,-1.4e-05,-6e-05,3.2e-06,7.9e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-10,6.6e-10,7.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18090000,0.98,-0.0072,-0.011,0.19,0.0033,-0.0091,0.042,0.0035,-0.0027,0.098,-1.4e-05,-6e-05,3.2e-06,8.2e-05,3.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-10,6.6e-10,7.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18190000,0.98,-0.0073,-0.011,0.19,0.0034,-0.0081,0.042,0.0041,-0.0019,0.096,-1.5e-05,-6e-05,3.6e-06,8.9e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.032,0.032,0.0086,0.045,0.045,0.035,6e-10,6e-10,7.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18290000,0.98,-0.0073,-0.011,0.19,0.0043,-0.0085,0.041,0.0045,-0.0028,0.095,-1.4e-05,-6e-05,3.6e-06,9.2e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.4e-05,0.036,0.036,0.0087,0.051,0.051,0.035,6e-10,6e-10,7.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18390000,0.98,-0.0072,-0.011,0.19,0.0053,-0.0073,0.041,0.0061,-0.0021,0.094,-1.5e-05,-6e-05,3.4e-06,9.8e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00012,0.00012,8.4e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-10,5.4e-10,7.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18490000,0.98,-0.0073,-0.011,0.19,0.008,-0.0073,0.04,0.0069,-0.0029,0.096,-1.5e-05,-6e-05,3.6e-06,9.9e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00013,0.00012,8.3e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-10,5.4e-10,6.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18590000,0.98,-0.0071,-0.011,0.19,0.0064,-0.0067,0.04,0.0055,-0.0022,0.099,-1.5e-05,-6e-05,3.3e-06,9.9e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.3e-05,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-10,4.9e-10,6.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18690000,0.98,-0.0071,-0.011,0.19,0.0065,-0.0057,0.039,0.0062,-0.0028,0.098,-1.5e-05,-6e-05,3.5e-06,0.0001,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-10,4.9e-10,6.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10390000,0.98,-0.0059,-0.012,0.19,0.007,0.0043,-0.0063,0.00075,0.00011,0.12,-1.5e-05,-5.8e-05,-9.6e-07,1.5e-09,-1.1e-09,-0.0015,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.00048,0.00048,0.00011,0.25,0.25,0.56,0.25,0.25,0.048,9.3e-09,9.3e-09,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10490000,0.98,-0.0058,-0.012,0.19,0.0082,0.0058,-0.01,0.0015,0.00058,0.12,-1.5e-05,-5.8e-05,-1.4e-06,5.9e-09,-4.4e-09,-0.0014,0.2,0.002,0.43,0,0,0,0,0,4e-06,0.0005,0.0005,0.00011,0.26,0.26,0.55,0.26,0.26,0.057,9.3e-09,9.3e-09,3.6e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10590000,0.98,-0.0058,-0.012,0.19,-0.0014,0.0037,-0.0056,-0.0012,-0.0055,0.11,-1.5e-05,-5.8e-05,-1e-06,3.1e-06,-1.8e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0005,0.0005,0.0001,0.13,0.13,0.27,0.13,0.13,0.055,9.2e-09,9.2e-09,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10690000,0.98,-0.0057,-0.012,0.19,-0.00039,0.004,-0.012,-0.0013,-0.0051,0.11,-1.5e-05,-5.8e-05,-1.2e-06,3.1e-06,-1.9e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00052,0.00052,0.0001,0.14,0.14,0.26,0.14,0.14,0.065,9.2e-09,9.2e-09,3.5e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10790000,0.98,-0.0058,-0.012,0.19,0.0014,0.00059,-0.014,-0.00079,-0.0047,0.1,-1.5e-05,-5.8e-05,-1.2e-06,4.7e-06,3.8e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00051,0.00051,0.0001,0.1,0.1,0.17,0.091,0.091,0.062,9e-09,9e-09,3.4e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10890000,0.98,-0.0058,-0.012,0.19,0.0014,0.0032,-0.025,-0.00064,-0.0046,0.088,-1.5e-05,-5.8e-05,-5.4e-07,4.7e-06,3.8e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00053,0.00053,0.0001,0.12,0.12,0.16,0.098,0.098,0.068,9e-09,9e-09,3.4e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
10990000,0.98,-0.0058,-0.013,0.19,0.00095,0.0094,-0.017,-0.00047,-0.0032,0.089,-1.5e-05,-5.8e-05,-7e-07,5.4e-06,5.1e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0005,0.0005,0.0001,0.091,0.091,0.12,0.073,0.073,0.065,8.7e-09,8.7e-09,3.3e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11090000,0.98,-0.0059,-0.012,0.19,0.0018,0.014,-0.018,-0.00037,-0.0021,0.084,-1.5e-05,-5.8e-05,-1.3e-06,5.4e-06,5.1e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00052,0.00052,0.0001,0.11,0.11,0.11,0.079,0.079,0.069,8.7e-09,8.7e-09,3.3e-09,3.9e-06,3.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11190000,0.98,-0.0062,-0.013,0.19,0.0035,0.014,-0.0092,0.001,-0.002,0.087,-1.4e-05,-5.8e-05,-1.6e-06,4.2e-06,1.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00047,0.00047,0.0001,0.09,0.09,0.083,0.063,0.063,0.066,8.1e-09,8.1e-09,3.2e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11290000,0.98,-0.0061,-0.013,0.19,0.0035,0.014,-0.012,0.0013,-0.00055,0.08,-1.4e-05,-5.8e-05,-1.8e-06,4.2e-06,1.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00048,0.00048,0.0001,0.11,0.11,0.077,0.07,0.07,0.069,8.1e-09,8.1e-09,3.2e-09,3.8e-06,3.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11390000,0.98,-0.0062,-0.012,0.19,0.002,0.013,-0.019,0.00084,-0.0011,0.068,-1.4e-05,-5.8e-05,-1.7e-06,8.5e-06,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00043,0.00043,0.0001,0.091,0.091,0.062,0.057,0.057,0.066,7.5e-09,7.5e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11490000,0.98,-0.0062,-0.012,0.19,0.001,0.013,-0.016,0.00093,0.00026,0.068,-1.4e-05,-5.8e-05,-1.6e-06,8.4e-06,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00044,0.00044,0.0001,0.11,0.11,0.057,0.065,0.065,0.067,7.5e-09,7.5e-09,3.1e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11590000,0.98,-0.0064,-0.012,0.19,0.0029,0.011,-0.016,0.0008,-0.0005,0.065,-1.3e-05,-5.9e-05,-1.6e-06,1.1e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00038,0.00038,0.0001,0.091,0.091,0.048,0.054,0.054,0.065,6.9e-09,6.9e-09,3e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11690000,0.98,-0.0064,-0.012,0.19,0.0033,0.014,-0.016,0.0011,0.00073,0.058,-1.3e-05,-5.9e-05,-1.4e-06,1.1e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00039,0.00039,0.0001,0.11,0.11,0.044,0.062,0.062,0.066,6.9e-09,6.9e-09,3e-09,3.7e-06,3.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11790000,0.98,-0.0067,-0.012,0.19,0.0021,0.0092,-0.013,0.00068,-0.0018,0.06,-1.3e-05,-5.9e-05,-7.7e-07,1.6e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00034,0.00034,0.0001,0.088,0.088,0.037,0.052,0.052,0.063,6.4e-09,6.4e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11890000,0.98,-0.0068,-0.012,0.19,0.0047,0.01,-0.015,0.00096,-0.00089,0.056,-1.3e-05,-5.9e-05,-8.8e-07,1.6e-05,3.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00035,0.00035,0.0001,0.11,0.11,0.034,0.06,0.06,0.063,6.4e-09,6.4e-09,2.9e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
11990000,0.98,-0.0069,-0.012,0.19,0.0077,0.011,-0.015,0.0021,-0.0018,0.051,-1.2e-05,-5.9e-05,-6.7e-07,1.5e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.0003,0.0003,0.0001,0.085,0.085,0.03,0.051,0.051,0.061,5.9e-09,5.9e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12090000,0.98,-0.0069,-0.012,0.19,0.0092,0.011,-0.011,0.0029,-0.00079,0.054,-1.2e-05,-5.9e-05,-6.8e-07,1.5e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00031,0.00031,0.0001,0.1,0.1,0.027,0.059,0.059,0.06,5.9e-09,5.9e-09,2.8e-09,3.6e-06,3.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12190000,0.98,-0.0067,-0.012,0.19,0.0075,0.01,-0.01,0.0018,0.00035,0.055,-1.3e-05,-5.9e-05,-9.2e-07,1.7e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00027,0.00027,0.0001,0.08,0.08,0.024,0.05,0.05,0.058,5.5e-09,5.5e-09,2.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12290000,0.98,-0.0068,-0.012,0.19,0.0051,0.0095,-0.011,0.0024,0.0014,0.054,-1.3e-05,-5.9e-05,-1.1e-06,1.7e-05,3.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00028,0.00028,0.0001,0.095,0.095,0.022,0.059,0.059,0.058,5.5e-09,5.5e-09,2.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12390000,0.98,-0.0069,-0.012,0.19,0.0038,0.0065,-0.011,0.0017,0.00048,0.047,-1.2e-05,-6e-05,-1.1e-06,1.9e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00025,0.00025,0.0001,0.076,0.076,0.02,0.05,0.05,0.056,5.2e-09,5.2e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12490000,0.98,-0.0069,-0.012,0.19,0.0037,0.0075,-0.0056,0.0021,0.0012,0.047,-1.2e-05,-6e-05,-1.2e-06,1.9e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00026,0.00026,0.0001,0.089,0.089,0.018,0.058,0.058,0.055,5.2e-09,5.2e-09,2.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12590000,0.98,-0.0071,-0.012,0.19,0.0075,0.0011,-0.0026,0.0033,-0.0013,0.049,-1.2e-05,-6e-05,-1.2e-06,1.9e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00023,0.00023,0.0001,0.071,0.071,0.017,0.049,0.049,0.054,4.9e-09,4.9e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12690000,0.98,-0.007,-0.012,0.19,0.008,-0.001,-0.0019,0.004,-0.0013,0.049,-1.2e-05,-6e-05,-1.2e-06,1.9e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00024,0.00024,0.0001,0.082,0.082,0.016,0.058,0.058,0.053,4.9e-09,4.9e-09,2.5e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12790000,0.98,-0.0073,-0.012,0.19,0.0096,-0.0042,0.0011,0.0041,-0.0044,0.051,-1.1e-05,-6e-05,-3.8e-07,1.9e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00022,0.00022,0.0001,0.067,0.067,0.014,0.049,0.049,0.052,4.6e-09,4.6e-09,2.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12890000,0.98,-0.0073,-0.012,0.19,0.0097,-0.0051,0.0031,0.0051,-0.0049,0.053,-1.1e-05,-6e-05,1.4e-07,1.9e-05,4.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.9e-06,0.00023,0.00023,0.0001,0.077,0.077,0.013,0.057,0.057,0.051,4.6e-09,4.6e-09,2.4e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
12990000,0.98,-0.0072,-0.012,0.19,0.0077,-0.003,0.0047,0.0036,-0.0036,0.054,-1.1e-05,-6e-05,6.2e-07,1.9e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.063,0.063,0.012,0.049,0.049,0.05,4.4e-09,4.4e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13090000,0.98,-0.0073,-0.012,0.19,0.0085,-0.0029,0.0034,0.0044,-0.0038,0.052,-1.1e-05,-6e-05,1.3e-06,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00022,0.00022,0.0001,0.072,0.072,0.012,0.057,0.057,0.049,4.4e-09,4.4e-09,2.3e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13190000,0.98,-0.0073,-0.012,0.19,0.0036,-0.0045,0.0039,0.00097,-0.0045,0.053,-1.1e-05,-6e-05,1.7e-06,2.1e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.059,0.059,0.011,0.049,0.049,0.047,4.2e-09,4.2e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13290000,0.98,-0.0073,-0.012,0.19,0.0031,-0.0054,0.0023,0.0013,-0.005,0.051,-1.1e-05,-6e-05,1.7e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.067,0.067,0.01,0.057,0.057,0.047,4.2e-09,4.2e-09,2.2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13390000,0.98,-0.0072,-0.012,0.19,0.0023,-0.0034,0.0033,0.00085,-0.0037,0.052,-1.2e-05,-6e-05,1.5e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.056,0.056,0.0097,0.049,0.049,0.046,4e-09,4e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13490000,0.98,-0.0072,-0.012,0.19,0.0027,-0.0016,0.0037,0.0011,-0.0039,0.048,-1.2e-05,-6e-05,1.7e-06,2.1e-05,3.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00021,0.00021,0.0001,0.064,0.064,0.0093,0.056,0.056,0.045,4e-09,4e-09,2.1e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13590000,0.98,-0.0072,-0.012,0.19,0.0072,-0.0018,0.0063,0.004,-0.0032,0.047,-1.1e-05,-6e-05,1.5e-06,2.3e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.053,0.053,0.0089,0.048,0.048,0.044,3.8e-09,3.8e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13690000,0.98,-0.0071,-0.012,0.19,0.0071,-0.0032,0.0074,0.0047,-0.0034,0.049,-1.1e-05,-6e-05,1.9e-06,2.2e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.06,0.06,0.0085,0.056,0.056,0.044,3.8e-09,3.8e-09,2e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13790000,0.98,-0.0071,-0.012,0.19,0.014,0.00098,0.0084,0.0083,-0.00094,0.049,-1.2e-05,-5.9e-05,1.7e-06,2.5e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.051,0.051,0.0082,0.048,0.048,0.043,3.6e-09,3.6e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13890000,0.98,-0.007,-0.012,0.19,0.015,0.0018,0.01,0.0097,-0.00079,0.051,-1.2e-05,-5.9e-05,2.2e-06,2.5e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.057,0.057,0.008,0.056,0.056,0.042,3.6e-09,3.6e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
13990000,0.98,-0.0071,-0.012,0.19,0.015,0.0019,0.01,0.0073,-0.0023,0.051,-1.1e-05,-6e-05,2.6e-06,2.3e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.048,0.048,0.0077,0.048,0.048,0.041,3.4e-09,3.5e-09,1.9e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14090000,0.98,-0.0071,-0.012,0.19,0.012,-0.0024,0.012,0.0088,-0.0023,0.047,-1.1e-05,-6e-05,1.6e-06,2.4e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.0002,0.0002,0.0001,0.055,0.055,0.0076,0.055,0.055,0.041,3.4e-09,3.5e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14190000,0.98,-0.007,-0.011,0.19,0.0095,-0.0011,0.013,0.008,-0.0017,0.048,-1.2e-05,-6e-05,1.2e-06,2.5e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.8e-06,0.00019,0.00019,0.0001,0.047,0.047,0.0074,0.048,0.048,0.04,3.3e-09,3.3e-09,1.8e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14290000,0.98,-0.007,-0.011,0.19,0.011,-0.0011,0.012,0.0089,-0.0019,0.052,-1.2e-05,-6e-05,1.2e-06,2.4e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.053,0.053,0.0073,0.055,0.055,0.04,3.3e-09,3.3e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14390000,0.98,-0.0071,-0.011,0.19,0.011,-0.0041,0.014,0.0084,-0.0031,0.057,-1.1e-05,-6e-05,1.5e-06,2.3e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,0.0001,0.045,0.045,0.0071,0.048,0.048,0.039,3.1e-09,3.1e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14490000,0.98,-0.0072,-0.011,0.19,0.0095,-0.0038,0.019,0.0094,-0.0035,0.06,-1.1e-05,-6e-05,1e-06,2.2e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.051,0.051,0.0071,0.055,0.055,0.038,3.1e-09,3.1e-09,1.7e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14590000,0.98,-0.0072,-0.011,0.19,0.0074,-0.0039,0.017,0.0058,-0.0041,0.056,-1.2e-05,-6e-05,9.3e-07,2e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,0.0001,0.044,0.044,0.007,0.047,0.047,0.038,2.9e-09,2.9e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14690000,0.98,-0.0072,-0.011,0.19,0.0065,-0.0038,0.018,0.0065,-0.0045,0.057,-1.2e-05,-6e-05,1.1e-06,2.1e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.0002,0.0002,0.0001,0.05,0.05,0.007,0.054,0.054,0.037,2.9e-09,2.9e-09,1.6e-09,3.5e-06,3.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14790000,0.98,-0.0071,-0.011,0.19,0.0082,0.0031,0.019,0.0052,0.00085,0.06,-1.2e-05,-6e-05,1.7e-06,2.1e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.043,0.043,0.0069,0.047,0.047,0.037,2.7e-09,2.7e-09,1.6e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14890000,0.98,-0.0071,-0.011,0.19,0.0068,0.00084,0.024,0.0059,0.0011,0.062,-1.2e-05,-6e-05,2.1e-06,2.1e-05,4.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.048,0.048,0.007,0.054,0.054,0.037,2.7e-09,2.7e-09,1.5e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
14990000,0.98,-0.0072,-0.011,0.19,0.0056,-0.00083,0.027,0.0047,-0.00061,0.064,-1.2e-05,-6.1e-05,2.3e-06,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.7e-06,0.00019,0.00019,9.9e-05,0.042,0.042,0.0069,0.047,0.047,0.036,2.6e-09,2.6e-09,1.5e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15090000,0.98,-0.0072,-0.011,0.19,0.0056,0.00034,0.032,0.0052,-0.00067,0.068,-1.2e-05,-6.1e-05,2.3e-06,2e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00019,0.00019,9.8e-05,0.047,0.047,0.007,0.054,0.054,0.036,2.6e-09,2.6e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15190000,0.98,-0.0073,-0.011,0.19,0.0038,-0.00077,0.033,0.0041,-0.00066,0.07,-1.2e-05,-6.1e-05,2.1e-06,1.9e-05,4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.8e-05,0.041,0.041,0.007,0.047,0.047,0.036,2.4e-09,2.4e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15290000,0.98,-0.0074,-0.011,0.19,0.0043,-0.0018,0.033,0.0046,-0.00076,0.067,-1.2e-05,-6.1e-05,2.5e-06,2.2e-05,3.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00019,0.00019,9.7e-05,0.046,0.046,0.0071,0.054,0.054,0.035,2.4e-09,2.4e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15390000,0.98,-0.0075,-0.011,0.19,0.0046,0.00058,0.034,0.0037,-0.00052,0.068,-1.2e-05,-6.1e-05,2.5e-06,2.2e-05,3.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.7e-05,0.041,0.041,0.0071,0.047,0.047,0.035,2.2e-09,2.2e-09,1.4e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15490000,0.98,-0.0075,-0.011,0.19,0.0039,-0.0019,0.034,0.0041,-0.00056,0.07,-1.2e-05,-6.1e-05,2.5e-06,2.3e-05,3.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00019,0.00019,9.7e-05,0.046,0.046,0.0072,0.053,0.053,0.035,2.2e-09,2.2e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15590000,0.98,-0.0077,-0.011,0.19,0.0075,-0.0058,0.034,0.0061,-0.0046,0.069,-1.1e-05,-6.1e-05,2.7e-06,2.7e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.04,0.04,0.0072,0.047,0.047,0.035,2.1e-09,2.1e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15690000,0.98,-0.0077,-0.011,0.19,0.0092,-0.0088,0.036,0.007,-0.0053,0.071,-1.1e-05,-6.1e-05,3.1e-06,2.7e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.6e-06,0.00018,0.00018,9.6e-05,0.045,0.045,0.0073,0.053,0.053,0.034,2.1e-09,2.1e-09,1.3e-09,3.4e-06,3.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15790000,0.98,-0.0077,-0.011,0.19,0.0058,-0.0081,0.036,0.0054,-0.0041,0.073,-1.2e-05,-6.1e-05,3.6e-06,2.6e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00017,9.5e-05,0.039,0.039,0.0073,0.046,0.046,0.034,1.9e-09,1.9e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15890000,0.98,-0.0077,-0.011,0.19,0.0046,-0.0065,0.037,0.0059,-0.0049,0.073,-1.2e-05,-6.1e-05,3.2e-06,2.9e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00018,9.5e-05,0.044,0.044,0.0074,0.053,0.053,0.034,1.9e-09,1.9e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
15990000,0.98,-0.0075,-0.011,0.19,0.0027,-0.0051,0.035,0.0047,-0.0038,0.073,-1.2e-05,-6.1e-05,3.2e-06,3.1e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.5e-05,0.039,0.039,0.0074,0.046,0.046,0.034,1.7e-09,1.7e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16090000,0.98,-0.0075,-0.011,0.19,0.002,-0.0063,0.033,0.0049,-0.0043,0.074,-1.2e-05,-6.1e-05,2.9e-06,3.3e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00018,0.00018,9.4e-05,0.044,0.044,0.0076,0.053,0.053,0.034,1.7e-09,1.7e-09,1.2e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16190000,0.98,-0.0074,-0.011,0.19,-0.0019,-0.004,0.032,0.0026,-0.0032,0.071,-1.2e-05,-6.1e-05,2.7e-06,3.4e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.5e-06,0.00017,0.00017,9.4e-05,0.038,0.038,0.0076,0.046,0.046,0.034,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16290000,0.98,-0.0075,-0.011,0.19,-0.0016,-0.0054,0.033,0.0024,-0.0037,0.074,-1.2e-05,-6.1e-05,2.8e-06,3.5e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00017,0.00017,9.3e-05,0.043,0.043,0.0077,0.053,0.053,0.034,1.6e-09,1.6e-09,1.1e-09,3.3e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16390000,0.98,-0.0074,-0.011,0.19,0.00091,-0.0048,0.033,0.0035,-0.0028,0.074,-1.2e-05,-6.1e-05,3.1e-06,4.1e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.3e-05,0.038,0.038,0.0077,0.046,0.046,0.034,1.5e-09,1.5e-09,1.1e-09,3.2e-06,3.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16490000,0.98,-0.0075,-0.011,0.19,0.0028,-0.0063,0.036,0.0037,-0.0034,0.079,-1.2e-05,-6.1e-05,3e-06,4e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00017,0.00017,9.3e-05,0.043,0.043,0.0079,0.053,0.053,0.034,1.5e-09,1.5e-09,1.1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16590000,0.98,-0.0075,-0.011,0.19,0.007,-0.0064,0.04,0.0032,-0.0027,0.08,-1.2e-05,-6.1e-05,3e-06,4.2e-05,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.2e-05,0.037,0.037,0.0079,0.046,0.046,0.034,1.3e-09,1.3e-09,1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16690000,0.98,-0.0076,-0.011,0.19,0.0084,-0.011,0.041,0.004,-0.0035,0.081,-1.2e-05,-6.1e-05,3.1e-06,4.3e-05,2.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00016,9.1e-05,0.042,0.042,0.008,0.052,0.052,0.034,1.3e-09,1.3e-09,1e-09,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16790000,0.98,-0.0074,-0.011,0.19,0.0093,-0.0099,0.04,0.0031,-0.0025,0.082,-1.3e-05,-6.1e-05,3.3e-06,4.5e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.4e-06,0.00016,0.00015,9.1e-05,0.037,0.037,0.008,0.046,0.046,0.034,1.2e-09,1.2e-09,9.9e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16890000,0.98,-0.0074,-0.011,0.19,0.0083,-0.01,0.041,0.004,-0.0035,0.081,-1.3e-05,-6.1e-05,3.7e-06,4.8e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00016,0.00016,9.1e-05,0.041,0.041,0.0082,0.052,0.052,0.034,1.2e-09,1.2e-09,9.7e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
16990000,0.98,-0.0074,-0.011,0.19,0.0081,-0.0097,0.041,0.0039,-0.0026,0.08,-1.3e-05,-6.1e-05,3.8e-06,5.4e-05,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,9e-05,0.036,0.036,0.0082,0.046,0.046,0.034,1.1e-09,1.1e-09,9.5e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17090000,0.98,-0.0075,-0.011,0.19,0.0096,-0.012,0.041,0.0048,-0.0038,0.08,-1.3e-05,-6.1e-05,3.7e-06,5.7e-05,1.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.04,0.04,0.0083,0.052,0.052,0.034,1.1e-09,1.1e-09,9.3e-10,3.2e-06,3.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17190000,0.98,-0.0076,-0.011,0.19,0.0085,-0.018,0.043,0.0032,-0.0073,0.084,-1.3e-05,-6.1e-05,3.2e-06,5.6e-05,1.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.036,0.036,0.0083,0.046,0.046,0.034,9.9e-10,9.9e-10,9.1e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17290000,0.98,-0.0076,-0.011,0.19,0.0094,-0.018,0.043,0.0042,-0.0091,0.084,-1.3e-05,-6.1e-05,2.9e-06,5.9e-05,1.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.3e-06,0.00015,0.00015,8.9e-05,0.04,0.04,0.0084,0.052,0.052,0.034,9.9e-10,9.9e-10,8.9e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17390000,0.98,-0.0075,-0.011,0.19,0.0062,-0.018,0.042,0.0056,-0.0057,0.084,-1.3e-05,-6e-05,3.2e-06,6.7e-05,1.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.8e-05,0.035,0.035,0.0084,0.046,0.046,0.034,8.9e-10,8.9e-10,8.7e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17490000,0.98,-0.0075,-0.011,0.19,0.0043,-0.018,0.042,0.0061,-0.0075,0.087,-1.3e-05,-6e-05,3.1e-06,6.9e-05,1.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00015,0.00014,8.8e-05,0.039,0.039,0.0085,0.052,0.052,0.034,8.9e-10,8.9e-10,8.5e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17590000,0.98,-0.0074,-0.011,0.19,0.00051,-0.014,0.042,0.0023,-0.0056,0.085,-1.4e-05,-6.1e-05,3.1e-06,6.9e-05,2.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.034,0.034,0.0085,0.046,0.046,0.034,8.1e-10,8.1e-10,8.3e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17690000,0.98,-0.0075,-0.011,0.19,-0.00045,-0.015,0.043,0.0024,-0.0071,0.088,-1.4e-05,-6.1e-05,3.1e-06,6.9e-05,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.7e-05,0.038,0.038,0.0086,0.052,0.052,0.034,8.1e-10,8.1e-10,8.2e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17790000,0.98,-0.0074,-0.011,0.19,0.0023,-0.013,0.044,0.0034,-0.006,0.094,-1.4e-05,-6e-05,3.1e-06,7.4e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00013,0.00013,8.7e-05,0.034,0.034,0.0086,0.046,0.046,0.034,7.3e-10,7.3e-10,8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17890000,0.98,-0.0074,-0.011,0.19,0.0044,-0.015,0.044,0.0038,-0.0074,0.099,-1.4e-05,-6e-05,3.2e-06,7.3e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.2e-06,0.00014,0.00014,8.6e-05,0.037,0.037,0.0086,0.052,0.052,0.035,7.3e-10,7.3e-10,7.8e-10,3.1e-06,3.1e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
17990000,0.98,-0.0071,-0.011,0.19,0.0038,-0.0085,0.043,0.003,-0.0017,0.099,-1.4e-05,-6e-05,3.2e-06,7.8e-05,3.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.033,0.033,0.0086,0.045,0.045,0.034,6.6e-10,6.6e-10,7.7e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18090000,0.98,-0.0072,-0.011,0.19,0.0033,-0.009,0.043,0.0035,-0.0027,0.098,-1.4e-05,-6e-05,3.1e-06,8.2e-05,3.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.036,0.036,0.0087,0.052,0.052,0.035,6.6e-10,6.6e-10,7.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18190000,0.98,-0.0073,-0.011,0.19,0.0034,-0.0081,0.043,0.0041,-0.0019,0.096,-1.5e-05,-6e-05,3.6e-06,8.8e-05,3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.5e-05,0.032,0.032,0.0086,0.045,0.045,0.035,6e-10,6e-10,7.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18290000,0.98,-0.0073,-0.011,0.19,0.0043,-0.0085,0.042,0.0044,-0.0028,0.095,-1.4e-05,-6e-05,3.6e-06,9.1e-05,2.8e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00013,8.4e-05,0.036,0.036,0.0087,0.051,0.051,0.035,6e-10,6e-10,7.2e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18390000,0.98,-0.0072,-0.011,0.19,0.0053,-0.0073,0.041,0.0061,-0.0021,0.095,-1.5e-05,-6e-05,3.4e-06,9.8e-05,2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00012,0.00012,8.4e-05,0.031,0.031,0.0086,0.045,0.045,0.035,5.4e-10,5.4e-10,7.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18490000,0.98,-0.0073,-0.011,0.19,0.008,-0.0073,0.041,0.0069,-0.0029,0.097,-1.5e-05,-6e-05,3.6e-06,9.9e-05,2.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3.1e-06,0.00013,0.00012,8.3e-05,0.035,0.035,0.0087,0.051,0.051,0.035,5.4e-10,5.4e-10,6.9e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18590000,0.98,-0.0071,-0.011,0.19,0.0064,-0.0067,0.041,0.0055,-0.0022,0.099,-1.5e-05,-6e-05,3.3e-06,9.8e-05,2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.3e-05,0.031,0.031,0.0087,0.045,0.045,0.035,4.9e-10,4.9e-10,6.8e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18690000,0.98,-0.0071,-0.011,0.19,0.0065,-0.0056,0.039,0.0062,-0.0028,0.098,-1.5e-05,-6e-05,3.5e-06,0.0001,2.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.034,0.034,0.0087,0.051,0.051,0.035,4.9e-10,4.9e-10,6.6e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18790000,0.98,-0.007,-0.011,0.19,0.0055,-0.0054,0.038,0.0062,-0.0023,0.096,-1.5e-05,-6e-05,3.4e-06,0.00011,2.2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.03,0.03,0.0087,0.045,0.045,0.035,4.4e-10,4.4e-10,6.5e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18890000,0.98,-0.007,-0.011,0.19,0.0042,-0.005,0.036,0.0067,-0.0029,0.092,-1.5e-05,-6e-05,3.3e-06,0.00011,1.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-10,4.4e-10,6.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18890000,0.98,-0.007,-0.011,0.19,0.0042,-0.005,0.036,0.0067,-0.0029,0.093,-1.5e-05,-6e-05,3.3e-06,0.00011,1.9e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.2e-05,0.033,0.033,0.0087,0.051,0.051,0.035,4.4e-10,4.4e-10,6.4e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
18990000,0.98,-0.007,-0.011,0.19,0.0026,-0.0052,0.037,0.0055,-0.0023,0.096,-1.5e-05,-6e-05,3.2e-06,0.00011,2e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00011,8.1e-05,0.029,0.029,0.0086,0.045,0.045,0.035,4e-10,4e-10,6.3e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19090000,0.98,-0.0071,-0.011,0.19,0.00058,-0.0056,0.037,0.0058,-0.0028,0.092,-1.5e-05,-6e-05,3.4e-06,0.00011,1.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.1e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-10,4e-10,6.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19190000,0.98,-0.007,-0.011,0.19,-0.00089,-0.0053,0.036,0.0048,-0.0023,0.091,-1.5e-05,-6e-05,3e-06,0.00012,1.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,8e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-10,3.7e-10,6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19090000,0.98,-0.0071,-0.011,0.19,0.00058,-0.0056,0.037,0.0058,-0.0028,0.093,-1.5e-05,-6e-05,3.4e-06,0.00011,1.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,3e-06,0.00012,0.00012,8.1e-05,0.032,0.032,0.0087,0.051,0.051,0.036,4e-10,4e-10,6.1e-10,3e-06,3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19190000,0.98,-0.007,-0.011,0.19,-0.00089,-0.0053,0.037,0.0048,-0.0023,0.092,-1.5e-05,-6e-05,3e-06,0.00012,1.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,8e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.7e-10,3.7e-10,6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19290000,0.98,-0.0069,-0.011,0.19,-0.0017,-0.0051,0.037,0.0047,-0.0028,0.091,-1.5e-05,-6e-05,2.9e-06,0.00012,1.4e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,8e-05,0.031,0.031,0.0087,0.05,0.05,0.036,3.7e-10,3.7e-10,5.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19390000,0.98,-0.007,-0.011,0.19,-0.0022,-0.0017,0.038,0.0041,-0.00095,0.09,-1.5e-05,-6e-05,2.8e-06,0.00012,1.5e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,8e-05,0.028,0.028,0.0086,0.045,0.045,0.036,3.3e-10,3.3e-10,5.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19490000,0.98,-0.0071,-0.011,0.19,-0.003,-0.0017,0.037,0.0038,-0.0011,0.089,-1.5e-05,-6e-05,2.5e-06,0.00012,1.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.9e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-10,3.3e-10,5.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19490000,0.98,-0.0071,-0.011,0.19,-0.003,-0.0017,0.038,0.0038,-0.0011,0.09,-1.5e-05,-6e-05,2.5e-06,0.00012,1.3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.9e-05,0.03,0.03,0.0087,0.05,0.05,0.036,3.3e-10,3.3e-10,5.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19590000,0.98,-0.007,-0.011,0.19,-0.0041,-0.0046,0.039,0.0044,-0.0022,0.09,-1.5e-05,-6e-05,2.4e-06,0.00013,9.6e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.9e-05,0.027,0.027,0.0086,0.044,0.044,0.036,3e-10,3e-10,5.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19690000,0.98,-0.007,-0.011,0.19,-0.0057,-0.0031,0.037,0.0039,-0.0026,0.089,-1.5e-05,-6e-05,2.6e-06,0.00013,7.8e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.8e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-10,3e-10,5.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19790000,0.98,-0.0071,-0.011,0.19,-0.0057,-0.0018,0.035,0.0064,-0.0021,0.085,-1.5e-05,-6e-05,2.4e-06,0.00014,4.2e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.00011,0.0001,7.8e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.8e-10,2.8e-10,5.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19890000,0.98,-0.0072,-0.011,0.19,-0.0058,-0.0015,0.036,0.0058,-0.0022,0.084,-1.5e-05,-6e-05,2.2e-06,0.00014,2.4e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.00011,0.00011,7.7e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-10,2.8e-10,5.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19990000,0.98,-0.0072,-0.011,0.19,-0.0054,-0.0015,0.033,0.0061,-0.00071,0.08,-1.5e-05,-5.9e-05,2.3e-06,0.00014,5e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.7e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-10,2.5e-10,5.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20090000,0.98,-0.0072,-0.011,0.19,-0.0049,-0.0037,0.033,0.0056,-0.00097,0.084,-1.5e-05,-5.9e-05,2.2e-06,0.00014,6.5e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.7e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-10,2.5e-10,5.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20190000,0.98,-0.0072,-0.011,0.19,-0.0039,-0.0011,0.033,0.0066,-0.00071,0.083,-1.5e-05,-5.9e-05,2e-06,0.00015,-6.1e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-10,2.3e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20290000,0.98,-0.0072,-0.011,0.19,-0.0071,-0.0022,0.033,0.0061,-0.00082,0.084,-1.5e-05,-5.9e-05,1.9e-06,0.00015,-1.5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-10,2.3e-10,4.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20390000,0.98,-0.0072,-0.011,0.19,-0.0078,-0.0011,0.033,0.0069,-0.00058,0.085,-1.5e-05,-5.9e-05,2.1e-06,0.00015,-2.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,9.9e-05,7.5e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-10,2.1e-10,4.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20490000,0.98,-0.0072,-0.011,0.19,-0.012,-0.002,0.033,0.0059,-0.00071,0.083,-1.5e-05,-5.9e-05,2e-06,0.00015,-4.6e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,0.0001,7.5e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-10,2.1e-10,4.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20590000,0.98,-0.0071,-0.011,0.19,-0.011,-0.003,0.032,0.007,-0.0006,0.081,-1.5e-05,-5.9e-05,2.3e-06,0.00016,-7.2e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.9e-05,9.8e-05,7.4e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-10,2e-10,4.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20690000,0.98,-0.0071,-0.011,0.19,-0.013,-0.0017,0.033,0.0058,-0.00079,0.082,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,9.8e-05,7.4e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-10,2e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20790000,0.98,-0.0065,-0.011,0.19,-0.016,0.00078,0.018,0.0049,-0.00062,0.08,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-9.9e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.8e-05,9.6e-05,7.4e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.8e-10,1.8e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20890000,0.98,0.0026,-0.0074,0.19,-0.021,0.013,-0.1,0.003,9.2e-05,0.074,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-1.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.8e-05,9.7e-05,7.3e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-10,1.8e-10,4.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20990000,0.98,0.006,-0.004,0.19,-0.032,0.031,-0.24,0.0023,0.0007,0.059,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-1.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.6e-05,9.5e-05,7.3e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-10,1.7e-10,4.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19690000,0.98,-0.007,-0.011,0.19,-0.0057,-0.0032,0.038,0.0039,-0.0026,0.09,-1.5e-05,-6e-05,2.6e-06,0.00013,7.7e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.9e-06,0.00011,0.00011,7.8e-05,0.03,0.03,0.0086,0.05,0.05,0.036,3e-10,3e-10,5.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19790000,0.98,-0.0071,-0.011,0.19,-0.0057,-0.0018,0.036,0.0064,-0.0021,0.085,-1.5e-05,-6e-05,2.4e-06,0.00014,4e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.00011,0.0001,7.8e-05,0.026,0.026,0.0086,0.044,0.044,0.036,2.8e-10,2.8e-10,5.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19890000,0.98,-0.0072,-0.011,0.19,-0.0058,-0.0015,0.036,0.0058,-0.0022,0.084,-1.5e-05,-6e-05,2.2e-06,0.00014,2.2e-06,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.00011,0.00011,7.7e-05,0.029,0.029,0.0086,0.05,0.05,0.036,2.8e-10,2.8e-10,5.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
19990000,0.98,-0.0072,-0.011,0.19,-0.0054,-0.0015,0.033,0.0061,-0.00071,0.081,-1.5e-05,-5.9e-05,2.3e-06,0.00014,2.9e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.7e-05,0.026,0.026,0.0085,0.044,0.044,0.036,2.5e-10,2.5e-10,5.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20090000,0.98,-0.0072,-0.011,0.19,-0.0049,-0.0037,0.033,0.0056,-0.00098,0.084,-1.5e-05,-5.9e-05,2.2e-06,0.00014,4.2e-07,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.7e-05,0.028,0.028,0.0086,0.05,0.05,0.036,2.5e-10,2.5e-10,5.1e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20190000,0.98,-0.0072,-0.011,0.19,-0.0039,-0.0012,0.034,0.0066,-0.00071,0.084,-1.5e-05,-5.9e-05,2e-06,0.00015,-8.7e-07,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.025,0.025,0.0085,0.044,0.044,0.036,2.3e-10,2.3e-10,5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20290000,0.98,-0.0072,-0.011,0.19,-0.0071,-0.0022,0.034,0.0061,-0.00082,0.085,-1.5e-05,-5.9e-05,1.9e-06,0.00015,-1.8e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,0.0001,7.6e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.3e-10,2.3e-10,4.9e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20390000,0.98,-0.0072,-0.011,0.19,-0.0077,-0.0011,0.034,0.0069,-0.00058,0.086,-1.5e-05,-5.9e-05,2.1e-06,0.00015,-3.1e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.8e-06,0.0001,9.9e-05,7.5e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2.1e-10,2.1e-10,4.8e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20490000,0.98,-0.0072,-0.011,0.19,-0.012,-0.002,0.033,0.0059,-0.00072,0.084,-1.5e-05,-5.9e-05,2e-06,0.00015,-5e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,0.0001,7.5e-05,0.027,0.027,0.0085,0.049,0.049,0.036,2.1e-10,2.1e-10,4.7e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20590000,0.98,-0.0071,-0.011,0.19,-0.011,-0.003,0.033,0.007,-0.0006,0.082,-1.5e-05,-5.9e-05,2.3e-06,0.00016,-7.6e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.9e-05,9.8e-05,7.4e-05,0.024,0.024,0.0084,0.044,0.044,0.036,2e-10,2e-10,4.6e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20690000,0.98,-0.0071,-0.011,0.19,-0.013,-0.0017,0.033,0.0058,-0.00079,0.082,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-8.3e-06,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,0.0001,9.8e-05,7.4e-05,0.026,0.026,0.0084,0.049,0.049,0.036,2e-10,2e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20790000,0.98,-0.0065,-0.011,0.19,-0.016,0.00077,0.018,0.0049,-0.00063,0.081,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.8e-05,9.6e-05,7.4e-05,0.023,0.023,0.0084,0.043,0.043,0.036,1.8e-10,1.8e-10,4.5e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20890000,0.98,0.0026,-0.0074,0.19,-0.021,0.013,-0.1,0.003,8.9e-05,0.074,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-1.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.7e-06,9.8e-05,9.7e-05,7.3e-05,0.026,0.026,0.0084,0.049,0.049,0.036,1.8e-10,1.8e-10,4.4e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
20990000,0.98,0.006,-0.004,0.19,-0.032,0.031,-0.24,0.0023,0.00069,0.059,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-1.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.6e-05,9.5e-05,7.3e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.7e-10,1.7e-10,4.3e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21090000,0.98,0.0044,-0.0043,0.19,-0.045,0.047,-0.36,-0.0016,0.0046,0.029,-1.5e-05,-5.9e-05,2.1e-06,0.00016,-1.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.7e-05,9.5e-05,7.3e-05,0.026,0.026,0.0084,0.048,0.048,0.036,1.7e-10,1.7e-10,4.2e-10,2.9e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21190000,0.98,0.0015,-0.006,0.19,-0.049,0.051,-0.49,-0.0012,0.0036,-0.0075,-1.4e-05,-5.9e-05,2.1e-06,0.00016,-2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.4e-05,9.3e-05,7.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-10,1.6e-10,4.2e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21290000,0.98,-0.00065,-0.0073,0.19,-0.049,0.054,-0.62,-0.006,0.0089,-0.066,-1.4e-05,-5.9e-05,1.9e-06,0.00016,-2.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.5e-05,9.4e-05,7.2e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-10,1.6e-10,4.1e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21390000,0.98,-0.0021,-0.008,0.19,-0.044,0.05,-0.74,-0.0049,0.011,-0.13,-1.4e-05,-5.9e-05,1.9e-06,0.00017,-2.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.3e-05,9.1e-05,7.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-10,1.4e-10,4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21190000,0.98,0.0015,-0.006,0.19,-0.049,0.051,-0.49,-0.0012,0.0036,-0.0072,-1.4e-05,-5.9e-05,2.1e-06,0.00016,-2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.4e-05,9.3e-05,7.2e-05,0.023,0.023,0.0083,0.043,0.043,0.036,1.6e-10,1.6e-10,4.2e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21290000,0.98,-0.00066,-0.0073,0.19,-0.049,0.054,-0.62,-0.006,0.0089,-0.066,-1.4e-05,-5.9e-05,1.9e-06,0.00016,-2.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.5e-05,9.4e-05,7.2e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.6e-10,1.6e-10,4.1e-10,2.8e-06,2.9e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21390000,0.98,-0.0021,-0.008,0.19,-0.044,0.05,-0.74,-0.0049,0.011,-0.13,-1.4e-05,-5.9e-05,1.9e-06,0.00017,-2.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.3e-05,9.1e-05,7.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.4e-10,1.4e-10,4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21490000,0.98,-0.0029,-0.0084,0.19,-0.04,0.047,-0.88,-0.0091,0.016,-0.22,-1.4e-05,-5.9e-05,2e-06,0.00017,-2.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.3e-05,9.2e-05,7.1e-05,0.026,0.026,0.0083,0.048,0.048,0.036,1.4e-10,1.4e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21590000,0.98,-0.0034,-0.0084,0.19,-0.031,0.043,-1,-0.0078,0.017,-0.31,-1.4e-05,-5.9e-05,2.1e-06,0.00017,-2.6e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.1e-05,9e-05,7.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-10,1.3e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21690000,0.98,-0.0038,-0.0083,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.42,-1.4e-05,-5.9e-05,2.2e-06,0.00017,-2.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.1e-05,9e-05,7e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.3e-10,1.3e-10,3.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21590000,0.98,-0.0034,-0.0084,0.19,-0.031,0.043,-1,-0.0078,0.017,-0.31,-1.4e-05,-5.9e-05,2.1e-06,0.00017,-2.7e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.1e-05,9e-05,7.1e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.3e-10,1.3e-10,3.9e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21690000,0.98,-0.0038,-0.0083,0.19,-0.029,0.039,-1.1,-0.011,0.021,-0.42,-1.4e-05,-5.9e-05,2.2e-06,0.00017,-2.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,9.1e-05,9e-05,7e-05,0.025,0.025,0.0083,0.048,0.048,0.036,1.3e-10,1.3e-10,3.8e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21790000,0.98,-0.0041,-0.0085,0.19,-0.021,0.033,-1.3,-0.0036,0.018,-0.54,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.9e-05,8.8e-05,7e-05,0.023,0.023,0.0082,0.043,0.043,0.036,1.2e-10,1.2e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21890000,0.98,-0.0044,-0.0087,0.19,-0.017,0.028,-1.4,-0.0055,0.021,-0.68,-1.4e-05,-5.8e-05,2.3e-06,0.00018,-3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.9e-05,8.8e-05,7e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-10,1.2e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21990000,0.98,-0.0051,-0.0089,0.19,-0.014,0.023,-1.4,-0.00018,0.017,-0.82,-1.4e-05,-5.8e-05,2.4e-06,0.00017,-3e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.7e-05,8.6e-05,6.9e-05,0.022,0.022,0.0081,0.043,0.043,0.036,1.1e-10,1.1e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22090000,0.98,-0.0059,-0.0098,0.19,-0.011,0.019,-1.3,-0.0015,0.019,-0.96,-1.4e-05,-5.8e-05,2.6e-06,0.00018,-3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.7e-05,8.6e-05,6.9e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-10,1.1e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21890000,0.98,-0.0044,-0.0087,0.19,-0.017,0.028,-1.4,-0.0055,0.021,-0.68,-1.4e-05,-5.8e-05,2.3e-06,0.00018,-3.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.9e-05,8.8e-05,7e-05,0.025,0.025,0.0082,0.048,0.048,0.036,1.2e-10,1.2e-10,3.7e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
21990000,0.98,-0.0051,-0.0089,0.19,-0.014,0.023,-1.4,-0.00017,0.017,-0.82,-1.4e-05,-5.8e-05,2.4e-06,0.00017,-3.1e-05,-0.0014,0.2,0.002,0.43,0,0,0,0,0,2.6e-06,8.7e-05,8.6e-05,6.9e-05,0.022,0.022,0.0082,0.043,0.043,0.036,1.1e-10,1.1e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22090000,0.98,-0.0059,-0.0098,0.19,-0.011,0.019,-1.3,-0.0014,0.019,-0.96,-1.4e-05,-5.8e-05,2.6e-06,0.00018,-3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.7e-05,8.6e-05,6.9e-05,0.024,0.024,0.0082,0.048,0.048,0.036,1.1e-10,1.1e-10,3.6e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22190000,0.98,-0.0063,-0.01,0.19,-0.0031,0.013,-1.4,0.0062,0.013,-1.1,-1.4e-05,-5.8e-05,2.7e-06,0.00018,-3.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.5e-05,8.4e-05,6.9e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1.1e-10,1.1e-10,3.5e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22290000,0.98,-0.007,-0.01,0.19,0.002,0.0078,-1.4,0.0062,0.014,-1.2,-1.4e-05,-5.8e-05,2.6e-06,0.00018,-3.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.6e-05,8.4e-05,6.8e-05,0.023,0.023,0.0081,0.048,0.048,0.036,1.1e-10,1.1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22390000,0.98,-0.0074,-0.01,0.19,0.007,-0.0017,-1.4,0.013,0.0042,-1.4,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-3.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.4e-05,8.3e-05,6.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1e-10,1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22390000,0.98,-0.0074,-0.01,0.19,0.007,-0.0018,-1.4,0.013,0.0042,-1.4,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-3.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.4e-05,8.3e-05,6.8e-05,0.021,0.021,0.0081,0.043,0.043,0.036,1e-10,1e-10,3.4e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22490000,0.98,-0.0076,-0.011,0.19,0.011,-0.0077,-1.4,0.014,0.0037,-1.5,-1.4e-05,-5.8e-05,2.3e-06,0.00018,-3.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.4e-05,8.3e-05,6.8e-05,0.022,0.022,0.0081,0.047,0.047,0.036,1e-10,1e-10,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22590000,0.98,-0.0075,-0.012,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-3.9e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.2e-05,8.1e-05,6.7e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-11,9.4e-11,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22690000,0.98,-0.0074,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.8,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.3e-05,8.2e-05,6.7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-11,9.4e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22790000,0.98,-0.0074,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-1.4e-05,-5.8e-05,2.2e-06,0.00018,-4.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.1e-05,8e-05,6.7e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-11,8.9e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22590000,0.98,-0.0075,-0.012,0.19,0.02,-0.017,-1.4,0.026,-0.0053,-1.7,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.2e-05,8.1e-05,6.7e-05,0.02,0.02,0.0081,0.042,0.042,0.036,9.4e-11,9.4e-11,3.3e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22690000,0.98,-0.0074,-0.012,0.19,0.022,-0.021,-1.4,0.028,-0.0072,-1.8,-1.4e-05,-5.8e-05,2.4e-06,0.00018,-4.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.3e-05,8.2e-05,6.7e-05,0.021,0.021,0.0081,0.047,0.047,0.036,9.4e-11,9.4e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22790000,0.98,-0.0074,-0.012,0.19,0.028,-0.029,-1.4,0.038,-0.017,-2,-1.4e-05,-5.8e-05,2.2e-06,0.00019,-4.2e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.5e-06,8.1e-05,8e-05,6.7e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.9e-11,8.9e-11,3.2e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22890000,0.98,-0.0076,-0.013,0.19,0.032,-0.034,-1.4,0.041,-0.02,-2.1,-1.4e-05,-5.8e-05,2.4e-06,0.00019,-4.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8.1e-05,8e-05,6.6e-05,0.021,0.021,0.0081,0.047,0.047,0.036,8.9e-11,8.9e-11,3.1e-10,2.8e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22990000,0.98,-0.0075,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-1.4e-05,-5.8e-05,2.6e-06,0.00019,-4.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8e-05,7.9e-05,6.6e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-11,8.4e-11,3.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
22990000,0.98,-0.0075,-0.013,0.19,0.036,-0.04,-1.4,0.051,-0.031,-2.3,-1.4e-05,-5.8e-05,2.6e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8e-05,7.9e-05,6.6e-05,0.019,0.019,0.0081,0.042,0.042,0.036,8.4e-11,8.4e-11,3.1e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23090000,0.98,-0.0076,-0.013,0.19,0.041,-0.044,-1.4,0.055,-0.035,-2.4,-1.4e-05,-5.8e-05,2.6e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,8e-05,7.9e-05,6.6e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8.4e-11,8.4e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23190000,0.98,-0.0076,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.5,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.9e-05,7.8e-05,6.5e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-11,7.9e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23290000,0.98,-0.0081,-0.014,0.18,0.052,-0.051,-1.4,0.071,-0.05,-2.7,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.9e-05,7.8e-05,6.5e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8e-11,8e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23390000,0.98,-0.008,-0.014,0.18,0.057,-0.053,-1.4,0.082,-0.055,-2.8,-1.4e-05,-5.8e-05,2.3e-06,0.00019,-4.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.5e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-11,7.6e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23490000,0.98,-0.0081,-0.014,0.18,0.061,-0.055,-1.4,0.088,-0.061,-3,-1.4e-05,-5.8e-05,2.4e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.9e-05,7.8e-05,6.4e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-11,7.6e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23590000,0.98,-0.0083,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.1,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.4e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-11,7.2e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23690000,0.98,-0.009,-0.014,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-1.4e-05,-5.8e-05,2.6e-06,0.00019,-4.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.4e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-11,7.2e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23190000,0.98,-0.0076,-0.013,0.19,0.047,-0.046,-1.4,0.066,-0.045,-2.5,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.9e-05,7.8e-05,6.5e-05,0.018,0.018,0.008,0.042,0.042,0.035,7.9e-11,7.9e-11,3e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23290000,0.98,-0.0081,-0.014,0.19,0.052,-0.051,-1.4,0.071,-0.05,-2.7,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.4e-06,7.9e-05,7.8e-05,6.5e-05,0.02,0.02,0.0081,0.046,0.046,0.036,8e-11,8e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23390000,0.98,-0.008,-0.014,0.18,0.057,-0.053,-1.4,0.082,-0.055,-2.8,-1.4e-05,-5.8e-05,2.3e-06,0.00019,-4.5e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.5e-05,0.018,0.018,0.008,0.041,0.041,0.036,7.5e-11,7.6e-11,2.9e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23490000,0.98,-0.0081,-0.014,0.18,0.061,-0.055,-1.4,0.088,-0.061,-3,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.6e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.9e-05,7.8e-05,6.4e-05,0.019,0.019,0.0081,0.046,0.046,0.036,7.6e-11,7.6e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23590000,0.98,-0.0083,-0.014,0.18,0.064,-0.058,-1.4,0.095,-0.07,-3.1,-1.4e-05,-5.8e-05,2.5e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.4e-05,0.017,0.017,0.008,0.041,0.041,0.035,7.2e-11,7.2e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23690000,0.98,-0.009,-0.015,0.18,0.062,-0.061,-1.3,0.1,-0.076,-3.3,-1.4e-05,-5.8e-05,2.6e-06,0.00019,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.8e-05,7.7e-05,6.4e-05,0.018,0.018,0.0081,0.046,0.046,0.036,7.2e-11,7.2e-11,2.8e-10,2.7e-06,2.8e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23790000,0.98,-0.011,-0.017,0.18,0.057,-0.058,-0.95,0.11,-0.081,-3.4,-1.4e-05,-5.8e-05,2.8e-06,0.0002,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.016,0.016,0.008,0.041,0.041,0.035,6.9e-11,6.9e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23890000,0.98,-0.014,-0.021,0.18,0.052,-0.058,-0.52,0.12,-0.087,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.0002,-4.7e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-11,6.9e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23990000,0.98,-0.016,-0.024,0.18,0.054,-0.057,-0.14,0.13,-0.089,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.0002,-5.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-11,6.6e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24090000,0.98,-0.016,-0.023,0.18,0.06,-0.066,0.096,0.13,-0.095,-3.5,-1.4e-05,-5.8e-05,2.7e-06,0.0002,-5.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-11,6.6e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24190000,0.98,-0.013,-0.019,0.18,0.071,-0.071,0.083,0.14,-0.1,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.00021,-6.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.2e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-11,6.3e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24290000,0.98,-0.011,-0.016,0.18,0.075,-0.074,0.061,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.00021,-6.1e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.2e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-11,6.3e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24390000,0.98,-0.0097,-0.015,0.18,0.068,-0.069,0.077,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,2.9e-06,0.00021,-6.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.2e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-11,6.1e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24490000,0.98,-0.01,-0.015,0.18,0.064,-0.066,0.075,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00021,-6.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.016,0.016,0.0081,0.044,0.044,0.035,6.1e-11,6.1e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24590000,0.98,-0.011,-0.015,0.18,0.061,-0.061,0.07,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00021,-7.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-11,5.9e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24690000,0.98,-0.011,-0.015,0.18,0.058,-0.061,0.069,0.17,-0.12,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00021,-7.6e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-11,5.9e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24790000,0.98,-0.011,-0.014,0.18,0.055,-0.058,0.061,0.17,-0.11,-3.5,-1.5e-05,-5.8e-05,3.2e-06,0.00021,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-11,5.7e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24890000,0.98,-0.011,-0.014,0.18,0.054,-0.062,0.05,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00021,-8.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-11,5.7e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24990000,0.98,-0.011,-0.013,0.18,0.045,-0.057,0.042,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00021,-8.8e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-11,5.5e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25090000,0.98,-0.011,-0.013,0.18,0.041,-0.057,0.039,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.2e-06,0.00021,-8.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.6e-05,6e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-11,5.5e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.039,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.1e-06,0.00021,-9.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.6e-05,5.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-11,5.3e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25290000,0.98,-0.011,-0.013,0.18,0.032,-0.051,0.034,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,2.9e-06,0.00021,-9.4e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-11,5.3e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23890000,0.98,-0.014,-0.021,0.18,0.052,-0.058,-0.52,0.12,-0.087,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.0002,-4.8e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.017,0.017,0.008,0.045,0.045,0.035,6.9e-11,6.9e-11,2.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
23990000,0.98,-0.016,-0.024,0.18,0.054,-0.057,-0.14,0.13,-0.089,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.00021,-5.3e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.015,0.015,0.008,0.041,0.041,0.036,6.6e-11,6.6e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24090000,0.98,-0.016,-0.023,0.18,0.06,-0.066,0.097,0.13,-0.095,-3.5,-1.4e-05,-5.8e-05,2.7e-06,0.00021,-5.4e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.3e-05,0.016,0.016,0.0081,0.045,0.045,0.036,6.6e-11,6.6e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24190000,0.98,-0.013,-0.019,0.18,0.071,-0.071,0.083,0.14,-0.1,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.00021,-6.1e-05,-0.0013,0.2,0.002,0.43,0,0,0,0,0,2.3e-06,7.7e-05,7.6e-05,6.2e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.3e-11,6.3e-11,2.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24290000,0.98,-0.011,-0.016,0.18,0.075,-0.074,0.061,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,2.8e-06,0.00021,-6.2e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.2e-05,0.016,0.016,0.0081,0.044,0.044,0.036,6.3e-11,6.3e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24390000,0.98,-0.0097,-0.015,0.18,0.068,-0.069,0.077,0.15,-0.11,-3.5,-1.4e-05,-5.8e-05,3e-06,0.00022,-6.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.2e-05,0.015,0.015,0.008,0.04,0.04,0.035,6.1e-11,6.1e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24490000,0.98,-0.01,-0.015,0.18,0.064,-0.066,0.075,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00022,-7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.016,0.016,0.0081,0.044,0.044,0.035,6.1e-11,6.1e-11,2.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24590000,0.98,-0.011,-0.015,0.18,0.061,-0.061,0.07,0.16,-0.11,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00021,-7.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.015,0.015,0.008,0.04,0.04,0.036,5.9e-11,5.9e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24690000,0.98,-0.011,-0.015,0.18,0.058,-0.061,0.069,0.17,-0.12,-3.5,-1.4e-05,-5.8e-05,3.2e-06,0.00021,-7.7e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.016,0.016,0.0081,0.044,0.044,0.036,5.9e-11,5.9e-11,2.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24790000,0.98,-0.011,-0.014,0.18,0.055,-0.058,0.061,0.17,-0.11,-3.5,-1.5e-05,-5.8e-05,3.2e-06,0.00021,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6.1e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.7e-11,5.7e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24890000,0.98,-0.011,-0.014,0.18,0.054,-0.062,0.05,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00022,-8.3e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6e-05,0.016,0.016,0.008,0.043,0.043,0.035,5.7e-11,5.7e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
24990000,0.98,-0.011,-0.013,0.18,0.045,-0.057,0.042,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.3e-06,0.00021,-8.9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.7e-05,7.6e-05,6e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.5e-11,5.5e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25090000,0.98,-0.011,-0.013,0.18,0.041,-0.057,0.04,0.18,-0.12,-3.5,-1.5e-05,-5.8e-05,3.2e-06,0.00021,-9e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.6e-05,6e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.5e-11,5.5e-11,2.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25190000,0.98,-0.011,-0.013,0.18,0.037,-0.05,0.039,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3.1e-06,0.00021,-9.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.2e-06,7.8e-05,7.6e-05,5.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.3e-11,5.3e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25290000,0.98,-0.011,-0.013,0.18,0.032,-0.051,0.034,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,3e-06,0.00021,-9.5e-05,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.036,5.3e-11,5.3e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25390000,0.98,-0.011,-0.012,0.18,0.024,-0.044,0.032,0.18,-0.1,-3.5,-1.5e-05,-5.8e-05,2.9e-06,0.00021,-0.0001,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.9e-05,0.015,0.015,0.008,0.039,0.039,0.035,5.1e-11,5.1e-11,2.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25490000,0.98,-0.012,-0.012,0.18,0.019,-0.044,0.031,0.18,-0.11,-3.5,-1.5e-05,-5.8e-05,2.9e-06,0.00021,-0.0001,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.9e-05,0.016,0.016,0.0081,0.043,0.043,0.035,5.1e-11,5.1e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25590000,0.98,-0.012,-0.012,0.18,0.014,-0.04,0.032,0.18,-0.098,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00021,-0.0001,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-11,5e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25690000,0.98,-0.011,-0.012,0.18,0.013,-0.039,0.021,0.18,-0.1,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00021,-0.0001,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-11,5e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25790000,0.98,-0.011,-0.011,0.18,0.0018,-0.03,0.02,0.17,-0.092,-3.5,-1.6e-05,-5.8e-05,2.7e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-11,4.8e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25590000,0.98,-0.012,-0.012,0.18,0.014,-0.04,0.032,0.18,-0.098,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,5e-11,5e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25690000,0.98,-0.011,-0.012,0.18,0.013,-0.039,0.021,0.18,-0.1,-3.5,-1.5e-05,-5.8e-05,2.8e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.015,0.015,0.0081,0.043,0.043,0.035,5e-11,5e-11,2.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25790000,0.98,-0.011,-0.011,0.18,0.0018,-0.03,0.021,0.17,-0.092,-3.5,-1.6e-05,-5.8e-05,2.7e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.8e-11,4.8e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25890000,0.98,-0.011,-0.011,0.18,-0.004,-0.028,0.023,0.17,-0.095,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.8e-05,0.015,0.015,0.0081,0.043,0.043,0.036,4.8e-11,4.8e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25990000,0.98,-0.011,-0.011,0.18,-0.013,-0.021,0.016,0.16,-0.086,-3.5,-1.6e-05,-5.8e-05,2.4e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26090000,0.98,-0.011,-0.011,0.18,-0.018,-0.021,0.014,0.16,-0.088,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00021,-0.00011,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26190000,0.98,-0.011,-0.011,0.18,-0.024,-0.015,0.0095,0.15,-0.081,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26290000,0.98,-0.011,-0.012,0.18,-0.026,-0.013,0.0036,0.15,-0.082,-3.5,-1.6e-05,-5.8e-05,2.4e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
25990000,0.98,-0.011,-0.011,0.18,-0.013,-0.021,0.016,0.16,-0.086,-3.5,-1.6e-05,-5.8e-05,2.4e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.8e-05,7.7e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26090000,0.98,-0.011,-0.011,0.18,-0.018,-0.021,0.015,0.16,-0.088,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.7e-11,4.7e-11,2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26190000,0.98,-0.011,-0.012,0.18,-0.024,-0.015,0.0095,0.15,-0.081,-3.5,-1.6e-05,-5.8e-05,2.5e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2.1e-06,7.9e-05,7.7e-05,5.7e-05,0.014,0.014,0.008,0.039,0.039,0.035,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26290000,0.98,-0.011,-0.012,0.18,-0.026,-0.013,0.0037,0.15,-0.082,-3.5,-1.6e-05,-5.8e-05,2.4e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.7e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.6e-11,4.6e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26390000,0.98,-0.01,-0.012,0.18,-0.032,-0.0061,0.0075,0.13,-0.074,-3.5,-1.6e-05,-5.8e-05,2.3e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.7e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.4e-11,4.4e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26490000,0.98,-0.0098,-0.012,0.18,-0.035,-0.0029,0.017,0.13,-0.075,-3.5,-1.6e-05,-5.8e-05,2.2e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.5e-11,4.5e-11,1.9e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26590000,0.98,-0.0092,-0.012,0.18,-0.036,0.005,0.017,0.12,-0.068,-3.5,-1.6e-05,-5.8e-05,2.1e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26690000,0.98,-0.009,-0.012,0.18,-0.038,0.01,0.015,0.12,-0.067,-3.5,-1.6e-05,-5.8e-05,1.9e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26790000,0.98,-0.0088,-0.011,0.18,-0.045,0.014,0.014,0.1,-0.062,-3.5,-1.6e-05,-5.8e-05,1.8e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26890000,0.98,-0.0082,-0.011,0.18,-0.051,0.017,0.0095,0.1,-0.06,-3.5,-1.6e-05,-5.8e-05,1.8e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26990000,0.98,-0.0077,-0.012,0.18,-0.058,0.023,0.0085,0.087,-0.054,-3.5,-1.6e-05,-5.8e-05,1.7e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27090000,0.98,-0.0075,-0.012,0.18,-0.06,0.03,0.011,0.082,-0.051,-3.5,-1.6e-05,-5.8e-05,1.7e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-11,4.1e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27190000,0.98,-0.0076,-0.012,0.18,-0.066,0.036,0.013,0.071,-0.045,-3.5,-1.6e-05,-5.8e-05,1.6e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26690000,0.98,-0.0091,-0.012,0.18,-0.038,0.01,0.015,0.12,-0.067,-3.5,-1.6e-05,-5.8e-05,1.9e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.6e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.3e-11,4.3e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26790000,0.98,-0.0089,-0.011,0.18,-0.045,0.014,0.014,0.1,-0.062,-3.5,-1.6e-05,-5.8e-05,1.8e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26890000,0.98,-0.0082,-0.011,0.18,-0.051,0.017,0.0095,0.1,-0.06,-3.5,-1.6e-05,-5.8e-05,1.8e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.036,4.2e-11,4.2e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
26990000,0.98,-0.0077,-0.012,0.18,-0.058,0.023,0.0086,0.087,-0.054,-3.5,-1.6e-05,-5.8e-05,1.7e-06,0.00022,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4.1e-11,4.1e-11,1.8e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27090000,0.98,-0.0075,-0.012,0.18,-0.06,0.03,0.011,0.082,-0.051,-3.5,-1.6e-05,-5.8e-05,1.7e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4.1e-11,4.1e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27190000,0.98,-0.0076,-0.012,0.18,-0.066,0.036,0.013,0.071,-0.045,-3.5,-1.6e-05,-5.8e-05,1.6e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,2e-06,7.9e-05,7.8e-05,5.5e-05,0.014,0.014,0.008,0.038,0.038,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27290000,0.98,-0.0077,-0.013,0.18,-0.073,0.042,0.13,0.064,-0.041,-3.5,-1.6e-05,-5.8e-05,1.6e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,7.9e-05,7.8e-05,5.4e-05,0.015,0.015,0.0081,0.042,0.042,0.035,4e-11,4e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27390000,0.98,-0.0091,-0.015,0.18,-0.078,0.048,0.45,0.055,-0.034,-3.5,-1.6e-05,-5.8e-05,1.5e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,7.9e-05,7.8e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.7e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27490000,0.98,-0.01,-0.017,0.18,-0.082,0.053,0.76,0.046,-0.029,-3.4,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.8e-05,5.4e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27590000,0.98,-0.01,-0.016,0.18,-0.076,0.056,0.86,0.038,-0.025,-3.4,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.8e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27590000,0.98,-0.01,-0.016,0.18,-0.076,0.056,0.86,0.038,-0.025,-3.4,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00014,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.8e-05,5.4e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27690000,0.98,-0.0091,-0.013,0.18,-0.072,0.052,0.76,0.031,-0.02,-3.3,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00014,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.042,0.042,0.035,3.9e-11,3.9e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27790000,0.98,-0.0078,-0.012,0.18,-0.071,0.05,0.75,0.025,-0.017,-3.2,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.8e-11,3.8e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27890000,0.98,-0.0074,-0.012,0.18,-0.078,0.057,0.79,0.017,-0.012,-3.1,-1.6e-05,-5.8e-05,1.2e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.8e-11,3.8e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
27990000,0.98,-0.0079,-0.012,0.18,-0.078,0.058,0.78,0.012,-0.01,-3.1,-1.6e-05,-5.8e-05,1.2e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.7e-11,3.7e-11,1.6e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28090000,0.98,-0.0082,-0.012,0.18,-0.082,0.059,0.78,0.0041,-0.0044,-3,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28190000,0.98,-0.0076,-0.012,0.18,-0.082,0.056,0.79,-0.0024,-0.004,-2.9,-1.6e-05,-5.8e-05,1.2e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28090000,0.98,-0.0082,-0.012,0.18,-0.082,0.059,0.78,0.0041,-0.0044,-3,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.3e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28190000,0.98,-0.0076,-0.012,0.18,-0.082,0.056,0.79,-0.0024,-0.004,-2.9,-1.6e-05,-5.8e-05,1.2e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28290000,0.98,-0.0071,-0.013,0.18,-0.088,0.059,0.79,-0.011,0.0017,-2.8,-1.6e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8e-05,7.9e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.035,3.7e-11,3.7e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28390000,0.98,-0.0071,-0.013,0.18,-0.088,0.062,0.79,-0.015,0.0047,-2.8,-1.5e-05,-5.8e-05,1.3e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28390000,0.98,-0.0071,-0.013,0.18,-0.088,0.062,0.79,-0.015,0.0047,-2.8,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28490000,0.98,-0.0074,-0.014,0.18,-0.09,0.066,0.79,-0.024,0.011,-2.7,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.2e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.6e-11,3.6e-11,1.5e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28590000,0.98,-0.0075,-0.014,0.18,-0.083,0.061,0.79,-0.028,0.0087,-2.6,-1.5e-05,-5.8e-05,1.3e-06,0.00022,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28690000,0.98,-0.0072,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28590000,0.98,-0.0075,-0.014,0.18,-0.083,0.061,0.79,-0.028,0.0087,-2.6,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00012,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.9e-06,8.1e-05,7.9e-05,5.2e-05,0.013,0.013,0.008,0.038,0.038,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28690000,0.98,-0.0072,-0.013,0.18,-0.083,0.062,0.79,-0.036,0.015,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28790000,0.98,-0.0066,-0.013,0.18,-0.079,0.062,0.79,-0.038,0.017,-2.5,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28890000,0.98,-0.0064,-0.013,0.18,-0.084,0.064,0.79,-0.046,0.023,-2.4,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.5e-11,3.5e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28990000,0.98,-0.0062,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.3,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
28990000,0.98,-0.0062,-0.013,0.18,-0.079,0.06,0.78,-0.046,0.022,-2.3,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29090000,0.98,-0.006,-0.013,0.18,-0.082,0.063,0.78,-0.054,0.028,-2.3,-1.5e-05,-5.8e-05,1.3e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5.1e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29190000,0.98,-0.006,-0.013,0.18,-0.078,0.061,0.78,-0.051,0.027,-2.2,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0012,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.4e-11,3.4e-11,1.4e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29290000,0.98,-0.0062,-0.013,0.18,-0.08,0.067,0.78,-0.059,0.034,-2.1,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.4e-11,3.4e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29390000,0.98,-0.0067,-0.013,0.18,-0.075,0.066,0.78,-0.058,0.034,-2,-1.5e-05,-5.8e-05,1.4e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29490000,0.98,-0.0067,-0.012,0.18,-0.078,0.066,0.78,-0.065,0.041,-2,-1.5e-05,-5.8e-05,1.5e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.014,0.014,0.0081,0.041,0.041,0.036,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29590000,0.98,-0.0066,-0.012,0.18,-0.074,0.064,0.79,-0.062,0.04,-1.9,-1.5e-05,-5.8e-05,1.6e-06,0.00023,-0.00013,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29690000,0.98,-0.0066,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.047,-1.8,-1.5e-05,-5.8e-05,1.7e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29590000,0.98,-0.0066,-0.012,0.18,-0.074,0.064,0.79,-0.062,0.04,-1.9,-1.5e-05,-5.8e-05,1.6e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,5e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29690000,0.98,-0.0067,-0.012,0.18,-0.078,0.063,0.78,-0.07,0.047,-1.8,-1.5e-05,-5.8e-05,1.7e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.3e-11,3.3e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29790000,0.98,-0.0065,-0.013,0.18,-0.073,0.056,0.78,-0.065,0.044,-1.7,-1.4e-05,-5.8e-05,1.8e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29890000,0.98,-0.006,-0.013,0.18,-0.074,0.057,0.77,-0.072,0.049,-1.7,-1.4e-05,-5.8e-05,1.9e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.3e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29990000,0.98,-0.0061,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.045,-1.6,-1.4e-05,-5.8e-05,1.9e-06,0.00023,-0.00014,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30090000,0.98,-0.0063,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.5,-1.4e-05,-5.8e-05,1.7e-06,0.00023,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
29990000,0.98,-0.0061,-0.013,0.18,-0.069,0.052,0.77,-0.068,0.045,-1.6,-1.4e-05,-5.8e-05,1.9e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30090000,0.98,-0.0063,-0.013,0.18,-0.069,0.053,0.77,-0.075,0.05,-1.5,-1.4e-05,-5.8e-05,1.7e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.2e-05,8e-05,4.9e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.2e-11,3.2e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30190000,0.98,-0.0062,-0.013,0.18,-0.063,0.05,0.77,-0.068,0.048,-1.4,-1.4e-05,-5.7e-05,1.6e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.8e-06,8.1e-05,8e-05,4.9e-05,0.013,0.013,0.008,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30290000,0.98,-0.0063,-0.013,0.18,-0.062,0.05,0.77,-0.074,0.053,-1.4,-1.4e-05,-5.7e-05,1.6e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.2e-05,8e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30390000,0.98,-0.0063,-0.013,0.18,-0.055,0.044,0.76,-0.066,0.05,-1.3,-1.4e-05,-5.7e-05,1.8e-06,0.00024,-0.00015,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30390000,0.98,-0.0063,-0.013,0.18,-0.055,0.044,0.76,-0.066,0.05,-1.3,-1.4e-05,-5.7e-05,1.8e-06,0.00024,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30490000,0.98,-0.0063,-0.013,0.18,-0.057,0.044,0.77,-0.072,0.054,-1.2,-1.4e-05,-5.7e-05,1.8e-06,0.00024,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.014,0.014,0.008,0.041,0.041,0.036,3.1e-11,3.1e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30590000,0.98,-0.0066,-0.014,0.18,-0.053,0.041,0.77,-0.065,0.05,-1.2,-1.4e-05,-5.7e-05,1.9e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30690000,0.98,-0.007,-0.014,0.18,-0.051,0.04,0.76,-0.07,0.054,-1.1,-1.4e-05,-5.7e-05,1.9e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.041,0.041,0.035,3e-11,3e-11,1.2e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30790000,0.98,-0.0067,-0.014,0.18,-0.044,0.035,0.76,-0.063,0.052,-1,-1.4e-05,-5.7e-05,1.9e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30790000,0.98,-0.0067,-0.014,0.18,-0.044,0.035,0.76,-0.063,0.052,-1,-1.4e-05,-5.7e-05,2e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.8e-05,0.013,0.013,0.008,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30890000,0.98,-0.006,-0.013,0.18,-0.044,0.032,0.76,-0.067,0.056,-0.95,-1.4e-05,-5.7e-05,1.9e-06,0.00025,-0.00016,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30990000,0.98,-0.0062,-0.013,0.18,-0.036,0.026,0.76,-0.057,0.049,-0.88,-1.4e-05,-5.7e-05,1.9e-06,0.00025,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31090000,0.98,-0.0064,-0.014,0.18,-0.035,0.025,0.76,-0.061,0.051,-0.81,-1.4e-05,-5.7e-05,1.8e-06,0.00025,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31190000,0.98,-0.0065,-0.014,0.18,-0.031,0.02,0.76,-0.052,0.046,-0.74,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
30990000,0.98,-0.0062,-0.013,0.18,-0.036,0.026,0.76,-0.057,0.049,-0.88,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.0079,0.037,0.037,0.035,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31090000,0.98,-0.0064,-0.014,0.18,-0.035,0.025,0.76,-0.061,0.051,-0.81,-1.4e-05,-5.7e-05,1.8e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.036,3e-11,3e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31190000,0.98,-0.0066,-0.014,0.18,-0.031,0.02,0.76,-0.052,0.046,-0.74,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31290000,0.98,-0.0068,-0.014,0.18,-0.028,0.018,0.76,-0.055,0.048,-0.67,-1.4e-05,-5.7e-05,2e-06,0.00026,-0.00017,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.7e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31390000,0.98,-0.0066,-0.014,0.18,-0.022,0.012,0.76,-0.046,0.042,-0.6,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,7.9e-05,4.7e-05,0.013,0.013,0.0079,0.037,0.037,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31490000,0.98,-0.0063,-0.014,0.18,-0.022,0.0089,0.76,-0.048,0.043,-0.52,-1.4e-05,-5.7e-05,1.9e-06,0.00026,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,8e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1.1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
@@ -319,11 +319,11 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
||||
31690000,0.98,-0.0062,-0.015,0.18,-0.02,0.0055,0.76,-0.039,0.039,-0.38,-1.4e-05,-5.7e-05,2.1e-06,0.00027,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8.1e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.9e-11,2.9e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31790000,0.98,-0.0064,-0.015,0.18,-0.011,0.003,0.76,-0.028,0.037,-0.31,-1.4e-05,-5.7e-05,2.2e-06,0.00027,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31890000,0.98,-0.0061,-0.015,0.18,-0.0078,0.00068,0.76,-0.029,0.038,-0.24,-1.4e-05,-5.7e-05,2.2e-06,0.00027,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31990000,0.98,-0.0064,-0.015,0.18,0.00011,2.1e-05,0.75,-0.017,0.034,-0.18,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32090000,0.98,-0.0067,-0.014,0.18,-0.00042,-0.0034,0.76,-0.017,0.034,-0.1,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
31990000,0.98,-0.0064,-0.015,0.18,0.00012,1.8e-05,0.75,-0.017,0.034,-0.18,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.7e-06,8e-05,7.9e-05,4.6e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32090000,0.98,-0.0067,-0.014,0.18,-0.0004,-0.0034,0.76,-0.017,0.034,-0.1,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.6e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32190000,0.98,-0.0069,-0.015,0.18,0.0049,-0.0066,0.76,-0.0059,0.033,-0.037,-1.3e-05,-5.7e-05,2.1e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.5e-05,0.012,0.012,0.0079,0.037,0.037,0.035,2.8e-11,2.8e-11,1e-10,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32290000,0.98,-0.0068,-0.015,0.18,0.0065,-0.0093,0.75,-0.0054,0.032,0.031,-1.3e-05,-5.7e-05,2.2e-06,0.00028,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.5e-05,0.013,0.013,0.008,0.04,0.04,0.035,2.8e-11,2.8e-11,9.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32390000,0.98,-0.0069,-0.015,0.18,0.013,-0.011,0.75,0.0059,0.03,0.11,-1.3e-05,-5.7e-05,2.1e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.8e-05,4.5e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-11,2.7e-11,9.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32390000,0.98,-0.0069,-0.015,0.18,0.013,-0.011,0.75,0.0059,0.03,0.11,-1.3e-05,-5.7e-05,2.2e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.8e-05,4.5e-05,0.012,0.012,0.008,0.037,0.037,0.035,2.7e-11,2.7e-11,9.8e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32490000,0.98,-0.0098,-0.013,0.18,0.04,-0.074,-0.12,0.0091,0.023,0.11,-1.3e-05,-5.7e-05,2.1e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,8e-05,7.9e-05,4.5e-05,0.015,0.015,0.0078,0.04,0.04,0.035,2.8e-11,2.8e-11,9.7e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32590000,0.98,-0.0097,-0.013,0.18,0.04,-0.075,-0.12,0.021,0.02,0.09,-1.4e-05,-5.7e-05,2.2e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.9e-05,7.7e-05,4.5e-05,0.016,0.016,0.0075,0.037,0.037,0.035,2.7e-11,2.7e-11,9.6e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
32690000,0.98,-0.0097,-0.013,0.18,0.036,-0.081,-0.12,0.025,0.012,0.075,-1.4e-05,-5.7e-05,2.2e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,7.9e-05,7.8e-05,4.5e-05,0.019,0.019,0.0074,0.041,0.041,0.035,2.7e-11,2.7e-11,9.6e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
@@ -335,17 +335,17 @@ Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7
|
||||
33290000,0.98,-0.0088,-0.013,0.18,0.019,-0.081,-0.12,0.056,-0.019,0.0099,-1.4e-05,-5.6e-05,2.4e-06,0.00029,-0.00018,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6.7e-05,6.6e-05,4.4e-05,0.035,0.035,0.0063,0.043,0.043,0.034,2.6e-11,2.6e-11,9.1e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33390000,0.98,-0.0083,-0.013,0.18,0.014,-0.067,-0.12,0.059,-0.014,-0.0011,-1.4e-05,-5.6e-05,2.4e-06,0.00028,-0.00021,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6e-05,5.9e-05,4.4e-05,0.035,0.035,0.0062,0.039,0.039,0.034,2.6e-11,2.6e-11,9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33490000,0.98,-0.0083,-0.013,0.18,0.0097,-0.067,-0.12,0.061,-0.021,-0.015,-1.4e-05,-5.6e-05,2.4e-06,0.00028,-0.00021,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,6e-05,5.9e-05,4.4e-05,0.042,0.042,0.0061,0.044,0.044,0.034,2.6e-11,2.6e-11,8.9e-11,2.7e-06,2.7e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33590000,0.98,-0.0079,-0.013,0.18,0.0057,-0.058,-0.12,0.063,-0.017,-0.026,-1.4e-05,-5.6e-05,2.4e-06,0.00027,-0.00023,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,5.3e-05,5.2e-05,4.3e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-11,2.6e-11,8.8e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33690000,0.98,-0.0079,-0.013,0.18,0.001,-0.058,-0.12,0.063,-0.023,-0.038,-1.4e-05,-5.6e-05,2.4e-06,0.00027,-0.00023,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,5.3e-05,5.2e-05,4.3e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-11,2.6e-11,8.8e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33590000,0.98,-0.0079,-0.013,0.18,0.0057,-0.058,-0.12,0.063,-0.017,-0.026,-1.4e-05,-5.6e-05,2.4e-06,0.00028,-0.00023,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,5.3e-05,5.2e-05,4.3e-05,0.04,0.041,0.006,0.04,0.04,0.034,2.6e-11,2.6e-11,8.8e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33690000,0.98,-0.0079,-0.013,0.18,0.001,-0.058,-0.12,0.063,-0.023,-0.038,-1.4e-05,-5.6e-05,2.4e-06,0.00028,-0.00023,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,5.3e-05,5.2e-05,4.3e-05,0.048,0.048,0.0059,0.046,0.046,0.034,2.6e-11,2.6e-11,8.8e-11,2.6e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33790000,0.98,-0.0077,-0.013,0.18,-0.0022,-0.048,-0.11,0.067,-0.018,-0.048,-1.4e-05,-5.6e-05,2.4e-06,0.00026,-0.00026,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.6e-06,4.7e-05,4.6e-05,4.3e-05,0.044,0.045,0.0059,0.041,0.041,0.034,2.6e-11,2.6e-11,8.7e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33890000,0.98,-0.0077,-0.013,0.18,-0.0064,-0.045,-0.11,0.067,-0.023,-0.06,-1.4e-05,-5.6e-05,2.4e-06,0.00026,-0.00026,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,4.7e-05,4.6e-05,4.3e-05,0.052,0.052,0.0058,0.047,0.047,0.033,2.6e-11,2.6e-11,8.6e-11,2.5e-06,2.6e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
33990000,0.98,-0.0074,-0.013,0.18,-0.0061,-0.031,-0.11,0.07,-0.015,-0.069,-1.4e-05,-5.6e-05,2.4e-06,0.00024,-0.00029,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,4.1e-05,4.1e-05,4.3e-05,0.047,0.047,0.0058,0.042,0.042,0.033,2.6e-11,2.6e-11,8.6e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34090000,0.98,-0.0073,-0.013,0.18,-0.01,-0.031,-0.11,0.069,-0.018,-0.081,-1.4e-05,-5.6e-05,2.3e-06,0.00024,-0.00029,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,4.1e-05,4.1e-05,4.3e-05,0.054,0.054,0.0058,0.049,0.049,0.033,2.6e-11,2.6e-11,8.5e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34190000,0.98,-0.0073,-0.013,0.18,-0.011,-0.02,-0.11,0.072,-0.013,-0.091,-1.4e-05,-5.6e-05,2.3e-06,0.00022,-0.00031,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.7e-05,3.6e-05,4.3e-05,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-11,2.6e-11,8.4e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34090000,0.98,-0.0074,-0.013,0.18,-0.01,-0.031,-0.11,0.069,-0.018,-0.081,-1.4e-05,-5.6e-05,2.3e-06,0.00024,-0.00029,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,4.1e-05,4.1e-05,4.3e-05,0.054,0.054,0.0058,0.049,0.049,0.033,2.6e-11,2.6e-11,8.5e-11,2.5e-06,2.5e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34190000,0.98,-0.0073,-0.013,0.18,-0.011,-0.02,-0.11,0.072,-0.013,-0.091,-1.4e-05,-5.6e-05,2.4e-06,0.00022,-0.00031,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.7e-05,3.6e-05,4.3e-05,0.048,0.048,0.0058,0.043,0.043,0.033,2.6e-11,2.6e-11,8.4e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34290000,0.98,-0.0071,-0.013,0.18,-0.012,-0.02,-0.11,0.071,-0.015,-0.1,-1.4e-05,-5.6e-05,2.4e-06,0.00022,-0.00031,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.7e-05,3.6e-05,4.2e-05,0.054,0.055,0.0058,0.05,0.05,0.033,2.6e-11,2.6e-11,8.3e-11,2.4e-06,2.4e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34390000,0.98,-0.007,-0.013,0.18,-0.013,-0.01,-0.11,0.073,-0.01,-0.11,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.3e-05,3.3e-05,4.2e-05,0.047,0.047,0.0059,0.044,0.044,0.033,2.6e-11,2.6e-11,8.3e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34490000,0.98,-0.0071,-0.013,0.18,-0.016,-0.009,-0.11,0.071,-0.011,-0.12,-1.4e-05,-5.6e-05,2.4e-06,0.00021,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.3e-05,3.3e-05,4.2e-05,0.053,0.053,0.0059,0.051,0.051,0.032,2.6e-11,2.6e-11,8.2e-11,2.3e-06,2.3e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34590000,0.98,-0.007,-0.013,0.18,-0.015,-0.0045,0.69,0.073,-0.0087,-0.098,-1.4e-05,-5.6e-05,2.3e-06,0.00019,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.1e-05,3.1e-05,4.2e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-11,2.6e-11,8.2e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34690000,0.98,-0.007,-0.013,0.18,-0.018,-0.0021,1.7,0.071,-0.0091,0.02,-1.4e-05,-5.6e-05,2.3e-06,0.00019,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.1e-05,3.1e-05,4.2e-05,0.047,0.047,0.006,0.052,0.052,0.032,2.6e-11,2.6e-11,8.1e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34590000,0.98,-0.007,-0.013,0.18,-0.015,-0.0045,0.69,0.073,-0.0088,-0.098,-1.4e-05,-5.6e-05,2.3e-06,0.0002,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.1e-05,3.1e-05,4.2e-05,0.044,0.044,0.0059,0.045,0.045,0.032,2.6e-11,2.6e-11,8.2e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34690000,0.98,-0.007,-0.013,0.18,-0.018,-0.0021,1.7,0.071,-0.0091,0.02,-1.4e-05,-5.6e-05,2.3e-06,0.0002,-0.00032,-0.0011,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3.1e-05,3.1e-05,4.2e-05,0.047,0.047,0.006,0.052,0.052,0.032,2.6e-11,2.6e-11,8.1e-11,2.2e-06,2.2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34790000,0.98,-0.007,-0.012,0.18,-0.02,0.0026,2.6,0.072,-0.0068,0.2,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00034,-0.001,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,2.9e-05,2.9e-05,4.2e-05,0.04,0.04,0.0061,0.045,0.045,0.032,2.6e-11,2.6e-11,8e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
34890000,0.98,-0.007,-0.012,0.18,-0.024,0.0053,3.6,0.07,-0.0062,0.49,-1.4e-05,-5.6e-05,2.3e-06,0.00021,-0.00034,-0.001,0.2,0.002,0.43,0,0,0,0,0,1.5e-06,3e-05,2.9e-05,4.2e-05,0.043,0.043,0.0061,0.052,0.052,0.032,2.6e-11,2.6e-11,8e-11,2e-06,2e-06,5e-08,0,0,0,0,0,0,0,0
|
||||
|
||||
|
@@ -0,0 +1,185 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (C) 2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#include <gtest/gtest.h>
|
||||
#include "EKF/ekf.h"
|
||||
#include "test_helper/comparison_helper.h"
|
||||
|
||||
#include "../EKF/python/ekf_derivation/generated/compute_mag_declination_innov_innov_var_and_h.h"
|
||||
|
||||
using namespace matrix;
|
||||
|
||||
TEST(MagDeclinationGenerated, declination90deg)
|
||||
{
|
||||
// GIVEN: an estimated mag declination of 90 degrees
|
||||
Vector24f state_vector{};
|
||||
state_vector(16) = 0.f; // North mag field
|
||||
state_vector(17) = 0.2f; // East mag field
|
||||
|
||||
const float R = sq(radians(sq(0.5f)));
|
||||
SquareMatrix24f P = createRandomCovarianceMatrix24f();
|
||||
|
||||
Vector24f H;
|
||||
float innov;
|
||||
float innov_var;
|
||||
|
||||
const float decl = radians(90.f);
|
||||
sym::ComputeMagDeclinationInnovInnovVarAndH(state_vector, P, decl, R, FLT_EPSILON, &innov, &innov_var, &H);
|
||||
|
||||
// THEN: Even at the singularity point, atan2 is still defined
|
||||
EXPECT_TRUE(innov_var < 5000.f && innov_var > R) << "innov_var = " << innov_var;
|
||||
EXPECT_LT(fabsf(innov), 1e-6f);
|
||||
}
|
||||
|
||||
TEST(MagDeclinationGenerated, declinationUndefined)
|
||||
{
|
||||
// GIVEN: an undefined declination
|
||||
Vector24f state_vector{};
|
||||
state_vector(16) = 0.f; // North mag field
|
||||
state_vector(17) = 0.f; // East mag field
|
||||
|
||||
const float R = sq(radians(sq(0.5f)));
|
||||
SquareMatrix24f P = createRandomCovarianceMatrix24f();
|
||||
|
||||
Vector24f H;
|
||||
float innov;
|
||||
float innov_var;
|
||||
|
||||
const float decl = radians(0.f);
|
||||
sym::ComputeMagDeclinationInnovInnovVarAndH(state_vector, P, decl, R, FLT_EPSILON, &innov, &innov_var, &H);
|
||||
|
||||
// THEN: the innovation variance is gigantic but finite
|
||||
EXPECT_TRUE(PX4_ISFINITE(innov_var) && innov_var > R && innov_var > 1e9f) << "innov_var = " << innov_var;
|
||||
EXPECT_LT(fabsf(innov), 1e-6f);
|
||||
}
|
||||
|
||||
void sympyMagDeclInnovVarHAndK(float magN, float magE, const SquareMatrix24f &P, float R_DECL,
|
||||
float &innovation_variance, Vector24f &H, Vector24f &Kfusion)
|
||||
{
|
||||
const float h_field_min = 1e-3f;
|
||||
const float magN_sq = sq(magN);
|
||||
|
||||
if (magN_sq < sq(h_field_min)) {
|
||||
printf("bad numerical conditioning\n");
|
||||
return;
|
||||
}
|
||||
|
||||
const float HK0 = 1.0F / magN_sq;
|
||||
const float HK1 = HK0 * sq(magE) + 1.0F;
|
||||
const float HK2 = 1.0F / HK1;
|
||||
const float HK3 = 1.0F / magN;
|
||||
const float HK4 = HK2 * HK3;
|
||||
const float HK5 = HK3 * magE;
|
||||
const float HK6 = HK5 * P(16, 17) - P(17, 17);
|
||||
const float HK7 = 1.0F / sq(HK1);
|
||||
const float HK8 = HK5 * P(16, 16) - P(16, 17);
|
||||
innovation_variance = -HK0 * HK6 * HK7 + HK7 * HK8 * magE / (magN * magN_sq) + R_DECL;
|
||||
float HK9;
|
||||
|
||||
if (innovation_variance > R_DECL) {
|
||||
HK9 = HK4 / innovation_variance;
|
||||
|
||||
} else {
|
||||
printf("bad numerical conditioning\n");
|
||||
return;
|
||||
}
|
||||
|
||||
// Calculate the observation Jacobian
|
||||
// Note only 2 terms are non-zero which can be used in matrix operations for calculation of Kalman gains and covariance update to significantly reduce cost
|
||||
float Hfusion[24] = {};
|
||||
Hfusion[16] = -HK0 * HK2 * magE;
|
||||
Hfusion[17] = HK4;
|
||||
|
||||
// Calculate the Kalman gains
|
||||
for (unsigned row = 0; row <= 15; row++) {
|
||||
Kfusion(row) = -HK9 * (HK5 * P(row, 16) - P(row, 17));
|
||||
}
|
||||
|
||||
Kfusion(16) = -HK8 * HK9;
|
||||
Kfusion(17) = -HK6 * HK9;
|
||||
|
||||
for (unsigned row = 18; row <= 23; row++) {
|
||||
Kfusion(row) = -HK9 * (HK5 * P(16, row) - P(17, row));
|
||||
}
|
||||
|
||||
for (int row = 0; row < 24; row++) {
|
||||
H(row) = Hfusion[row];
|
||||
}
|
||||
}
|
||||
|
||||
TEST(MagDeclinationGenerated, SympyVsSymforce)
|
||||
{
|
||||
const float R_DECL = sq(0.3f);
|
||||
const float mag_n = 0.08f;
|
||||
const float mag_e = -0.06f;
|
||||
|
||||
Vector24f state_vector{};
|
||||
state_vector(16) = mag_n;
|
||||
state_vector(17) = mag_e;
|
||||
|
||||
const float decl = M_PI_F;
|
||||
|
||||
SquareMatrix24f P = createRandomCovarianceMatrix24f();
|
||||
|
||||
Vector24f H_sympy;
|
||||
Vector24f H_symforce;
|
||||
Vector24f K_sympy;
|
||||
Vector24f K_symforce;
|
||||
float innov_sympy;
|
||||
float innov_symforce;
|
||||
float innov_var_sympy;
|
||||
float innov_var_symforce;
|
||||
|
||||
sympyMagDeclInnovVarHAndK(mag_n, mag_e, P, R_DECL, innov_var_sympy, H_sympy, K_sympy);
|
||||
innov_sympy = std::atan2(mag_e, mag_n) - decl;
|
||||
sym::ComputeMagDeclinationInnovInnovVarAndH(state_vector, P, decl, R_DECL, FLT_EPSILON, &innov_symforce,
|
||||
&innov_var_symforce, &H_symforce);
|
||||
K_symforce = P * H_symforce / innov_var_symforce;
|
||||
|
||||
EXPECT_NEAR(innov_sympy, innov_symforce, 1e-5f);
|
||||
EXPECT_NEAR(innov_var_sympy, innov_var_symforce, 1e-2f); // Slightly different because of epsilon
|
||||
|
||||
DiffRatioReport report = computeDiffRatioVector24f(H_sympy, H_symforce);
|
||||
EXPECT_LT(report.max_diff_fraction, 2e-4f)
|
||||
<< "Max diff fraction = " << report.max_diff_fraction
|
||||
<< " location index = " << report.max_row
|
||||
<< " sympy = " << report.max_v1
|
||||
<< " symforce = " << report.max_v2;
|
||||
|
||||
report = computeDiffRatioVector24f(K_sympy, K_symforce);
|
||||
EXPECT_LT(report.max_diff_fraction, 2e-4f)
|
||||
<< "Max diff fraction = " << report.max_diff_fraction
|
||||
<< " location index = " << report.max_row
|
||||
<< " sympy = " << report.max_v1
|
||||
<< " symforce = " << report.max_v2;
|
||||
}
|
||||
@@ -500,7 +500,6 @@ PARAM_DEFINE_FLOAT(FW_MAN_P_MAX, 30.0f);
|
||||
* Flaps setting during take-off
|
||||
*
|
||||
* Sets a fraction of full flaps during take-off.
|
||||
* Also applies to flaperons if enabled in the mixer/allocation.
|
||||
*
|
||||
* @unit norm
|
||||
* @min 0.0
|
||||
@@ -515,7 +514,6 @@ PARAM_DEFINE_FLOAT(FW_FLAPS_TO_SCL, 0.0f);
|
||||
* Flaps setting during landing
|
||||
*
|
||||
* Sets a fraction of full flaps during landing.
|
||||
* Also applies to flaperons if enabled in the mixer/allocation.
|
||||
*
|
||||
* @unit norm
|
||||
* @min 0.0
|
||||
|
||||
@@ -231,7 +231,7 @@ FixedwingPositionControl::vehicle_command_poll()
|
||||
if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_DO_GO_AROUND) {
|
||||
// only abort landing before point of no return (horizontal and vertical)
|
||||
if (_control_mode.flag_control_auto_enabled &&
|
||||
_pos_sp_triplet.current.valid &&
|
||||
_position_setpoint_current_valid &&
|
||||
(_pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_LAND)) {
|
||||
|
||||
updateLandingAbortStatus(position_controller_landing_status_s::ABORTED_BY_OPERATOR);
|
||||
@@ -683,11 +683,9 @@ FixedwingPositionControl::get_waypoint_heading_distance(float heading, position_
|
||||
|
||||
waypoint_prev = temp_prev;
|
||||
waypoint_prev.alt = _current_altitude;
|
||||
waypoint_prev.valid = true;
|
||||
|
||||
waypoint_next = temp_next;
|
||||
waypoint_next.alt = _current_altitude;
|
||||
waypoint_next.valid = true;
|
||||
}
|
||||
|
||||
float
|
||||
@@ -743,7 +741,7 @@ FixedwingPositionControl::updateManualTakeoffStatus()
|
||||
}
|
||||
|
||||
void
|
||||
FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now, bool pos_sp_curr_valid)
|
||||
FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now)
|
||||
{
|
||||
/* only run position controller in fixed-wing mode and during transitions for VTOL */
|
||||
if (_vehicle_status.vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING && !_vehicle_status.in_transition_mode) {
|
||||
@@ -756,7 +754,7 @@ FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now, bool
|
||||
_skipping_takeoff_detection = false;
|
||||
|
||||
if (((_control_mode.flag_control_auto_enabled && _control_mode.flag_control_position_enabled) ||
|
||||
_control_mode.flag_control_offboard_enabled) && pos_sp_curr_valid) {
|
||||
_control_mode.flag_control_offboard_enabled) && _position_setpoint_current_valid) {
|
||||
|
||||
if (_pos_sp_triplet.current.type == position_setpoint_s::SETPOINT_TYPE_TAKEOFF) {
|
||||
|
||||
@@ -791,12 +789,16 @@ FixedwingPositionControl::set_control_mode_current(const hrt_abstime &now, bool
|
||||
_control_mode_current = FW_POSCTRL_MODE_AUTO;
|
||||
}
|
||||
|
||||
} else if (_control_mode.flag_control_auto_enabled && _control_mode.flag_control_climb_rate_enabled
|
||||
&& pos_sp_curr_valid) {
|
||||
} else if (_control_mode.flag_control_auto_enabled
|
||||
&& _control_mode.flag_control_climb_rate_enabled
|
||||
&& _control_mode.flag_armed // only enter this modes if armed, as pure failsafe modes
|
||||
&& !_control_mode.flag_control_position_enabled) {
|
||||
|
||||
// failsafe modes engaged if position estimate is invalidated
|
||||
|
||||
// reset timer the first time we switch into this mode
|
||||
if (commanded_position_control_mode != FW_POSCTRL_MODE_AUTO_ALTITUDE
|
||||
&& commanded_position_control_mode != FW_POSCTRL_MODE_AUTO_CLIMBRATE) {
|
||||
// reset timer the first time we switch into this mode
|
||||
_time_in_fixed_bank_loiter = now;
|
||||
}
|
||||
|
||||
@@ -1089,7 +1091,7 @@ FixedwingPositionControl::control_auto_position(const float control_interval, co
|
||||
/* current waypoint (the one currently heading for) */
|
||||
curr_wp = Vector2d(pos_sp_curr.lat, pos_sp_curr.lon);
|
||||
|
||||
if (pos_sp_prev.valid && pos_sp_prev.type != position_setpoint_s::SETPOINT_TYPE_TAKEOFF) {
|
||||
if (_position_setpoint_previous_valid && pos_sp_prev.type != position_setpoint_s::SETPOINT_TYPE_TAKEOFF) {
|
||||
prev_wp(0) = pos_sp_prev.lat;
|
||||
prev_wp(1) = pos_sp_prev.lon;
|
||||
|
||||
@@ -1118,7 +1120,7 @@ FixedwingPositionControl::control_auto_position(const float control_interval, co
|
||||
float position_sp_alt = pos_sp_curr.alt;
|
||||
|
||||
// Altitude first order hold (FOH)
|
||||
if (pos_sp_prev.valid && PX4_ISFINITE(pos_sp_prev.alt) &&
|
||||
if (_position_setpoint_previous_valid &&
|
||||
((pos_sp_prev.type == position_setpoint_s::SETPOINT_TYPE_POSITION) ||
|
||||
(pos_sp_prev.type == position_setpoint_s::SETPOINT_TYPE_LOITER))
|
||||
) {
|
||||
@@ -1268,7 +1270,7 @@ FixedwingPositionControl::control_auto_loiter(const float control_interval, cons
|
||||
/* current waypoint (the one currently heading for) */
|
||||
curr_wp = Vector2d(pos_sp_curr.lat, pos_sp_curr.lon);
|
||||
|
||||
if (pos_sp_prev.valid && pos_sp_prev.type != position_setpoint_s::SETPOINT_TYPE_TAKEOFF) {
|
||||
if (_position_setpoint_previous_valid && pos_sp_prev.type != position_setpoint_s::SETPOINT_TYPE_TAKEOFF) {
|
||||
prev_wp(0) = pos_sp_prev.lat;
|
||||
prev_wp(1) = pos_sp_prev.lon;
|
||||
|
||||
@@ -1310,7 +1312,7 @@ FixedwingPositionControl::control_auto_loiter(const float control_interval, cons
|
||||
|
||||
const bool in_circle_mode = (_param_fw_use_npfg.get()) ? _npfg.circleMode() : _l1_control.circle_mode();
|
||||
|
||||
if (pos_sp_next.type == position_setpoint_s::SETPOINT_TYPE_LAND && pos_sp_next.valid
|
||||
if (pos_sp_next.type == position_setpoint_s::SETPOINT_TYPE_LAND && _position_setpoint_next_valid
|
||||
&& in_circle_mode && _param_fw_lnd_earlycfg.get()) {
|
||||
// We're in a loiter directly before a landing WP. Enable our landing configuration (flaps,
|
||||
// landing airspeed and potentially tighter altitude control) already such that we don't
|
||||
@@ -2183,6 +2185,19 @@ FixedwingPositionControl::Run()
|
||||
|
||||
} else {
|
||||
if (_pos_sp_triplet_sub.update(&_pos_sp_triplet)) {
|
||||
|
||||
_position_setpoint_previous_valid = PX4_ISFINITE(_pos_sp_triplet.previous.lat)
|
||||
&& PX4_ISFINITE(_pos_sp_triplet.previous.lon)
|
||||
&& PX4_ISFINITE(_pos_sp_triplet.previous.alt);
|
||||
|
||||
_position_setpoint_current_valid = PX4_ISFINITE(_pos_sp_triplet.current.lat)
|
||||
&& PX4_ISFINITE(_pos_sp_triplet.current.lon)
|
||||
&& PX4_ISFINITE(_pos_sp_triplet.current.alt);
|
||||
|
||||
_position_setpoint_next_valid = PX4_ISFINITE(_pos_sp_triplet.next.lat)
|
||||
&& PX4_ISFINITE(_pos_sp_triplet.next.lon)
|
||||
&& PX4_ISFINITE(_pos_sp_triplet.next.alt);
|
||||
|
||||
// reset the altitude foh (first order hold) logic
|
||||
_min_current_sp_distance_xy = FLT_MAX;
|
||||
}
|
||||
@@ -2214,7 +2229,7 @@ FixedwingPositionControl::Run()
|
||||
Vector2d curr_pos(_current_latitude, _current_longitude);
|
||||
Vector2f ground_speed(_local_pos.vx, _local_pos.vy);
|
||||
|
||||
set_control_mode_current(_local_pos.timestamp, _pos_sp_triplet.current.valid);
|
||||
set_control_mode_current(_local_pos.timestamp);
|
||||
|
||||
update_in_air_states(_local_pos.timestamp);
|
||||
|
||||
@@ -2563,7 +2578,7 @@ FixedwingPositionControl::initializeAutoLanding(const hrt_abstime &now, const po
|
||||
// set the landing approach entrance location when we have just started the landing and store it
|
||||
// NOTE: the landing approach vector is relative to the land point. ekf resets may cause a local frame
|
||||
// jump, so we reference to the land point, which is globally referenced and will update
|
||||
if (pos_sp_prev.valid) {
|
||||
if (_position_setpoint_previous_valid) {
|
||||
height_above_land_point = pos_sp_prev.alt - pos_sp_curr.alt;
|
||||
local_approach_entrance = _global_local_proj_ref.project(pos_sp_prev.lat, pos_sp_prev.lon);
|
||||
|
||||
|
||||
@@ -222,6 +222,10 @@ private:
|
||||
vehicle_local_position_s _local_pos{};
|
||||
vehicle_status_s _vehicle_status{};
|
||||
|
||||
bool _position_setpoint_previous_valid{false};
|
||||
bool _position_setpoint_current_valid{false};
|
||||
bool _position_setpoint_next_valid{false};
|
||||
|
||||
perf_counter_t _loop_perf; // loop performance counter
|
||||
|
||||
// [us] Last absolute time position control has been called
|
||||
@@ -664,9 +668,8 @@ private:
|
||||
* May also change the position setpoint type depending on the desired behavior.
|
||||
*
|
||||
* @param now Current system time [us]
|
||||
* @param pos_sp_curr_valid True if the current position setpoint is valid
|
||||
*/
|
||||
void set_control_mode_current(const hrt_abstime &now, bool pos_sp_curr_valid);
|
||||
void set_control_mode_current(const hrt_abstime &now);
|
||||
|
||||
/**
|
||||
* @brief Compensate trim throttle for air density and vehicle weight.
|
||||
|
||||
@@ -60,6 +60,31 @@ add_library(mavlink_c INTERFACE)
|
||||
target_sources(mavlink_c INTERFACE ${MAVLINK_LIBRARY_DIR}/${CONFIG_MAVLINK_DIALECT}/${CONFIG_MAVLINK_DIALECT}.h)
|
||||
set_source_files_properties(${MAVLINK_LIBRARY_DIR}/${CONFIG_MAVLINK_DIALECT}/${CONFIG_MAVLINK_DIALECT}.h PROPERTIES GENERATED true)
|
||||
target_include_directories(mavlink_c INTERFACE ${MAVLINK_LIBRARY_DIR} ${MAVLINK_LIBRARY_DIR}/${CONFIG_MAVLINK_DIALECT})
|
||||
|
||||
set(MAVLINK_DIALECT_UAVIONIX "uAvionix")
|
||||
|
||||
add_custom_command(
|
||||
OUTPUT ${MAVLINK_LIBRARY_DIR}/${MAVLINK_DIALECT_UAVIONIX}/${MAVLINK_DIALECT_UAVIONIX}.h
|
||||
COMMAND
|
||||
${PYTHON_EXECUTABLE} ${MAVLINK_GIT_DIR}/pymavlink/tools/mavgen.py
|
||||
--lang C --wire-protocol 2.0
|
||||
#--no-validate
|
||||
#--strict-units
|
||||
--output ${MAVLINK_LIBRARY_DIR}
|
||||
${MAVLINK_GIT_DIR}/message_definitions/v1.0/${MAVLINK_DIALECT_UAVIONIX}.xml
|
||||
DEPENDS
|
||||
git_mavlink_v2
|
||||
${MAVLINK_GIT_DIR}/pymavlink/tools/mavgen.py
|
||||
${MAVLINK_GIT_DIR}/message_definitions/v1.0/${MAVLINK_DIALECT_UAVIONIX}.xml
|
||||
COMMENT "Generating Mavlink ${MAVLINK_DIALECT_UAVIONIX}: ${MAVLINK_GIT_DIR_RELATIVE}/message_definitions/v1.0/${MAVLINK_DIALECT_UAVIONIX}.xml"
|
||||
USES_TERMINAL
|
||||
)
|
||||
|
||||
add_custom_target(mavlink_c_generate_uavionix DEPENDS ${MAVLINK_LIBRARY_DIR}/${MAVLINK_DIALECT_UAVIONIX}/${MAVLINK_DIALECT_UAVIONIX}.h)
|
||||
target_sources(mavlink_c INTERFACE ${MAVLINK_LIBRARY_DIR}/${MAVLINK_DIALECT_UAVIONIX}/${MAVLINK_DIALECT_UAVIONIX}.h)
|
||||
set_source_files_properties(${MAVLINK_LIBRARY_DIR}/${MAVLINK_DIALECT_UAVIONIX}/${MAVLINK_DIALECT_UAVIONIX}.h PROPERTIES GENERATED true)
|
||||
target_include_directories(mavlink_c INTERFACE ${MAVLINK_LIBRARY_DIR} ${MAVLINK_LIBRARY_DIR}/${MAVLINK_DIALECT_UAVIONIX})
|
||||
|
||||
target_compile_options(mavlink_c INTERFACE -Wno-address-of-packed-member -Wno-cast-align)
|
||||
|
||||
|
||||
@@ -91,6 +116,7 @@ px4_add_module(
|
||||
MODULE_CONFIG
|
||||
module.yaml
|
||||
DEPENDS
|
||||
adsb
|
||||
airspeed
|
||||
component_general_json # for checksums.h
|
||||
drivers_accelerometer
|
||||
@@ -114,6 +140,7 @@ px4_add_unit_gtest(SRC MavlinkStatustextHandlerTest.cpp
|
||||
INCLUDES
|
||||
${MAVLINK_LIBRARY_DIR}
|
||||
${MAVLINK_LIBRARY_DIR}/${CONFIG_MAVLINK_DIALECT}
|
||||
${MAVLINK_LIBRARY_DIR}/${MAVLINK_DIALECT_UAVIONIX}
|
||||
COMPILE_FLAGS
|
||||
-Wno-address-of-packed-member # TODO: fix in c_library_v2
|
||||
-Wno-cast-align # TODO: fix
|
||||
|
||||
@@ -93,6 +93,9 @@ extern mavlink_status_t *mavlink_get_channel_status(uint8_t chan);
|
||||
extern mavlink_message_t *mavlink_get_channel_buffer(uint8_t chan);
|
||||
|
||||
#include <mavlink.h>
|
||||
#if !MAVLINK_FTP_UNIT_TEST
|
||||
#include <uAvionix.h>
|
||||
#endif
|
||||
|
||||
__END_DECLS
|
||||
|
||||
|
||||
@@ -1833,6 +1833,11 @@ Mavlink::configure_streams_to_default(const char *configure_single_stream)
|
||||
#endif // !CONSTRAINED_FLASH
|
||||
break;
|
||||
|
||||
case MAVLINK_MODE_UAVIONIX:
|
||||
configure_stream_local("UAVIONIX_ADSB_OUT_CFG", 0.1f);
|
||||
configure_stream_local("UAVIONIX_ADSB_OUT_DYNAMIC", 5.0f);
|
||||
break;
|
||||
|
||||
default:
|
||||
ret = -1;
|
||||
break;
|
||||
@@ -2046,6 +2051,9 @@ Mavlink::task_main(int argc, char *argv[])
|
||||
} else if (strcmp(myoptarg, "onboard_low_bandwidth") == 0) {
|
||||
_mode = MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH;
|
||||
|
||||
} else if (strcmp(myoptarg, "uavionix") == 0) {
|
||||
_mode = MAVLINK_MODE_UAVIONIX;
|
||||
|
||||
} else {
|
||||
PX4_ERR("invalid mode");
|
||||
err_flag = true;
|
||||
@@ -3307,7 +3315,7 @@ $ mavlink stream -u 14556 -s HIGHRES_IMU -r 50
|
||||
PRINT_MODULE_USAGE_PARAM_INT('o', 14550, 0, 65536, "Select UDP Network Port (remote)", true);
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('t', "127.0.0.1", nullptr, "Partner IP (broadcasting can be enabled via -p flag)", true);
|
||||
#endif
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('m', "normal", "custom|camera|onboard|osd|magic|config|iridium|minimal|extvision|extvisionmin|gimbal",
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('m', "normal", "custom|camera|onboard|osd|magic|config|iridium|minimal|extvision|extvisionmin|gimbal|uavionix",
|
||||
"Mode: sets default streams and rates", true);
|
||||
PRINT_MODULE_USAGE_PARAM_STRING('n', nullptr, "<interface_name>", "wifi/ethernet interface name", true);
|
||||
#if defined(CONFIG_NET_IGMP) && defined(CONFIG_NET_ROUTE)
|
||||
|
||||
@@ -210,6 +210,7 @@ public:
|
||||
MAVLINK_MODE_EXTVISIONMIN,
|
||||
MAVLINK_MODE_GIMBAL,
|
||||
MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH,
|
||||
MAVLINK_MODE_UAVIONIX,
|
||||
MAVLINK_MODE_COUNT
|
||||
};
|
||||
|
||||
@@ -264,6 +265,9 @@ public:
|
||||
case MAVLINK_MODE_ONBOARD_LOW_BANDWIDTH:
|
||||
return "OnboardLowBandwidth";
|
||||
|
||||
case MAVLINK_MODE_UAVIONIX:
|
||||
return "uAvionix";
|
||||
|
||||
default:
|
||||
return "Unknown";
|
||||
}
|
||||
|
||||
@@ -139,6 +139,8 @@
|
||||
# include "streams/SCALED_PRESSURE2.hpp"
|
||||
# include "streams/SCALED_PRESSURE3.hpp"
|
||||
# include "streams/SMART_BATTERY_INFO.hpp"
|
||||
# include "streams/UAVIONIX_ADSB_OUT_CFG.hpp"
|
||||
# include "streams/UAVIONIX_ADSB_OUT_DYNAMIC.hpp"
|
||||
# include "streams/UTM_GLOBAL_POSITION.hpp"
|
||||
#endif // !CONSTRAINED_FLASH
|
||||
|
||||
@@ -474,8 +476,14 @@ static const StreamListItem streams_list[] = {
|
||||
create_stream_list_item<MavlinkStreamEfiStatus>(),
|
||||
#endif // EFI_STATUS_HPP
|
||||
#if defined(GPS_RTCM_DATA_HPP)
|
||||
create_stream_list_item<MavlinkStreamGPSRTCMData>()
|
||||
create_stream_list_item<MavlinkStreamGPSRTCMData>(),
|
||||
#endif // GPS_RTCM_DATA_HPP
|
||||
#if defined(UAVIONIX_ADSB_OUT_CFG_HPP)
|
||||
create_stream_list_item<MavlinkStreamUavionixADSBOutCfg>(),
|
||||
#endif // UAVIONIX_ADSB_OUT_CFG_HPP
|
||||
#if defined(UAVIONIX_ADSB_OUT_DYNAMIC_HPP)
|
||||
create_stream_list_item<MavlinkStreamUavionixADSBOutDynamic>()
|
||||
#endif // UAVIONIX_ADSB_OUT_DYNAMIC_HPP
|
||||
};
|
||||
|
||||
const char *get_stream_name(const uint16_t msg_id)
|
||||
|
||||
@@ -68,6 +68,7 @@ parameters:
|
||||
#9: External Vision Minimal # hidden
|
||||
10: Gimbal
|
||||
11: Onboard Low Bandwidth
|
||||
12: uAvionix
|
||||
reboot_required: true
|
||||
num_instances: *max_num_config_instances
|
||||
default: [0, 2, 0]
|
||||
|
||||
@@ -0,0 +1,103 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef UAVIONIX_ADSB_OUT_CFG_HPP
|
||||
#define UAVIONIX_ADSB_OUT_CFG_HPP
|
||||
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
|
||||
class MavlinkStreamUavionixADSBOutCfg : public ModuleParams, public MavlinkStream
|
||||
{
|
||||
public:
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamUavionixADSBOutCfg(mavlink); }
|
||||
|
||||
static constexpr const char *get_name_static() { return "UAVIONIX_ADSB_OUT_CFG"; }
|
||||
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG; }
|
||||
|
||||
const char *get_name() const override { return get_name_static(); }
|
||||
uint16_t get_id() override { return get_id_static(); }
|
||||
|
||||
bool const_rate() override { return true; }
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
return MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_CFG_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
}
|
||||
|
||||
private:
|
||||
explicit MavlinkStreamUavionixADSBOutCfg(Mavlink *mavlink) : ModuleParams(nullptr), MavlinkStream(mavlink)
|
||||
{
|
||||
param_t param_fw_airspd_stall = param_find("FW_AIRSPD_STALL");
|
||||
|
||||
if (param_fw_airspd_stall != PARAM_INVALID) {
|
||||
float fw_airspd_stall;
|
||||
|
||||
if (param_get(param_fw_airspd_stall, &fw_airspd_stall) == PX4_OK) {
|
||||
_stall_speed = static_cast<uint16_t>(fw_airspd_stall * 100.0f); // convert [m/s] to [cm/s]
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
DEFINE_PARAMETERS(
|
||||
(ParamInt<px4::params::ADSB_ICAO_ID>) _adsb_icao,
|
||||
(ParamInt<px4::params::ADSB_LEN_WIDTH>) _adsb_len_width,
|
||||
(ParamInt<px4::params::ADSB_EMIT_TYPE>) _adsb_emit_type,
|
||||
(ParamInt<px4::params::ADSB_GPS_OFF_LAT>) _adsb_gps_offset_lat,
|
||||
(ParamInt<px4::params::ADSB_GPS_OFF_LON>) _adsb_gps_offset_lon
|
||||
);
|
||||
|
||||
uint16_t _stall_speed{0}; // [cm/s]
|
||||
|
||||
bool send() override
|
||||
{
|
||||
// Required update for static message is 0.1 [Hz]
|
||||
mavlink_uavionix_adsb_out_cfg_t cfg_msg = {
|
||||
.ICAO = static_cast<uint32_t>(_adsb_icao.get()),
|
||||
.stallSpeed = _stall_speed,
|
||||
.callsign = {'\0'},
|
||||
.emitterType = static_cast<uint8_t>(_adsb_emit_type.get()),
|
||||
.aircraftSize = static_cast<uint8_t>(_adsb_len_width.get()),
|
||||
.gpsOffsetLat = static_cast<uint8_t>(_adsb_gps_offset_lat.get()),
|
||||
.gpsOffsetLon = static_cast<uint8_t>(_adsb_gps_offset_lon.get()),
|
||||
.rfSelect = UAVIONIX_ADSB_OUT_RF_SELECT_TX_ENABLED
|
||||
};
|
||||
|
||||
//memcpy(cfg_msg.callsign, "PX4 UAV ", sizeof(cfg_msg.callsign)); //TODO: add support for callsign
|
||||
|
||||
mavlink_msg_uavionix_adsb_out_cfg_send_struct(_mavlink->get_channel(), &cfg_msg);
|
||||
|
||||
return true;
|
||||
}
|
||||
};
|
||||
|
||||
#endif // UAVIONIX_ADSB_OUT_CFG_HPP
|
||||
@@ -0,0 +1,116 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
#ifndef UAVIONIX_ADSB_OUT_DYNAMIC_HPP
|
||||
#define UAVIONIX_ADSB_OUT_DYNAMIC_HPP
|
||||
|
||||
#include <uORB/topics/sensor_gps.h>
|
||||
#include <uORB/topics/vehicle_air_data.h>
|
||||
#include <uORB/topics/vehicle_status.h>
|
||||
#include <uORB/topics/parameter_update.h>
|
||||
|
||||
class MavlinkStreamUavionixADSBOutDynamic : public ModuleParams, public MavlinkStream
|
||||
{
|
||||
public:
|
||||
static MavlinkStream *new_instance(Mavlink *mavlink) { return new MavlinkStreamUavionixADSBOutDynamic(mavlink); }
|
||||
|
||||
static constexpr const char *get_name_static() { return "UAVIONIX_ADSB_OUT_DYNAMIC"; }
|
||||
static constexpr uint16_t get_id_static() { return MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC; }
|
||||
|
||||
const char *get_name() const override { return get_name_static(); }
|
||||
uint16_t get_id() override { return get_id_static(); }
|
||||
|
||||
bool const_rate() override { return true; }
|
||||
|
||||
unsigned get_size() override
|
||||
{
|
||||
return MAVLINK_MSG_ID_UAVIONIX_ADSB_OUT_DYNAMIC_LEN + MAVLINK_NUM_NON_PAYLOAD_BYTES;
|
||||
}
|
||||
|
||||
private:
|
||||
explicit MavlinkStreamUavionixADSBOutDynamic(Mavlink *mavlink) : ModuleParams(nullptr), MavlinkStream(mavlink) {}
|
||||
|
||||
|
||||
uORB::Subscription _vehicle_gps_position_sub{ORB_ID(vehicle_gps_position)};
|
||||
uORB::Subscription _vehicle_air_data_sub{ORB_ID(vehicle_air_data)};
|
||||
uORB::Subscription _vehicle_status_sub{ORB_ID(vehicle_status)};
|
||||
|
||||
DEFINE_PARAMETERS(
|
||||
(ParamInt<px4::params::ADSB_SQUAWK>) _adsb_squawk,
|
||||
(ParamInt<px4::params::ADSB_EMERGC>) _adsb_emergc
|
||||
);
|
||||
|
||||
|
||||
bool send() override
|
||||
{
|
||||
|
||||
vehicle_status_s vehicle_status;
|
||||
_vehicle_status_sub.copy(&vehicle_status);
|
||||
|
||||
sensor_gps_s vehicle_gps_position;
|
||||
_vehicle_gps_position_sub.copy(&vehicle_gps_position);
|
||||
|
||||
vehicle_air_data_s vehicle_air_data;
|
||||
_vehicle_air_data_sub.copy(&vehicle_air_data);
|
||||
|
||||
// Required update for dynamic message is 5 [Hz]
|
||||
mavlink_uavionix_adsb_out_dynamic_t dynamic_msg = {
|
||||
.utcTime = static_cast<uint32_t>(vehicle_gps_position.time_utc_usec / 1000000ULL),
|
||||
.gpsLat = vehicle_gps_position.lat,
|
||||
.gpsLon = vehicle_gps_position.lon,
|
||||
.gpsAlt = vehicle_gps_position.alt_ellipsoid,
|
||||
.baroAltMSL = static_cast<int32_t>(vehicle_air_data.baro_pressure_pa / 100.0f), // convert [Pa] to [mBar]
|
||||
.accuracyHor = static_cast<uint32_t>(vehicle_gps_position.eph * 1000.0f), // convert [m] to [mm]
|
||||
.accuracyVert = static_cast<uint16_t>(vehicle_gps_position.epv * 100.0f), // convert [m] to [cm]
|
||||
.accuracyVel = static_cast<uint16_t>(vehicle_gps_position.s_variance_m_s * 1000.f), // convert [m/s] to [mm/s],
|
||||
.velVert = static_cast<int16_t>(-1.0f * vehicle_gps_position.vel_d_m_s * 100.0f), // convert [m/s] to [cm/s]
|
||||
.velNS = static_cast<int16_t>(vehicle_gps_position.vel_n_m_s * 100.0f), // convert [m/s] to [cm/s]
|
||||
.VelEW = static_cast<int16_t>(vehicle_gps_position.vel_e_m_s * 100.0f), // convert [m/s] to [cm/s]
|
||||
.state = UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND,
|
||||
.squawk = static_cast<uint16_t>(_adsb_squawk.get()),
|
||||
.gpsFix = vehicle_gps_position.fix_type,
|
||||
.numSats = vehicle_gps_position.satellites_used,
|
||||
.emergencyStatus = static_cast<uint8_t>(_adsb_emergc.get())
|
||||
};
|
||||
|
||||
if (vehicle_status.arming_state == vehicle_status_s::ARMING_STATE_ARMED) {
|
||||
dynamic_msg.state |= ~UAVIONIX_ADSB_OUT_DYNAMIC_STATE_ON_GROUND;
|
||||
}
|
||||
|
||||
mavlink_msg_uavionix_adsb_out_dynamic_send_struct(_mavlink->get_channel(), &dynamic_msg);
|
||||
|
||||
return true;
|
||||
}
|
||||
};
|
||||
|
||||
#endif // UAVIONIX_ADSB_OUT_DYNAMIC_HPP
|
||||
@@ -38,8 +38,7 @@
|
||||
#include <qurt_thread.h>
|
||||
#include <pthread.h>
|
||||
|
||||
// TODO: Move this out of here once we have px4-log functionality
|
||||
extern "C" void HAP_debug(const char *msg, int level, const char *filename, int line);
|
||||
#include <px4_platform_common/log.h>
|
||||
|
||||
// Definition of test to run when in muorb test mode
|
||||
static MUORBTestType test_to_run;
|
||||
@@ -48,7 +47,7 @@ fc_func_ptrs muorb_func_ptrs;
|
||||
|
||||
static void *test_runner(void *test)
|
||||
{
|
||||
HAP_debug("test_runner called", 1, muorb_test_topic_name, 0);
|
||||
PX4_INFO("test_runner called");
|
||||
|
||||
switch (*((MUORBTestType *) test)) {
|
||||
case ADVERTISE_TEST_TYPE:
|
||||
@@ -84,7 +83,7 @@ int px4muorb_orb_initialize(fc_func_ptrs *func_ptrs, int32_t clock_offset_us)
|
||||
// so they must be saved off here
|
||||
if (func_ptrs != nullptr) { muorb_func_ptrs = *func_ptrs; }
|
||||
|
||||
HAP_debug("px4muorb_orb_initialize called", 1, "init", 0);
|
||||
PX4_INFO("px4muorb_orb_initialize called");
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -107,7 +106,7 @@ int px4muorb_topic_advertised(const char *topic_name)
|
||||
{
|
||||
if (IS_MUORB_TEST(topic_name)) { run_test(ADVERTISE_TEST_TYPE); }
|
||||
|
||||
HAP_debug("px4muorb_topic_advertised called", 1, topic_name, 0);
|
||||
PX4_INFO("px4muorb_topic_advertised called");
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -116,7 +115,7 @@ int px4muorb_add_subscriber(const char *topic_name)
|
||||
{
|
||||
if (IS_MUORB_TEST(topic_name)) { run_test(SUBSCRIBE_TEST_TYPE); }
|
||||
|
||||
HAP_debug("px4muorb_add_subscriber called", 1, topic_name, 0);
|
||||
PX4_INFO("px4muorb_add_subscriber called");
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -125,7 +124,7 @@ int px4muorb_remove_subscriber(const char *topic_name)
|
||||
{
|
||||
if (IS_MUORB_TEST(topic_name)) { run_test(UNSUBSCRIBE_TEST_TYPE); }
|
||||
|
||||
HAP_debug("px4muorb_remove_subscriber called", 1, topic_name, 0);
|
||||
PX4_INFO("px4muorb_remove_subscriber called");
|
||||
|
||||
return 0;
|
||||
}
|
||||
@@ -152,7 +151,7 @@ int px4muorb_send_topic_data(const char *topic_name, const uint8_t *data,
|
||||
if (test_passed) { run_test(TOPIC_TEST_TYPE); }
|
||||
}
|
||||
|
||||
HAP_debug("px4muorb_send_topic_data called", 1, topic_name, 0);
|
||||
PX4_INFO("px4muorb_send_topic_data called");
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
@@ -228,7 +228,8 @@ void RTL::find_RTL_destination()
|
||||
}
|
||||
}
|
||||
|
||||
if (_navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
|
||||
if (_param_rtl_cone_half_angle_deg.get() > 0
|
||||
&& _navigator->get_vstatus()->vehicle_type == vehicle_status_s::VEHICLE_TYPE_ROTARY_WING) {
|
||||
_rtl_alt = calculate_return_alt_from_cone_half_angle((float)_param_rtl_cone_half_angle_deg.get());
|
||||
|
||||
} else {
|
||||
@@ -701,7 +702,7 @@ float RTL::calculate_return_alt_from_cone_half_angle(float cone_half_angle_deg)
|
||||
|
||||
} else {
|
||||
|
||||
if (cone_half_angle_deg > 0.0f && destination_dist <= _param_rtl_min_dist.get()) {
|
||||
if (destination_dist <= _param_rtl_min_dist.get()) {
|
||||
|
||||
// constrain cone half angle to meaningful values. All other cases are already handled above.
|
||||
const float cone_half_angle_rad = radians(constrain(cone_half_angle_deg, 1.0f, 89.0f));
|
||||
|
||||
@@ -61,6 +61,7 @@ VehicleAngularVelocity::~VehicleAngularVelocity()
|
||||
#if !defined(CONSTRAINED_FLASH)
|
||||
delete[] _dynamic_notch_filter_esc_rpm;
|
||||
perf_free(_dynamic_notch_filter_esc_rpm_disable_perf);
|
||||
perf_free(_dynamic_notch_filter_esc_rpm_init_perf);
|
||||
perf_free(_dynamic_notch_filter_esc_rpm_update_perf);
|
||||
|
||||
perf_free(_dynamic_notch_filter_fft_disable_perf);
|
||||
@@ -458,6 +459,11 @@ void VehicleAngularVelocity::ParametersUpdate(bool force)
|
||||
MODULE_NAME": gyro dynamic notch filter ESC RPM disable");
|
||||
}
|
||||
|
||||
if (_dynamic_notch_filter_esc_rpm_init_perf == nullptr) {
|
||||
_dynamic_notch_filter_esc_rpm_init_perf = perf_alloc(PC_COUNT,
|
||||
MODULE_NAME": gyro dynamic notch filter ESC RPM init");
|
||||
}
|
||||
|
||||
if (_dynamic_notch_filter_esc_rpm_update_perf == nullptr) {
|
||||
_dynamic_notch_filter_esc_rpm_update_perf = perf_alloc(PC_COUNT,
|
||||
MODULE_NAME": gyro dynamic notch filter ESC RPM update");
|
||||
@@ -467,9 +473,11 @@ void VehicleAngularVelocity::ParametersUpdate(bool force)
|
||||
_esc_rpm_harmonics = 0;
|
||||
|
||||
perf_free(_dynamic_notch_filter_esc_rpm_disable_perf);
|
||||
perf_free(_dynamic_notch_filter_esc_rpm_init_perf);
|
||||
perf_free(_dynamic_notch_filter_esc_rpm_update_perf);
|
||||
|
||||
_dynamic_notch_filter_esc_rpm_disable_perf = nullptr;
|
||||
_dynamic_notch_filter_esc_rpm_init_perf = nullptr;
|
||||
_dynamic_notch_filter_esc_rpm_update_perf = nullptr;
|
||||
}
|
||||
}
|
||||
@@ -566,76 +574,89 @@ void VehicleAngularVelocity::UpdateDynamicNotchEscRpm(const hrt_abstime &time_no
|
||||
|
||||
if (enabled && (_esc_status_sub.updated() || force)) {
|
||||
|
||||
bool axis_init[3] {false, false, false};
|
||||
|
||||
esc_status_s esc_status;
|
||||
|
||||
if (_esc_status_sub.copy(&esc_status) && (time_now_us < esc_status.timestamp + DYNAMIC_NOTCH_FITLER_TIMEOUT)) {
|
||||
|
||||
static constexpr float FREQ_MIN = 10.f; // TODO: configurable
|
||||
const float bandwidth_hz = _param_imu_gyro_dnf_bw.get();
|
||||
const float freq_min = math::max(_param_imu_gyro_dnf_min.get(), bandwidth_hz);
|
||||
|
||||
for (size_t esc = 0; esc < math::min(esc_status.esc_count, (uint8_t)MAX_NUM_ESCS); esc++) {
|
||||
const esc_report_s &esc_report = esc_status.esc[esc];
|
||||
|
||||
// only update if ESC RPM range seems valid
|
||||
if ((esc_report.esc_rpm != 0) && (time_now_us < esc_report.timestamp + DYNAMIC_NOTCH_FITLER_TIMEOUT)) {
|
||||
const bool esc_connected = (esc_status.esc_online_flags & (1 << esc)) || (esc_report.esc_rpm != 0);
|
||||
|
||||
bool esc_enabled = false;
|
||||
bool update = force || !_esc_available[esc]; // force parameter update or notch was previously disabled
|
||||
// only update if ESC RPM range seems valid
|
||||
if (esc_connected && (time_now_us < esc_report.timestamp + DYNAMIC_NOTCH_FITLER_TIMEOUT)) {
|
||||
|
||||
const float esc_hz = abs(esc_report.esc_rpm) / 60.f;
|
||||
|
||||
const bool force_update = force || !_esc_available[esc]; // force parameter update or notch was previously disabled
|
||||
|
||||
for (int harmonic = 0; harmonic < _esc_rpm_harmonics; harmonic++) {
|
||||
const float frequency_hz = esc_hz * (harmonic + 1);
|
||||
// as RPM drops leave the notch filter "parked" at the minimum rather than disabling
|
||||
// keep harmonics separated by half the notch filter bandwidth
|
||||
const float frequency_hz = math::max(esc_hz * (harmonic + 1), freq_min + (harmonic * 0.5f * bandwidth_hz));
|
||||
|
||||
// for each ESC harmonic determine if enabled/disabled from first notch (x axis)
|
||||
auto &nfx = _dynamic_notch_filter_esc_rpm[harmonic][0][esc];
|
||||
// update filter parameters if frequency changed or forced
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
auto &nf = _dynamic_notch_filter_esc_rpm[harmonic][axis][esc];
|
||||
|
||||
if (frequency_hz > FREQ_MIN) {
|
||||
// update filter parameters if frequency changed or forced
|
||||
if (update || !nfx.initialized() || (fabsf(nfx.getNotchFreq() - frequency_hz) > 0.1f)) {
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
auto &nf = _dynamic_notch_filter_esc_rpm[harmonic][axis][esc];
|
||||
nf.setParameters(_filter_sample_rate_hz, frequency_hz, _param_imu_gyro_dnf_bw.get());
|
||||
const float notch_freq_delta = fabsf(nf.getNotchFreq() - frequency_hz);
|
||||
|
||||
const bool notch_freq_changed = (notch_freq_delta > 0.1f);
|
||||
|
||||
// only allow initializing one new filter per axis each iteration
|
||||
const bool allow_update = !axis_init[axis] || (nf.initialized() && notch_freq_delta < nf.getBandwidth());
|
||||
|
||||
if ((force_update || notch_freq_changed) && allow_update) {
|
||||
if (nf.setParameters(_filter_sample_rate_hz, frequency_hz, bandwidth_hz)) {
|
||||
perf_count(_dynamic_notch_filter_esc_rpm_update_perf);
|
||||
}
|
||||
}
|
||||
|
||||
esc_enabled = true;
|
||||
|
||||
} else {
|
||||
// disable these notch filters (if they aren't already)
|
||||
if (nfx.getNotchFreq() > 0.f) {
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
auto &nf = _dynamic_notch_filter_esc_rpm[harmonic][axis][esc];
|
||||
nf.disable();
|
||||
perf_count(_dynamic_notch_filter_esc_rpm_disable_perf);
|
||||
if (!nf.initialized()) {
|
||||
perf_count(_dynamic_notch_filter_esc_rpm_init_perf);
|
||||
axis_init[axis] = true;
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (esc_enabled) {
|
||||
_esc_available.set(esc, true);
|
||||
_last_esc_rpm_notch_update[esc] = esc_report.timestamp;
|
||||
|
||||
} else {
|
||||
_esc_available.set(esc, false);
|
||||
}
|
||||
_esc_available.set(esc, true);
|
||||
_last_esc_rpm_notch_update[esc] = esc_report.timestamp;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
// check ESC feedback timeout
|
||||
// check notch filter timeout
|
||||
for (size_t esc = 0; esc < MAX_NUM_ESCS; esc++) {
|
||||
if (_esc_available[esc] && (time_now_us > _last_esc_rpm_notch_update[esc] + DYNAMIC_NOTCH_FITLER_TIMEOUT)) {
|
||||
bool all_disabled = true;
|
||||
|
||||
_esc_available.set(esc, false);
|
||||
|
||||
for (int harmonic = 0; harmonic < _esc_rpm_harmonics; harmonic++) {
|
||||
// disable notch filters from highest frequency to lowest
|
||||
for (int harmonic = _esc_rpm_harmonics - 1; harmonic >= 0; harmonic--) {
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
_dynamic_notch_filter_esc_rpm[harmonic][axis][esc].disable();
|
||||
perf_count(_dynamic_notch_filter_esc_rpm_disable_perf);
|
||||
auto &nf = _dynamic_notch_filter_esc_rpm[harmonic][axis][esc];
|
||||
|
||||
if (nf.getNotchFreq() > 0.f) {
|
||||
if (nf.initialized() && !axis_init[axis]) {
|
||||
nf.disable();
|
||||
perf_count(_dynamic_notch_filter_esc_rpm_disable_perf);
|
||||
axis_init[axis] = true;
|
||||
}
|
||||
}
|
||||
|
||||
if (nf.getNotchFreq() > 0.f) {
|
||||
all_disabled = false;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
if (all_disabled) {
|
||||
_esc_available.set(esc, false);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -711,7 +732,9 @@ float VehicleAngularVelocity::FilterAngularVelocity(int axis, float data[], int
|
||||
for (int esc = 0; esc < MAX_NUM_ESCS; esc++) {
|
||||
if (_esc_available[esc]) {
|
||||
for (int harmonic = 0; harmonic < _esc_rpm_harmonics; harmonic++) {
|
||||
_dynamic_notch_filter_esc_rpm[harmonic][axis][esc].applyArray(data, N);
|
||||
if (_dynamic_notch_filter_esc_rpm[harmonic][axis][esc].getNotchFreq() > 0.f) {
|
||||
_dynamic_notch_filter_esc_rpm[harmonic][axis][esc].applyArray(data, N);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -941,6 +964,7 @@ void VehicleAngularVelocity::PrintStatus()
|
||||
perf_print_counter(_selection_changed_perf);
|
||||
#if !defined(CONSTRAINED_FLASH)
|
||||
perf_print_counter(_dynamic_notch_filter_esc_rpm_disable_perf);
|
||||
perf_print_counter(_dynamic_notch_filter_esc_rpm_init_perf);
|
||||
perf_print_counter(_dynamic_notch_filter_esc_rpm_update_perf);
|
||||
|
||||
perf_print_counter(_dynamic_notch_filter_fft_disable_perf);
|
||||
|
||||
@@ -142,7 +142,7 @@ private:
|
||||
FFT = 2,
|
||||
};
|
||||
|
||||
static constexpr hrt_abstime DYNAMIC_NOTCH_FITLER_TIMEOUT = 1_s;
|
||||
static constexpr hrt_abstime DYNAMIC_NOTCH_FITLER_TIMEOUT = 3_s;
|
||||
|
||||
// ESC RPM
|
||||
static constexpr int MAX_NUM_ESCS = sizeof(esc_status_s::esc) / sizeof(esc_status_s::esc[0]);
|
||||
@@ -154,8 +154,9 @@ private:
|
||||
px4::Bitset<MAX_NUM_ESCS> _esc_available{};
|
||||
hrt_abstime _last_esc_rpm_notch_update[MAX_NUM_ESCS] {};
|
||||
|
||||
perf_counter_t _dynamic_notch_filter_esc_rpm_update_perf{nullptr};
|
||||
perf_counter_t _dynamic_notch_filter_esc_rpm_disable_perf{nullptr};
|
||||
perf_counter_t _dynamic_notch_filter_esc_rpm_init_perf{nullptr};
|
||||
perf_counter_t _dynamic_notch_filter_esc_rpm_update_perf{nullptr};
|
||||
|
||||
// FFT
|
||||
static constexpr int MAX_NUM_FFT_PEAKS = sizeof(sensor_gyro_fft_s::peak_frequencies_x)
|
||||
@@ -187,6 +188,7 @@ private:
|
||||
(ParamInt<px4::params::IMU_GYRO_DNF_EN>) _param_imu_gyro_dnf_en,
|
||||
(ParamInt<px4::params::IMU_GYRO_DNF_HMC>) _param_imu_gyro_dnf_hmc,
|
||||
(ParamFloat<px4::params::IMU_GYRO_DNF_BW>) _param_imu_gyro_dnf_bw,
|
||||
(ParamFloat<px4::params::IMU_GYRO_DNF_MIN>) _param_imu_gyro_dnf_min,
|
||||
#endif // !CONSTRAINED_FLASH
|
||||
(ParamFloat<px4::params::IMU_GYRO_CUTOFF>) _param_imu_gyro_cutoff,
|
||||
(ParamFloat<px4::params::IMU_GYRO_NF0_FRQ>) _param_imu_gyro_nf0_frq,
|
||||
|
||||
@@ -178,6 +178,7 @@ PARAM_DEFINE_INT32(IMU_GYRO_DNF_EN, 0);
|
||||
* Bandwidth per notch filter when using dynamic notch filtering with ESC RPM.
|
||||
*
|
||||
* @group Sensors
|
||||
* @unit Hz
|
||||
* @min 5
|
||||
* @max 30
|
||||
*/
|
||||
@@ -193,3 +194,13 @@ PARAM_DEFINE_FLOAT(IMU_GYRO_DNF_BW, 15.f);
|
||||
* @max 7
|
||||
*/
|
||||
PARAM_DEFINE_INT32(IMU_GYRO_DNF_HMC, 3);
|
||||
|
||||
/**
|
||||
* IMU gyro dynamic notch filter minimum frequency
|
||||
*
|
||||
* Minimum notch filter frequency in Hz.
|
||||
*
|
||||
* @group Sensors
|
||||
* @unit Hz
|
||||
*/
|
||||
PARAM_DEFINE_FLOAT(IMU_GYRO_DNF_MIN, 25.f);
|
||||
|
||||
@@ -682,11 +682,11 @@ int Sih::print_usage(const char *reason)
|
||||
PRINT_MODULE_DESCRIPTION(
|
||||
R"DESCR_STR(
|
||||
### Description
|
||||
This module provide a simulator for quadrotors and fixed-wings running fully
|
||||
This module provides a simulator for quadrotors and fixed-wings running fully
|
||||
inside the hardware autopilot.
|
||||
|
||||
This simulator subscribes to "actuator_outputs" which are the actuator pwm
|
||||
signals given by the mixer.
|
||||
signals given by the control allocation module.
|
||||
|
||||
This simulator publishes the sensors signals corrupted with realistic noise
|
||||
in order to incorporate the state estimator in the loop.
|
||||
|
||||
@@ -105,6 +105,19 @@ VtolAttitudeControl::init()
|
||||
return true;
|
||||
}
|
||||
|
||||
void VtolAttitudeControl::vehicle_status_poll()
|
||||
{
|
||||
_vehicle_status_sub.copy(&_vehicle_status);
|
||||
|
||||
// abort front transition when RTL is triggered
|
||||
if (_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL
|
||||
&& _nav_state_prev != vehicle_status_s::NAVIGATION_STATE_AUTO_RTL && _vtol_type->get_mode() == mode::TRANSITION_TO_FW) {
|
||||
_transition_command = vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC;
|
||||
}
|
||||
|
||||
_nav_state_prev = _vehicle_status.nav_state;
|
||||
}
|
||||
|
||||
void VtolAttitudeControl::action_request_poll()
|
||||
{
|
||||
while (_action_request_sub.updated()) {
|
||||
@@ -132,8 +145,6 @@ void VtolAttitudeControl::vehicle_cmd_poll()
|
||||
|
||||
while (_vehicle_cmd_sub.update(&vehicle_command)) {
|
||||
if (vehicle_command.command == vehicle_command_s::VEHICLE_CMD_DO_VTOL_TRANSITION) {
|
||||
vehicle_status_s vehicle_status{};
|
||||
_vehicle_status_sub.copy(&vehicle_status);
|
||||
|
||||
uint8_t result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_ACCEPTED;
|
||||
|
||||
@@ -141,10 +152,10 @@ void VtolAttitudeControl::vehicle_cmd_poll()
|
||||
|
||||
// deny transition from MC to FW in Takeoff, Land, RTL and Orbit
|
||||
if (transition_command_param1 == vtol_vehicle_status_s::VEHICLE_VTOL_STATE_FW &&
|
||||
(vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF
|
||||
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND
|
||||
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL
|
||||
|| vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_ORBIT)) {
|
||||
(_vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_TAKEOFF
|
||||
|| _vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_LAND
|
||||
|| _vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_AUTO_RTL
|
||||
|| _vehicle_status.nav_state == vehicle_status_s::NAVIGATION_STATE_ORBIT)) {
|
||||
|
||||
result = vehicle_command_ack_s::VEHICLE_CMD_RESULT_TEMPORARILY_REJECTED;
|
||||
|
||||
@@ -309,6 +320,7 @@ VtolAttitudeControl::Run()
|
||||
_airspeed_validated_sub.update(&_airspeed_validated);
|
||||
_tecs_status_sub.update(&_tecs_status);
|
||||
_land_detected_sub.update(&_land_detected);
|
||||
vehicle_status_poll();
|
||||
action_request_poll();
|
||||
vehicle_cmd_poll();
|
||||
|
||||
|
||||
@@ -210,6 +210,7 @@ private:
|
||||
vehicle_land_detected_s _land_detected{};
|
||||
vehicle_local_position_s _local_pos{};
|
||||
vehicle_local_position_setpoint_s _local_pos_sp{};
|
||||
vehicle_status_s _vehicle_status{};
|
||||
vtol_vehicle_status_s _vtol_vehicle_status{};
|
||||
|
||||
float _air_density{CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C}; // [kg/m^3]
|
||||
@@ -222,12 +223,16 @@ private:
|
||||
int _transition_command{vtol_vehicle_status_s::VEHICLE_VTOL_STATE_MC};
|
||||
bool _immediate_transition{false};
|
||||
|
||||
uint8_t _nav_state_prev;
|
||||
|
||||
VtolType *_vtol_type{nullptr}; // base class for different vtol types
|
||||
|
||||
bool _initialized{false};
|
||||
|
||||
perf_counter_t _loop_perf; // loop performance counter
|
||||
|
||||
void vehicle_status_poll();
|
||||
|
||||
void action_request_poll();
|
||||
|
||||
void vehicle_cmd_poll();
|
||||
|
||||
Reference in New Issue
Block a user