diff --git a/.github/workflows/ekf_functional_change_indicator.yml b/.github/workflows/ekf_functional_change_indicator.yml index c453ba8ec4..6c5225df5b 100644 --- a/.github/workflows/ekf_functional_change_indicator.yml +++ b/.github/workflows/ekf_functional_change_indicator.yml @@ -8,13 +8,14 @@ jobs: container: px4io/px4-dev-base-focal:2021-05-04 steps: - uses: actions/checkout@v2.3.1 + with: + fetch-depth: 0 - name: checkout newest version of branch run: | git fetch origin pull/${{github.event.pull_request.number}}/head:${{github.head_ref}} git checkout ${GITHUB_HEAD_REF} - name: main test - run: cd ${GITHUB_WORKSPACE}/src/lib/ecl; make test - working-directory: src/lib/ecl + run: make tests TESTFILTER=EKF - name: Check if there is a functional change run: git diff --exit-code - working-directory: src/lib/ecl/test/change_indication + working-directory: src/modules/ekf2/test/change_indication diff --git a/.github/workflows/ekf_standalone_build_tests.yml b/.github/workflows/ekf_standalone_build_tests.yml deleted file mode 100644 index 5fc09ad8de..0000000000 --- a/.github/workflows/ekf_standalone_build_tests.yml +++ /dev/null @@ -1,56 +0,0 @@ - -name: EKF Build Tests - -on: - push: - branches: - - master - pull_request: - branches: - - '*' - -jobs: - Linux-GCC: - runs-on: ubuntu-latest - container: px4io/px4-dev-base-focal:2021-05-04 - steps: - - uses: actions/checkout@v1 - - name: main build - run: make - working-directory: src/lib/ecl - - name: clean build - run: make clean - working-directory: src/lib/ecl - - name: main test - run: make test - working-directory: src/lib/ecl - Linux-Clang: - runs-on: ubuntu-latest - container: px4io/px4-dev-clang:2021-05-04 - env: - CC: clang - CXX: clang++ - steps: - - uses: actions/checkout@v1 - - name: main build - run: make - working-directory: src/lib/ecl - - name: clean build - run: make clean - working-directory: src/lib/ecl - - name: main test - run: make test - working-directory: src/lib/ecl - Mac-OS: - runs-on: macos-latest - steps: - - uses: actions/checkout@v1 - - name: main build - run: make - working-directory: src/lib/ecl - - name: clean build - run: make clean - working-directory: src/lib/ecl - - name: main test - run: make test - working-directory: src/lib/ecl diff --git a/.github/workflows/ekf_update_change_indicator.yml b/.github/workflows/ekf_update_change_indicator.yml index fc23b7b2f4..8c3e55d6af 100644 --- a/.github/workflows/ekf_update_change_indicator.yml +++ b/.github/workflows/ekf_update_change_indicator.yml @@ -11,11 +11,13 @@ jobs: GIT_COMMITTER_NAME: PX4BuildBot steps: - uses: actions/checkout@v2.3.1 + with: + fetch-depth: 0 - name: main test updates change indication files - run: cd ${GITHUB_WORKSPACE}/src/lib/ecl; make test + run: make tests TESTFILTER=EKF - name: Check if there exists diff and save result in variable run: echo "CHANGE_INDICATED=$(git diff --exit-code --output=/dev/null || echo $?)" >> $GITHUB_ENV - working-directory: src/lib/ecl/test/change_indication + working-directory: src/modules/ekf2/test/change_indication - name: auto-commit any changes to change indication uses: stefanzweifel/git-auto-commit-action@v4 with: diff --git a/Tools/astyle/files_to_check_code_style.sh b/Tools/astyle/files_to_check_code_style.sh index d39c4c397d..3ef1e01e29 100755 --- a/Tools/astyle/files_to_check_code_style.sh +++ b/Tools/astyle/files_to_check_code_style.sh @@ -12,16 +12,16 @@ exec find boards msg src platforms test \ -path platforms/nuttx/NuttX -prune -o \ -path platforms/qurt/dspal -prune -o \ -path src/drivers/uavcan/libuavcan -prune -o \ + -path src/drivers/uavcan/uavcan_drivers/kinetis/driver/include/uavcan_kinetis -prune -o \ -path src/drivers/uavcan_v1/libcanard -prune -o \ -path src/drivers/uavcannode_gps_demo/libcanard -prune -o \ - -path src/drivers/uavcan/uavcan_drivers/kinetis/driver/include/uavcan_kinetis -prune -o \ - -path src/lib/ecl -prune -o \ + -path src/lib/crypto/monocypher -prune -o \ -path src/lib/events/libevents -prune -o \ -path src/lib/matrix -prune -o \ -path src/lib/parameters/uthash -prune -o \ + -path src/modules/ekf2/EKF -prune -o \ -path src/modules/gyro_fft/CMSIS_5 -prune -o \ -path src/modules/micrortps_bridge/micro-CDR -prune -o \ -path src/modules/micrortps_bridge/microRTPS_client -prune -o \ -path test/mavsdk_tests/catch2 -prune -o \ - -path src/lib/crypto/monocypher -prune -o \ -type f \( -name "*.c" -o -name "*.h" -o -name "*.cpp" -o -name "*.hpp" \) | grep $PATTERN diff --git a/boards/px4/fmu-v5/optimized.cmake b/boards/px4/fmu-v5/optimized.cmake index 3f2ceb19d6..e59e32f353 100644 --- a/boards/px4/fmu-v5/optimized.cmake +++ b/boards/px4/fmu-v5/optimized.cmake @@ -96,7 +96,7 @@ px4_add_board( #uuv_att_control #uuv_pos_control #vmount - vtol_att_control + #vtol_att_control SYSTEMCMDS #bl_update dmesg diff --git a/src/lib/CMakeLists.txt b/src/lib/CMakeLists.txt index 6d6c2d34e7..39097256bb 100644 --- a/src/lib/CMakeLists.txt +++ b/src/lib/CMakeLists.txt @@ -46,7 +46,6 @@ add_subdirectory(controllib) add_subdirectory(conversion) add_subdirectory(crypto) add_subdirectory(drivers) -add_subdirectory(ecl) add_subdirectory(geo) add_subdirectory(hysteresis) add_subdirectory(l1) diff --git a/src/lib/ecl/.clang-format b/src/lib/ecl/.clang-format deleted file mode 100644 index c8ed09f5cc..0000000000 --- a/src/lib/ecl/.clang-format +++ /dev/null @@ -1,117 +0,0 @@ ---- -Language: Cpp -# BasedOnStyle: Google -AccessModifierOffset: -8 # Modified -AlignAfterOpenBracket: Align -AlignConsecutiveAssignments: false -AlignConsecutiveDeclarations: false -AlignEscapedNewlines: Left -AlignOperands: true -AlignTrailingComments: true -AllowAllParametersOfDeclarationOnNextLine: true -AllowShortBlocksOnASingleLine: false -AllowShortCaseLabelsOnASingleLine: false -AllowShortFunctionsOnASingleLine: All -AllowShortIfStatementsOnASingleLine: true -AllowShortLoopsOnASingleLine: true -AlwaysBreakAfterDefinitionReturnType: None -AlwaysBreakAfterReturnType: None -AlwaysBreakBeforeMultilineStrings: true -AlwaysBreakTemplateDeclarations: true -BinPackArguments: true -BinPackParameters: true -BraceWrapping: - AfterClass: false - AfterControlStatement: false - AfterEnum: false - AfterFunction: false - AfterNamespace: false - AfterObjCDeclaration: false - AfterStruct: false - AfterUnion: false - AfterExternBlock: false - BeforeCatch: false - BeforeElse: false - IndentBraces: false - SplitEmptyFunction: true - SplitEmptyRecord: true - SplitEmptyNamespace: true -BreakBeforeBinaryOperators: None -BreakBeforeBraces: Linux -BreakBeforeInheritanceComma: false -BreakBeforeTernaryOperators: true -BreakConstructorInitializersBeforeComma: false -BreakConstructorInitializers: BeforeColon -BreakAfterJavaFieldAnnotations: false -BreakStringLiterals: true -ColumnLimit: 120 -CommentPragmas: '^ IWYU pragma:' -CompactNamespaces: false -ConstructorInitializerAllOnOneLineOrOnePerLine: true -ConstructorInitializerIndentWidth: 4 -ContinuationIndentWidth: 4 -Cpp11BracedListStyle: true -DerivePointerAlignment: true -DisableFormat: false -ExperimentalAutoDetectBinPacking: false -FixNamespaceComments: true -ForEachMacros: - - foreach - - Q_FOREACH - - BOOST_FOREACH -IncludeBlocks: Preserve -IncludeCategories: - - Regex: '^' - Priority: 2 - - Regex: '^<.*\.h>' - Priority: 1 - - Regex: '^<.*' - Priority: 2 - - Regex: '.*' - Priority: 3 -IncludeIsMainRegex: '([-_](test|unittest))?$' -IndentCaseLabels: true -IndentPPDirectives: None -IndentWidth: 8 # Modified -IndentWrappedFunctionNames: false -JavaScriptQuotes: Leave -JavaScriptWrapImports: true -KeepEmptyLinesAtTheStartOfBlocks: true # Modified -MacroBlockBegin: '' -MacroBlockEnd: '' -MaxEmptyLinesToKeep: 1 -NamespaceIndentation: None -ObjCBlockIndentWidth: 2 -ObjCSpaceAfterProperty: false -ObjCSpaceBeforeProtocolList: false -PenaltyBreakAssignment: 200 # Modified -PenaltyBreakBeforeFirstCallParameter: 20 # Modified -PenaltyBreakComment: 300 -PenaltyBreakFirstLessLess: 120 -PenaltyBreakString: 1000 -PenaltyExcessCharacter: 1000000 -PenaltyReturnTypeOnItsOwnLine: 200 -PointerAlignment: Left -RawStringFormats: - - Delimiter: pb - Language: TextProto - BasedOnStyle: google -ReflowComments: true -SortIncludes: true -SortUsingDeclarations: true -SpaceAfterCStyleCast: false -SpaceAfterTemplateKeyword: true -SpaceBeforeAssignmentOperators: true -SpaceBeforeParens: ControlStatements -SpaceInEmptyParentheses: false -SpacesBeforeTrailingComments: 2 -SpacesInAngles: false -SpacesInContainerLiterals: true -SpacesInCStyleCastParentheses: false -SpacesInParentheses: false -SpacesInSquareBrackets: false -Standard: Auto -TabWidth: 8 # Modified -UseTab: Always # Modified -... - diff --git a/src/lib/ecl/.editorconfig b/src/lib/ecl/.editorconfig deleted file mode 100644 index 73387be0f2..0000000000 --- a/src/lib/ecl/.editorconfig +++ /dev/null @@ -1,5 +0,0 @@ -# EditorConfig https://EditorConfig.org -root = true - -[{Makefile,CMakeLists.txt}] -indent_style = tab diff --git a/src/lib/ecl/.gitignore b/src/lib/ecl/.gitignore deleted file mode 100644 index 9fd936329f..0000000000 --- a/src/lib/ecl/.gitignore +++ /dev/null @@ -1,18 +0,0 @@ -*.DS_Store -*.gcov -*~ -*.orig - -.cache/ -build/ - -*/*.a -.ninja_deps -.ninja_log -build.ninja -cmake_install.cmake -CMakeCache.txt -CMakeFiles -compile_commands.json -matrix-prefix/ -rules.ninja diff --git a/src/lib/ecl/.travis.yml b/src/lib/ecl/.travis.yml deleted file mode 100644 index 1b8571f0a7..0000000000 --- a/src/lib/ecl/.travis.yml +++ /dev/null @@ -1,31 +0,0 @@ - -sudo: required - -services: - - docker - -language: cpp - -matrix: - fast_finish: true - include: - - env: BUILD_TARGET=coverity_scan - dist: trusty - if: branch = coverity_scan - -before_install: - - echo -n | openssl s_client -connect scan.coverity.com:443 | sed -ne '/-BEGIN CERTIFICATE-/,/-END CERTIFICATE-/p' | sudo tee -a /etc/ssl/certs/ca- - -script: - - make distclean - - make - -addons: - coverity_scan: - project: - name: "PX4/ecl" - description: "Build submitted via Travis CI" - notification_email: ci@px4.io - build_command_prepend: "make distclean" - build_command: "make" - branch_pattern: coverity_scan diff --git a/src/lib/ecl/CMakeLists.txt b/src/lib/ecl/CMakeLists.txt deleted file mode 100644 index 9c1fba2d1e..0000000000 --- a/src/lib/ecl/CMakeLists.txt +++ /dev/null @@ -1,251 +0,0 @@ -############################################################################ -# -# Copyright (c) 2015-2018 ECL 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 ECL 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. -# -############################################################################ - -cmake_minimum_required(VERSION 3.0) - -project(ECL CXX) - -if(NOT CMAKE_BUILD_TYPE) - # force debug builds if we test ECL as standalone - if(BUILD_TESTING AND CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR) - set(CMAKE_BUILD_TYPE "Debug" CACHE STRING "Build type" FORCE) - else() - set(CMAKE_BUILD_TYPE "RelWithDebInfo" CACHE STRING "Build type" FORCE) - endif() -endif() -message(STATUS "build type is ${CMAKE_BUILD_TYPE}") - -set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS "Debug;Release;RelWithDebInfo;MinSizeRel;Coverage") - -if(EXISTS ${CMAKE_CURRENT_SOURCE_DIR}/.git) - execute_process( - COMMAND git describe --always --tags - OUTPUT_VARIABLE git_tag - OUTPUT_STRIP_TRAILING_WHITESPACE - WORKING_DIRECTORY ${CMAKE_CURRENT_SOURCE_DIR} - ) -endif() - -message(STATUS "PX4 ECL: Very lightweight Estimation & Control Library ${git_tag}") - -set(CMAKE_CXX_STANDARD 14) -set(CMAKE_CXX_STANDARD_REQUIRED ON) -set(CMAKE_EXPORT_COMPILE_COMMANDS ON) - -# code coverage support -option(COV_HTML "Display html for coverage" OFF) -option(ECL_ASAN "Enable ECL address sanitizer" OFF) - -if (("${CMAKE_CXX_COMPILER_ID}" MATCHES "Clang") OR ("${CMAKE_CXX_COMPILER_ID}" MATCHES "AppleClang")) - set(CMAKE_CXX_FLAGS_COVERAGE - "--coverage -ftest-coverage -fdiagnostics-absolute-paths -O0 -fprofile-arcs -fno-inline-functions -fno-elide-constructors" - CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE) - set(CMAKE_EXE_LINKER_FLAGS_COVERAGE - "-ftest-coverage -fdiagnostics-absolute-paths" - CACHE STRING "Flags used for linking binaries during coverage builds" FORCE) -else() - set(CMAKE_CXX_FLAGS_COVERAGE - # Bring back -fprofile-abs-path when GCC 9 is available on Ubuntu LTS - "--coverage -fprofile-arcs -ftest-coverage -O0 -fno-default-inline -fno-inline -fno-inline-small-functions -fno-elide-constructors" - CACHE STRING "Flags used by the C++ compiler during coverage builds" FORCE) - set(CMAKE_EXE_LINKER_FLAGS_COVERAGE - "--coverage -ftest-coverage -lgcov" - CACHE STRING "Flags used for linking binaries during coverage builds" FORCE) -endif() - -mark_as_advanced(CMAKE_CXX_FLAGS_COVERAGE CMAKE_C_FLAGS_COVERAGE CMAKE_EXE_LINKER_FLAGS_COVERAGE) - - -set(ECL_SOURCE_DIR ${CMAKE_CURRENT_SOURCE_DIR} CACHE STRING "ECL source location" FORCE) - -if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR) - # ECL standalone build - add_definitions(-DECL_STANDALONE) - set(ECL_STANDALONE 1) - - add_custom_target(prebuild_targets) - - if(MSVC) - add_compile_options( - /W4 - /WX - - /D_USE_MATH_DEFINES - - /wd4100 # warning C4100: unreferenced formal parameter - /wd4244 # warning C4244: '=': conversion from 'double' to 'int32_t', possible loss of data - ) - elseif(CMAKE_COMPILER_IS_GNUCC OR CMAKE_COMPILER_IS_GNUCXX) - add_compile_options( - -pedantic - - -Wall - -Wextra - -Werror - - -Wno-missing-field-initializers # ignore for GCC 4.8 support - ) - endif() - - if(BUILD_TESTING) - - include(CTest) - - option(ECL_TESTS "Build ECL tests" ON) - - add_custom_target(check - COMMAND GTEST_COLOR=1 ${CMAKE_CTEST_COMMAND} --output-on-failure -C Debug - DEPENDS ecl_EKF - USES_TERMINAL - ) - endif() - - # fetch latest matrix from github - include(ExternalProject) - ExternalProject_Add(matrix - GIT_REPOSITORY "https://github.com/PX4/Matrix.git" - GIT_TAG f981cea2aebfc9cfd930dce73ba6d4d6681e99c1 - UPDATE_COMMAND "" - PATCH_COMMAND "" - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND "" - ) - add_dependencies(prebuild_targets matrix) - include_directories(${CMAKE_BINARY_DIR}/matrix-prefix/src/matrix) - - # temporary - configure_file(${CMAKE_CURRENT_SOURCE_DIR}/../mathlib/math/filter/AlphaFilter.hpp ${CMAKE_CURRENT_BINARY_DIR}/mathlib/math/filter/AlphaFilter.hpp COPYONLY) - include_directories(${CMAKE_CURRENT_BINARY_DIR}) - - include_directories(${CMAKE_CURRENT_SOURCE_DIR}) - add_definitions(-Dhrt_absolute_time=uint64_t) - add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../geo geo) - add_subdirectory(${CMAKE_CURRENT_SOURCE_DIR}/../world_magnetic_model world_magnetic_model) - include_directories(${CMAKE_CURRENT_SOURCE_DIR}/../..) - - -endif() - -if(NOT (${CMAKE_BUILD_TYPE} MATCHES "Coverage") AND NOT (${CMAKE_BUILD_TYPE} MATCHES "Debug")) - if(MAX_CUSTOM_OPT_LEVEL) - add_compile_options(${MAX_CUSTOM_OPT_LEVEL}) - endif() -endif() - -# santiziers (ASAN) -if(ECL_ASAN) - message(STATUS "ecl address sanitizer enabled ") - - # environment variables - # ASAN_OPTIONS=detect_stack_use_after_return=1 - # ASAN_OPTIONS=check_initialization_order=1 - - add_compile_options( - -fsanitize=address - -g3 - -O1 - -fno-omit-frame-pointer - ) - - set(CMAKE_EXE_LINKER_FLAGS ${CMAKE_EXE_LINKER_FLAGS} -fsanitize=address) -endif() - -add_subdirectory(EKF) - -if(BUILD_TESTING AND CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR) - add_subdirectory(test) -endif() - -#============================================================================= -# Coverage -# -if (${CMAKE_BUILD_TYPE} STREQUAL "Coverage") - - add_custom_target(coverage - COMMAND ${CMAKE_CTEST_COMMAND} - COMMAND lcov --capture --directory . --output-file coverage.info - COMMAND lcov --remove coverage.info --output-file coverage.info '/usr/*' '${CMAKE_BINARY_DIR}/*' # filter out system - COMMAND lcov --summary coverage.info - WORKING_DIRECTORY ${CMAKE_BUILD_DIR} - DEPENDS check - ) - - add_custom_target(coverage_html - COMMAND genhtml coverage.info --output-directory out - WORKING_DIRECTORY ${CMAKE_BUILD_DIR} - DEPENDS coverage - ) - - add_custom_target(coverage_html_view - COMMAND x-www-browser out/index.html - WORKING_DIRECTORY ${CMAKE_BUILD_DIR} - DEPENDS coverage_html - ) - -endif() - -#============================================================================= -# Doxygen -# -# Only in standalone build -if(CMAKE_SOURCE_DIR STREQUAL PROJECT_SOURCE_DIR) - - option(BUILD_DOXYGEN "Build doxygen documentation" OFF) - - if (BUILD_DOXYGEN) - find_package(Doxygen) - if (DOXYGEN_FOUND) - # set input and output files - set(DOXYGEN_IN ${CMAKE_CURRENT_SOURCE_DIR}/docs/Doxyfile.in) - set(DOXYGEN_OUT ${CMAKE_CURRENT_BINARY_DIR}/Doxyfile) - - # request to configure the file - configure_file(${DOXYGEN_IN} ${DOXYGEN_OUT} @ONLY) - - # note the option ALL which allows to build the docs together with the application - add_custom_target(doxygen ALL - COMMAND ${DOXYGEN_EXECUTABLE} ${DOXYGEN_OUT} - WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR} - COMMENT "Generating documentation with Doxygen" - DEPENDS - VERBATIM - USES_TERMINAL - ) - - else() - message(FATAL_ERROR "Doxygen needs to be installed to generate documentation") - endif() - endif() -endif() - diff --git a/src/lib/ecl/CONTRIBUTING.md b/src/lib/ecl/CONTRIBUTING.md deleted file mode 100644 index 263a27e796..0000000000 --- a/src/lib/ecl/CONTRIBUTING.md +++ /dev/null @@ -1,36 +0,0 @@ -# Contribution Guidelines - -## Auto-Formatting -ECL uses clang-format to auto-format the code. Currently it is using the clang-format-6.0. -The enforced style is based on the google style. Google's [Style Guide](https://google.github.io/styleguide/cppguide.html) is the place to look for advice. -The format is not enforced on all files. The list of files on which the auto-format checks are run on can be found in `tools/format.sh` - -On Ubuntu (tested on 18.04) the following command can be used to check if the code is complying with the format requirements -``` -make check_format -``` -To auto-format the code run -``` -make format -``` - -## Continuous Integration -There are multiple checks run on a submitted PR: - -| Test | Description | -| ------------- | ------------- | -| - **Build tests** | Checks if the submitted code is building on various platforms. | -| - **Unit tests** | Run checks if the code is satisfying test cases in `tests/` and report code coverage. | -| - **Format checks** | Check if the files specified in `/tools/format.sh` match the style specified in `.clang-format`. Run [auto-formatting](#Auto-Formatting) | -| - **Firmware build tests**| Pulls PX4/Firmware and checks if the current branch of ECL compiles with it. It tries to checkout a branch in PX4/Firmware with the name matching the current ECL branch name. If a branch with that name does not exist then it will checkout master. | - -## Unit tests -# How to run the tests -The test can be executed by running: -``` -make test -``` - -# How to add a test -tbd - diff --git a/src/lib/ecl/LICENSE b/src/lib/ecl/LICENSE deleted file mode 100644 index ec8290fc37..0000000000 --- a/src/lib/ecl/LICENSE +++ /dev/null @@ -1,28 +0,0 @@ -Copyright (c) 2015, Lorenz Meier -All rights reserved. - -Redistribution and use in source and binary forms, with or without -modification, are permitted provided that the following conditions are met: - -* Redistributions of source code must retain the above copyright notice, this - list of conditions and the following disclaimer. - -* 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. - -* Neither the name of libgnc 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 HOLDER 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. - diff --git a/src/lib/ecl/Makefile b/src/lib/ecl/Makefile deleted file mode 100644 index 0392ba8dd2..0000000000 --- a/src/lib/ecl/Makefile +++ /dev/null @@ -1,154 +0,0 @@ -############################################################################ -# -# Copyright (c) 2018 ECL 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. -# -############################################################################ - -# Parsing -# -------------------------------------------------------------------- -# assume 1st argument passed is the main target, the -# rest are arguments to pass to the makefile generated -# by cmake in the subdirectory -FIRST_ARG := $(firstword $(MAKECMDGOALS)) -ARGS := $(wordlist 2,$(words $(MAKECMDGOALS)),$(MAKECMDGOALS)) -j ?= 4 -BLUE='\033[1;36m' -NC='\033[0m' # No Color - -NINJA_BIN := ninja -ifndef NO_NINJA_BUILD - NINJA_BUILD := $(shell $(NINJA_BIN) --version 2>/dev/null) - - ifndef NINJA_BUILD - NINJA_BIN := ninja-build - NINJA_BUILD := $(shell $(NINJA_BIN) --version 2>/dev/null) - endif -endif - -ifdef NINJA_BUILD - PX4_CMAKE_GENERATOR := Ninja - PX4_MAKE := $(NINJA_BIN) - - ifdef VERBOSE - PX4_MAKE_ARGS := -v - else - PX4_MAKE_ARGS := - endif -else - ifdef SYSTEMROOT - # Windows - PX4_CMAKE_GENERATOR := "MSYS\ Makefiles" - else - PX4_CMAKE_GENERATOR := "Unix\ Makefiles" - endif - PX4_MAKE = $(MAKE) - PX4_MAKE_ARGS = -j$(j) --no-print-directory -endif - -SRC_DIR := $(shell dirname $(realpath $(lastword $(MAKEFILE_LIST)))) - -# Functions -# -------------------------------------------------------------------- -# describe how to build a cmake config -define cmake-build -+@$(eval BUILD_DIR = $(SRC_DIR)/build/$@$(BUILD_DIR_SUFFIX)) -+@if [ $(PX4_CMAKE_GENERATOR) = "Ninja" ] && [ -e $(BUILD_DIR)/Makefile ]; then rm -rf $(BUILD_DIR); fi -+@if [ ! -e $(BUILD_DIR)/CMakeCache.txt ]; then mkdir -p $(BUILD_DIR) && cd $(BUILD_DIR) && cmake $(2) -G"$(PX4_CMAKE_GENERATOR)" $(CMAKE_ARGS) $(3) $(4) $(5) || (rm -rf $(BUILD_DIR)); fi -+@(cd $(BUILD_DIR) && $(PX4_MAKE) $(PX4_MAKE_ARGS) $(ARGS)) -endef - - -all: - @$(call cmake-build,$@,$(SRC_DIR)) - -# Documentation -# -------------------------------------------------------------------- -doxygen: - @$(call cmake-build,$@,$(SRC_DIR), "-DBUILD_DOXYGEN=ON") - @cmake --build $(SRC_DIR)/build/doxygen --target doxygen - -# Testing -# -------------------------------------------------------------------- - -.PHONY: test_build test - -test_build: - @$(call cmake-build,$@,$(SRC_DIR), "-DBUILD_TESTING=ON") - -test: test_build - @cmake --build $(SRC_DIR)/build/test_build --target check - -test_build_asan: - @$(call cmake-build,$@,$(SRC_DIR), "-DECL_ASAN=ON", "-DBUILD_TESTING=ON") - -test_asan: test_build_asan - @cmake --build $(SRC_DIR)/build/test_build_asan --target check - -# Code coverage -# -------------------------------------------------------------------- - -coverage_build: - @$(call cmake-build,$@,$(SRC_DIR), "-DCMAKE_BUILD_TYPE=Coverage", "-DBUILD_TESTING=ON") - -coverage: coverage_build - @cmake --build $(SRC_DIR)/build/coverage_build --target coverage - -coverage_html: coverage_build - @cmake --build $(SRC_DIR)/build/coverage_build --target coverage_html - -coverage_html_view: coverage_build - @cmake --build $(SRC_DIR)/build/coverage_build --target coverage_html_view - -# Code formatting -# -------------------------------------------------------------------- -.PHONY: check_format format clang-format - -clang-format: - @echo -e ${BLUE}Check clang-format-6.0 installation${NC} - @if ! hash clang-format-6.0; then sudo apt install clang-format-6.0 -y; fi - -check_format: clang-format - @echo -e ${BLUE}Checking formatting with clang-format${NC} - @$(SRC_DIR)/tools/format.sh 0 - -format: clang-format - @echo -e ${BLUE}Formatting with clang-format${NC} - @$(SRC_DIR)/tools/format.sh 1 - -# Cleanup -# -------------------------------------------------------------------- -.PHONY: clean distclean - -clean: - @rm -rf $(SRC_DIR)/build - -distclean: - @git clean -ff -x -d . - diff --git a/src/lib/ecl/README.md b/src/lib/ecl/README.md deleted file mode 100644 index 19ea0b29a4..0000000000 --- a/src/lib/ecl/README.md +++ /dev/null @@ -1,61 +0,0 @@ -# ECL - -**Very lightweight Estimation & Control Library.** - -[![DOI](https://zenodo.org/badge/22634/PX4/PX4-ECL.svg)](https://zenodo.org/badge/latestdoi/22634/PX4/PX4-ECL) - -This library solves the estimation & control problems of a number of robots and drones. It accepts GPS, vision and inertial sensor inputs. It is extremely lightweight and efficient and yet has the rugged field-proven performance. - -The library is BSD 3-clause licensed. - -## EKF Documentation - - * [EKF Documentation and Tuning Guide](https://docs.px4.io/master/en/advanced_config/tuning_the_ecl_ekf.html) - -## Building EKF - -### Prerequisites: - - * Matrix: A lightweight, BSD-licensed matrix math library: https://github.com/px4/matrix - it is automatically included as submodule. - - -By following the steps mentioned below you can create a static library which can be included in projects: - -``` -make -// OR -mkdir build/ -cd build/ -cmake .. -make -``` - -## Testing ECL -By following the steps you can run the unit tests - -``` -make test -``` -### Change Indicator / Unit Tests -Change indication is the concept of running the EKF on different data-sets and compare the state of the EKF to a previous version. If a contributor makes a functional change that is run during the change_indication tests, this will produce a different output of the EKF's state. As the tests are run in CI, this checks if a contributor forgot to run the checks themselves and add the [new EKF's state outputs](https://github.com/PX4/ecl/blob/master/test/change_indication/iris_gps.csv) to the pull request. - -The unit tests include a check to see if the pull request results in a difference to the [output data csv file](https://github.com/PX4/ecl/blob/master/test/change_indication/iris_gps.csv) when replaying the [sensor data csv file](https://github.com/PX4/ecl/blob/master/test/replay_data/iris_gps.csv). If a pull request results in an expected difference, then it is important that the output reference file be re-generated and included as part of the pull request. A non-functional pull request should not result in changes to this file, however the default test case does not exercise all sensor types so this test passing is a necessary, but not sufficient requirement for a non-functional pull request. - -The functionality that supports this test consists of: -* Python scripts that extract sensor data from ulog files and writes them to a sensor data csv file. The default [sensor data csv file](https://github.com/PX4/ecl/blob/master/test/replay_data/iris_gps.csv) used by the unit test was generated from a ulog created from an iris SITL flight. -* A [script file](https://github.com/PX4/ecl/blob/master/test/test_EKF_withReplayData.cpp) using functionality provided by the [sensor simulator](https://github.com/PX4/ecl/blob/master/test/sensor_simulator/sensor_simulator.cpp), that loads sensor data from the [sensor data csv file](https://github.com/PX4/ecl/blob/master/test/replay_data/iris_gps.csv) , replays the EKF with it and logs the EKF's state and covariance data to the [output data csv file](https://github.com/PX4/ecl/blob/master/test/replay_data/iris_gps.csv). -* CI action that checks if the logs of the test running with replay data is changing. This helps to see if there are functional changes. - -#### How to run the Change Indicator test during development on your own logs: - -* create sensor_data.csv file from ulog file 'cd test/sensor_simulator/ -python3 createSensorDataFile.py ../replay_data/.csv' -* Setup the test file to use the EKF with the created sensor data by copy&paste an existing test case in [test/test_EKF_withReplayData.cpp](https://github.com/PX4/ecl/blob/master/test/test_EKF_withReplayData.cpp) and adapt the paths to load the right sensor data and write it to the right place, eg -_sensor_simulator.loadSensorDataFromFile("../../../test/replay_data/.csv"); -_ekf_logger.setFilePath("../../../test/change_indication/.csv"); -* You can feed the EKF with the data in the csv file, by running '_sensor_simulator.runReplaySeconds(duration_in_seconds)'. Be aware that replay sensor data will only be available when the corresponding sensor simulation are running. By default only imu, baro and mag sensor simulators are running. You can start a sensor simulation by calling _sensor_simulator._.start(). Be also aware that you still have to setup the EKF yourself. This includes setting the bit mask (fusion_mode in common.h) according to what you intend to fuse. -* In between _sensor_simulator.runReplaySeconds(duration_in_seconds) calls, write the state and covariances to the change_indication file by including a _ekf_logger.writeStateToFile(); line. -* Run the EKF with your data and all the other tests by running 'make test' from the ecl directory. The [default output data csv file](https://github.com/PX4/ecl/blob/master/test/change_indication/iris_gps.csv) changes can then be included in the PR if differences are causing the CI test to fail. - -#### Known Issues -If compiler versions other than GCC 7.5 are used to generate the output data file, then is is possible that the file will cause CI failures due to small numerical differences to file generated by the CI test. diff --git a/src/lib/ecl/docs/Doxyfile.in b/src/lib/ecl/docs/Doxyfile.in deleted file mode 100644 index 87413e35ef..0000000000 --- a/src/lib/ecl/docs/Doxyfile.in +++ /dev/null @@ -1,121 +0,0 @@ -# Use: `doxygen -g test.txt` to generate all possible settings for this file - -# For modern doxygen style uncomment these three lines: - #HTML_EXTRA_STYLESHEET = @CMAKE_CURRENT_SOURCE_DIR@/doxygen/customdoxygen.css - #HTML_HEADER = @CMAKE_SOURCE_DIR@/Documentation/header.html - #HTML_FOOTER = @CMAKE_SOURCE_DIR@/Documentation/footer.html - -# not interested build output -QUIET = YES - -# Basic settings: -PROJECT_NAME = "@CMAKE_PROJECT_NAME@" -PROJECT_NUMBER = @PROJECT_VERSION_MAJOR@.@PROJECT_VERSION_MINOR@.@PROJECT_VERSION_PATCH@@VERSION_TYPE@ -STRIP_FROM_PATH = @CMAKE_SOURCE_DIR@ - -INPUT = @CMAKE_SOURCE_DIR@/README.md \ - @CMAKE_SOURCE_DIR@ \ - @CMAKE_SOURCE_DIR@/src \ - @CMAKE_BINARY_DIR@/ \ - @CMAKE_BINARY_DIR@/uORB - -FILE_PATTERNS = *.h \ - *.hpp \ - *.hh \ - *.c \ - *.cc \ - *.cpp.in \ - *.cpp \ - *.md - -RECURSIVE = YES -USE_MDFILE_AS_MAINPAGE = "@CMAKE_SOURCE_DIR@/README.md" -# output location -HTML_OUTPUT = "@CMAKE_BINARY_DIR@/Documentation" - -IMAGE_PATH = "@CMAKE_SOURCE_DIR@" - -# The OUTPUT_LANGUAGE tag is used to specify the language in which all -# documentation generated by doxygen is written. Doxygen will use this -# information to generate all constant output in the proper language. -# Possible values are: Afrikaans, Arabic, Armenian, Brazilian, Catalan, Chinese, -# Chinese-Traditional, Croatian, Czech, Danish, Dutch, English (United States), -# Esperanto, Farsi (Persian), Finnish, French, German, Greek, Hungarian, -# Indonesian, Italian, Japanese, Japanese-en (Japanese with English messages), -# Korean, Korean-en (Korean with English messages), Latvian, Lithuanian, -# Macedonian, Norwegian, Persian (Farsi), Polish, Portuguese, Romanian, Russian, -# Serbian, Serbian-Cyrillic, Slovak, Slovene, Spanish, Swedish, Turkish, -# Ukrainian and Vietnamese. -# The default value is: English. -OUTPUT_LANGUAGE = English - -# Color style -HTML_COLORSTYLE_HUE = 220 -HTML_COLORSTYLE_SAT = 40 -HTML_COLORSTYLE_GAMMA = 80 - -# max size 200x55px -PROJECT_LOGO = - - -# If the REFERENCED_BY_RELATION tag is set to YES then for each documented -# function all documented functions referencing it will be listed. -# The default value is: NO. -REFERENCED_BY_RELATION = YES - -# If the REFERENCES_RELATION tag is set to YES then for each documented function -# all documented entities called/used by that function will be listed. -# The default value is: NO. -REFERENCES_RELATION = YES - -# This is nice to have - callgraphs of functions -HAVE_DOT = YES -CALL_GRAPH = YES -CALLER_GRAPH = YES - -GRAPHICAL_HIERARCHY = YES -DIRECTORY_GRAPH = YES -GENERATE_LEGEND = YES -INCLUDED_BY_GRAPH = YES -INCLUDE_GRAPH = YES -DOT_IMAGE_FORMAT = svg -INTERACTIVE_SVG = YES - -# More insight to templates, generaly not needed -TEMPLATE_RELATIONS = NO - -# in class diagrams, you will have members and such -# Also they will be bigger -UML_LOOK = YES -UML_LIMIT_NUM_FIELDS = 6 - -# should all pictures be collapsed? -HTML_DYNAMIC_SECTIONS = NO - - -# use with: /// @todo Do more stuff. -GENERATE_TODOLIST = YES - -# we want all we can get -EXTRACT_ALL = YES -EXTRACT_STATIC = YES -EXTRACT_PRIVATE = YES - -# We do not need latex output -GENERATE_LATEX = NO -USE_PDFLATEX = NO - -# this makes first sentence from comment block a brief description. -# It is VERY useful -JAVADOC_AUTOBRIEF = YES - -# Why not... -BUILTIN_STL_SUPPORT = YES - -# Do we want source code browser? YES! Do we want strip comments? NO -SOURCE_BROWSER = YES -STRIP_CODE_COMMENTS = NO - -# Side panel -# If you enable this, change .container max-width: 960px; to 1240px -GENERATE_TREEVIEW = YES diff --git a/src/lib/ecl/ecl.h b/src/lib/ecl/ecl.h deleted file mode 100644 index d961193b01..0000000000 --- a/src/lib/ecl/ecl.h +++ /dev/null @@ -1,90 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2013 Estimation and Control Library (ECL). 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 APL 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 ecl.h - * Adapter / shim layer for system calls needed by ECL - * - */ -#pragma once - -#if defined(__PX4_POSIX) || defined(__PX4_NUTTX) - -#include -#include - -#define ecl_absolute_time hrt_absolute_time -#define ecl_elapsed_time hrt_elapsed_time -using ecl_abstime = hrt_abstime; - -#if defined(__PX4_NUTTX) -# define ECL_INFO PX4_DEBUG -# define ECL_WARN PX4_DEBUG -# define ECL_ERR PX4_DEBUG -#else -# define ECL_INFO PX4_INFO -# define ECL_WARN PX4_WARN -# define ECL_ERR PX4_ERR -#endif - -#elif defined(__PAPARAZZI) - -#include "std.h" - -#define ecl_absolute_time() (0) -#define ecl_elapsed_time(t) (*t * 0UL) // TODO: add simple time functions - -using ecl_abstime = uint64_t; - -#define ECL_INFO(...) -#define ECL_WARN(...) -#define ECL_ERR(...) - -#else - -#include -#include - -#define ecl_absolute_time() (0) -#define ecl_elapsed_time(t) (*t * 0UL) // TODO: add simple time functions - -using ecl_abstime = uint64_t; - -#define ECL_INFO(X, ...) printf(X "\n", ##__VA_ARGS__) -#define ECL_WARN(X, ...) fprintf(stderr, X "\n", ##__VA_ARGS__) -#define ECL_ERR(X, ...) fprintf(stderr, X "\n", ##__VA_ARGS__) - -#endif /* PX4_POSIX || PX4_NUTTX */ - -#include -#define ISFINITE(x) __builtin_isfinite(x) diff --git a/src/lib/ecl/mathlib/mathlib.h b/src/lib/ecl/mathlib/mathlib.h deleted file mode 100644 index 8b24c94aea..0000000000 --- a/src/lib/ecl/mathlib/mathlib.h +++ /dev/null @@ -1,96 +0,0 @@ -/**************************************************************************** - * - * Copyright (C) 2012, 2014 PX4 Development Team. All rights reserved. - * - * Redistribution and use in source and binary forms, with or without - * modification, are permitted provided that the following conditions - * are met: - * - * 1. Redistributions of source code must retain the above copyright - * notice, this list of conditions and the following disclaimer. - * 2. Redistributions in binary form must reproduce the above copyright - * notice, this list of conditions and the following disclaimer in - * the documentation and/or other materials provided with the - * distribution. - * 3. Neither the name PX4 nor the names of its contributors may be - * used to endorse or promote products derived from this software - * without specific prior written permission. - * - * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS - * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT - * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS - * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE - * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, - * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, - * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS - * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED - * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT - * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN - * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE - * POSSIBILITY OF SUCH DAMAGE. - * - ****************************************************************************/ - -/** - * @file mathlib.h - * - * Target specific math functions and definitions - * - * @author Siddharth Bharat Purohit - */ -#ifndef MATHLIB_H -#define MATHLIB_H - -#ifdef ECL_STANDALONE - -#ifndef M_PI_F -#define M_PI_F 3.14159265358979323846f -#endif - -#ifndef M_PI_2_F -#define M_PI_2_F (M_PI / 2.0f) -#endif - -#ifndef M_PI -#define M_PI 3.141592653589793238462643383280 -#endif - -namespace math -{ -template -static constexpr Type min(Type val1, Type val2) -{ - return (val1 < val2) ? val1 : val2; -} - -template -static constexpr Type max(Type val1, Type val2) -{ - return (val1 > val2) ? val1 : val2; -} - -template -static constexpr Type constrain(Type val, Type min, Type max) -{ - return (val < min) ? min : ((val > max) ? max : val); -} - -template -static constexpr Type radians(Type degrees) -{ - return (degrees / Type(180)) * Type(M_PI); -} - -template -static constexpr Type degrees(Type radians) -{ - return (radians * Type(180)) / Type(M_PI); -} - -} // namespace math -#else - -#include - -#endif // ECL_STANDALONE -#endif // MATHLIB_H diff --git a/src/lib/ecl/test/CMakeLists.txt.in b/src/lib/ecl/test/CMakeLists.txt.in deleted file mode 100644 index a119c417b4..0000000000 --- a/src/lib/ecl/test/CMakeLists.txt.in +++ /dev/null @@ -1,19 +0,0 @@ -cmake_minimum_required(VERSION 2.8.4) - -project(googletest-download NONE) - -include(ExternalProject) -ExternalProject_Add(googletest - URL https://github.com/google/googletest/archive/8b6d3f9c4a774bef3081195d422993323b6bb2e0.zip - SOURCE_DIR "${CMAKE_CURRENT_BINARY_DIR}/googletest-src" - BINARY_DIR "${CMAKE_CURRENT_BINARY_DIR}/googletest-build" - CONFIGURE_COMMAND "" - BUILD_COMMAND "" - INSTALL_COMMAND "" - TEST_COMMAND "" - # Wrap download, configure and build steps in a script to log output - LOG_DOWNLOAD ON - LOG_CONFIGURE ON - LOG_BUILD ON -) - diff --git a/src/lib/ecl/test/change_indication/ekf_gsf_reset.csv b/src/lib/ecl/test/change_indication/ekf_gsf_reset.csv deleted file mode 100644 index 2c2021a84b..0000000000 --- a/src/lib/ecl/test/change_indication/ekf_gsf_reset.csv +++ /dev/null @@ -1,391 +0,0 @@ -Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -15000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -85000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -185000,0.999749,-0.0104069,-0.0107853,-0.0166343,0.000120003,-0.000106777,-0.0115085,1.36672e-05,-4.60598e-06,-0.000265304,1.72362e-15,-3.18881e-15,-1.02506e-16,0,0,-7.93589e-11,0.191514,0.00185997,0.404127,0,0,0,0,0,1.95304e-06,0.00251574,0.0025157,0.00501391,0.256461,0.256461,0.562563,0.126414,0.126414,1.00079,1e-06,1e-06,1e-06,4e-06,4e-06,4.00001e-06,0,0,0,0,0,0,0,0 -285000,0.999745,-0.010498,-0.0111248,-0.0166139,0.00135604,0.000386777,-0.0252008,7.07068e-05,-1.58746e-05,-0.00161356,2.51669e-14,2.38317e-14,-5.59251e-17,0,0,-1.75435e-09,0.191514,0.00185997,0.404127,0,0,0,0,0,2.00622e-06,0.0025808,0.00258074,0.00507893,0.282565,0.282564,0.562506,0.132891,0.132891,0.576885,1e-06,1e-06,1e-06,4e-06,4e-06,4.00001e-06,0,0,0,0,0,0,0,0 -385000,0.999742,-0.0105086,-0.0114167,-0.0165992,0.00279367,0.000841279,-0.0397786,0.000234117,6.61504e-05,-0.00379265,3.97567e-11,-5.70702e-10,-1.26583e-11,0,0,-1.90055e-08,0.191514,0.00185997,0.404127,0,0,0,0,0,2.07976e-06,0.00269232,0.00269222,0.00519394,0.320083,0.320083,0.560114,0.0942307,0.0942307,0.375592,9.99994e-07,9.99994e-07,1e-06,4e-06,4e-06,3.99998e-06,0,0,0,0,0,0,0,0 -485000,0.999736,-0.0105821,-0.0117682,-0.0166396,0.00565568,1.37733e-05,-0.0548207,0.00067319,9.33786e-05,-0.00682881,3.12871e-11,-5.37575e-10,-1.17921e-11,0,0,-9.60387e-08,0.191514,0.00185997,0.404127,0,0,0,0,0,2.19976e-06,0.00285733,0.00285719,0.00535892,0.388412,0.388412,0.553871,0.109483,0.109483,0.287379,9.99994e-07,9.99994e-07,1e-06,4e-06,4e-06,3.99978e-06,0,0,0,0,0,0,0,0 -585000,0.999733,-0.0105813,-0.0120572,-0.0166371,0.00777812,0.000772913,-0.0669065,0.00103104,9.86188e-05,-0.0105822,4.48799e-09,-3.17219e-08,-7.49171e-10,0,0,-3.1415e-07,0.191514,0.00185997,0.404127,0,0,0,0,0,2.32138e-06,0.00302178,0.0030216,0.00557389,0.437997,0.437998,0.542812,0.0905593,0.0905593,0.242024,9.99626e-07,9.99626e-07,1e-06,4e-06,4e-06,3.99919e-06,0,0,0,0,0,0,0,0 -685000,0.999729,-0.0107148,-0.0123314,-0.0165748,0.0105358,-6.92627e-05,-0.079897,0.00191778,0.000106049,-0.0148862,4.46063e-09,-3.12371e-08,-7.38593e-10,0,0,-8.02325e-07,0.191514,0.00185997,0.404127,0,0,0,0,0,2.48169e-06,0.00328539,0.00328518,0.00583886,0.550739,0.55074,0.525906,0.117326,0.117326,0.217499,9.99626e-07,9.99626e-07,1e-06,4e-06,4e-06,3.99786e-06,0,0,0,0,0,0,0,0 -785000,0.999725,-0.0108223,-0.0126169,-0.0165619,0.011657,0.000229059,-0.0924465,0.00210485,5.69564e-05,-0.0206973,2.09481e-08,-2.70114e-07,-6.00229e-09,0,0,-1.43884e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.6284e-06,0.00338379,0.00338354,0.00615375,0.570988,0.57099,0.510947,0.101431,0.101431,0.215594,9.96274e-07,9.96274e-07,9.99998e-07,4e-06,4e-06,3.99614e-06,0,0,0,0,0,0,0,0 -885000,0.999721,-0.0109303,-0.0128766,-0.0165376,0.0162462,-0.000778969,-0.10711,0.00348551,-7.81696e-06,-0.0306738,2.09481e-08,-2.70114e-07,-6.00229e-09,0,0,-1.43884e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.85507e-06,0.00373878,0.00373848,0.00651869,0.7243,0.724304,0.516584,0.14145,0.14145,0.256222,9.96274e-07,9.96274e-07,9.99998e-07,4e-06,4e-06,3.99615e-06,0,0,0,0,0,0,0,0 -985000,0.999721,-0.0109898,-0.0128333,-0.0165236,0.0126831,-0.00203945,-0.122007,0.000610238,-5.99813e-05,-0.0421172,4.99418e-08,-2.11702e-06,-4.45929e-08,0,0,-1.49185e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.78209e-06,0.00300321,0.00300296,0.00693337,0.356058,0.356061,0.523019,0.0107839,0.0107838,0.307346,9.6711e-07,9.67111e-07,9.99974e-07,4e-06,4e-06,3.99611e-06,0,0,0,0,0,0,0,0 -1085000,0.999716,-0.011085,-0.0131015,-0.0165326,0.0163993,-0.00349004,-0.137292,0.00204637,-0.000342056,-0.0550953,4.99418e-08,-2.11702e-06,-4.45929e-08,0,0,-1.49185e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,3.05749e-06,0.00339941,0.00339912,0.00739825,0.478053,0.47806,0.530253,0.0206295,0.0206295,0.369156,9.67111e-07,9.67111e-07,9.99974e-07,4e-06,4e-06,3.99612e-06,0,0,0,0,0,0,0,0 -1185000,0.99972,-0.0110493,-0.0127801,-0.0165422,0.0105042,-0.00320134,-0.151796,0.000948076,-0.000202109,-0.0695985,-6.90706e-07,-6.81453e-06,-1.24191e-07,0,0,-1.57127e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.93855e-06,0.00247981,0.00247963,0.0079129,0.267211,0.267215,0.538284,0.00905214,0.00905216,0.441868,8.82401e-07,8.82403e-07,9.99906e-07,4e-06,4e-06,3.9961e-06,0,0,0,0,0,0,0,0 -1285000,0.999717,-0.0110792,-0.013054,-0.0164982,0.0137383,-0.00402021,-0.165326,0.00216359,-0.000581329,-0.0854412,-6.90706e-07,-6.81453e-06,-1.24191e-07,0,0,-1.57127e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,3.21786e-06,0.0028631,0.00286286,0.00847774,0.363878,0.363885,0.547115,0.0191651,0.0191653,0.52572,8.82401e-07,8.82403e-07,9.99906e-07,4e-06,4e-06,3.99611e-06,0,0,0,0,0,0,0,0 -1385000,0.999723,-0.0110103,-0.0127015,-0.0164742,0.00884309,-0.00296782,-0.177908,0.000873293,-0.000243153,-0.102594,-2.04449e-06,-1.2483e-05,-2.09704e-07,0,0,-1.63645e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,3.11044e-06,0.00198877,0.00198865,0.00909238,0.171571,0.171575,0.556743,0.0083586,0.00835862,0.620974,7.70981e-07,7.70983e-07,9.99818e-07,4e-06,4e-06,3.9961e-06,0,0,0,0,0,0,0,0 -1485000,0.999719,-0.0110905,-0.0129045,-0.0164924,0.0119022,-0.00370286,-0.192233,0.00192499,-0.000563666,-0.121082,-2.04449e-06,-1.2483e-05,-2.09704e-07,0,0,-1.63645e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,3.41836e-06,0.00233704,0.00233689,0.00975716,0.242067,0.242074,0.56717,0.0162905,0.0162907,0.727918,7.70981e-07,7.70983e-07,9.99818e-07,4e-06,4e-06,3.99611e-06,0,0,0,0,0,0,0,0 -1585000,0.999724,-0.0109819,-0.0126149,-0.0164979,0.00823143,-0.0020588,-0.205922,0.000810815,-0.000237979,-0.141007,-3.48262e-06,-1.80565e-05,-2.91971e-07,0,0,-1.66801e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,3.4203e-06,0.00173659,0.00173653,0.0104718,0.1272,0.127203,0.578395,0.00753193,0.00753196,0.846859,6.56482e-07,6.56484e-07,9.99726e-07,4e-06,4e-06,3.99612e-06,0,0,0,0,0,0,0,0 -1685000,0.99972,-0.0110818,-0.0127909,-0.0165248,0.0126289,-0.00481329,-0.218062,0.00187481,-0.00059383,-0.162185,-3.48262e-06,-1.80565e-05,-2.91971e-07,0,0,-1.66801e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,3.74773e-06,0.00205275,0.00205267,0.0112365,0.186462,0.186468,0.590421,0.0138714,0.0138716,0.978135,6.56482e-07,6.56484e-07,9.99726e-07,4e-06,4e-06,3.99613e-06,0,0,0,0,0,0,0,0 -1785000,0.999717,-0.0111059,-0.0130337,-0.0165447,0.0174087,-0.0071462,-0.232864,0.00335067,-0.00118341,-0.184735,-3.48262e-06,-1.80565e-05,-2.91971e-07,0,0,-1.66801e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,4.10208e-06,0.00240174,0.00240161,0.0120512,0.266815,0.266826,0.603247,0.0251807,0.0251811,1.1221,6.56482e-07,6.56485e-07,9.99726e-07,4e-06,4e-06,3.99614e-06,0,0,0,0,0,0,0,0 -1885000,0.999724,-0.0109131,-0.0126204,-0.0165675,0.0145994,-0.00608426,-0.247028,0.00209916,-0.000832639,-0.208741,-5.58209e-06,-2.46293e-05,-3.78757e-07,0,0,-1.67365e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,4.14032e-06,0.00180571,0.00180567,0.0129158,0.16315,0.163157,0.616867,0.0123711,0.0123713,1.27914,5.32085e-07,5.32087e-07,9.99632e-07,4e-06,4e-06,3.99615e-06,0,0,0,0,0,0,0,0 -1985000,0.999722,-0.0109281,-0.0127319,-0.0165596,0.0185479,-0.00731918,-0.260969,0.00377431,-0.00151836,-0.234154,-5.58209e-06,-2.46293e-05,-3.78757e-07,0,0,-1.67365e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,4.48496e-06,0.00210689,0.00210684,0.0138305,0.235655,0.235666,0.631289,0.0222676,0.0222681,1.44967,5.32086e-07,5.32087e-07,9.99632e-07,4e-06,4e-06,3.99616e-06,0,0,0,0,0,0,0,0 -2085000,0.999731,-0.0106724,-0.0121965,-0.0165908,0.0123375,-0.00560843,-0.274824,0.00210328,-0.00087578,-0.260959,-8.51046e-06,-3.26707e-05,-4.75077e-07,0,0,-1.64944e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,4.55686e-06,0.00150666,0.0015067,0.0147951,0.146622,0.146627,0.646504,0.0113683,0.0113684,1.6341,4.04342e-07,4.04344e-07,9.99545e-07,4e-06,4e-06,3.99617e-06,0,0,0,0,0,0,0,0 -2185000,0.999729,-0.0107365,-0.0123217,-0.0165933,0.0159377,-0.00628195,-0.289414,0.00351657,-0.00149576,-0.289197,-8.51046e-06,-3.26707e-05,-4.75077e-07,0,0,-1.64944e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,4.91517e-06,0.00174896,0.00174901,0.0158098,0.210266,0.210274,0.662523,0.0203171,0.0203175,1.83289,4.04342e-07,4.04344e-07,9.99546e-07,4e-06,4e-06,3.99618e-06,0,0,0,0,0,0,0,0 -2285000,0.999737,-0.0105501,-0.0117876,-0.0166091,0.0109237,-0.00428364,-0.303984,0.00185086,-0.000737683,-0.318902,-1.13391e-05,-4.00908e-05,-5.59947e-07,0,0,-1.60256e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,5.02567e-06,0.00118464,0.00118478,0.0168743,0.128273,0.128277,0.679335,0.0105102,0.0105103,2.04653,2.90729e-07,2.90728e-07,9.99469e-07,4e-06,4e-06,3.99618e-06,0,0,0,0,0,0,0,0 -2385000,0.999736,-0.0105717,-0.0118673,-0.0166011,0.0131399,-0.00529621,-0.31731,0.0030607,-0.00123697,-0.349949,-1.13391e-05,-4.00908e-05,-5.59947e-07,0,0,-1.60256e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,5.38216e-06,0.00136757,0.00136772,0.0179889,0.181106,0.181111,0.69695,0.0184948,0.0184951,2.27552,2.90729e-07,2.90729e-07,9.99469e-07,4e-06,4e-06,3.99619e-06,0,0,0,0,0,0,0,0 -2485000,0.999743,-0.0103847,-0.0114318,-0.0166135,0.00780226,-0.00292395,-0.329472,0.00155296,-0.000585634,-0.382301,-1.34874e-05,-4.60584e-05,-6.31815e-07,0,0,-1.5468e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,5.5552e-06,0.000896994,0.0008972,0.0191534,0.108508,0.108511,0.715359,0.00967057,0.00967065,2.52037,2.0276e-07,2.02757e-07,9.99406e-07,4e-06,4e-06,3.9962e-06,0,0,0,0,0,0,0,0 -2585000,0.999742,-0.0104239,-0.0115025,-0.0165968,0.00929095,-0.00277751,-0.343195,0.00241653,-0.000866416,-0.415926,-1.34874e-05,-4.60584e-05,-6.31815e-07,0,0,-1.5468e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,5.91664e-06,0.00103011,0.00103034,0.020368,0.15068,0.150684,0.73457,0.0166302,0.0166304,2.78164,2.0276e-07,2.02757e-07,9.99406e-07,4e-06,4e-06,3.99621e-06,0,0,0,0,0,0,0,0 -2685000,0.999746,-0.0103141,-0.0112307,-0.0166006,0.00498836,-0.00082403,-0.356256,0.00115934,-0.00037715,-0.45096,-1.47737e-05,-5.01819e-05,-6.88362e-07,0,0,-1.49624e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,6.15435e-06,0.000671478,0.000671713,0.0216324,0.0902532,0.0902555,0.754576,0.00886233,0.00886238,3.05991,1.40504e-07,1.40497e-07,9.99352e-07,4e-06,4e-06,3.99621e-06,0,0,0,0,0,0,0,0 -2785000,0.999745,-0.0102919,-0.0113506,-0.0166055,0.00587219,-0.00112477,-0.368436,0.00170691,-0.000490661,-0.487199,-1.47737e-05,-5.01819e-05,-6.88362e-07,0,0,-1.49624e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,6.54653e-06,0.000767411,0.000767618,0.0229469,0.123297,0.123301,0.775384,0.0148475,0.0148477,3.35577,1.40504e-07,1.40497e-07,9.99352e-07,4e-06,4e-06,3.99622e-06,0,0,0,0,0,0,0,0 -2885000,0.999746,-0.0102773,-0.0111622,-0.0166504,0.00297893,-0.000395802,-0.380623,0.00081154,-0.000187033,-0.524675,-1.53365e-05,-5.2666e-05,-7.30853e-07,0,0,-1.45928e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,6.87997e-06,0.000505931,0.000506148,0.024311,0.074804,0.074807,0.796988,0.00811991,0.00811996,3.66985,9.81646e-08,9.81522e-08,9.993e-07,4e-06,4e-06,3.99622e-06,0,0,0,0,0,0,0,0 -2985000,0.999747,-0.0102553,-0.0112032,-0.0166067,0.00446986,-0.000166719,-0.394401,0.00120227,-0.000227821,-0.563429,-1.53365e-05,-5.2666e-05,-7.30853e-07,0,0,-1.45928e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,7.2521e-06,0.000575515,0.00057573,0.0257255,0.100801,0.100805,0.819393,0.0132525,0.0132527,4.00278,9.81647e-08,9.81523e-08,9.993e-07,4e-06,4e-06,3.99623e-06,0,0,0,0,0,0,0,0 -3085000,0.999748,-0.0102449,-0.0110944,-0.0165994,0.00203413,0.000269205,-0.406812,0.000597363,-7.47543e-05,-0.603508,-1.55316e-05,-5.4192e-05,-7.6432e-07,0,0,-1.43326e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,7.59609e-06,0.000387005,0.000387189,0.0271894,0.0624176,0.0624208,0.842594,0.00746182,0.00746188,4.35524,6.95679e-08,6.95493e-08,9.99252e-07,4e-06,4e-06,3.99622e-06,0,0,0,0,0,0,0,0 -3185000,0.999747,-0.0102881,-0.0110949,-0.0166652,0.00261467,0.00116192,-0.420885,0.000807255,-1.66481e-05,-0.644885,-1.55316e-05,-5.4192e-05,-7.6432e-07,0,0,-1.43326e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,8.08873e-06,0.000438212,0.000438446,0.0287037,0.083064,0.0830681,0.866595,0.0118841,0.0118843,4.72793,6.9568e-08,6.95494e-08,9.99252e-07,4e-06,4e-06,3.99623e-06,0,0,0,0,0,0,0,0 -3285000,0.701637,0.000871347,-0.0150624,0.712375,0.00205559,0.00109695,-0.433446,0.00041899,5.60196e-05,-0.687606,-1.54297e-05,-5.50655e-05,-7.95374e-07,0,0,-1.41857e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00122249,0.00030044,0.00030043,0.0184788,0.0526107,0.0526128,0.891394,0.00688816,0.00688823,5.12156,5.00578e-08,5.00329e-08,9.99203e-07,4e-06,4e-06,3.99623e-06,0,0,0,0,0,0,0,0 -3385000,0.703027,0.0009077,-0.0150464,0.711003,0.00222349,0.00104745,-0.446891,0.000627231,0.000186165,-0.73161,-1.54298e-05,-5.50654e-05,-8.028e-07,0,0,-1.41857e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00119054,0.000300584,0.000300863,0.00754229,0.053949,0.0539485,0.916993,0.0104947,0.0104948,5.53687,5.00575e-08,5.00327e-08,9.98239e-07,4e-06,4e-06,3.99624e-06,0,0,0,0,0,0,0,0 -3485000,0.70384,0.000912779,-0.0150788,0.710198,0.0020629,0.00171202,-0.459796,0.000367248,0.000148319,-0.776957,-1.51483e-05,-5.56928e-05,8.30235e-07,0,0,-1.41668e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00121458,0.000302527,0.000302862,0.00507472,0.0306476,0.0306386,0.943389,0.00615882,0.00615885,5.97462,3.78057e-08,3.77791e-08,9.93525e-07,4e-06,4e-06,3.99625e-06,0,0,0,0,0,0,0,0 -3585000,0.702861,0.000936012,-0.0150605,0.711167,0.00312702,0.00113959,-0.473305,0.000636736,0.000281521,-0.823619,-1.52408e-05,-5.56188e-05,-3.3147e-06,0,0,-1.41639e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00126726,0.0003072,0.00030755,0.00420134,0.0363313,0.0363062,0.970584,0.00864883,0.00864861,6.43562,3.78022e-08,3.77767e-08,9.86113e-07,4e-06,4e-06,3.99626e-06,0,0,0,0,0,0,0,0 -3685000,0.702933,0.000939886,-0.0150723,0.711096,0.00344369,0.00149284,-0.48707,0.000459848,0.000209357,-0.871597,-1.49485e-05,-5.62066e-05,-1.6323e-06,0,0,-1.44388e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133888,0.00030464,0.000304929,0.00350528,0.0282524,0.0282195,0.998574,0.00544157,0.00544132,6.92065,3.11093e-08,3.10942e-08,9.69546e-07,4e-06,4e-06,3.99624e-06,0,0,0,0,0,0,0,0 -3785000,0.703333,0.000915315,-0.0151066,0.7107,0.00496018,0.00179594,-0.500085,0.000865214,0.000372312,-0.920968,-1.48278e-05,-5.6302e-05,3.69425e-06,0,0,-1.44439e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00142813,0.000311623,0.000311914,0.0030701,0.0375394,0.0374823,1.02737,0.0075113,0.00750991,7.43058,3.10966e-08,3.10862e-08,9.44479e-07,4e-06,4e-06,3.99625e-06,0,0,0,0,0,0,0,0 -3885000,0.703456,0.000963708,-0.0150419,0.710579,0.00458651,0.00125405,-0.514048,0.00134431,0.000522976,-0.971647,-1.47952e-05,-5.63295e-05,5.17044e-06,0,0,-1.44449e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0015296,0.000320156,0.000320435,0.00277173,0.0493655,0.0492895,1.05696,0.0104863,0.0104823,7.96626,3.10798e-08,3.10743e-08,9.09799e-07,4e-06,4e-06,3.99626e-06,0,0,0,0,0,0,0,0 -3985000,0.703211,0.00103389,-0.0149289,0.710824,0.00347091,0.0019525,-0.527857,0.000993822,0.00037343,-1.02366,-1.47515e-05,-5.6789e-05,-5.31838e-07,0,0,-1.5251e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00163627,0.000301087,0.00030118,0.00255298,0.0450911,0.0450389,1.08733,0.00715604,0.00715336,8.52853,2.77693e-08,2.77911e-08,8.65713e-07,4e-06,4e-06,3.99617e-06,0,0,0,0,0,0,0,0 -4085000,0.703228,0.000995615,-0.0148888,0.710808,0.00403674,0.00275245,-0.541046,0.00135098,0.00061975,-1.07709,-1.47458e-05,-5.67943e-05,-2.62964e-07,0,0,-1.52512e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0017439,0.000311253,0.000311333,0.00238852,0.0593387,0.0592727,1.11852,0.0104191,0.0104133,9.11838,2.77444e-08,2.77727e-08,8.14174e-07,4e-06,4e-06,3.99618e-06,0,0,0,0,0,0,0,0 -4185000,0.703088,0.00100845,-0.0147646,0.710949,0.00351098,0.00302234,-0.55546,0.000925745,0.000537039,-1.13184,-1.47742e-05,-5.70989e-05,-3.84606e-06,0,0,-1.65669e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0018603,0.000268403,0.000268164,0.00229042,0.0507241,0.0506995,1.15048,0.00725721,0.00725457,9.73659,2.65264e-08,2.65774e-08,7.71486e-07,4e-06,4e-06,3.99601e-06,0,0,0,0,0,0,0,0 -4285000,0.703296,0.00102692,-0.0147835,0.710743,0.00182314,0.00356943,-0.568617,0.00121654,0.000860023,-1.18808,-1.46737e-05,-5.71896e-05,8.04332e-07,0,0,-1.6571e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00195602,0.000280005,0.000279755,0.00218045,0.0654376,0.0654274,1.18326,0.0109092,0.0109047,10.3843,2.64982e-08,2.65547e-08,7.11163e-07,4e-06,4e-06,3.99602e-06,0,0,0,0,0,0,0,0 -4385000,0.703886,0.00103428,-0.0146685,0.710161,-0.000268434,0.00244277,-0.582867,0.000569534,0.000604775,-1.24554,-1.44425e-05,-5.76626e-05,1.50689e-05,0,0,-1.81533e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00203568,0.000222562,0.000221843,0.00208707,0.0503406,0.0503669,1.21681,0.00736153,0.00736056,11.0623,2.60972e-08,2.61585e-08,6.48903e-07,4e-06,4e-06,3.99581e-06,0,0,0,0,0,0,0,0 -4485000,0.703489,0.0010631,-0.0146466,0.710555,-0.000672014,0.00218402,-0.597721,0.000498423,0.000830294,-1.30454,-1.46501e-05,-5.74653e-05,5.20306e-06,0,0,-1.81465e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00210334,0.000235307,0.00023458,0.00201137,0.0637404,0.063785,1.25118,0.01113,0.0111298,11.7719,2.60702e-08,2.61342e-08,5.87709e-07,4e-06,4e-06,3.99582e-06,0,0,0,0,0,0,0,0 -4585000,0.703942,0.00100433,-0.0145994,0.710106,-0.00106875,0.00245564,-0.612174,0.000136471,0.000533379,-1.36496,-1.45424e-05,-5.77882e-05,1.58621e-05,0,0,-1.90498e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00215288,0.000180449,0.000179163,0.00194492,0.0453619,0.0454026,1.28633,0.00722652,0.00722733,12.5137,2.55276e-08,2.558e-08,5.2855e-07,4e-06,4e-06,3.99563e-06,0,0,0,0,0,0,0,0 -4685000,0.704446,0.000987719,-0.0145742,0.709607,-0.000364425,0.00246148,-0.626181,4.80882e-05,0.000782339,-1.42689,-1.43324e-05,-5.79946e-05,2.60816e-05,0,0,-1.9054e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00219127,0.000193994,0.000192697,0.0018894,0.0566813,0.0567355,1.3223,0.0107973,0.0108002,13.2892,2.55045e-08,2.55575e-08,4.73402e-07,4e-06,4e-06,3.99564e-06,0,0,0,0,0,0,0,0 -4785000,0.704052,0.000900703,-0.0145471,0.709999,-0.000149626,0.00164942,-0.640941,-9.9146e-06,0.000464204,-1.49021,-1.46654e-05,-5.79241e-05,1.51182e-05,0,0,-1.94655e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0022144,0.000150756,0.000148956,0.0018398,0.0391263,0.0391597,1.35905,0.00688943,0.00689096,14.0991,2.44939e-08,2.45313e-08,4.22374e-07,4e-06,4e-06,3.99552e-06,0,0,0,0,0,0,0,0 -4885000,0.704322,0.000884567,-0.0145656,0.70973,0.000604872,0.00170643,-0.655736,-2.667e-07,0.000653911,-1.55502,-1.45737e-05,-5.80164e-05,1.96921e-05,0,0,-1.94659e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00226189,0.000164789,0.000162965,0.00181064,0.048605,0.0486477,1.39662,0.0101116,0.0101152,14.9449,2.44798e-08,2.45171e-08,3.87171e-07,4e-06,4e-06,3.99553e-06,0,0,0,0,0,0,0,0 -4985000,0.70413,0.000908059,-0.0144941,0.709923,0.000156579,0.00197266,-0.670499,2.91234e-05,0.000419559,-1.62127,-1.48166e-05,-5.80501e-05,1.38777e-05,0,0,-1.97057e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00226502,0.000132879,0.000130662,0.00177119,0.0337472,0.0337682,1.43497,0.00647384,0.00647534,15.8273,2.30491e-08,2.30733e-08,3.44408e-07,4e-06,4e-06,3.99547e-06,0,0,0,0,0,0,0,0 -5085000,0.704537,0.00088895,-0.0145282,0.709518,-4.30217e-05,0.00168262,-0.685267,2.9867e-05,0.000603484,-1.68902,-1.46638e-05,-5.82034e-05,2.15627e-05,0,0,-1.97043e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0022619,0.000147101,0.000144854,0.00173686,0.0419261,0.0419527,1.47413,0.00934289,0.00934596,16.7478,2.30342e-08,2.30583e-08,3.06462e-07,4e-06,4e-06,3.99548e-06,0,0,0,0,0,0,0,0 -5185000,0.705085,0.000865908,-0.0144712,0.708975,0.000435831,0.00126992,-0.698872,4.00596e-05,0.000350809,-1.75823,-1.46009e-05,-5.85477e-05,3.12103e-05,0,0,-1.9819e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00225181,0.000122801,0.000120302,0.00170561,0.0298132,0.0298231,1.51409,0.00606765,0.00606883,17.7073,2.12909e-08,2.13057e-08,2.72761e-07,4e-06,4e-06,3.99544e-06,0,0,0,0,0,0,0,0 -5285000,0.705521,0.000892848,-0.0144489,0.708541,-0.000251793,-0.00022385,-0.713212,7.75639e-05,0.00040553,-1.8288,-1.44851e-05,-5.86629e-05,3.70693e-05,0,0,-1.98166e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00223822,0.000136936,0.000134387,0.00167733,0.0371857,0.0371985,1.55485,0.00864401,0.00864614,18.7072,2.12795e-08,2.12943e-08,2.43042e-07,4e-06,4e-06,3.99545e-06,0,0,0,0,0,0,0,0 -5385000,0.705152,0.000985199,-0.0144351,0.708908,-0.000187114,-0.00205154,-0.727386,1.9716e-05,0.000111313,-1.90084,-1.47114e-05,-5.85716e-05,2.86292e-05,0,0,-1.98396e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00222093,0.000116725,0.000114012,0.00165167,0.0271922,0.0271959,1.5964,0.00571041,0.0057112,19.7486,1.92964e-08,1.9305e-08,2.1696e-07,4e-06,4e-06,3.99544e-06,0,0,0,0,0,0,0,0 -5485000,0.705163,0.00102396,-0.0143954,0.708898,-0.000188797,-0.00248183,-0.740667,1.87685e-05,-0.000129287,-1.97423,-1.47394e-05,-5.85441e-05,2.72076e-05,0,0,-1.98406e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00223223,0.000130475,0.000127705,0.00163617,0.0340905,0.0340934,1.63876,0.00806703,0.00806832,20.8329,1.92897e-08,1.92985e-08,1.99486e-07,4e-06,4e-06,3.99545e-06,0,0,0,0,0,0,0,0 -5585000,0.705135,0.00103969,-0.0143704,0.708927,-0.000559596,-0.00251137,-0.755011,-2.47287e-05,-0.000207264,-2.049,-1.47194e-05,-5.83946e-05,2.48532e-05,0,0,-1.98686e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00220894,0.000111809,0.000108968,0.00161449,0.0254952,0.0254928,1.68192,0.00541145,0.00541188,21.9611,1.71228e-08,1.71272e-08,1.78641e-07,4e-06,4e-06,3.99545e-06,0,0,0,0,0,0,0,0 -5685000,0.704826,0.00109142,-0.0143024,0.709235,-0.0017163,-0.00304645,-0.770182,-0.000117786,-0.000470992,-2.12524,-1.48321e-05,-5.82849e-05,1.91091e-05,0,0,-1.98742e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00218451,0.00012486,0.000121954,0.00159493,0.0321107,0.0321057,1.72587,0.00760982,0.00761034,23.1347,1.71158e-08,1.71206e-08,1.60314e-07,4e-06,4e-06,3.99546e-06,0,0,0,0,0,0,0,0 -5785000,0.704597,0.001158,-0.0142999,0.709463,-0.00298092,-0.00280311,-0.00303779,-0.000173468,-0.000396554,-365.429,-1.47112e-05,-5.79885e-05,1.43772e-05,0,0,-1.99699e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0021592,0.000106297,0.000103379,0.00157703,0.024316,0.0243088,9.99879,0.00516443,0.00516454,2.00225,1.48377e-08,1.48397e-08,1.44218e-07,4e-06,4e-06,3.99546e-06,0,0,0,0,0,0,0,0 -5885000,0.704474,0.00116391,-0.0142687,0.709586,-0.00356442,-0.00245435,-0.00579809,-0.000465582,-0.000645752,-365.42,-1.47656e-05,-5.79366e-05,1.16233e-05,0,0,-2.02577e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00213385,0.000118344,0.000115371,0.00156061,0.0306657,0.0306544,9.73938,0.00724604,0.00724594,0.709951,1.48323e-08,1.48347e-08,1.30038e-07,4e-06,4e-06,3.99547e-06,0,0,0,0,0,0,0,0 -5985000,0.704454,0.00120575,-0.0142667,0.709605,-0.00571984,-0.0028318,0.0038086,-0.000963281,-0.000915015,-365.403,-1.47802e-05,-5.79226e-05,1.08868e-05,0,0,-2.12893e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00210866,0.000131138,0.000128104,0.00154558,0.0382562,0.038239,8.83902,0.0101614,0.0101608,0.518921,1.48275e-08,1.48304e-08,1.17561e-07,4e-06,4e-06,3.99546e-06,0,0,0,0,0,0,0,0 -6085000,0.704836,0.00121021,-0.0142873,0.709226,-0.00605772,-0.00136597,-0.0126427,-0.00100289,-0.000611105,-365.405,-1.42615e-05,-5.78232e-05,1.56839e-05,0,0,-2.11806e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00208372,0.000110166,0.000107196,0.00153144,0.0293607,0.0293448,7.28748,0.00694191,0.00694131,0.482341,1.25409e-08,1.25421e-08,1.06524e-07,4e-06,4e-06,3.99537e-06,0,0,0,0,0,0,0,0 -6185000,0.704841,0.00115664,-0.0142604,0.709221,-0.00812101,-0.00189629,-0.0130962,-0.00171753,-0.000762373,-365.401,-1.42919e-05,-5.77947e-05,1.41556e-05,0,0,-2.27441e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00208274,0.000121596,0.000118585,0.00152251,0.0365655,0.0365433,5.96608,0.00972679,0.00972529,0.537941,1.25381e-08,1.25396e-08,9.90897e-08,4e-06,4e-06,3.99522e-06,0,0,0,0,0,0,0,0 -6285000,0.705126,0.00110918,-0.0143353,0.708936,-0.00650199,-0.000383389,-0.0110314,-0.0014345,-0.000436212,-365.395,-1.35721e-05,-5.77621e-05,1.71016e-05,0,0,-2.52806e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00205797,0.000100378,9.74958e-05,0.00150978,0.027926,0.0279096,4.37463,0.00666734,0.00666641,0.516967,1.03584e-08,1.03587e-08,9.0164e-08,4e-06,4e-06,3.99486e-06,0,0,0,0,0,0,0,0 -6385000,0.705519,0.00117359,-0.0142449,0.708547,-0.00755228,-0.000272296,-0.0439104,-0.00215177,-0.000467562,-365.407,-1.34843e-05,-5.78433e-05,2.14701e-05,0,0,-2.11389e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00203442,0.000110358,0.000107414,0.00149798,0.0346565,0.0346349,3.15615,0.00932364,0.00932166,0.485838,1.03553e-08,1.03561e-08,8.22552e-08,4e-06,4e-06,3.99432e-06,0,0,0,0,0,0,0,0 -6485000,0.705697,0.00113938,-0.0143772,0.708367,-0.00584833,0.000222699,-0.0486984,-0.00157909,-0.000211207,-365.407,-1.2701e-05,-5.78901e-05,2.27678e-05,0,0,-2.45022e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00201168,8.9644e-05,8.68632e-05,0.00148661,0.0262591,0.0262451,2.27834,0.00640157,0.00640053,0.448309,8.38415e-09,8.38404e-09,7.52044e-08,4e-06,4e-06,3.99352e-06,0,0,0,0,0,0,0,0 -6585000,0.705451,0.00113562,-0.0143866,0.708611,-0.006002,2.44531e-05,-0.0894239,-0.00212764,-0.000196356,-365.429,-1.27961e-05,-5.78039e-05,1.81227e-05,0,0,-1.27896e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00198971,9.81295e-05,9.53131e-05,0.00147606,0.032432,0.0324152,1.6665,0.00891905,0.00891706,0.410362,8.38163e-09,8.38197e-09,6.88984e-08,4e-06,4e-06,3.99242e-06,0,0,0,0,0,0,0,0 -6685000,0.705358,0.00108481,-0.0144406,0.708704,-0.00346643,0.000572833,-0.0732188,-0.00139551,-7.49692e-05,-365.418,-1.21631e-05,-5.7827e-05,1.5561e-05,0,0,-3.2572e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00196846,7.87145e-05,7.60731e-05,0.00146601,0.0244052,0.0243962,1.24585,0.00613465,0.00613371,0.376164,6.68294e-09,6.68238e-09,6.32624e-08,4e-06,4e-06,3.99095e-06,0,0,0,0,0,0,0,0 -6785000,0.705637,0.00107451,-0.0144157,0.708426,-0.00404707,6.27119e-05,-0.109105,-0.00177304,-2.35534e-05,-365.443,-1.21076e-05,-5.78773e-05,1.82544e-05,0,0,-1.59947e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00196529,8.58082e-05,8.31384e-05,0.00145996,0.0299814,0.0299703,1.01663,0.00850214,0.00850048,0.378799,6.6814e-09,6.68115e-09,5.94214e-08,4e-06,4e-06,3.98955e-06,0,0,0,0,0,0,0,0 -6885000,0.70552,0.00101666,-0.0144,0.708543,-0.00416447,-9.37883e-05,-0.117648,-0.00120493,-1.08863e-05,-365.449,-1.16263e-05,-5.79146e-05,1.60844e-05,0,0,-2.19859e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00194452,6.82889e-05,6.57865e-05,0.00145102,0.0224518,0.0224446,0.787985,0.00586541,0.00586467,0.346716,5.27456e-09,5.27346e-09,5.475e-08,4e-06,4e-06,3.98711e-06,0,0,0,0,0,0,0,0 -6985000,0.705341,0.00106031,-0.0143778,0.708722,-0.00357621,0.000390333,-0.125625,-0.00160351,2.51791e-05,-365.456,-1.16916e-05,-5.78562e-05,1.29562e-05,0,0,-3.13509e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00192484,7.41551e-05,7.16215e-05,0.00144258,0.0274247,0.0274169,0.622716,0.00807552,0.0080742,0.318725,5.27282e-09,5.27209e-09,5.05416e-08,4e-06,4e-06,3.9839e-06,0,0,0,0,0,0,0,0 -7085000,0.704829,0.000989585,-0.014404,0.70923,-0.00193441,-0.000607271,-0.124035,-0.000996326,-1.71486e-05,-365.454,-1.139e-05,-5.7802e-05,6.84206e-06,0,0,-5.87891e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00190546,5.88294e-05,5.64535e-05,0.00143475,0.0204944,0.020491,0.502242,0.00559693,0.00559638,0.294864,4.14257e-09,4.14111e-09,4.67438e-08,4e-06,4e-06,3.97974e-06,0,0,0,0,0,0,0,0 -7185000,0.704701,0.000980985,-0.0143608,0.709359,-0.00293003,-0.00113312,-0.144611,-0.0012319,-9.00088e-05,-365.473,-1.14348e-05,-5.77625e-05,4.72371e-06,0,0,-4.65321e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00188692,6.36306e-05,6.1237e-05,0.00142744,0.0248946,0.0248899,0.412265,0.00764799,0.00764709,0.273973,4.14113e-09,4.14e-09,4.3305e-08,4e-06,4e-06,3.97436e-06,0,0,0,0,0,0,0,0 -7285000,0.704694,0.000957121,-0.014348,0.709366,-0.00235596,-0.00118816,-0.145855,-0.000810848,-0.000137281,-365.474,-1.11323e-05,-5.77481e-05,4.32763e-06,0,0,-8.4585e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00186885,5.05415e-05,4.82731e-05,0.00142056,0.0186212,0.0186186,0.344664,0.00533395,0.00533357,0.255987,3.25218e-09,3.25044e-09,4.01908e-08,4e-06,4e-06,3.96757e-06,0,0,0,0,0,0,0,0 -7385000,0.704594,0.000953149,-0.0143216,0.709465,-0.001501,-0.000369927,-0.156372,-0.00102711,-0.00020002,-365.486,-1.11613e-05,-5.77224e-05,2.96507e-06,0,0,-9.93116e-06,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0018517,5.44677e-05,5.21867e-05,0.0014141,0.0224858,0.0224836,0.292872,0.00722993,0.00722932,0.240117,3.251e-09,3.24954e-09,3.73621e-08,4e-06,4e-06,3.95897e-06,0,0,0,0,0,0,0,0 -7485000,0.704766,0.000981688,-0.0142912,0.709295,-0.00130126,-0.000355452,-0.162695,-0.000642147,-0.000124842,-365.494,-1.09129e-05,-5.77203e-05,3.98699e-06,0,0,-1.31101e-05,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00184799,4.34656e-05,4.12814e-05,0.00140988,0.0168714,0.0168703,0.263719,0.00508038,0.00508014,0.239887,2.56145e-09,2.55947e-09,3.54068e-08,4e-06,4e-06,3.95111e-06,0,0,0,0,0,0,0,0 -7585000,0.704953,0.000969945,-0.0142248,0.70911,-0.00185361,0.000234982,-0.167124,-0.000763735,-0.000135142,-365.5,-1.08755e-05,-5.77526e-05,5.71662e-06,0,0,-1.83433e-05,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00183164,4.6678e-05,4.44832e-05,0.00140397,0.0202658,0.0202642,0.230763,0.00682903,0.00682866,0.226153,2.56044e-09,2.55871e-09,3.30062e-08,4e-06,4e-06,3.93851e-06,0,0,0,0,0,0,0,0 -7685000,0.704873,0.00101446,-0.0141885,0.709191,-0.00199358,0.000430233,-0.16438,-0.000529747,-5.4388e-05,-365.496,-1.07305e-05,-5.7731e-05,4.87237e-06,0,0,-2.98336e-05,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00181591,3.75138e-05,3.53972e-05,0.00139828,0.0152875,0.0152865,0.205196,0.00483939,0.00483923,0.214199,2.02889e-09,2.02685e-09,3.0817e-08,4e-06,4e-06,3.92324e-06,0,0,0,0,0,0,0,0 -7785000,0.704557,0.00100828,-0.0142133,0.709504,-0.00189895,0.00103466,-0.164148,-0.000704925,1.47684e-05,-365.496,-1.07985e-05,-5.76708e-05,1.7129e-06,0,0,-4.09178e-05,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00180092,4.0154e-05,3.80351e-05,0.00139287,0.0182687,0.0182679,0.185138,0.00645146,0.00645122,0.203587,2.02805e-09,2.02623e-09,2.88134e-08,4e-06,4e-06,3.90468e-06,0,0,0,0,0,0,0,0 -7885000,0.704679,0.000995452,-0.0142395,0.709383,-0.00265242,0.0021615,-0.163415,-0.000509539,9.58573e-05,-365.493,-1.06447e-05,-5.77197e-05,2.41554e-06,0,0,-5.5248e-05,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00178634,3.25438e-05,3.05051e-05,0.00138763,0.0138715,0.0138706,0.169383,0.00461294,0.00461283,0.194158,1.61936e-09,1.61733e-09,2.69744e-08,4e-06,4e-06,3.88231e-06,0,0,0,0,0,0,0,0 -7985000,0.704795,0.0010071,-0.0142265,0.709268,-0.00287392,0.00278588,-0.170147,-0.000804805,0.000313097,-365.501,-1.06281e-05,-5.77338e-05,3.16973e-06,0,0,-6.26678e-05,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00177251,3.47291e-05,3.26845e-05,0.00138271,0.0165015,0.0165005,0.157133,0.00610014,0.00609995,0.185907,1.61866e-09,1.61682e-09,2.52901e-08,4e-06,4e-06,3.85599e-06,0,0,0,0,0,0,0,0 -8085000,0.704992,0.000983765,-0.014225,0.709072,-0.0034583,0.00358259,-0.182004,-0.00114143,0.000643535,-365.517,-1.05931e-05,-5.77643e-05,4.7776e-06,0,0,-6.4272e-05,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00176934,3.69893e-05,3.49455e-05,0.00137966,0.0194704,0.0194692,0.152048,0.00803651,0.00803622,0.187037,1.61821e-09,1.6165e-09,2.41174e-08,4e-06,4e-06,3.83329e-06,0,0,0,0,0,0,0,0 -8185000,0.704781,0.000924558,-0.014212,0.709282,-0.0036587,0.00412923,-0.188417,-0.000895104,0.000703705,-365.525,-1.04898e-05,-5.78228e-05,2.69088e-06,0,0,-7.52286e-05,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00175617,3.02272e-05,2.82626e-05,0.00137496,0.0149477,0.0149467,0.144218,0.00577584,0.0057757,0.180003,1.30357e-09,1.30172e-09,2.26618e-08,4e-06,4e-06,3.79857e-06,0,0,0,0,0,0,0,0 -8285000,0.70476,0.000943871,-0.0142711,0.709301,-0.00364089,0.00430616,-0.18704,-0.00127982,0.00113554,-365.523,-1.05008e-05,-5.78123e-05,2.16574e-06,0,0,-9.87422e-05,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00174352,3.21129e-05,3.01476e-05,0.00137052,0.0175671,0.0175662,0.138173,0.00755513,0.00755489,0.173776,1.30303e-09,1.30134e-09,2.13188e-08,4e-06,4e-06,3.75825e-06,0,0,0,0,0,0,0,0 -8385000,0.704821,0.000945192,-0.0142679,0.709241,-0.00294534,0.0042656,-0.186834,-0.000963911,0.00101923,-365.522,-1.03352e-05,-5.79766e-05,2.90754e-06,0,0,-0.0001223,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00173111,2.65195e-05,2.46181e-05,0.00136641,0.0135884,0.0135881,0.133629,0.00547814,0.00547803,0.16837,1.05981e-09,1.05804e-09,2.00803e-08,4e-06,4e-06,3.7124e-06,0,0,0,0,0,0,0,0 -8485000,0.704695,0.000918302,-0.0142879,0.709366,-0.00309942,0.00505222,-0.186367,-0.00130305,0.00147329,-365.522,-1.03521e-05,-5.79611e-05,2.11622e-06,0,0,-0.000147682,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00171924,2.80934e-05,2.61974e-05,0.00136254,0.0159102,0.01591,0.130202,0.00711709,0.00711692,0.163601,1.05937e-09,1.05772e-09,1.89345e-08,4e-06,4e-06,3.66019e-06,0,0,0,0,0,0,0,0 -8585000,0.704549,0.000886908,-0.0142535,0.709512,-0.00277464,0.00578544,-0.186968,-0.000987243,0.00127986,-365.524,-1.02456e-05,-5.81092e-05,7.03993e-07,0,0,-0.0001733,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00170793,2.34387e-05,2.16022e-05,0.00135857,0.0124036,0.0124036,0.127721,0.00520546,0.00520539,0.159494,8.70298e-10,8.68609e-10,1.78745e-08,4e-06,4e-06,3.60191e-06,0,0,0,0,0,0,0,0 -8685000,0.704831,0.000921715,-0.0142187,0.709232,-0.00398998,0.00632279,-0.182581,-0.00130835,0.00188086,-365.519,-1.0201e-05,-5.81475e-05,2.72325e-06,0,0,-0.000210775,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00169703,2.47785e-05,2.29352e-05,0.00135488,0.014474,0.0144733,0.125906,0.00671949,0.00671938,0.155893,8.69926e-10,8.68347e-10,1.68909e-08,4e-06,4e-06,3.53675e-06,0,0,0,0,0,0,0,0 -8785000,0.704644,0.000792309,-0.0141906,0.709419,-0.00331503,0.00639909,-0.181151,-0.00104641,0.0015907,-365.52,-1.01067e-05,-5.83216e-05,1.21479e-06,0,0,-0.000240646,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00169428,2.08744e-05,1.91008e-05,0.00135251,0.0113703,0.0113699,0.12756,0.00495611,0.00495605,0.158895,7.22063e-10,7.20441e-10,1.61995e-08,4e-06,4e-06,3.48332e-06,0,0,0,0,0,0,0,0 -8885000,0.704605,0.000812577,-0.0142084,0.709457,-0.00340032,0.00664521,-0.181555,-0.00139148,0.00227261,-365.522,-1.01197e-05,-5.83098e-05,6.10703e-07,0,0,-0.00026902,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00168394,2.20157e-05,2.02423e-05,0.00134897,0.0132272,0.013227,0.126564,0.00635907,0.00635899,0.156006,7.21747e-10,7.2022e-10,1.5335e-08,4e-06,4e-06,3.40622e-06,0,0,0,0,0,0,0,0 -8985000,0.704522,0.000787063,-0.0141828,0.70954,-0.00248735,0.00510151,-0.17608,-0.00103385,0.00175798,-365.517,-1.00166e-05,-5.85129e-05,-1.76564e-07,0,0,-0.000311693,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00167389,1.8749e-05,1.7024e-05,0.00134553,0.0104704,0.0104705,0.125873,0.00472805,0.00472801,0.153578,6.05071e-10,6.03543e-10,1.45313e-08,4e-06,4e-06,3.32299e-06,0,0,0,0,0,0,0,0 -9085000,0.704424,0.000812424,-0.0142156,0.709637,-0.00273171,0.00518675,-0.177551,-0.00127662,0.00225827,-365.523,-1.00303e-05,-5.85008e-05,-8.01546e-07,0,0,-0.000334757,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00166409,1.97324e-05,1.80089e-05,0.00134241,0.0121445,0.0121446,0.125309,0.00603225,0.00603221,0.151473,6.04809e-10,6.03363e-10,1.37819e-08,4e-06,4e-06,3.23312e-06,0,0,0,0,0,0,0,0 -9185000,0.704762,0.000777087,-0.0142272,0.7093,-0.00134275,0.00404172,-0.17844,-0.00090793,0.00170202,-365.527,-9.88121e-06,-5.8738e-05,1.40244e-06,0,0,-0.000361266,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00165465,1.69711e-05,1.52931e-05,0.00133922,0.00968498,0.00968548,0.124775,0.00451932,0.00451931,0.149641,5.1208e-10,5.10641e-10,1.30823e-08,4e-06,4e-06,3.13695e-06,0,0,0,0,0,0,0,0 -9285000,0.704807,0.000745094,-0.0142761,0.709255,-0.000355368,0.00426384,-0.177126,-0.000992618,0.0021272,-365.528,-9.87583e-06,-5.87426e-05,1.64115e-06,0,0,-0.00039713,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00164569,1.7817e-05,1.61503e-05,0.00133623,0.0112075,0.0112085,0.12426,0.00573566,0.0057357,0.148113,5.11864e-10,5.10496e-10,1.24303e-08,4e-06,4e-06,3.03584e-06,0,0,0,0,0,0,0,0 -9385000,0.70483,0.000655968,-0.014212,0.709233,0.00108009,0.00431285,-0.179315,-0.000561336,0.00159189,-365.535,-9.81888e-06,-5.89033e-05,1.43317e-06,0,0,-0.000421686,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00164355,1.54608e-05,1.38359e-05,0.00133418,0.00900239,0.00900358,0.126539,0.00432825,0.0043283,0.152439,4.37629e-10,4.36262e-10,1.19694e-08,4e-06,4e-06,2.95687e-06,0,0,0,0,0,0,0,0 -9485000,0.705036,0.000639132,-0.014244,0.709029,0.00153981,0.00401024,-0.176763,-0.000435129,0.00202527,-365.538,-9.78868e-06,-5.893e-05,2.80045e-06,0,0,-0.000453068,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00163498,1.62033e-05,1.45868e-05,0.00133135,0.0103905,0.0103919,0.125793,0.00546644,0.00546657,0.151218,4.37448e-10,4.36143e-10,1.13894e-08,4e-06,4e-06,2.8477e-06,0,0,0,0,0,0,0,0 -9585000,0.705142,0.000618044,-0.0142174,0.708923,0.00137831,0.00322516,-0.173482,-0.000178821,0.0014862,-365.539,-9.75995e-06,-5.90826e-05,3.33671e-06,0,0,-0.000490458,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00162676,1.41948e-05,1.2606e-05,0.0013285,0.00840132,0.00840215,0.124843,0.004153,0.0041531,0.150104,3.77397e-10,3.76123e-10,1.0846e-08,4e-06,4e-06,2.73472e-06,0,0,0,0,0,0,0,0 -9685000,0.704981,0.000660546,-0.0142367,0.709083,0.00196541,0.00449687,-0.16784,-5.64145e-06,0.00187809,-365.537,-9.78594e-06,-5.90597e-05,2.1523e-06,0,0,-0.000534221,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00161883,1.48587e-05,1.32694e-05,0.00132579,0.00967862,0.00967981,0.123729,0.0052213,0.00522148,0.149138,3.7725e-10,3.7603e-10,1.0337e-08,4e-06,4e-06,2.61967e-06,0,0,0,0,0,0,0,0 -9785000,0.705165,0.000624355,-0.0141716,0.708902,0.00399379,0.00453037,-0.159684,0.000192897,0.00146327,-365.532,-9.7838e-06,-5.92032e-05,3.00559e-06,0,0,-0.000583046,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00161119,1.31253e-05,1.15581e-05,0.00132306,0.00787449,0.00787586,0.122368,0.00399196,0.00399208,0.148205,3.28326e-10,3.27145e-10,9.85889e-09,4e-06,4e-06,2.50259e-06,0,0,0,0,0,0,0,0 -9885000,0.705135,0.000609532,-0.0141069,0.708933,0.00457251,0.00472747,-0.156763,0.000637002,0.00192846,-365.535,-9.78523e-06,-5.92021e-05,2.93752e-06,0,0,-0.000612422,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00160368,1.37087e-05,1.21437e-05,0.00132065,0.00905362,0.00905518,0.120817,0.00499768,0.00499791,0.147356,3.28208e-10,3.27074e-10,9.41035e-09,4e-06,4e-06,2.38523e-06,0,0,0,0,0,0,0,0 -9985000,0.705035,0.000624333,-0.0141044,0.709032,0.00482334,0.00321058,-0.150943,0.000689848,0.00146859,-365.532,-9.85846e-06,-5.93063e-05,2.24806e-06,0,0,-0.0006534,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00159643,1.22109e-05,1.06614e-05,0.00131819,0.00741027,0.00741119,0.119014,0.00384363,0.00384378,0.146484,2.88024e-10,2.86938e-10,8.98821e-09,4e-06,4e-06,2.26761e-06,0,0,0,0,0,0,0,0 -10085000,0.705138,0.000633032,-0.0140995,0.708929,0.00605275,0.00215124,-0.149472,0.00123842,0.00174748,-365.537,-9.85082e-06,-5.93132e-05,2.59228e-06,0,0,-0.000676961,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00159472,1.27375e-05,1.11917e-05,0.00131655,0.0085064,0.00850711,0.119886,0.00479322,0.00479347,0.151148,2.87979e-10,2.86924e-10,8.68787e-09,4e-06,4e-06,2.1798e-06,0,0,0,0,0,0,0,0 -10185000,0.704931,0.000612942,-0.0141646,0.709134,0.00693731,0.00350649,-0.147031,0.00189406,0.00199552,-365.54,-9.87964e-06,-5.92878e-05,1.28142e-06,0,0,-0.000703358,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00158775,1.32742e-05,1.17402e-05,0.00131425,0.00970733,0.00970852,0.117622,0.00596705,0.00596742,0.150178,2.87894e-10,2.86879e-10,8.30787e-09,4e-06,4e-06,2.06415e-06,0,0,0,0,0,0,0,0 -10285000,0.704839,0.000565385,-0.0141193,0.709227,0.00745443,0.00165146,-0.135629,0.00182321,0.00142237,-365.53,-9.9886e-06,-5.93627e-05,4.54556e-07,0,0,-0.000757747,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00158105,1.18933e-05,1.03756e-05,0.00131191,0.00802481,0.00802506,0.115204,0.00460585,0.00460606,0.149211,2.54632e-10,2.53669e-10,7.94984e-09,4e-06,4e-06,1.95118e-06,0,0,0,0,0,0,0,0 -10385000,0.70484,0.000523147,-0.0140705,0.709227,0.0119197,-0.0206212,0.00583849,0.000974778,-0.0018229,-365.515,-9.98569e-06,-5.93655e-05,5.81095e-07,0,0,-0.000793313,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00157431,1.23747e-05,1.08643e-05,0.00130989,0.0346609,0.0346609,0.0375922,0.12528,0.12528,0.131927,2.54568e-10,2.5364e-10,7.61179e-09,4e-06,4e-06,1.85198e-06,0,0,0,0,0,0,0,0 -10485000,0.704709,0.000532829,-0.0140778,0.709356,0.0133297,-0.020521,0.00333434,0.00221872,-0.00388141,-365.498,-1.00013e-05,-5.93519e-05,-1.32899e-07,0,0,-0.000829472,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00156781,1.28759e-05,1.137e-05,0.00130788,0.0349369,0.0349367,0.038115,0.126249,0.126249,0.11805,2.54512e-10,2.53619e-10,7.29247e-09,4e-06,4e-06,1.77503e-06,0,0,0,0,0,0,0,0 -10585000,0.704761,0.00054605,-0.0141259,0.709304,0.0142947,-0.017948,0.00196683,0.0026891,-0.00381864,-365.488,-9.99948e-06,-5.93428e-05,4.12398e-08,0,0,-0.000850659,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0015616,1.33837e-05,1.18847e-05,0.00130583,0.030892,0.0308918,0.0363718,0.0848492,0.0848492,0.107675,2.54357e-10,2.53496e-10,6.99099e-09,4e-06,4e-06,1.71125e-06,0,0,0,0,0,0,0,0 -10685000,0.704784,0.000566741,-0.0141224,0.709281,0.0149874,-0.019277,-0.000903606,0.0041907,-0.00569478,-365.481,-9.99699e-06,-5.9345e-05,1.51251e-07,0,0,-0.000865459,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00155995,1.39116e-05,1.24156e-05,0.00130459,0.031328,0.0313274,0.0372788,0.0865246,0.0865245,0.102838,2.54352e-10,2.53514e-10,6.77574e-09,4e-06,4e-06,1.67162e-06,0,0,0,0,0,0,0,0 -10785000,0.704823,0.000532088,-0.0141395,0.709242,0.0151645,-0.0183514,-0.00344179,0.00436041,-0.00526823,-365.477,-9.99974e-06,-5.93244e-05,3.19544e-07,0,0,-0.000875425,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00155394,1.44175e-05,1.29328e-05,0.00130267,0.0280823,0.0280814,0.0358719,0.0656291,0.0656291,0.0964069,2.53904e-10,2.53097e-10,6.50217e-09,4e-06,4e-06,1.62027e-06,0,0,0,0,0,0,0,0 -10885000,0.704846,0.000458296,-0.0140995,0.70922,0.0164332,-0.0191593,-0.0074797,0.0059194,-0.00712647,-365.475,-1.00003e-05,-5.93239e-05,2.93293e-07,0,0,-0.000880497,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00154816,1.49563e-05,1.34849e-05,0.00130076,0.0286832,0.0286817,0.0368606,0.0677757,0.0677756,0.0922749,2.53878e-10,2.53099e-10,6.24303e-09,4e-06,4e-06,1.58022e-06,0,0,0,0,0,0,0,0 -10985000,0.705036,0.000450307,-0.0140953,0.709031,0.0160676,-0.0170313,-0.01145,0.00639229,-0.0082993,-365.472,-9.97662e-06,-5.92892e-05,1.13543e-06,0,0,-0.00089076,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00154259,1.54547e-05,1.39883e-05,0.00129884,0.0259851,0.0259838,0.0356087,0.0549231,0.054923,0.0882102,2.52954e-10,2.52204e-10,5.99773e-09,4e-06,4e-06,1.53501e-06,0,0,0,0,0,0,0,0 -11085000,0.705217,0.000437812,-0.014033,0.708852,0.0172814,-0.0170782,-0.0125265,0.00808359,-0.0100506,-365.465,-9.958e-06,-5.93056e-05,1.97307e-06,0,0,-0.000906058,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00153717,1.60249e-05,1.45618e-05,0.00129702,0.0267549,0.0267532,0.0366703,0.0574235,0.0574233,0.08625,2.5294e-10,2.52216e-10,5.76505e-09,4e-06,4e-06,1.50291e-06,0,0,0,0,0,0,0,0 -11185000,0.705135,0.000433744,-0.0140324,0.708934,0.0193682,-0.0153379,-0.0170369,0.00849394,-0.0103267,-365.467,-9.96303e-06,-5.92358e-05,1.61918e-06,0,0,-0.000905623,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00153178,1.64928e-05,1.50341e-05,0.00129535,0.0244484,0.0244462,0.0354981,0.0484756,0.0484754,0.0834873,2.51365e-10,2.50668e-10,5.54446e-09,4e-06,4e-06,1.45948e-06,0,0,0,0,0,0,0,0 -11285000,0.705006,0.000489733,-0.0140571,0.709062,0.0209393,-0.0154776,-0.0194026,0.010516,-0.0118599,-365.465,-9.98257e-06,-5.92187e-05,7.35096e-07,0,0,-0.000913657,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00152672,1.70933e-05,1.56345e-05,0.00129355,0.0253934,0.0253904,0.0365977,0.0512596,0.0512593,0.0828739,2.51362e-10,2.50689e-10,5.3349e-09,4e-06,4e-06,1.43228e-06,0,0,0,0,0,0,0,0 -11385000,0.704942,0.000531934,-0.0140601,0.709126,0.0198969,-0.0138265,-0.0220652,0.00945473,-0.0103294,-365.465,-1.00584e-05,-5.91567e-05,3.1835e-07,0,0,-0.00091902,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00152538,1.75133e-05,1.60539e-05,0.00129246,0.023371,0.0233679,0.0357524,0.0444452,0.0444449,0.0825031,2.48992e-10,2.4834e-10,5.18454e-09,4e-06,4e-06,1.39453e-06,0,0,0,0,0,0,0,0 -11485000,0.704785,0.000521625,-0.0140794,0.709281,0.0198338,-0.0136596,-0.0241811,0.0114423,-0.0117033,-365.465,-1.00765e-05,-5.91409e-05,-4.99146e-07,0,0,-0.000924711,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00152032,1.81229e-05,1.66719e-05,0.00129087,0.0244924,0.0244892,0.0369108,0.0474677,0.0474672,0.0827503,2.48998e-10,2.48368e-10,4.99269e-09,4e-06,4e-06,1.37039e-06,0,0,0,0,0,0,0,0 -11585000,0.704681,0.000515715,-0.0141321,0.709383,0.0167765,-0.0110492,-0.0269367,0.0101289,-0.0101771,-365.465,-1.01632e-05,-5.90745e-05,-9.7963e-07,0,0,-0.000930412,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0015153,1.84585e-05,1.70156e-05,0.00128937,0.0226753,0.022673,0.0357963,0.0419002,0.0418998,0.081036,2.45639e-10,2.45035e-10,4.81026e-09,4e-06,4e-06,1.32486e-06,0,0,0,0,0,0,0,0 -11685000,0.704651,0.000474984,-0.0141328,0.709413,0.0161041,-0.0101934,-0.0302221,0.0117507,-0.0112747,-365.469,-1.017e-05,-5.90685e-05,-1.28682e-06,0,0,-0.000929464,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00151055,1.90788e-05,1.76471e-05,0.00128779,0.0239741,0.0239719,0.036962,0.0451316,0.0451309,0.0818387,2.45653e-10,2.4507e-10,4.63655e-09,4e-06,4e-06,1.30301e-06,0,0,0,0,0,0,0,0 -11785000,0.704684,0.00051513,-0.014159,0.70938,0.0120655,-0.00863116,-0.0324518,0.00955169,-0.00909271,-365.467,-1.02845e-05,-5.89763e-05,-1.30563e-06,0,0,-0.0009378,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00150591,1.93153e-05,1.78854e-05,0.00128622,0.0223003,0.0222986,0.0358415,0.040317,0.0403165,0.0803126,2.41217e-10,2.40659e-10,4.47103e-09,4e-06,4e-06,1.25597e-06,0,0,0,0,0,0,0,0 -11885000,0.704579,0.000501774,-0.0141474,0.709484,0.0135179,-0.00916982,-0.0340462,0.0108538,-0.00998812,-365.467,-1.02958e-05,-5.89664e-05,-1.81997e-06,0,0,-0.000943633,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00150129,1.99504e-05,1.85269e-05,0.00128483,0.023776,0.0237735,0.0370067,0.0437382,0.0437374,0.0814509,2.41239e-10,2.407e-10,4.31341e-09,4e-06,4e-06,1.23574e-06,0,0,0,0,0,0,0,0 -11985000,0.70466,0.000581753,-0.014116,0.709404,0.0111894,-0.00725613,-0.0373883,0.00875395,-0.00791067,-365.47,-1.04031e-05,-5.88741e-05,-1.47845e-06,0,0,-0.000945864,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00150004,2.00659e-05,1.86336e-05,0.00128392,0.0221898,0.0221875,0.0362764,0.0393788,0.0393781,0.0816569,2.35672e-10,2.35151e-10,4.20006e-09,4e-06,4e-06,1.19208e-06,0,0,0,0,0,0,0,0 -12085000,0.70483,0.000586764,-0.0141235,0.709236,0.0122994,-0.0068231,-0.0427829,0.00992472,-0.00863784,-365.475,-1.03875e-05,-5.88877e-05,-7.75462e-07,0,0,-0.000942839,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00149564,2.071e-05,1.92828e-05,0.0012825,0.0238366,0.0238337,0.0374699,0.0429774,0.0429765,0.083042,2.357e-10,2.35196e-10,4.055e-09,4e-06,4e-06,1.17319e-06,0,0,0,0,0,0,0,0 -12185000,0.704785,0.000587707,-0.0141285,0.70928,0.0119708,-0.00455302,-0.0387744,0.00950382,-0.00743261,-365.468,-1.04192e-05,-5.88382e-05,-9.75482e-07,0,0,-0.000967078,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00149128,2.06705e-05,1.9241e-05,0.00128117,0.0222872,0.0222848,0.0363126,0.0388828,0.038882,0.0815538,2.28946e-10,2.28466e-10,3.91654e-09,4e-06,4e-06,1.1234e-06,0,0,0,0,0,0,0,0 -12285000,0.704825,0.000551345,-0.0141384,0.709241,0.0113241,-0.00420901,-0.0390026,0.0106951,-0.00785627,-365.466,-1.04159e-05,-5.88411e-05,-8.30285e-07,0,0,-0.000978054,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00148709,2.13105e-05,1.98916e-05,0.00127986,0.0240913,0.0240889,0.0374901,0.0426507,0.0426496,0.0830372,2.28981e-10,2.28516e-10,3.78441e-09,4e-06,4e-06,1.10545e-06,0,0,0,0,0,0,0,0 -12385000,0.704764,0.000537931,-0.0141492,0.7093,0.0114912,-0.00276289,-0.036313,0.0101453,-0.00672532,-365.461,-1.04534e-05,-5.87967e-05,-1.25878e-06,0,0,-0.000997711,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00148305,2.11047e-05,1.96852e-05,0.00127848,0.0225366,0.0225345,0.0363132,0.0386933,0.0386924,0.0815282,2.21107e-10,2.20665e-10,3.65814e-09,4e-06,4e-06,1.05518e-06,0,0,0,0,0,0,0,0 -12485000,0.704648,0.00049483,-0.01417,0.709415,0.0117606,-0.00162834,-0.0390488,0.0113248,-0.0069487,-365.462,-1.04662e-05,-5.87855e-05,-1.83721e-06,0,0,-0.0010017,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00147903,2.17404e-05,2.03329e-05,0.00127723,0.0244865,0.0244843,0.0374671,0.0426242,0.0426231,0.0830455,2.21148e-10,2.2072e-10,3.53747e-09,4e-06,4e-06,1.038e-06,0,0,0,0,0,0,0,0 -12585000,0.704589,0.00055703,-0.0141553,0.709475,0.00808284,0.000188944,-0.043022,0.00722333,-0.00587007,-365.467,-1.07142e-05,-5.87552e-05,-2.01731e-06,0,0,-0.00100253,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00147499,2.13649e-05,1.99548e-05,0.00127609,0.0228886,0.0228868,0.0362674,0.038716,0.0387151,0.0815005,2.1226e-10,2.11853e-10,3.42203e-09,4e-06,4e-06,9.87778e-07,0,0,0,0,0,0,0,0 -12685000,0.704543,0.000584705,-0.0141165,0.70952,0.00932528,0.00120904,-0.0459248,0.0080841,-0.00580267,-365.472,-1.07174e-05,-5.87524e-05,-2.16158e-06,0,0,-0.00100234,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00147384,2.20017e-05,2.05904e-05,0.00127542,0.0249639,0.0249618,0.0378555,0.0428042,0.042803,0.0847704,2.12319e-10,2.11922e-10,3.33872e-09,4e-06,4e-06,9.75411e-07,0,0,0,0,0,0,0,0 -12785000,0.704551,0.000678744,-0.0140679,0.709514,0.00559552,0.00138477,-0.0471114,0.00430483,-0.00489422,-365.472,-1.09517e-05,-5.87406e-05,-2.17946e-06,0,0,-0.00101179,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00146998,2.14571e-05,2.00358e-05,0.00127424,0.0232888,0.0232868,0.0366016,0.0388833,0.0388824,0.0831192,2.02578e-10,2.02204e-10,3.23177e-09,4e-06,4e-06,9.25347e-07,0,0,0,0,0,0,0,0 -12885000,0.704555,0.000617943,-0.014113,0.709508,0.00642159,0.000817432,-0.0471248,0.00490177,-0.00480661,-365.47,-1.09528e-05,-5.87396e-05,-2.23505e-06,0,0,-0.00102199,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00146628,2.20687e-05,2.06629e-05,0.00127306,0.0254723,0.0254697,0.0377099,0.0431219,0.0431207,0.0846617,2.02628e-10,2.02266e-10,3.12946e-09,4e-06,4e-06,9.09603e-07,0,0,0,0,0,0,0,0 -12985000,0.704689,0.000593102,-0.0141635,0.709375,0.00940676,0.00099227,-0.0449551,0.00778673,-0.0041005,-365.469,-1.08516e-05,-5.87424e-05,-1.79838e-06,0,0,-0.00104045,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0014627,2.13547e-05,1.99434e-05,0.00127185,0.0236921,0.0236895,0.0364284,0.039145,0.039144,0.0829746,1.92239e-10,1.91897e-10,3.03141e-09,4e-06,4e-06,8.6065e-07,0,0,0,0,0,0,0,0 -13085000,0.704491,0.000591553,-0.0141167,0.709573,0.0100246,0.00101124,-0.0450292,0.00875985,-0.0039938,-365.47,-1.08661e-05,-5.87297e-05,-2.45891e-06,0,0,-0.00104649,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00145895,2.19566e-05,2.05471e-05,0.00127093,0.0259565,0.0259533,0.0374763,0.0435249,0.0435235,0.0844518,1.92293e-10,1.91963e-10,2.93738e-09,4e-06,4e-06,8.45359e-07,0,0,0,0,0,0,0,0 -13185000,0.704473,0.000563142,-0.0141164,0.70959,0.0130016,0.00238115,-0.0402653,0.0111274,-0.00331087,-365.462,-1.08067e-05,-5.8724e-05,-2.53829e-06,0,0,-0.0010732,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0014554,2.10935e-05,1.96753e-05,0.00126988,0.024059,0.0240562,0.0361687,0.0394624,0.0394614,0.0827375,1.81488e-10,1.81177e-10,2.84727e-09,4e-06,4e-06,7.97975e-07,0,0,0,0,0,0,0,0 -13285000,0.704555,0.000569141,-0.0141204,0.709509,0.0137054,0.00314897,-0.0383159,0.0124693,-0.00303137,-365.457,-1.07999e-05,-5.87299e-05,-2.23633e-06,0,0,-0.00108591,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00145446,2.16755e-05,2.0261e-05,0.00126921,0.0263844,0.0263814,0.0376412,0.0439725,0.0439711,0.0859871,1.81556e-10,1.81253e-10,2.78213e-09,4e-06,4e-06,7.87028e-07,0,0,0,0,0,0,0,0 -13385000,0.704647,0.000508264,-0.0140749,0.709419,0.0126353,0.00383915,-0.0335426,0.00992921,-0.00254104,-365.447,-1.08827e-05,-5.87439e-05,-1.96998e-06,0,0,-0.00110863,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00145112,2.06759e-05,1.92617e-05,0.00126811,0.0243611,0.0243587,0.0362769,0.0398063,0.0398052,0.0841795,1.70569e-10,1.70285e-10,2.69832e-09,4e-06,4e-06,7.41198e-07,0,0,0,0,0,0,0,0 -13485000,0.704718,0.000534004,-0.0140747,0.709348,0.012884,0.0039349,-0.0325891,0.0112381,-0.00215797,-365.443,-1.08776e-05,-5.87483e-05,-1.74282e-06,0,0,-0.00111816,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00144784,2.12366e-05,1.98229e-05,0.00126707,0.0267236,0.0267209,0.037222,0.0444331,0.0444316,0.0856018,1.7063e-10,1.70356e-10,2.61784e-09,4e-06,4e-06,7.27175e-07,0,0,0,0,0,0,0,0 -13585000,0.704661,0.000542824,-0.0140336,0.709405,0.0115455,0.00552646,-0.0324717,0.00883474,-0.00175463,-365.444,-1.09685e-05,-5.87574e-05,-2.07114e-06,0,0,-0.0011243,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00144465,2.01466e-05,1.87241e-05,0.001266,0.0245748,0.0245731,0.0358388,0.040154,0.040153,0.0837854,1.59685e-10,1.59429e-10,2.5406e-09,4e-06,4e-06,6.8362e-07,0,0,0,0,0,0,0,0 -13685000,0.704739,0.000517846,-0.0140045,0.709328,0.0129978,0.00747803,-0.0358156,0.0100294,-0.00112702,-365.447,-1.09604e-05,-5.87644e-05,-1.70112e-06,0,0,-0.00112427,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00144143,2.06745e-05,1.92573e-05,0.0012651,0.0269541,0.0269526,0.0367099,0.044882,0.0448807,0.0851443,1.59749e-10,1.59502e-10,2.46636e-09,4e-06,4e-06,6.70133e-07,0,0,0,0,0,0,0,0 -13785000,0.704687,0.000532523,-0.0139371,0.709381,0.011564,0.00561167,-0.0357588,0.00944874,-0.00200632,-365.449,-1.10101e-05,-5.88528e-05,-1.84018e-06,0,0,-0.00113181,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00143826,1.95148e-05,1.80856e-05,0.00126421,0.0246936,0.0246924,0.035314,0.0404885,0.0404875,0.0833283,1.49045e-10,1.48815e-10,2.39505e-09,4e-06,4e-06,6.29077e-07,0,0,0,0,0,0,0,0 -13885000,0.704647,0.000485022,-0.0139695,0.709421,0.0125759,0.00587639,-0.0388919,0.0106407,-0.00143902,-365.452,-1.10115e-05,-5.88516e-05,-1.90328e-06,0,0,-0.00113161,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00143515,2.00126e-05,1.85954e-05,0.00126337,0.0270678,0.0270663,0.0361076,0.0453012,0.0453,0.0846236,1.49112e-10,1.4889e-10,2.32646e-09,4e-06,4e-06,6.16151e-07,0,0,0,0,0,0,0,0 -13985000,0.70475,0.000519564,-0.0139324,0.709319,0.0110477,0.00512938,-0.0374337,0.00996845,-0.00227192,-365.452,-1.10498e-05,-5.89387e-05,-1.59477e-06,0,0,-0.00114208,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00143439,1.88112e-05,1.73818e-05,0.00126272,0.0247098,0.0247089,0.0351417,0.0407974,0.0407964,0.0845665,1.38819e-10,1.3861e-10,2.27675e-09,4e-06,4e-06,5.80665e-07,0,0,0,0,0,0,0,0 -14085000,0.704785,0.000498821,-0.0139486,0.709284,0.0115329,0.00545969,-0.0380614,0.0110681,-0.0017526,-365.454,-1.10463e-05,-5.89417e-05,-1.43393e-06,0,0,-0.00114326,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00143142,1.92849e-05,1.78629e-05,0.00126185,0.0270572,0.0270561,0.0358776,0.0456774,0.0456763,0.0858512,1.38888e-10,1.38686e-10,2.21265e-09,4e-06,4e-06,5.68465e-07,0,0,0,0,0,0,0,0 -14185000,0.704851,0.000467223,-0.013912,0.709219,0.0125335,0.00519879,-0.0386296,0.0114095,-0.00151116,-365.457,-1.10303e-05,-5.89714e-05,-1.13617e-06,0,0,-0.001147,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00142852,1.80558e-05,1.66294e-05,0.001261,0.0246233,0.0246224,0.034446,0.041072,0.0410711,0.0839815,1.29114e-10,1.28925e-10,2.15099e-09,4e-06,4e-06,5.32435e-07,0,0,0,0,0,0,0,0 -14285000,0.704895,0.000472268,-0.0138783,0.709176,0.0134654,0.00630423,-0.0377924,0.0127047,-0.000954877,-365.456,-1.10283e-05,-5.89731e-05,-1.04717e-06,0,0,-0.00115314,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00142578,1.85054e-05,1.70797e-05,0.00126007,0.0269348,0.026934,0.0351017,0.046002,0.046001,0.0851999,1.29185e-10,1.29003e-10,2.09161e-09,4e-06,4e-06,5.20816e-07,0,0,0,0,0,0,0,0 -14385000,0.705015,0.000439566,-0.0138319,0.709057,0.0134367,0.00717024,-0.0386984,0.0127365,-0.000797094,-365.458,-1.10268e-05,-5.90112e-05,-6.29513e-07,0,0,-0.00115683,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00142306,1.72787e-05,1.58496e-05,0.00125918,0.0244464,0.024446,0.0336746,0.041307,0.0413063,0.0833355,1.20019e-10,1.19849e-10,2.0344e-09,4e-06,4e-06,4.87469e-07,0,0,0,0,0,0,0,0 -14485000,0.704991,0.000435267,-0.0137799,0.709082,0.0136984,0.00904189,-0.0410764,0.0140889,1.86553e-05,-365.464,-1.10259e-05,-5.9012e-05,-5.85099e-07,0,0,-0.00115424,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00142029,1.77003e-05,1.62721e-05,0.00125846,0.0267086,0.0267086,0.0342514,0.0462704,0.0462696,0.0844873,1.20093e-10,1.19929e-10,1.97931e-09,4e-06,4e-06,4.76444e-07,0,0,0,0,0,0,0,0 -14585000,0.704929,0.000412468,-0.0136447,0.709147,0.0110143,0.00839528,-0.0404193,0.010723,-0.0010318,-365.467,-1.11844e-05,-5.90958e-05,-8.29794e-07,0,0,-0.00116032,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0014196,1.64913e-05,1.50634e-05,0.00125794,0.0241854,0.0241857,0.033267,0.0414998,0.0414993,0.084413,1.11591e-10,1.11436e-10,1.93933e-09,4e-06,4e-06,4.48361e-07,0,0,0,0,0,0,0,0 -14685000,0.705015,0.000385429,-0.0136387,0.709061,0.0129104,0.00610547,-0.0382707,0.0119533,-0.000287614,-365.464,-1.11764e-05,-5.91028e-05,-4.67101e-07,0,0,-0.00116784,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00141696,1.68842e-05,1.54629e-05,0.00125716,0.0263898,0.0263896,0.0337857,0.0464808,0.0464802,0.0855462,1.11667e-10,1.11517e-10,1.88765e-09,4e-06,4e-06,4.3804e-07,0,0,0,0,0,0,0,0 -14785000,0.704997,0.00039478,-0.0135415,0.70908,0.0102702,0.00479311,-0.0349036,0.00893349,-0.00131196,-365.459,-1.13141e-05,-5.91716e-05,-5.11184e-07,0,0,-0.00118139,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00141438,1.57168e-05,1.42924e-05,0.00125638,0.0238561,0.023856,0.0323742,0.0416498,0.0416493,0.0836658,1.03834e-10,1.03693e-10,1.8378e-09,4e-06,4e-06,4.09736e-07,0,0,0,0,0,0,0,0 -14885000,0.70505,0.000388792,-0.0135054,0.709029,0.0117411,0.00647259,-0.0371168,0.0100188,-0.000757374,-365.462,-1.13094e-05,-5.91758e-05,-2.93402e-07,0,0,-0.00118202,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00141186,1.60883e-05,1.46658e-05,0.00125562,0.0259993,0.0259997,0.0328199,0.0466342,0.0466337,0.0847305,1.03911e-10,1.03776e-10,1.78972e-09,4e-06,4e-06,4.00009e-07,0,0,0,0,0,0,0,0 -14985000,0.70497,0.000361283,-0.0134876,0.709109,0.0103175,0.00582094,-0.0334105,0.00834993,-0.000662574,-365.459,-1.13928e-05,-5.91968e-05,-4.63824e-07,0,0,-0.00119413,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00140931,1.4962e-05,1.35453e-05,0.00125494,0.0234704,0.0234707,0.0314435,0.0417579,0.0417576,0.0828889,9.67474e-11,9.66211e-11,1.74331e-09,4e-06,4e-06,3.74223e-07,0,0,0,0,0,0,0,0 -15085000,0.704976,0.000298086,-0.013468,0.709104,0.0109023,0.0060804,-0.0349123,0.00940573,-7.69141e-05,-365.465,-1.13947e-05,-5.91951e-05,-5.4917e-07,0,0,-0.00119102,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00140701,1.53031e-05,1.38967e-05,0.00125409,0.0255409,0.0255413,0.0318211,0.0467328,0.0467324,0.0838864,9.68265e-11,9.67047e-11,1.69853e-09,4e-06,4e-06,3.65088e-07,0,0,0,0,0,0,0,0 -15185000,0.704975,0.000285171,-0.0134328,0.709105,0.00975315,0.00656525,-0.0323697,0.00784243,-4.29327e-05,-365.463,-1.14659e-05,-5.92181e-05,-5.97637e-07,0,0,-0.00120033,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00140468,1.42334e-05,1.283e-05,0.00125331,0.0230367,0.0230372,0.0304856,0.0418261,0.0418258,0.0820866,9.03115e-11,9.01974e-11,1.65527e-09,4e-06,4e-06,3.41678e-07,0,0,0,0,0,0,0,0 -15285000,0.705024,0.000258358,-0.0134757,0.709056,0.0105643,0.00733307,-0.0318047,0.00887089,0.000650889,-365.462,-1.14635e-05,-5.92202e-05,-4.90819e-07,0,0,-0.0012053,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00140413,1.45583e-05,1.31642e-05,0.00125279,0.0250394,0.0250401,0.0312022,0.0467803,0.04678,0.0847775,9.03969e-11,9.02859e-11,1.62381e-09,4e-06,4e-06,3.35269e-07,0,0,0,0,0,0,0,0 -15385000,0.705162,0.000246053,-0.0134296,0.708919,0.00987798,0.00735134,-0.0293938,0.00569513,0.000552551,-365.459,-1.15478e-05,-5.92583e-05,-2.65462e-08,0,0,-0.00121327,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00140186,1.35452e-05,1.21565e-05,0.00125204,0.0225729,0.0225739,0.0298834,0.041857,0.0418568,0.0829472,8.44948e-11,8.43908e-11,1.58308e-09,4e-06,4e-06,3.13857e-07,0,0,0,0,0,0,0,0 -15485000,0.705054,0.000263849,-0.0134403,0.709027,0.0113499,0.00731346,-0.0288746,0.0067483,0.00126726,-365.463,-1.15564e-05,-5.92506e-05,-4.27739e-07,0,0,-0.00121215,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00139964,1.38564e-05,1.24692e-05,0.00125129,0.0244998,0.0245008,0.030153,0.0467808,0.0467807,0.0838506,8.45766e-11,8.44765e-11,1.54374e-09,4e-06,4e-06,3.05927e-07,0,0,0,0,0,0,0,0 -15585000,0.704967,0.000255992,-0.0134004,0.709113,0.00926213,0.00697967,-0.026863,0.00384957,0.00102023,-365.464,-1.16478e-05,-5.92759e-05,-6.59205e-07,0,0,-0.00121573,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00139735,1.29045e-05,1.15227e-05,0.00125065,0.0220807,0.0220816,0.0288844,0.0418537,0.0418536,0.0820687,7.92462e-11,7.91527e-11,1.50568e-09,4e-06,4e-06,2.8659e-07,0,0,0,0,0,0,0,0 -15685000,0.704953,0.000266728,-0.0134304,0.709127,0.00988309,0.00735775,-0.0272771,0.00478465,0.00174283,-365.466,-1.16491e-05,-5.92748e-05,-7.16504e-07,0,0,-0.0012164,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00139518,1.3197e-05,1.18187e-05,0.00124995,0.0239398,0.0239407,0.0290958,0.046739,0.046739,0.0828903,7.93292e-11,7.92393e-11,1.46887e-09,4e-06,4e-06,2.79172e-07,0,0,0,0,0,0,0,0 -15785000,0.704948,0.000254648,-0.0134529,0.709132,0.00958514,0.0056247,-0.0282833,0.00403107,0.000383029,-365.47,-1.16962e-05,-5.93362e-05,-7.63033e-07,0,0,-0.0012159,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00139306,1.23087e-05,1.09371e-05,0.00124924,0.021581,0.0215817,0.0278803,0.0418195,0.0418195,0.0811588,7.45243e-11,7.44402e-11,1.43328e-09,4e-06,4e-06,2.61745e-07,0,0,0,0,0,0,0,0 -15885000,0.704896,0.000212789,-0.0134589,0.709183,0.0109498,0.005828,-0.0275493,0.00508464,0.000944499,-365.472,-1.1699e-05,-5.93336e-05,-8.95592e-07,0,0,-0.00121715,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00139246,1.25781e-05,1.12154e-05,0.00124887,0.0233695,0.0233704,0.0284164,0.0466601,0.0466602,0.0836459,7.46124e-11,7.45307e-11,1.40737e-09,4e-06,4e-06,2.56607e-07,0,0,0,0,0,0,0,0 -15985000,0.704973,0.000155104,-0.0134541,0.709107,0.0102944,0.00472634,-0.0241003,0.00425753,-0.000231796,-365.467,-1.1738e-05,-5.93945e-05,-4.91459e-07,0,0,-0.00122576,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00139021,1.17433e-05,1.03917e-05,0.00124835,0.0210747,0.0210754,0.0272299,0.0417582,0.0417582,0.0818946,7.02855e-11,7.02093e-11,1.37376e-09,4e-06,4e-06,2.40753e-07,0,0,0,0,0,0,0,0 -16085000,0.705028,0.000159554,-0.01348,0.709051,0.0121556,0.00519708,-0.0217901,0.00538006,0.000243581,-365.463,-1.17342e-05,-5.93979e-05,-3.16635e-07,0,0,-0.00123193,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00138817,1.20039e-05,1.06564e-05,0.0012477,0.0227976,0.0227985,0.027362,0.0465488,0.0465489,0.0826213,7.03706e-11,7.02974e-11,1.34122e-09,4e-06,4e-06,2.34393e-07,0,0,0,0,0,0,0,0 -16185000,0.705091,0.000160605,-0.0134356,0.70899,0.0118282,0.00498803,-0.0200079,0.00448208,0.000169109,-365.46,-1.17788e-05,-5.942e-05,-4.57552e-08,0,0,-0.00123823,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0013861,1.12322e-05,9.88713e-06,0.00124711,0.0205721,0.0205728,0.0262324,0.041673,0.0416731,0.0809245,6.64757e-11,6.64076e-11,1.30973e-09,4e-06,4e-06,2.20144e-07,0,0,0,0,0,0,0,0 -16285000,0.705216,0.00017887,-0.0134588,0.708865,0.0140089,0.00495166,-0.0207422,0.00578733,0.000682832,-365.463,-1.17708e-05,-5.94271e-05,3.3013e-07,0,0,-0.00123766,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00138417,1.14812e-05,1.01383e-05,0.00124644,0.0222308,0.0222316,0.0263276,0.0464098,0.04641,0.0815902,6.65618e-11,6.64965e-11,1.27923e-09,4e-06,4e-06,2.14259e-07,0,0,0,0,0,0,0,0 -16385000,0.705169,0.000139985,-0.0134577,0.708912,0.0127651,0.00376831,-0.0197348,0.00485331,0.00056105,-365.462,-1.18273e-05,-5.94392e-05,1.66519e-07,0,0,-0.001242,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00138226,1.07592e-05,9.42608e-06,0.0012458,0.020076,0.0200764,0.0252549,0.0415672,0.0415674,0.079948,6.30546e-11,6.29941e-11,1.2497e-09,4e-06,4e-06,2.01462e-07,0,0,0,0,0,0,0,0 -16485000,0.705144,0.000145306,-0.013415,0.708937,0.0122856,0.00481248,-0.0218717,0.00607998,0.000993397,-365.466,-1.18288e-05,-5.94378e-05,9.76501e-08,0,0,-0.00123963,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00138036,1.09944e-05,9.66129e-06,0.0012452,0.0216742,0.0216747,0.0253183,0.0462474,0.0462476,0.0805559,6.31416e-11,6.30837e-11,1.22107e-09,4e-06,4e-06,1.96028e-07,0,0,0,0,0,0,0,0 -16585000,0.705241,0.000255585,-0.0133556,0.708842,0.00971797,0.00526797,-0.0229298,0.00314186,0.00281743,-365.466,-1.19227e-05,-5.94025e-05,3.41228e-07,0,0,-0.00124129,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00137994,1.03383e-05,8.99777e-06,0.00124475,0.0195932,0.0195934,0.0246082,0.041444,0.0414442,0.080558,5.99848e-11,5.993e-11,1.20021e-09,4e-06,4e-06,1.85773e-07,0,0,0,0,0,0,0,0 -16685000,0.705184,0.000255307,-0.0133511,0.708899,0.0104882,0.00604291,-0.0207102,0.00416451,0.0033882,-365.461,-1.19278e-05,-5.9398e-05,9.91293e-08,0,0,-0.00124793,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00137816,1.05619e-05,9.22417e-06,0.00124409,0.0211341,0.0211344,0.0246497,0.0460658,0.046066,0.0811337,6.00724e-11,6.00201e-11,1.17309e-09,4e-06,4e-06,1.80767e-07,0,0,0,0,0,0,0,0 -16785000,0.705189,0.000269097,-0.0133116,0.708894,0.00778513,0.00656027,-0.0202197,0.00153913,0.00479548,-365.46,-1.20136e-05,-5.93686e-05,8.74649e-08,0,0,-0.00125039,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00137636,9.94272e-06,8.60967e-06,0.00124347,0.0191232,0.0191234,0.0236676,0.0413062,0.0413064,0.0795368,5.72212e-11,5.71722e-11,1.14681e-09,4e-06,4e-06,1.70346e-07,0,0,0,0,0,0,0,0 -16885000,0.705129,0.000283035,-0.0132659,0.708955,0.00801181,0.00778161,-0.018668,0.00234208,0.00547567,-365.456,-1.20155e-05,-5.9367e-05,-1.79249e-09,0,0,-0.00125517,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00137447,1.01583e-05,8.82398e-06,0.00124299,0.0206096,0.0206099,0.0236853,0.0458682,0.0458683,0.0800585,5.73097e-11,5.72629e-11,1.12132e-09,4e-06,4e-06,1.65734e-07,0,0,0,0,0,0,0,0 -16985000,0.70506,0.000244227,-0.0131992,0.709025,0.00786525,0.00612263,-0.018293,0.00106306,0.00367767,-365.456,-1.2069e-05,-5.9415e-05,-2.22138e-07,0,0,-0.00125494,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00137269,9.58259e-06,8.25373e-06,0.00124242,0.0186688,0.018669,0.0227542,0.0411562,0.0411564,0.0785039,5.47334e-11,5.46893e-11,1.09657e-09,4e-06,4e-06,1.56366e-07,0,0,0,0,0,0,0,0 -17085000,0.705076,0.000210657,-0.0132942,0.709007,0.00914229,0.00722485,-0.0177615,0.00190725,0.00432484,-365.458,-1.20681e-05,-5.94158e-05,-1.82097e-07,0,0,-0.00125466,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00137097,9.78342e-06,8.46726e-06,0.00124184,0.0201023,0.0201026,0.0227518,0.0456576,0.0456578,0.0789748,5.48225e-11,5.47806e-11,1.07257e-09,4e-06,4e-06,1.52121e-07,0,0,0,0,0,0,0,0 -17185000,0.705133,0.00022452,-0.0132451,0.708952,0.00925943,0.00775437,-0.0187863,0.000752542,0.00279828,-365.463,-1.21133e-05,-5.94663e-05,-4.83905e-08,0,0,-0.00125113,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00137055,9.25476e-06,7.93904e-06,0.00124147,0.0182314,0.018232,0.022151,0.0409962,0.0409964,0.0790193,5.24929e-11,5.24532e-11,1.05505e-09,4e-06,4e-06,1.44698e-07,0,0,0,0,0,0,0,0 -17285000,0.705105,0.000197579,-0.0132225,0.70898,0.0119322,0.00907131,-0.0150342,0.00181408,0.00363138,-365.456,-1.21138e-05,-5.9466e-05,-7.35042e-08,0,0,-0.00125835,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00136878,9.44838e-06,8.13775e-06,0.00124099,0.0196184,0.0196195,0.0221354,0.0454371,0.0454373,0.0794599,5.25826e-11,5.25449e-11,1.03227e-09,4e-06,4e-06,1.40792e-07,0,0,0,0,0,0,0,0 -17385000,0.705156,0.000189041,-0.0131722,0.70893,0.0119766,0.00875514,-0.0131293,0.00164032,0.00221887,-365.453,-1.21424e-05,-5.95157e-05,1.43535e-09,0,0,-0.00126309,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00136717,8.95425e-06,7.64607e-06,0.00124036,0.0178169,0.017818,0.0212912,0.0408285,0.0408287,0.0779572,5.04663e-11,5.0432e-11,1.01014e-09,4e-06,4e-06,1.3316e-07,0,0,0,0,0,0,0,0 -17485000,0.705166,0.000190078,-0.0131831,0.70892,0.013034,0.00870401,-0.0113482,0.0028694,0.00309153,-365.451,-1.21419e-05,-5.95161e-05,2.31535e-08,0,0,-0.00126548,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00136553,9.14426e-06,7.83957e-06,0.00123983,0.0191592,0.0191604,0.0212613,0.0452096,0.04521,0.0783517,5.05566e-11,5.05242e-11,9.8866e-10,4e-06,4e-06,1.29569e-07,0,0,0,0,0,0,0,0 -17585000,0.705161,0.000134691,-0.0131627,0.708925,0.0135813,0.00762207,-0.00652555,0.00254469,0.00173294,-365.443,-1.21731e-05,-5.95613e-05,8.01887e-08,0,0,-0.00127336,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00136382,8.67811e-06,7.38404e-06,0.00123938,0.0174219,0.017423,0.0204671,0.040655,0.0406553,0.0769046,4.86317e-11,4.86026e-11,9.67789e-10,4e-06,4e-06,1.22714e-07,0,0,0,0,0,0,0,0 -17685000,0.705171,0.000101169,-0.0131547,0.708915,0.0152122,0.00869645,-0.00688027,0.00399194,0.00254963,-365.443,-1.21713e-05,-5.9563e-05,1.65929e-07,0,0,-0.00127344,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00136217,8.85732e-06,7.56999e-06,0.00123893,0.0187244,0.0187259,0.0204259,0.0449773,0.0449777,0.0772564,4.87226e-11,4.86952e-11,9.47523e-10,4e-06,4e-06,1.19416e-07,0,0,0,0,0,0,0,0 -17785000,0.705294,3.84778e-05,-0.0131415,0.708793,0.0163298,0.00820935,-0.00711588,0.00368088,0.00219548,-365.446,-1.21784e-05,-5.95934e-05,5.91543e-07,0,0,-0.00127264,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00136053,8.42098e-06,7.14526e-06,0.00123849,0.0170501,0.0170515,0.0196792,0.0404776,0.0404779,0.0758633,4.69671e-11,4.69432e-11,9.27827e-10,4e-06,4e-06,1.13255e-07,0,0,0,0,0,0,0,0 -17885000,0.705307,4.85199e-05,-0.0131377,0.70878,0.0183194,0.00796005,-0.00639133,0.00540578,0.00303555,-365.446,-1.21777e-05,-5.95941e-05,6.27348e-07,0,0,-0.00127317,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00136015,8.59981e-06,7.32571e-06,0.00123817,0.0183141,0.0183156,0.0198732,0.0447425,0.044743,0.0776546,4.70609e-11,4.70377e-11,9.13443e-10,4e-06,4e-06,1.10977e-07,0,0,0,0,0,0,0,0 -17985000,0.705384,3.65968e-06,-0.0131145,0.708704,0.0190929,0.00569918,-0.00458154,0.00491678,0.00254608,-365.445,-1.21992e-05,-5.96156e-05,7.25106e-07,0,0,-0.0012753,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00135876,8.19419e-06,6.92875e-06,0.00123752,0.0166993,0.0167001,0.0191569,0.0402979,0.0402983,0.0762615,4.54557e-11,4.54352e-11,8.94703e-10,4e-06,4e-06,1.05374e-07,0,0,0,0,0,0,0,0 -18085000,0.705293,5.53012e-06,-0.0131351,0.708794,0.0201441,0.0058956,-0.00283966,0.00688354,0.00308844,-365.44,-1.22046e-05,-5.96105e-05,4.62553e-07,0,0,-0.00127906,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00135727,8.3667e-06,7.10524e-06,0.00123701,0.0179295,0.0179303,0.0191012,0.0445071,0.0445075,0.0765484,4.5548e-11,4.55281e-11,8.76489e-10,4e-06,4e-06,1.02585e-07,0,0,0,0,0,0,0,0 -18185000,0.705371,-3.41119e-05,-0.0130962,0.708717,0.020318,0.00613237,-0.00137819,0.00692216,0.00271016,-365.438,-1.22307e-05,-5.96289e-05,6.32829e-07,0,0,-0.00128102,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00135585,7.98806e-06,6.73335e-06,0.00123646,0.0163712,0.016372,0.0184286,0.0401175,0.0401178,0.0752084,4.40756e-11,4.40582e-11,8.58769e-10,4e-06,4e-06,9.75415e-08,0,0,0,0,0,0,0,0 -18285000,0.705386,-9.54927e-05,-0.0130596,0.708703,0.0208815,0.006072,-0.000307889,0.00897677,0.00332701,-365.436,-1.22329e-05,-5.96267e-05,5.21975e-07,0,0,-0.00128227,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00135456,8.148e-06,6.90163e-06,0.00123582,0.0175686,0.0175692,0.0183647,0.0442727,0.0442732,0.0754493,4.41683e-11,4.41515e-11,8.41527e-10,4e-06,4e-06,9.49713e-08,0,0,0,0,0,0,0,0 -18385000,0.705504,-9.55072e-05,-0.0130718,0.708586,0.0218138,0.00718912,0.00106111,0.00879298,0.00297249,-365.432,-1.22609e-05,-5.96467e-05,7.56543e-07,0,0,-0.00128493,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00135323,7.79766e-06,6.55643e-06,0.00123523,0.0160643,0.0160653,0.0177332,0.0399374,0.0399378,0.0741608,4.28139e-11,4.27995e-11,8.24763e-10,4e-06,4e-06,9.04272e-08,0,0,0,0,0,0,0,0 -18485000,0.705554,-6.67484e-05,-0.0130674,0.708536,0.0232937,0.00783233,0.000902742,0.0110942,0.00372242,-365.43,-1.22583e-05,-5.96492e-05,8.82926e-07,0,0,-0.00128608,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00135289,7.96447e-06,6.7225e-06,0.00123492,0.0172337,0.0172347,0.0178833,0.044041,0.0440415,0.0757906,4.29087e-11,4.28948e-11,8.12513e-10,4e-06,4e-06,8.86607e-08,0,0,0,0,0,0,0,0 -18585000,0.705649,-9.74425e-05,-0.0129997,0.708443,0.0226134,0.00747322,0.000266463,0.00972317,0.00323121,-365.432,-1.23094e-05,-5.96714e-05,1.08087e-06,0,0,-0.00128549,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00135157,7.62996e-06,6.39449e-06,0.00123437,0.0157794,0.0157804,0.0172783,0.0397591,0.0397595,0.0745042,4.16588e-11,4.16475e-11,7.96531e-10,4e-06,4e-06,8.45156e-08,0,0,0,0,0,0,0,0 -18685000,0.705627,-0.000142588,-0.0130286,0.708464,0.0234419,0.00744141,-0.00133095,0.0120276,0.00401677,-365.437,-1.23101e-05,-5.96707e-05,1.05068e-06,0,0,-0.00128218,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00135017,7.78384e-06,6.55846e-06,0.00123394,0.0169205,0.0169214,0.0172088,0.0438131,0.0438137,0.0746922,4.17522e-11,4.17415e-11,7.80971e-10,4e-06,4e-06,8.23404e-08,0,0,0,0,0,0,0,0 -18785000,0.705603,-0.00013728,-0.0130074,0.708488,0.0223142,0.00702254,-0.000698626,0.0105258,0.00353438,-365.438,-1.23672e-05,-5.96857e-05,9.52511e-07,0,0,-0.00128206,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00134885,7.47317e-06,6.25241e-06,0.00123343,0.0155123,0.015513,0.0166409,0.0395834,0.0395839,0.0734558,4.05952e-11,4.05872e-11,7.65828e-10,4e-06,4e-06,7.85983e-08,0,0,0,0,0,0,0,0 -18885000,0.705699,-0.000131822,-0.012992,0.708392,0.0235165,0.00808348,-0.000222535,0.0128131,0.00432289,-365.436,-1.23615e-05,-5.96911e-05,1.22863e-06,0,0,-0.00128322,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0013475,7.6297e-06,6.41036e-06,0.001233,0.0166295,0.0166303,0.0165699,0.04359,0.0435905,0.0736168,4.0689e-11,4.06815e-11,7.5108e-10,4e-06,4e-06,7.65994e-08,0,0,0,0,0,0,0,0 -18985000,0.705721,-0.000119966,-0.0129803,0.708371,0.0239087,0.0084277,-0.00164931,0.012939,0.00379921,-365.438,-1.23821e-05,-5.97119e-05,1.35434e-06,0,0,-0.00128182,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00134611,7.33872e-06,6.12172e-06,0.00123262,0.0152665,0.0152674,0.0160369,0.0394111,0.0394116,0.0724284,3.96149e-11,3.961e-11,7.36726e-10,4e-06,4e-06,7.3217e-08,0,0,0,0,0,0,0,0 -19085000,0.705747,-0.000140573,-0.0129345,0.708346,0.0251797,0.00953037,0.00160335,0.0153729,0.00472563,-365.431,-1.238e-05,-5.9714e-05,1.45564e-06,0,0,-0.00128555,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00134479,7.48882e-06,6.27469e-06,0.00123222,0.0163603,0.0163612,0.0159654,0.0433727,0.0433733,0.072565,3.9709e-11,3.97047e-11,7.2274e-10,4e-06,4e-06,7.13796e-08,0,0,0,0,0,0,0,0 -19185000,0.705755,-0.000134377,-0.0128239,0.70834,0.0243853,0.00922398,0.000386275,0.015138,0.0041666,-365.432,-1.24072e-05,-5.97351e-05,1.49219e-06,0,0,-0.00128431,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00134446,7.21217e-06,5.99647e-06,0.00123197,0.0150381,0.0150388,0.0156445,0.0392431,0.0392435,0.0727209,3.87102e-11,3.87083e-11,7.12512e-10,4e-06,4e-06,6.8742e-08,0,0,0,0,0,0,0,0 -19285000,0.705699,-0.000100928,-0.0127795,0.708397,0.0251735,0.00906944,0.00255597,0.0175831,0.00508899,-365.426,-1.241e-05,-5.97325e-05,1.35564e-06,0,0,-0.00128767,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00134319,7.36583e-06,6.14668e-06,0.00123155,0.0161122,0.0161128,0.0155733,0.043162,0.0431626,0.0728396,3.88046e-11,3.88032e-11,6.99149e-10,4e-06,4e-06,6.70457e-08,0,0,0,0,0,0,0,0 -19385000,0.705749,-0.000132895,-0.0127272,0.708347,0.0232908,0.00775109,0.00623817,0.0153487,0.00444644,-365.42,-1.24671e-05,-5.9754e-05,1.4781e-06,0,0,-0.00129091,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00134196,7.09714e-06,5.88665e-06,0.00123111,0.0148262,0.0148266,0.0150939,0.0390798,0.0390802,0.0717009,3.78704e-11,3.78713e-11,6.8613e-10,4e-06,4e-06,6.42412e-08,0,0,0,0,0,0,0,0 -19485000,0.705846,-0.000117169,-0.0127492,0.70825,0.0230393,0.00718392,0.00361323,0.017643,0.00517985,-365.424,-1.24625e-05,-5.97583e-05,1.70203e-06,0,0,-0.00128837,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00134077,7.24607e-06,6.03781e-06,0.00123064,0.0158824,0.0158825,0.0150236,0.0429584,0.0429589,0.0717991,3.7965e-11,3.79665e-11,6.73439e-10,4e-06,4e-06,6.26803e-08,0,0,0,0,0,0,0,0 -19585000,0.705925,-7.98295e-05,-0.0126628,0.708173,0.0212411,0.00581209,0.00312918,0.0154204,0.00448309,-365.426,-1.25117e-05,-5.978e-05,1.97501e-06,0,0,-0.00128732,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133949,6.99895e-06,5.78905e-06,0.0012303,0.0146329,0.014633,0.0145714,0.0389219,0.0389222,0.0706953,3.70899e-11,3.70932e-11,6.61068e-10,4e-06,4e-06,6.01313e-08,0,0,0,0,0,0,0,0 -19685000,0.705892,-9.00264e-05,-0.0127116,0.708206,0.0224745,0.00385958,0.00480809,0.0175977,0.00497062,-365.425,-1.25142e-05,-5.97776e-05,1.85014e-06,0,0,-0.00128746,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133838,7.14227e-06,5.93914e-06,0.00122982,0.0156698,0.0156698,0.0145024,0.0427625,0.0427629,0.070775,3.71848e-11,3.71887e-11,6.49011e-10,4e-06,4e-06,5.86943e-08,0,0,0,0,0,0,0,0 -19785000,0.70593,-4.7533e-05,-0.012702,0.708168,0.0198889,0.0023671,0.00505214,0.0153667,0.00425416,-365.424,-1.25652e-05,-5.97898e-05,1.8993e-06,0,0,-0.00128725,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133817,6.90807e-06,5.70601e-06,0.00122949,0.0144532,0.0144533,0.0142385,0.0387697,0.03877,0.0709596,3.6364e-11,3.63692e-11,6.40189e-10,4e-06,4e-06,5.67172e-08,0,0,0,0,0,0,0,0 -19885000,0.706054,-9.09401e-05,-0.0126502,0.708045,0.0194559,0.00243062,0.0065015,0.0173521,0.00448505,-365.423,-1.25587e-05,-5.97959e-05,2.21887e-06,0,0,-0.00128757,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133702,7.04518e-06,5.84835e-06,0.00122909,0.0154748,0.015475,0.0141712,0.0425746,0.0425748,0.0710249,3.64591e-11,3.64648e-11,6.28649e-10,4e-06,4e-06,5.53875e-08,0,0,0,0,0,0,0,0 -19985000,0.706171,-0.000136792,-0.0126336,0.707928,0.0167788,0.00101164,0.00837313,0.0151036,0.0037948,-365.419,-1.25996e-05,-5.98098e-05,2.49462e-06,0,0,-0.00128857,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133592,6.81139e-06,5.62527e-06,0.00122865,0.0142879,0.0142884,0.013764,0.0386235,0.0386237,0.0699682,3.56848e-11,3.56914e-11,6.17393e-10,4e-06,4e-06,5.32585e-08,0,0,0,0,0,0,0,0 -20085000,0.706327,-0.000158001,-0.0126107,0.707773,0.0170732,-0.00034688,0.00914497,0.0168083,0.00384896,-365.416,-1.25908e-05,-5.98181e-05,2.92353e-06,0,0,-0.00128964,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133479,6.94917e-06,5.76719e-06,0.00122828,0.0152964,0.0152973,0.0136987,0.0423949,0.042395,0.0700182,3.57802e-11,3.57873e-11,6.06419e-10,4e-06,4e-06,5.20327e-08,0,0,0,0,0,0,0,0 -20185000,0.706384,-8.0026e-05,-0.012591,0.707717,0.0150154,-0.00178092,0.011577,0.0138501,0.0032181,-365.412,-1.26428e-05,-5.98246e-05,3.08563e-06,0,0,-0.00129137,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133369,6.73966e-06,5.55389e-06,0.00122788,0.0141373,0.0141386,0.0133158,0.0384837,0.0384837,0.0690023,3.50487e-11,3.50563e-11,5.95712e-10,4e-06,4e-06,5.00938e-08,0,0,0,0,0,0,0,0 -20285000,0.706443,-0.000111695,-0.0125789,0.707658,0.0147169,-0.0030518,0.0100463,0.015332,0.0029754,-365.414,-1.26403e-05,-5.98269e-05,3.20728e-06,0,0,-0.00128996,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133268,6.87425e-06,5.69444e-06,0.00122744,0.0151334,0.0151353,0.0132529,0.0422238,0.0422238,0.0690387,3.51443e-11,3.51524e-11,5.85268e-10,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -20385000,0.706468,-0.000116521,-0.0126139,0.707633,0.0119019,-0.00455875,0.0123594,0.0125349,0.00242678,-365.409,-1.26893e-05,-5.98251e-05,3.18697e-06,0,0,-0.00129206,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133176,6.66428e-06,5.4924e-06,0.0012269,0.0140004,0.014003,0.0128929,0.0383504,0.0383504,0.0680618,3.44516e-11,3.44596e-11,5.75073e-10,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -20485000,0.706508,-8.04726e-05,-0.0126313,0.707592,0.0122238,-0.00516569,0.0124652,0.0137309,0.00194611,-365.41,-1.26889e-05,-5.98255e-05,3.20685e-06,0,0,-0.00129094,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133166,6.80519e-06,5.63286e-06,0.00122653,0.0149836,0.0149867,0.0129748,0.0420614,0.0420615,0.0692652,3.45484e-11,3.45568e-11,5.67609e-10,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -20585000,0.706472,-6.41706e-05,-0.0126774,0.707628,0.0116998,-0.00592422,0.00962808,0.0119845,0.00150939,-365.414,-1.27215e-05,-5.98189e-05,3.10051e-06,0,0,-0.00128803,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00133066,6.60674e-06,5.43891e-06,0.00122609,0.0138755,0.0138787,0.0126306,0.0382238,0.0382239,0.0682927,3.38908e-11,3.38986e-11,5.57831e-10,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -20685000,0.706533,-4.55347e-05,-0.0127039,0.707566,0.0124784,-0.00703427,0.0107788,0.0131874,0.000879763,-365.41,-1.27202e-05,-5.98201e-05,3.16555e-06,0,0,-0.00128945,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132977,6.74399e-06,5.57817e-06,0.00122558,0.0148488,0.0148526,0.0125753,0.0419079,0.041908,0.0683072,3.39868e-11,3.3995e-11,5.48287e-10,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -20785000,0.70658,-2.61289e-05,-0.0126767,0.70752,0.0105288,-0.00682163,0.0108203,0.0114921,0.000617676,-365.41,-1.2748e-05,-5.98136e-05,3.23278e-06,0,0,-0.00128831,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132881,6.55332e-06,5.38694e-06,0.00122511,0.0137609,0.013765,0.0122533,0.038104,0.0381041,0.0673718,3.33608e-11,3.33683e-11,5.38963e-10,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -20885000,0.706693,-4.18182e-05,-0.012673,0.707407,0.010757,-0.00907245,0.0104502,0.0125642,-0.000177488,-365.411,-1.27437e-05,-5.98176e-05,3.44308e-06,0,0,-0.00128735,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132792,6.68501e-06,5.52301e-06,0.00122464,0.0147243,0.0147298,0.0122021,0.0417629,0.0417633,0.0673692,3.34569e-11,3.3465e-11,5.29857e-10,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -20985000,0.706716,-3.63354e-05,-0.0126771,0.707384,0.00949774,-0.0105255,0.0111115,0.0125478,-0.000411205,-365.411,-1.27573e-05,-5.98069e-05,3.48662e-06,0,0,-0.00128683,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132695,6.50037e-06,5.33941e-06,0.0012242,0.0136561,0.0136626,0.0119015,0.0379908,0.0379912,0.0664696,3.28598e-11,3.28668e-11,5.20965e-10,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -21085000,0.70683,-5.20606e-05,-0.0126779,0.707269,0.0101918,-0.0128428,0.011941,0.0135181,-0.0015857,-365.41,-1.27545e-05,-5.98096e-05,3.62475e-06,0,0,-0.0012868,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132695,6.63067e-06,5.47427e-06,0.00122378,0.0146105,0.0146183,0.0119843,0.0416265,0.0416273,0.0675901,3.2957e-11,3.29644e-11,5.14457e-10,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -21185000,0.706837,-2.40992e-05,-0.0126655,0.707263,0.00981364,-0.0127569,0.0113878,0.013408,-0.00166107,-365.413,-1.27695e-05,-5.97915e-05,3.58047e-06,0,0,-0.00128466,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132605,6.45523e-06,5.29538e-06,0.00122327,0.0135604,0.0135681,0.0116988,0.0378841,0.0378848,0.0666951,3.23863e-11,3.23922e-11,5.0592e-10,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -21285000,0.706989,8.09925e-06,-0.0126319,0.707111,0.00970911,-0.014574,0.0128266,0.0143828,-0.00302103,-365.409,-1.27651e-05,-5.97955e-05,3.79145e-06,0,0,-0.00128559,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132533,6.5899e-06,5.42706e-06,0.00122269,0.0145067,0.0145161,0.0116605,0.0414983,0.0414996,0.0666785,3.24827e-11,3.24891e-11,4.97576e-10,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -21385000,0.706953,3.7846e-05,-0.0126126,0.707148,0.00817352,-0.0152197,0.0130346,0.0124972,-0.00220028,-365.411,-1.2792e-05,-5.97619e-05,3.72895e-06,0,0,-0.00128394,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132433,6.41907e-06,5.25285e-06,0.0012223,0.0134731,0.013483,0.0113949,0.0377839,0.0377851,0.0658179,3.19358e-11,3.1941e-11,4.89424e-10,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -21485000,0.707021,4.64958e-05,-0.0125955,0.70708,0.00835762,-0.0163519,0.0130451,0.0132916,-0.00376663,-365.411,-1.27895e-05,-5.97641e-05,3.8471e-06,0,0,-0.00128335,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132349,6.54975e-06,5.38423e-06,0.00122187,0.0144121,0.0144233,0.0113639,0.0413782,0.0413801,0.0657968,3.20323e-11,3.20383e-11,4.81454e-10,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -21585000,0.707025,3.7993e-05,-0.0125506,0.707077,0.00682724,-0.0145948,0.0128771,0.0115124,-0.00280885,-365.414,-1.28124e-05,-5.97297e-05,3.81885e-06,0,0,-0.00128141,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132259,6.37979e-06,5.21306e-06,0.00122139,0.0133934,0.0134038,0.0111172,0.0376899,0.0376917,0.0649691,3.15076e-11,3.15121e-11,4.73665e-10,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -21685000,0.70704,3.31267e-05,-0.0125923,0.707062,0.0075389,-0.0158352,0.0146194,0.0122255,-0.0043474,-365.413,-1.28117e-05,-5.97303e-05,3.85225e-06,0,0,-0.00128106,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132172,6.50778e-06,5.34651e-06,0.00122102,0.0143245,0.0143358,0.0110939,0.0412658,0.0412685,0.064945,3.16042e-11,3.16095e-11,4.66049e-10,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -21785000,0.707023,1.46277e-05,-0.0125739,0.707078,0.00630923,-0.0125438,0.013547,0.0098701,-0.00174825,-365.417,-1.2845e-05,-5.96729e-05,3.77841e-06,0,0,-0.00127863,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132153,6.33932e-06,5.18057e-06,0.00122068,0.0133202,0.0133298,0.0109745,0.037602,0.0376043,0.0651947,3.11008e-11,3.11044e-11,4.60472e-10,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -21885000,0.70706,1.39583e-05,-0.0125295,0.707042,0.00721792,-0.0127876,0.0144374,0.0105434,-0.00301138,-365.418,-1.28452e-05,-5.96727e-05,3.76609e-06,0,0,-0.00127759,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00132081,6.46669e-06,5.30816e-06,0.00122019,0.0142452,0.0142549,0.0109587,0.0411609,0.0411642,0.0651682,3.11975e-11,3.12018e-11,4.53147e-10,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -21985000,0.707111,1.29804e-05,-0.0125562,0.706991,0.00589024,-0.0114891,0.0149181,0.00844984,-0.000632796,-365.419,-1.28727e-05,-5.96232e-05,3.82533e-06,-1.6478e-12,1.64053e-12,-0.001276,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131997,6.3044e-06,5.14839e-06,0.00121969,0.013277,0.0132862,0.0107423,0.0375198,0.0375226,0.064378,3.07122e-11,3.0715e-11,4.45984e-10,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -22085000,0.707132,1.9016e-05,-0.0125474,0.706971,0.00623203,-0.0106702,0.0135134,0.00907691,-0.00173073,-365.421,-1.28728e-05,-5.96232e-05,3.82388e-06,1.08181e-09,-1.07726e-09,-0.00127478,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131919,6.43162e-06,5.27695e-06,0.00121928,0.0147976,0.0148069,0.0107347,0.0410653,0.0410692,0.0643515,3.08091e-11,3.08126e-11,4.38977e-10,4.00001e-06,4.00001e-06,5.0001e-08,0,0,0,0,0,0,0,0 -22185000,0.707181,3.98389e-06,-0.0125123,0.706922,0.0056721,-0.00990948,0.0144718,0.00793171,-0.00170483,-365.422,-1.28872e-05,-5.96107e-05,3.87911e-06,-2.25692e-06,-1.38474e-06,-0.00127353,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131837,6.27419e-06,5.11815e-06,0.0012188,0.0150774,0.0150854,0.0105339,0.0374514,0.0374546,0.0635855,3.03421e-11,3.03441e-11,4.3212e-10,3.98819e-06,3.98819e-06,5e-08,0,0,0,0,0,0,0,0 -22285000,0.707156,3.64391e-05,-0.0125508,0.706946,0.00486508,-0.0107222,0.0145767,0.00845968,-0.00274228,-365.424,-1.28884e-05,-5.96096e-05,3.8238e-06,-2.24667e-06,-1.39467e-06,-0.0012724,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131754,6.40361e-06,5.2484e-06,0.00121845,0.0181183,0.0181278,0.0105349,0.0410382,0.0410425,0.0635605,3.0439e-11,3.04418e-11,4.25414e-10,3.9882e-06,3.9882e-06,5e-08,0,0,0,0,0,0,0,0 -22385000,0.707182,2.55828e-05,-0.0125343,0.706921,0.00317433,-0.0100882,0.0161628,0.00731778,-0.0025983,-365.421,-1.28999e-05,-5.9597e-05,3.88615e-06,-7.57871e-06,-4.01562e-06,-0.00127275,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131731,6.25414e-06,5.09821e-06,0.00121818,0.0193376,0.0193463,0.0104512,0.0374669,0.0374705,0.0638335,2.99979e-11,2.9999e-11,4.20503e-10,3.92264e-06,3.92264e-06,5.0002e-08,0,0,0,0,0,0,0,0 -22485000,0.70722,3.13099e-05,-0.0125041,0.706883,0.00314694,-0.00994909,0.01758,0.00763859,-0.00362621,-365.417,-1.28989e-05,-5.95978e-05,3.9315e-06,-7.59767e-06,-3.99748e-06,-0.00127356,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131655,6.37956e-06,5.22376e-06,0.00121779,0.0237276,0.0237368,0.0104605,0.0412312,0.041236,0.0638106,3.0095e-11,3.00968e-11,4.14046e-10,3.92265e-06,3.92265e-06,5.0002e-08,0,0,0,0,0,0,0,0 -22585000,0.707267,5.45766e-06,-0.0124668,0.706837,0.00240174,-0.00890421,0.0166758,0.00579827,-0.0024792,-365.419,-1.29076e-05,-5.95757e-05,3.99152e-06,-2.25019e-05,-5.51651e-07,-0.00127203,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131574,6.24386e-06,5.08857e-06,0.00121734,0.0251085,0.0251162,0.0102858,0.0376874,0.0376913,0.0630809,2.96948e-11,2.96951e-11,4.07725e-10,3.77381e-06,3.77379e-06,5.0001e-08,0,0,0,0,0,0,0,0 -22685000,0.707309,4.12612e-05,-0.0124973,0.706795,0.00170416,-0.00874675,0.0180001,0.00602111,-0.0033686,-365.418,-1.29063e-05,-5.95768e-05,4.05297e-06,-2.24943e-05,-5.60517e-07,-0.00127188,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131499,6.3723e-06,5.21688e-06,0.00121696,0.0305674,0.0305757,0.0103032,0.0417947,0.0417997,0.0630622,2.97921e-11,2.9793e-11,4.0154e-10,3.77382e-06,3.7738e-06,5.0001e-08,0,0,0,0,0,0,0,0 -22785000,0.707229,2.47145e-05,-0.0124713,0.706874,0.000180016,-0.00680691,0.0187784,0.00350611,-0.00292125,-365.414,-1.29284e-05,-5.95613e-05,3.79409e-06,-3.09093e-05,-4.89748e-06,-0.00127247,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131428,6.2654e-06,5.11092e-06,0.00121646,0.0312168,0.0312224,0.0101411,0.0382008,0.0382047,0.0623615,2.9454e-11,2.94537e-11,3.95483e-10,3.53491e-06,3.53485e-06,5e-08,0,0,0,0,0,0,0,0 -22885000,0.707264,3.44389e-05,-0.0124518,0.70684,-0.000665174,-0.00648123,0.0204198,0.00349079,-0.00358456,-365.412,-1.29287e-05,-5.95611e-05,3.78006e-06,-3.09109e-05,-4.89543e-06,-0.00127252,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131362,6.3905e-06,5.23617e-06,0.00121601,0.0373761,0.0373819,0.0101659,0.0427853,0.0427902,0.0623484,2.95514e-11,2.95516e-11,3.89554e-10,3.53492e-06,3.53486e-06,5e-08,0,0,0,0,0,0,0,0 -22985000,0.707299,2.38765e-05,-0.0124334,0.706805,-0.00189168,-0.0060345,0.0214356,0.00132542,-0.00307792,-365.409,-1.29396e-05,-5.95536e-05,3.7984e-06,-3.80799e-05,-7.1951e-06,-0.00127269,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131288,6.32154e-06,5.16845e-06,0.00121557,0.0365647,0.0365686,0.0100149,0.0390068,0.0390105,0.0616756,2.9291e-11,2.92903e-11,3.83748e-10,3.22343e-06,3.22332e-06,5e-08,0,0,0,0,0,0,0,0 -23085000,0.707299,-1.73535e-05,-0.0123891,0.706806,-0.00208618,-0.00587287,0.0215798,0.00112554,-0.00365581,-365.405,-1.29403e-05,-5.9553e-05,3.76622e-06,-3.81531e-05,-7.12178e-06,-0.00127346,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131278,6.44094e-06,5.29267e-06,0.00121533,0.043029,0.0430328,0.0101402,0.0441282,0.0441328,0.0626346,2.93892e-11,2.93887e-11,3.79496e-10,3.22344e-06,3.22333e-06,5.0002e-08,0,0,0,0,0,0,0,0 -23185000,0.70733,2.90151e-05,-0.0123562,0.706776,-0.00701498,-0.00584271,0.0228747,-0.00404903,-0.0030754,-365.401,-1.29668e-05,-5.95462e-05,3.7498e-06,-4.53508e-05,-4.02604e-05,-0.00127402,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131209,6.41898e-06,5.26644e-06,0.00121487,0.0404351,0.0404374,0.00999581,0.0400178,0.0400211,0.061968,2.92105e-11,2.92093e-11,3.73897e-10,2.8724e-06,2.87223e-06,5.0001e-08,0,0,0,0,0,0,0,0 -23285000,0.707331,-3.96789e-05,-0.0123731,0.706774,-0.00749874,-0.00710775,0.0234307,-0.00477582,-0.00373762,-365.401,-1.29666e-05,-5.95463e-05,3.75727e-06,-4.52449e-05,-4.03648e-05,-0.00127315,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131132,6.5361e-06,5.39486e-06,0.00121458,0.046851,0.0468536,0.0100339,0.0456511,0.045655,0.0619687,2.93081e-11,2.93073e-11,3.68415e-10,2.8724e-06,2.87223e-06,5.0001e-08,0,0,0,0,0,0,0,0 -23385000,0.707372,2.18971e-05,-0.0123315,0.706733,-0.011542,-0.00633353,0.021982,-0.00919956,-0.00304959,-365.404,-1.29809e-05,-5.95402e-05,3.75984e-06,-5.34368e-05,-6.62523e-05,-0.00127095,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00131066,6.55595e-06,5.40756e-06,0.00121412,0.0425985,0.0425999,0.00989815,0.041104,0.0411067,0.0613285,2.92036e-11,2.92022e-11,3.63044e-10,2.5166e-06,2.51637e-06,5.0001e-08,0,0,0,0,0,0,0,0 -23485000,0.707436,0.00215851,-0.0101751,0.706701,-0.0183851,-0.00705204,-0.00995534,-0.0106419,-0.00372695,-365.405,-1.29788e-05,-5.9542e-05,3.86039e-06,-5.33635e-05,-6.63323e-05,-0.00127039,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00130971,6.94424e-06,5.43277e-06,0.00121387,0.0487182,0.04872,0.00994068,0.0471609,0.0471642,0.0613314,2.93012e-11,2.93004e-11,3.57782e-10,2.5166e-06,2.51637e-06,5e-08,0,0,0,0,0,0,0,0 -23585000,0.70705,0.00751155,-0.0025524,0.707119,-0.0276212,-0.00361727,-0.0416728,-0.010075,-0.00159642,-365.406,-1.29705e-05,-5.95331e-05,3.79611e-06,-7.1756e-05,-5.33723e-05,-0.00127093,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00130705,7.75488e-06,5.28903e-06,0.00121491,0.0432262,0.0432221,0.00981123,0.042145,0.0421472,0.0607164,2.92563e-11,2.92551e-11,3.52631e-10,2.1826e-06,2.18229e-06,5e-08,0,0,0,0,0,0,0,0 -23685000,0.706421,0.00736923,0.00369089,0.707744,-0.0581232,-0.011343,-0.0904181,-0.01426,-0.00226884,-365.414,-1.29703e-05,-5.95331e-05,3.80426e-06,-7.16664e-05,-5.34601e-05,-0.0012703,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00130448,7.87683e-06,5.46101e-06,0.00121712,0.0489062,0.0488816,0.00994511,0.0485088,0.0485111,0.0616699,2.93546e-11,2.93537e-11,3.48859e-10,2.1826e-06,2.18229e-06,5.0002e-08,0,0,0,0,0,0,0,0 -23785000,0.706128,0.00452115,0.000744216,0.70807,-0.0776397,-0.0200523,-0.144054,-0.0123407,-0.000588632,-365.424,-1.29517e-05,-5.95283e-05,3.83757e-06,-9.42506e-05,3.79269e-07,-0.00127201,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00130298,7.51936e-06,5.48783e-06,0.00121782,0.0426883,0.0426399,0.00981938,0.0430581,0.0430598,0.0610601,2.93541e-11,2.93527e-11,3.43885e-10,1.88537e-06,1.88504e-06,5.0002e-08,0,0,0,0,0,0,0,0 -23885000,0.705976,0.00182514,-0.00532704,0.708213,-0.0944699,-0.0290011,-0.197344,-0.0210703,-0.00309525,-365.445,-1.29504e-05,-5.95292e-05,3.89512e-06,-9.40635e-05,2.02299e-07,-0.00127072,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00130223,7.27956e-06,5.65977e-06,0.00121792,0.0478434,0.0477678,0.00986977,0.0496075,0.0496087,0.0610809,2.94519e-11,2.94509e-11,3.39011e-10,1.88537e-06,1.88504e-06,5.0001e-08,0,0,0,0,0,0,0,0 -23985000,0.705903,0.000373492,-0.010049,0.708237,-0.0939289,-0.0318753,-0.250222,-0.0250983,-0.00616334,-365.467,-1.29388e-05,-5.9532e-05,3.89575e-06,-9.97755e-05,2.10065e-05,-0.00127123,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00130126,7.19096e-06,5.90535e-06,0.00121717,0.0412802,0.0412182,0.0097538,0.0437995,0.0438004,0.0604946,2.94822e-11,2.9481e-11,3.34229e-10,1.63008e-06,1.62981e-06,5.0001e-08,0,0,0,0,0,0,0,0 -24085000,0.705941,0.00157218,-0.00902576,0.708212,-0.0953722,-0.0317933,-0.298164,-0.0345308,-0.0093465,-365.492,-1.29367e-05,-5.95343e-05,4.00687e-06,-9.9924e-05,2.11526e-05,-0.0012723,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00130038,7.46967e-06,5.99968e-06,0.00121697,0.0458681,0.0457998,0.00980986,0.0504249,0.0504243,0.0605247,2.95801e-11,2.95793e-11,3.29545e-10,1.63008e-06,1.62982e-06,5e-08,0,0,0,0,0,0,0,0 -24185000,0.705956,0.0027049,-0.00663558,0.70822,-0.0955245,-0.0314796,-0.345549,-0.0362076,-0.0110676,-365.517,-1.29224e-05,-5.95368e-05,4.05709e-06,-0.000109826,4.65933e-05,-0.00127655,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00129913,7.72008e-06,6.02844e-06,0.00121657,0.039348,0.0392893,0.00969997,0.044356,0.0443558,0.0599609,2.96312e-11,2.96304e-11,3.24953e-10,1.41542e-06,1.41531e-06,5e-08,0,0,0,0,0,0,0,0 -24285000,0.705863,0.00322037,-0.00572494,0.708318,-0.105583,-0.0353019,-0.400536,-0.0462597,-0.0144278,-365.558,-1.29241e-05,-5.95349e-05,3.96824e-06,-0.000109668,4.64391e-05,-0.00127539,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00129821,7.92347e-06,6.14385e-06,0.00121648,0.0434352,0.0433607,0.00975925,0.0509698,0.0509671,0.0600006,2.97291e-11,2.97287e-11,3.20454e-10,1.41542e-06,1.41532e-06,5e-08,0,0,0,0,0,0,0,0 -24385000,0.705821,0.00334551,-0.0059913,0.708357,-0.113747,-0.0462711,-0.452266,-0.053562,-0.0282105,-365.599,-1.29163e-05,-5.95484e-05,3.9642e-06,-7.93094e-05,5.27449e-05,-0.00127682,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00129762,8.05625e-06,6.26809e-06,0.00121609,0.0371757,0.0371084,0.00973829,0.0447351,0.0447335,0.0603551,2.97946e-11,2.97942e-11,3.17157e-10,1.2371e-06,1.23727e-06,5.0002e-08,0,0,0,0,0,0,0,0 -24485000,0.705852,0.00418153,-0.00202534,0.708344,-0.126493,-0.0511453,-0.50309,-0.0655111,-0.0330457,-365.646,-1.29171e-05,-5.95476e-05,3.92416e-06,-7.93327e-05,5.27541e-05,-0.00127695,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00129683,8.31149e-06,6.34969e-06,0.00121588,0.0408029,0.0407151,0.0098014,0.0512722,0.0512672,0.0604058,2.98926e-11,2.98925e-11,3.1281e-10,1.2371e-06,1.23727e-06,5.0001e-08,0,0,0,0,0,0,0,0 -24585000,0.705961,0.00474457,0.00180413,0.708232,-0.138416,-0.0636759,-0.552563,-0.0690297,-0.0432376,-365.697,-1.29045e-05,-5.95569e-05,4.05452e-06,-6.79617e-05,7.91883e-05,-0.00127968,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00129564,8.52127e-06,6.48935e-06,0.00121527,0.0349392,0.0348448,0.00969882,0.0449548,0.0449516,0.0598672,2.99669e-11,2.9967e-11,3.08542e-10,1.08982e-06,1.09035e-06,5.0001e-08,0,0,0,0,0,0,0,0 -24685000,0.705991,0.00479124,0.00287123,0.708198,-0.162713,-0.0770994,-0.632247,-0.084059,-0.0502872,-365.758,-1.29022e-05,-5.95585e-05,4.15401e-06,-6.7817e-05,7.91097e-05,-0.00127878,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00129485,8.66975e-06,6.64917e-06,0.0012151,0.0381802,0.0380371,0.00976429,0.0513697,0.0513613,0.0599273,3.0065e-11,3.00654e-11,3.04362e-10,1.08982e-06,1.09036e-06,5.0001e-08,0,0,0,0,0,0,0,0 -24785000,0.705925,0.00454266,0.00165464,0.70827,-0.177718,-0.0881077,-0.720113,-0.0910971,-0.0602759,-365.828,-1.28975e-05,-5.95717e-05,4.06642e-06,-8.0723e-05,0.000106303,-0.00127902,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00129354,8.76338e-06,6.76317e-06,0.00121426,0.0327522,0.0326013,0.00966532,0.0450374,0.0450321,0.0594027,3.01458e-11,3.01465e-11,3.00252e-10,9.68506e-07,9.69552e-07,5e-08,0,0,0,0,0,0,0,0 -24885000,0.705878,0.00618579,0.00317929,0.708299,-0.198875,-0.0991103,-0.743033,-0.109886,-0.0696305,-365.904,-1.28982e-05,-5.95704e-05,4.0174e-06,-8.0599e-05,0.000106176,-0.00127798,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00129263,9.14429e-06,6.93472e-06,0.00121399,0.035641,0.03544,0.00973357,0.0513005,0.0512873,0.059472,3.0244e-11,3.02449e-11,2.9623e-10,9.68508e-07,9.69556e-07,5e-08,0,0,0,0,0,0,0,0 -24985000,0.705822,0.0081151,0.005128,0.708324,-0.212027,-0.103926,-0.798036,-0.111601,-0.0756651,-365.978,-1.2896e-05,-5.9581e-05,3.91121e-06,-0.000108723,0.000157548,-0.00128063,0.208606,0.00202596,0.43355,0,0,0,0,0,0.0012913,9.57897e-06,7.12107e-06,0.00121287,0.0306764,0.0304603,0.00972129,0.0450052,0.0449965,0.0598533,3.03297e-11,3.03311e-11,2.93276e-10,8.68376e-07,8.70089e-07,5.0002e-08,0,0,0,0,0,0,0,0 -25085000,0.70579,0.00850416,0.00462844,0.708355,-0.241676,-0.114505,-0.848279,-0.134302,-0.0865846,-366.062,-1.28969e-05,-5.958e-05,3.86444e-06,-0.000108705,0.000157501,-0.00128035,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00129064,9.78292e-06,7.25715e-06,0.00121258,0.0332869,0.0329847,0.00979267,0.0510974,0.0510768,0.059934,3.04279e-11,3.04296e-11,2.89385e-10,8.68379e-07,8.70094e-07,5.0002e-08,0,0,0,0,0,0,0,0 -25185000,0.705809,0.00803166,0.00309492,0.708349,-0.266199,-0.130165,-0.898124,-0.155527,-0.114469,-366.147,-1.28898e-05,-5.95968e-05,3.9087e-06,-8.39847e-05,0.000160978,-0.00128213,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00128864,9.84564e-06,7.36532e-06,0.00121101,0.0287547,0.0284453,0.00969883,0.0448784,0.0448646,0.0594298,3.05166e-11,3.05188e-11,2.85548e-10,7.85512e-07,7.88124e-07,5.0001e-08,0,0,0,0,0,0,0,0 -25285000,0.705862,0.00984468,0.00954719,0.708217,-0.294143,-0.139363,-0.952419,-0.183459,-0.127901,-366.239,-1.28892e-05,-5.95974e-05,3.93965e-06,-8.39912e-05,0.000161009,-0.00128231,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00128762,1.03038e-05,7.73996e-06,0.00121063,0.0311076,0.0307006,0.00977212,0.0507903,0.0507592,0.0595193,3.06149e-11,3.06173e-11,2.81804e-10,7.85515e-07,7.88129e-07,5.0001e-08,0,0,0,0,0,0,0,0 -25385000,0.705931,0.0113368,0.0163196,0.708002,-0.321708,-0.159594,-1.00096,-0.195537,-0.148587,-366.335,-1.28841e-05,-5.96085e-05,3.97967e-06,-8.18096e-05,0.000199448,-0.00128522,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00128464,1.07298e-05,8.334e-06,0.00120825,0.0270272,0.0265783,0.00968056,0.0446761,0.0446546,0.0590314,3.07061e-11,3.07092e-11,2.78105e-10,7.16669e-07,7.20434e-07,5e-08,0,0,0,0,0,0,0,0 -25485000,0.705961,0.0116313,0.0178262,0.707931,-0.369632,-0.182911,-1.05411,-0.230109,-0.165712,-366.443,-1.28822e-05,-5.96091e-05,4.04654e-06,-8.15585e-05,0.00019933,-0.00128341,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00128392,1.09362e-05,8.61811e-06,0.00120794,0.0292598,0.028608,0.00975534,0.0504075,0.0503593,0.0591292,3.08044e-11,3.08078e-11,2.74501e-10,7.16672e-07,7.2044e-07,5e-08,0,0,0,0,0,0,0,0 -25585000,0.706056,0.0111578,0.0158437,0.707891,-0.409508,-0.214786,-1.10929,-0.258798,-0.205169,-366.555,-1.28751e-05,-5.96266e-05,4.08874e-06,-6.05434e-05,0.000213975,-0.00128268,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00128049,1.09903e-05,8.60399e-06,0.00120469,0.0255698,0.0248689,0.00966623,0.0444164,0.0443822,0.0586564,3.08976e-11,3.09018e-11,2.70924e-10,6.59294e-07,6.64579e-07,5e-08,0,0,0,0,0,0,0,0 -25685000,0.706,0.0145559,0.0221361,0.707717,-0.456784,-0.234974,-1.16149,-0.302013,-0.227641,-366.673,-1.28744e-05,-5.96262e-05,4.09733e-06,-6.03462e-05,0.000213852,-0.00128097,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00127958,1.17833e-05,9.35799e-06,0.00120411,0.0276559,0.0267025,0.0098248,0.0499723,0.0498973,0.059638,3.09964e-11,3.10008e-11,2.68339e-10,6.59299e-07,6.64586e-07,5.0002e-08,0,0,0,0,0,0,0,0 -25785000,0.705924,0.0174179,0.0289632,0.70748,-0.498536,-0.260359,-1.20845,-0.317714,-0.255988,-366.793,-1.28722e-05,-5.96382e-05,4.15425e-06,-7.16448e-05,0.000273845,-0.00128264,0.208606,0.00202596,0.43355,0,0,0,0,0,0.00127325,1.25285e-05,1.03678e-05,0.00119915,0.0244007,0.0233146,0.00973577,0.0441157,0.0440609,0.0591653,3.10913e-11,3.10966e-11,2.64858e-10,6.11302e-07,6.18523e-07,5.0001e-08,0,0,0,0,0,0,0,0 -25885000,0.711477,0.0180456,0.0295006,0.701858,-0.568598,-0.289,-1.25821,-0.371077,-0.283504,-366.921,-1.28717e-05,-5.96375e-05,4.15405e-06,-7.14624e-05,0.000273731,-0.00128092,0.216582,0.00210342,0.427819,0,0,0,0,0,0.00208965,1.41317e-05,1.10873e-05,0.00205608,0.0262371,0.025145,0.00981258,0.0495032,0.0493887,0.0592813,3.11913e-11,3.11965e-11,2.64958e-10,6.11307e-07,6.18531e-07,5.0001e-08,0,0,0,0,0,0,0,0 -25985000,0.71042,0.0170351,0.0262406,0.703082,-0.621767,-0.327327,-1.31423,-0.411872,-0.341065,-367.054,-1.28699e-05,-5.96569e-05,4.14287e-06,-4.76616e-05,0.000303256,-0.00127884,0.216582,0.00210342,0.427819,0,0,0,0,0,0.00187495,1.33698e-05,1.05134e-05,0.0018435,0.0232292,0.0223471,0.0097239,0.0437812,0.0437005,0.0588214,3.12847e-11,3.12908e-11,2.64993e-10,5.69138e-07,5.78597e-07,5.0001e-08,0,0,0,0,0,0,0,0 -26085000,0.705141,0.0215948,0.0356425,0.707841,-0.686776,-0.35376,-1.3407,-0.4772,-0.375125,-367.193,-1.28695e-05,-5.96562e-05,4.13847e-06,-4.75875e-05,0.000303119,-0.00127711,0.216582,0.00210342,0.427819,0,0,0,0,0,0.00173439,1.48394e-05,1.20828e-05,0.0017191,0.0253059,0.0243112,0.00980242,0.0489919,0.048852,0.0589385,3.13847e-11,3.13908e-11,2.65092e-10,5.69143e-07,5.78606e-07,5e-08,0,0,0,0,0,0,0,0 -26185000,0.702957,0.0242165,0.0456922,0.70935,-0.734101,-0.386567,-1.31055,-0.499823,-0.417183,-367.326,-1.29011e-05,-5.96919e-05,4.08866e-06,-6.48371e-05,0.000388691,-0.0012773,0.216582,0.00210342,0.427819,0,0,0,0,0,0.00163585,1.59814e-05,1.41094e-05,0.00163332,0.0229007,0.021894,0.00971673,0.0434184,0.0433175,0.0584905,3.14652e-11,3.14729e-11,2.65143e-10,5.29905e-07,5.41559e-07,5e-08,0,0,0,0,0,0,0,0 -26285000,0.70261,0.0252147,0.0483673,0.709482,-0.826104,-0.427716,-1.29853,-0.577769,-0.457915,-367.46,-1.29007e-05,-5.96915e-05,4.08583e-06,-6.48227e-05,0.000388595,-0.00127598,0.216582,0.00210342,0.427819,0,0,0,0,0,0.00158474,1.62786e-05,1.47579e-05,0.00158463,0.0254206,0.0239995,0.00988288,0.0484878,0.0483226,0.0594906,3.15652e-11,3.15729e-11,2.65241e-10,5.29909e-07,5.41568e-07,5.0002e-08,0,0,0,0,0,0,0,0 -26385000,0.703502,0.0243117,0.0447905,0.708863,-0.906015,-0.486499,-1.30344,-0.64537,-0.545831,-367.596,-1.28882e-05,-5.97284e-05,4.07098e-06,-2.76808e-05,0.000407187,-0.00127293,0.216582,0.00210342,0.427819,0,0,0,0,0,0.0015271,1.55542e-05,1.38549e-05,0.00152817,0.0234943,0.0218497,0.00979957,0.0430601,0.0429374,0.0590402,3.16289e-11,3.1638e-11,2.65306e-10,4.93271e-07,5.07135e-07,5.0002e-08,0,0,0,0,0,0,0,0 -26485000,0.703633,0.0318109,0.0596424,0.707341,-0.998926,-0.524907,-1.30746,-0.740373,-0.596443,-367.73,-1.28879e-05,-5.9728e-05,4.06732e-06,-2.77467e-05,0.000407082,-0.00127149,0.216582,0.00210342,0.427819,0,0,0,0,0,0.00148496,1.82824e-05,1.78278e-05,0.00148434,0.0263895,0.0239987,0.00988805,0.0480416,0.0478295,0.0591727,3.17289e-11,3.17379e-11,2.65401e-10,4.93266e-07,5.07143e-07,5.0001e-08,0,0,0,0,0,0,0,0 -26585000,0.703164,0.0384711,0.076528,0.70585,-1.08602,-0.577438,-1.29743,-0.781626,-0.661776,-367.865,-1.29592e-05,-5.98062e-05,3.99981e-06,-4.78226e-05,0.000504187,-0.00126886,0.216582,0.00210342,0.427819,0,0,0,0,0,0.00143619,2.10595e-05,2.32904e-05,0.00143604,0.0250573,0.0220583,0.00981263,0.0427465,0.0425826,0.058733,3.17749e-11,3.17841e-11,2.65475e-10,4.59118e-07,4.75401e-07,5.0001e-08,0,0,0,0,0,0,0,0 -26685000,0.704117,0.039922,0.0799706,0.704437,-1.23105,-0.638568,-1.28712,-0.897445,-0.722545,-368,-1.29589e-05,-5.98055e-05,4.00109e-06,-4.76124e-05,0.000504228,-0.00126693,0.216582,0.00210342,0.427819,0,0,0,0,0,0.0014116,2.15296e-05,2.46175e-05,0.00140738,0.0290285,0.0244099,0.00991722,0.0477179,0.0473976,0.0588711,3.18749e-11,3.1884e-11,2.65567e-10,4.59101e-07,4.75406e-07,5e-08,0,0,0,0,0,0,0,0 -26785000,0.705023,0.0379978,0.074175,0.70427,-1.34997,-0.723901,-1.29054,-0.99289,-0.854074,-368.139,-1.29764e-05,-5.9837e-05,3.94504e-06,9.67945e-06,0.000544653,-0.00126223,0.216582,0.00210342,0.427819,0,0,0,0,0,0.00136603,1.99272e-05,2.19751e-05,0.00136353,0.0278951,0.0225341,0.00984828,0.0425265,0.0422722,0.0584414,3.19062e-11,3.19119e-11,2.65646e-10,4.2751e-07,4.46905e-07,5e-08,0,0,0,0,0,0,0,0 -26885000,0.704593,0.0464842,0.0947254,0.701723,-1.49303,-0.781367,-1.30303,-1.13471,-0.929198,-368.276,-1.29763e-05,-5.98362e-05,3.9459e-06,9.87644e-06,0.000544752,-0.00125972,0.216582,0.00210342,0.427819,0,0,0,0,0,0.0013435,2.38148e-05,3.02154e-05,0.00133821,0.0324709,0.0248816,0.00996095,0.047579,0.0470429,0.0585859,3.20062e-11,3.20118e-11,2.65735e-10,4.27472e-07,4.46906e-07,5e-08,0,0,0,0,0,0,0,0 -26985000,0.70391,0.0535626,0.117379,0.698473,-1.60653,-0.857464,-1.28376,-1.19096,-1.02734,-368.412,-1.31591e-05,-5.9952e-05,3.86647e-06,-8.92822e-06,0.000687443,-0.00125731,0.216582,0.00210342,0.427819,0,0,0,0,0,0.00128375,2.71181e-05,4.00728e-05,0.00128214,0.0318161,0.0231197,0.00998979,0.0424464,0.0420196,0.0590243,3.20286e-11,3.2024e-11,2.6582e-10,3.9856e-07,4.22249e-07,5.0002e-08,0,0,0,0,0,0,0,0 -27085000,0.704561,0.0547525,0.122303,0.696877,-1.81063,-0.947813,-1.25643,-1.36176,-1.1176,-368.542,-1.31591e-05,-5.99517e-05,3.86636e-06,-8.87263e-06,0.000687508,-0.00125601,0.212984,0.00205671,0.429918,-0.00179412,0.00395211,0.00100798,0,0,0.00128463,2.80658e-05,4.28118e-05,0.00127788,0.0382954,0.0258775,0.0101461,0.0477019,0.0467888,0.0591806,3.21286e-11,3.2124e-11,2.6592e-10,3.98569e-07,4.22257e-07,5.0001e-08,0.00143045,1.85606e-05,0.00157849,0.000554823,0.00139834,0.00160316,0,0 -27185000,0.706723,0.0515278,0.112324,0.696614,-2.01184,-1.01045,-1.23919,-1.55799,-1.1945,-368.671,-1.31362e-05,-6.00787e-05,3.867e-06,-6.20795e-05,0.000678066,-0.00125321,0.213282,0.00205708,0.429919,-0.00212632,0.00365717,0.00106893,0,0,0.00122525,2.4852e-05,3.56317e-05,0.00122651,0.0394817,0.0261189,0.0101012,0.0502348,0.0493422,0.0587587,3.21555e-11,3.21302e-11,2.6602e-10,3.82121e-07,4.10655e-07,5.0001e-08,0.00137056,1.84258e-05,0.00153129,0.000344349,0.00133396,0.00155885,0,0 -27285000,0.708236,0.0458775,0.097261,0.697738,-2.17427,-1.07916,-1.22943,-1.76756,-1.29912,-368.801,-1.31366e-05,-6.00783e-05,3.86691e-06,-6.20244e-05,0.000678239,-0.00125112,0.21284,0.00205482,0.430256,-0.00180521,0.00397397,0.00148478,0,0,0.00123128,2.21032e-05,2.9007e-05,0.00123024,0.0458889,0.0288365,0.010246,0.0566769,0.0549379,0.058925,3.22555e-11,3.22302e-11,2.6612e-10,3.82131e-07,4.10662e-07,5.0001e-08,0.00134776,1.83028e-05,0.00152138,0.000264203,0.00131189,0.00154661,0,0 -27385000,0.709877,0.0395126,0.0812662,0.698504,-2.24825,-1.09498,-1.22774,-1.94931,-1.36867,-368.935,-1.32833e-05,-6.02843e-05,3.86912e-06,-0.000143938,0.000733297,-0.00124712,0.21355,0.00206114,0.431966,-0.00223339,0.00408189,0.00380207,0,0,0.00115325,1.83262e-05,2.16374e-05,0.00116774,0.0437521,0.0282207,0.0101443,0.0589016,0.0574089,0.0585062,3.22889e-11,3.22301e-11,2.66219e-10,3.66165e-07,4.01247e-07,5e-08,0.00132998,1.81841e-05,0.0015042,0.000220971,0.0012994,0.00151948,0,0 -27485000,0.710451,0.0337234,0.066163,0.699817,-2.33453,-1.13319,-1.21289,-2.17857,-1.48019,-369.065,-1.32842e-05,-6.02839e-05,3.86913e-06,-0.00014391,0.000733611,-0.00124429,0.213514,0.00206155,0.431645,-0.0023245,0.00451921,0.00404775,0,0,0.00115637,1.63594e-05,1.73812e-05,0.00117124,0.0482633,0.0305543,0.0102491,0.0664303,0.0638113,0.0586805,3.23888e-11,3.23301e-11,2.66319e-10,3.66175e-07,4.01252e-07,5e-08,0.0013156,1.80677e-05,0.00149851,0.000194442,0.00129102,0.00149828,0,0 -27585000,0.711256,0.0290751,0.0535342,0.700289,-2.43366,-1.14442,-1.215,-2.45405,-1.58082,-369.196,-1.31765e-05,-6.035e-05,3.84378e-06,-0.000169799,0.000694048,-0.00123776,0.213006,0.00205402,0.430237,-0.00259589,0.00474693,0.00235461,0,0,0.00107939,1.41292e-05,1.37862e-05,0.00111203,0.0438199,0.0293032,0.0102004,0.0681642,0.0660769,0.0591333,3.243e-11,3.23281e-11,2.66416e-10,3.50987e-07,3.93593e-07,5.0002e-08,0.001304,1.79813e-05,0.00147956,0.000179319,0.00128422,0.00146599,0,0 -27685000,0.711098,0.0281564,0.0513112,0.700653,-2.47218,-1.15928,-1.21611,-2.69928,-1.69598,-369.323,-1.31775e-05,-6.03498e-05,3.84386e-06,-0.000169804,0.000694333,-0.00123558,0.21295,0.00205235,0.430172,-0.00272983,0.00474782,0.00250562,0,0,0.00107935,1.39984e-05,1.34715e-05,0.00111289,0.047002,0.0314853,0.0102874,0.0765563,0.0732239,0.0593169,3.25299e-11,3.24281e-11,2.66516e-10,3.50997e-07,3.93596e-07,5.0002e-08,0.00129206,1.78676e-05,0.00147191,0.00016506,0.00127871,0.00143849,0,0 -27785000,0.711372,0.0286631,0.0532035,0.700213,-2.52954,-1.16133,-1.21429,-2.96885,-1.79354,-369.452,-1.31342e-05,-6.04295e-05,3.81546e-06,-0.000200024,0.000678723,-0.00123055,0.212608,0.00204541,0.429264,-0.00323843,0.00502814,0.00213959,0,0,0.00101391,1.3498e-05,1.32898e-05,0.00106433,0.0422473,0.0300302,0.0101552,0.0777714,0.0751983,0.0588935,3.25775e-11,3.24276e-11,2.66608e-10,3.36704e-07,3.87054e-07,5.0001e-08,0.00128343,1.77559e-05,0.00145499,0.000153682,0.00127474,0.00141011,0,0 -27885000,0.711425,0.0280356,0.0514663,0.700314,-2.56667,-1.17717,-1.21432,-3.22345,-1.91044,-369.584,-1.31363e-05,-6.04295e-05,3.81573e-06,-0.000200077,0.00067929,-0.00122679,0.21267,0.00204627,0.429313,-0.00321718,0.00501213,0.00205443,0,0,0.00101423,1.3454e-05,1.30995e-05,0.00106465,0.0451573,0.0323048,0.0102416,0.0868575,0.0830298,0.0590785,3.26774e-11,3.25276e-11,2.66708e-10,3.36714e-07,3.87054e-07,5.0001e-08,0.00127771,1.76461e-05,0.00145161,0.000145563,0.00127349,0.00139583,0,0 -27985000,0.711797,0.027084,0.0474474,0.700257,-2.64453,-1.18217,-1.21721,-3.53687,-2.02384,-369.714,-1.30211e-05,-6.04451e-05,3.76804e-06,-0.000206739,0.000638439,-0.00122096,0.21199,0.00203899,0.427564,-0.00331226,0.00556867,0.000803681,0,0,0.00096169,1.26582e-05,1.21105e-05,0.00102738,0.0406567,0.0307287,0.0101157,0.0875566,0.0846475,0.0586576,3.27307e-11,3.25317e-11,2.66793e-10,3.23471e-07,3.81328e-07,5e-08,0.00127206,1.75372e-05,0.00143741,0.000138281,0.00127086,0.0013746,0,0 -28085000,0.711339,0.0325556,0.0598808,0.699536,-2.68011,-1.19435,-1.22982,-3.80266,-2.14254,-369.843,-1.30228e-05,-6.04453e-05,3.76831e-06,-0.000206805,0.000638874,-0.00121848,0.212039,0.00203775,0.427607,-0.00353002,0.00551249,0.000914288,0,0,0.000960144,1.39129e-05,1.42333e-05,0.00102605,0.0433439,0.033102,0.0102014,0.0972207,0.0931079,0.0588426,3.28305e-11,3.26317e-11,2.66893e-10,3.23481e-07,3.81325e-07,5e-08,0.00126856,1.74301e-05,0.00143557,0.000133013,0.00127037,0.0013663,0,0 -28185000,0.711198,0.038062,0.074051,0.698044,-2.75233,-1.20598,-0.991707,-4.11004,-2.25473,-369.973,-1.29598e-05,-6.04694e-05,3.72637e-06,-0.000216303,0.000616407,-0.00121263,0.212033,0.00203879,0.426551,-0.00363656,0.00613378,0.000177901,0,0,0.000914973,1.46897e-05,1.65904e-05,0.000993573,0.0390738,0.0311616,0.010088,0.0974248,0.0943246,0.0584244,3.28892e-11,3.26433e-11,2.66972e-10,3.1141e-07,3.76211e-07,5e-08,0.00126498,1.73241e-05,0.00142635,0.000128159,0.00126723,0.00135879,0,0 -28285000,0.713117,0.0309878,0.0584977,0.697912,-2.75168,-1.2179,-0.133125,-4.38515,-2.3759,-370.035,-1.29613e-05,-6.04696e-05,3.72664e-06,-0.000216374,0.0006168,-0.00121061,0.212255,0.00204058,0.426571,-0.00375583,0.00619519,0.000276288,0,0,0.000919446,1.32281e-05,1.36885e-05,0.00099405,0.0399039,0.0324946,0.0102611,0.107529,0.103334,0.0594806,3.2989e-11,3.27433e-11,2.67072e-10,3.11419e-07,3.76209e-07,5.0002e-08,0.00126348,1.72462e-05,0.0014262,0.000125439,0.00126642,0.00135774,0,0 -28385000,0.715465,0.0149603,0.0272696,0.697956,-2.78556,-1.2198,0.734863,-4.72214,-2.49576,-370.014,-1.28418e-05,-6.04684e-05,3.66902e-06,-0.000216985,0.00057638,-0.00120503,0.21123,0.00202779,0.425578,-0.0037794,0.00592815,-0.000810058,0,0,0.000892534,1.06477e-05,9.95026e-06,0.000973511,0.035088,0.0299574,0.0103189,0.107358,0.104149,0.0596518,3.30441e-11,3.27513e-11,2.67148e-10,2.99983e-07,3.71049e-07,5.0001e-08,0.00125716,1.71419e-05,0.00141439,0.000121593,0.0012615,0.00133888,0,0 -28485000,0.715809,0.00534427,0.00799667,0.69823,-2.74237,-1.21228,1.06725,-4.9985,-2.61745,-369.927,-1.28453e-05,-6.0469e-05,3.66965e-06,-0.000217159,0.000577229,-0.00120118,0.209691,0.00200654,0.426183,-0.00368278,0.00428268,-0.000562978,0,0,0.000893884,1.0097e-05,9.49344e-06,0.00097381,0.0360289,0.0317716,0.0103841,0.117677,0.113594,0.0598341,3.31438e-11,3.28513e-11,2.67248e-10,2.99992e-07,3.71036e-07,5.0001e-08,0.00124017,1.70355e-05,0.00139742,0.000118446,0.00124667,0.00129798,0,0 -28585000,0.715119,0.00359995,0.00430183,0.69898,-2.7115,-1.1882,0.968138,-5.33585,-2.73688,-369.836,-1.27087e-05,-6.04609e-05,3.60532e-06,-0.000215266,0.000531024,-0.00119842,0.208557,0.0019921,0.426075,-0.00355947,0.00355227,-0.00240658,0,0,0.000871118,9.99722e-06,9.5543e-06,0.000961364,0.0510604,0.0487556,0.0293229,0.117294,0.114052,0.0600173,3.31912e-11,3.28572e-11,2.67319e-10,2.89034e-07,3.65203e-07,5e-08,0.00122318,1.69289e-05,0.00137297,0.000115287,0.00123161,0.00125002,0,0 -28685000,0.714145,0.00285716,0.00330004,0.699985,-2.63968,-1.17,0.96768,-5.60281,-2.85463,-369.753,-1.27136e-05,-6.04618e-05,3.60622e-06,-0.000215266,0.000531024,-0.00119842,0.20761,0.00197928,0.426448,-0.00347977,0.00253451,-0.0022606,0,0,0.000869842,1.0089e-05,9.68346e-06,0.000963003,0.0752446,0.0740029,0.0528885,0.128053,0.124121,0.0604901,3.32908e-11,3.29571e-11,2.67419e-10,2.89034e-07,3.65203e-07,5e-08,0.0012104,1.68235e-05,0.00135681,0.000112812,0.00122217,0.00121096,0,0 -28785000,0.713498,0.00267185,0.00304701,0.700646,-2.65169,-1.14523,0.969011,-5.93135,-2.96646,-369.67,-1.26284e-05,-6.0463e-05,3.5385e-06,-0.000215266,0.000531024,-0.00119842,0.206785,0.00196865,0.426234,-0.00350441,0.00195684,-0.00320036,0,0,0.000854266,1.00562e-05,9.71316e-06,0.000954194,0.0810502,0.0812193,0.0714108,0.12741,0.124168,0.060496,3.33612e-11,3.30084e-11,2.67482e-10,2.89034e-07,3.65203e-07,5e-08,0.00120066,1.67191e-05,0.00133962,0.000110465,0.00121512,0.00117695,0,0 -28885000,0.713005,0.0026264,0.00322063,0.701147,-2.58339,-1.12873,0.957097,-6.19262,-3.08004,-369.584,-1.26323e-05,-6.04639e-05,3.53922e-06,-0.000215266,0.000531024,-0.00119842,0.20625,0.00196173,0.426366,-0.00344461,0.00141363,-0.00298653,0,0,0.000853744,1.0172e-05,9.82567e-06,0.000955114,0.105397,0.106588,0.0948265,0.138331,0.13463,0.063208,3.34607e-11,3.31083e-11,2.67582e-10,2.89034e-07,3.65203e-07,5e-08,0.00119478,1.66415e-05,0.00133113,0.000108982,0.00121182,0.00115608,0,0 -28985000,0.712747,0.00288729,0.00368981,0.701406,-2.63992,-1.11793,0.941401,-6.52581,-3.19586,-369.505,-1.25814e-05,-6.04544e-05,3.48291e-06,-0.000215266,0.000531024,-0.00119842,0.205659,0.00195399,0.426145,-0.00346729,0.000914439,-0.00311014,0,0,0.000844819,1.01782e-05,9.85245e-06,0.000948198,0.0972423,0.0985785,0.10361,0.137524,0.134295,0.0638551,3.35487e-11,3.31928e-11,2.67645e-10,2.89034e-07,3.65203e-07,5e-08,0.00118828,1.65387e-05,0.00131895,0.000107139,0.00120803,0.00113157,0,0 -29085000,0.712604,0.0030053,0.00404603,0.701548,-2.5771,-1.10242,0.92964,-6.7861,-3.30671,-369.425,-1.25862e-05,-6.04555e-05,3.48378e-06,-0.000215266,0.000531024,-0.00119842,0.205224,0.00194813,0.426252,-0.00345856,0.000453711,-0.00288061,0,0,0.000844836,1.03022e-05,9.96573e-06,0.000948605,0.121688,0.123904,0.126141,0.148527,0.145036,0.0672492,3.36481e-11,3.32928e-11,2.67745e-10,2.89034e-07,3.65203e-07,5e-08,0.00118295,1.64368e-05,0.0013109,0.00010552,0.00120578,0.00111155,0,0 -29185000,0.712576,0.00316694,0.00435897,0.701574,-2.55514,-1.0934,0.898833,-7.06302,-3.41955,-369.356,-1.25886e-05,-6.04552e-05,3.47402e-06,-0.000215266,0.000531024,-0.00119842,0.20526,0.00194921,0.426716,-0.00337293,0.000295567,-0.00337214,0,0,0.000839761,1.03377e-05,1.00117e-05,0.000942642,0.104898,0.106526,0.12468,0.14764,0.144433,0.0680133,3.37431e-11,3.33907e-11,2.67813e-10,2.89034e-07,3.65203e-07,5e-08,0.00117834,1.63362e-05,0.0013021,0.000104054,0.00120361,0.00109398,0,0 -29285000,0.712521,0.00346542,0.0051259,0.701624,-2.49749,-1.0806,0.918311,-7.31511,-3.5281,-369.28,-1.25937e-05,-6.04564e-05,3.47489e-06,-0.000215266,0.000531024,-0.00119842,0.205074,0.0019466,0.426814,-0.00339289,6.80743e-05,-0.0032967,0,0,0.000839919,1.04681e-05,1.01247e-05,0.000942937,0.129363,0.131721,0.146235,0.158684,0.155349,0.0727127,3.38426e-11,3.34906e-11,2.67913e-10,2.89034e-07,3.65203e-07,5e-08,0.00117446,1.62369e-05,0.00129632,0.000102736,0.00120234,0.00107932,0,0 -29385000,0.71258,0.00392188,0.00647275,0.70155,-2.51254,-1.08204,0.904945,-7.5998,-3.64315,-369.212,-1.26037e-05,-6.04582e-05,3.46245e-06,-0.000215266,0.000531024,-0.00119842,0.205176,0.00194691,0.427013,-0.00351251,-4.42015e-05,-0.00326464,0,0,0.000836658,1.05277e-05,1.01809e-05,0.000937588,0.108264,0.109786,0.136867,0.157764,0.15458,0.0729696,3.39385e-11,3.35904e-11,2.67984e-10,2.89034e-07,3.65203e-07,5e-08,0.00117107,1.61389e-05,0.00128984,0.000101542,0.00120098,0.00106667,0,0 -29485000,0.712621,0.00439116,0.0075776,0.701494,-2.46187,-1.07217,0.897173,-7.84816,-3.75075,-369.133,-1.26071e-05,-6.0459e-05,3.46301e-06,-0.000215266,0.000531024,-0.00119842,0.205127,0.00194676,0.427113,-0.00345947,-0.000118347,-0.00328992,0,0,0.000836966,1.06672e-05,1.0302e-05,0.000937751,0.132753,0.134887,0.15744,0.168834,0.165602,0.0784013,3.4038e-11,3.36904e-11,2.68084e-10,2.89034e-07,3.65203e-07,5e-08,0.00116825,1.60421e-05,0.00128589,0.000100455,0.00120029,0.00105639,0,0 -29585000,0.71266,0.00468525,0.00854032,0.701442,-2.41582,-1.05189,0.875198,-8.0924,-3.85134,-369.062,-1.2614e-05,-6.04576e-05,3.45621e-06,-0.000215266,0.000531024,-0.00119842,0.20503,0.00194558,0.426989,-0.00347239,-0.000150345,-0.00313444,0,0,0.000834572,1.07418e-05,1.03823e-05,0.000932946,0.10971,0.11104,0.14392,0.167894,0.16473,0.0793456,3.41325e-11,3.37879e-11,2.68159e-10,2.89034e-07,3.65203e-07,5e-08,0.00116627,1.59706e-05,0.00128178,9.96984e-05,0.00119949,0.00104938,0,0 -29685000,0.712806,0.00495152,0.009184,0.701283,-2.37204,-1.04297,0.863979,-8.3315,-3.95599,-368.986,-1.26168e-05,-6.04582e-05,3.45667e-06,-0.000215266,0.000531024,-0.00119842,0.205033,0.00194552,0.426985,-0.00351064,-0.000162671,-0.00305215,0,0,0.000835046,1.0882e-05,1.05135e-05,0.000932965,0.134196,0.136048,0.163996,0.178987,0.175819,0.0852165,3.42321e-11,3.38879e-11,2.68259e-10,2.89034e-07,3.65203e-07,5e-08,0.00116403,1.58759e-05,0.00127879,9.87653e-05,0.00119901,0.00104155,0,0 -29785000,0.712951,0.00510864,0.00955936,0.701131,-2.36413,-1.03405,0.842732,-8.58435,-4.05944,-368.915,-1.26311e-05,-6.04589e-05,3.44763e-06,-0.000215266,0.000531024,-0.00119842,0.205027,0.00194598,0.427038,-0.0034443,-0.00020533,-0.00290783,0,0,0.000833287,1.09659e-05,1.06052e-05,0.000928543,0.11031,0.111453,0.14677,0.178027,0.174884,0.0836509,3.4324e-11,3.39819e-11,2.68337e-10,2.89034e-07,3.65203e-07,5e-08,0.00116192,1.57824e-05,0.00127473,9.79017e-05,0.00119827,0.00103435,0,0 -29885000,0.713048,0.00513599,0.00968842,0.70103,-2.32568,-1.02638,0.823103,-8.81849,-4.16238,-368.849,-1.26346e-05,-6.04597e-05,3.44818e-06,-0.000215266,0.000531024,-0.00119842,0.205106,0.00194666,0.427072,-0.00350273,-0.000170968,-0.00292606,0,0,0.000833711,1.11036e-05,1.07394e-05,0.000928645,0.134788,0.136381,0.166278,0.189144,0.186015,0.0893806,3.44237e-11,3.40818e-11,2.68437e-10,2.89034e-07,3.65203e-07,5e-08,0.00116011,1.56901e-05,0.00127237,9.7107e-05,0.00119791,0.00102816,0,0 -29985000,0.713171,0.0051348,0.00974835,0.700904,-2.27574,-1.00676,0.802518,-9.04294,-4.25766,-368.78,-1.26344e-05,-6.04547e-05,3.44389e-06,-0.000215266,0.000531024,-0.00119842,0.205129,0.00194707,0.427029,-0.00351313,-0.000115842,-0.00297865,0,0,0.000832294,1.11908e-05,1.0836e-05,0.000924763,0.110554,0.111548,0.147729,0.188164,0.185039,0.0869752,3.45129e-11,3.41723e-11,2.68516e-10,2.89034e-07,3.65203e-07,5e-08,0.00115834,1.55989e-05,0.00126892,9.6366e-05,0.00119729,0.00102225,0,0 -30085000,0.713297,0.00508392,0.0096193,0.700778,-2.23893,-0.999819,0.787104,-9.26854,-4.35796,-368.71,-1.26361e-05,-6.04551e-05,3.44413e-06,-0.000215266,0.000531024,-0.00119842,0.20521,0.0019478,0.427086,-0.00355354,-8.24505e-05,-0.00305694,0,0,0.000832776,1.13301e-05,1.09719e-05,0.000924837,0.135031,0.136429,0.16685,0.199299,0.196197,0.0923689,3.46127e-11,3.42723e-11,2.68616e-10,2.89034e-07,3.65203e-07,5e-08,0.00115682,1.55089e-05,0.00126693,9.56829e-05,0.00119699,0.00101704,0,0 -30185000,0.713464,0.00500769,0.00937589,0.700611,-2.22262,-0.989989,0.781334,-9.5013,-4.45585,-368.633,-1.26465e-05,-6.04537e-05,3.43749e-06,-0.000215266,0.000531024,-0.00119842,0.205231,0.00194848,0.42716,-0.00348292,-8.99103e-05,-0.0030768,0,0,0.000831665,1.14208e-05,1.10703e-05,0.000921317,0.110652,0.111527,0.148928,0.198306,0.195195,0.0914191,3.46994e-11,3.43597e-11,2.68695e-10,2.89034e-07,3.65203e-07,5e-08,0.00115563,1.54424e-05,0.00126432,9.51956e-05,0.00119652,0.00101311,0,0 -30285000,0.713597,0.00487556,0.00916793,0.700479,-2.18565,-0.984999,0.772043,-9.72169,-4.55461,-368.557,-1.26468e-05,-6.04538e-05,3.43752e-06,-0.000215266,0.000531024,-0.00119842,0.205256,0.00194859,0.427192,-0.00350269,-8.79432e-05,-0.00310521,0,0,0.000832172,1.15608e-05,1.12089e-05,0.000921395,0.135132,0.13637,0.168139,0.209453,0.20637,0.0966637,3.47992e-11,3.44597e-11,2.68795e-10,2.89034e-07,3.65203e-07,5e-08,0.00115427,1.53543e-05,0.00126253,9.45919e-05,0.00119624,0.00100843,0,0 -30385000,0.713699,0.00474897,0.00888437,0.70038,-2.13446,-0.980698,0.761873,-9.93005,-4.65384,-368.487,-1.26397e-05,-6.04551e-05,3.4426e-06,-0.000215266,0.000531024,-0.00119842,0.205118,0.0019469,0.427078,-0.00350323,-0.000151606,-0.00292494,0,0,0.000831155,1.16545e-05,1.13101e-05,0.000918343,0.110699,0.111486,0.148705,0.208452,0.205352,0.0930423,3.48836e-11,3.45444e-11,2.68875e-10,2.89034e-07,3.65203e-07,5e-08,0.00115288,1.52671e-05,0.0012597,9.40202e-05,0.00119574,0.00100378,0,0 -30485000,0.713782,0.00460578,0.00861046,0.7003,-2.10033,-0.974901,0.75034,-10.1418,-4.75162,-368.413,-1.26398e-05,-6.04551e-05,3.44262e-06,-0.000215266,0.000531024,-0.00119842,0.205095,0.00194662,0.427101,-0.003487,-0.000177217,-0.00292072,0,0,0.000831605,1.17976e-05,1.14516e-05,0.000918504,0.135181,0.136298,0.167758,0.219605,0.216538,0.0978968,3.49835e-11,3.46444e-11,2.68975e-10,2.89034e-07,3.65203e-07,5e-08,0.00115167,1.5181e-05,0.00125806,9.3488e-05,0.00119548,0.000999598,0,0 -30585000,0.714085,0.00438769,0.00816554,0.699998,-2.08039,-0.973615,0.722534,-10.3584,-4.85148,-368.341,-1.26488e-05,-6.04556e-05,3.47701e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.00082363,1.18906e-05,1.15541e-05,0.000903004,0.110731,0.111447,0.14838,0.218595,0.215468,0.0939819,3.50656e-11,3.47232e-11,2.68646e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -30685000,0.714161,0.00417398,0.00779197,0.699925,-2.04612,-0.966965,0.715629,-10.5647,-4.94856,-368.274,-1.26493e-05,-6.04561e-05,3.47234e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000815573,1.20336e-05,1.16985e-05,0.000888004,0.135217,0.136231,0.167331,0.229753,0.226617,0.0984992,3.51654e-11,3.48192e-11,2.68238e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -30785000,0.714144,0.00401457,0.00739464,0.699948,-2.00775,-0.951528,0.715404,-10.7652,-5.04001,-368.2,-1.26476e-05,-6.0452e-05,3.44607e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000807168,1.21302e-05,1.18031e-05,0.000872205,0.11074,0.111379,0.148062,0.228736,0.225531,0.0944102,3.52453e-11,3.48954e-11,2.67846e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -30885000,0.714125,0.00378453,0.00693223,0.699974,-1.97324,-0.944848,0.705197,-10.9642,-5.13482,-368.132,-1.26478e-05,-6.04521e-05,3.44569e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000802307,1.22768e-05,1.19507e-05,0.00086344,0.135235,0.13615,0.168313,0.239898,0.236709,0.101147,3.53452e-11,3.4993e-11,2.67611e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -30985000,0.71418,0.00360251,0.006335,0.699924,-1.96065,-0.937445,0.704295,-11.1715,-5.22818,-368.063,-1.26623e-05,-6.04514e-05,3.43853e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000795231,1.2376e-05,1.20567e-05,0.000850359,0.110754,0.111332,0.148825,0.23888,0.235623,0.0967575,3.54233e-11,3.50677e-11,2.67268e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -31085000,0.714179,0.00334787,0.00577508,0.699931,-1.92695,-0.930775,0.6927,-11.3658,-5.32171,-368.002,-1.26627e-05,-6.04527e-05,3.42414e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000789968,1.25254e-05,1.22081e-05,0.000840662,0.135255,0.13608,0.167937,0.250041,0.246804,0.100985,3.55232e-11,3.51651e-11,2.66964e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -31185000,0.714228,0.00311818,0.00537678,0.699885,-1.88862,-0.928557,0.66884,-11.5542,-5.41637,-367.951,-1.26598e-05,-6.04551e-05,3.42943e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000784018,1.26248e-05,1.23166e-05,0.000829894,0.110768,0.111288,0.148553,0.249026,0.245719,0.0965595,3.55995e-11,3.52384e-11,2.66661e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -31285000,0.714312,0.00285324,0.00479147,0.699805,-1.85367,-0.920604,0.670304,-11.7413,-5.50877,-367.891,-1.26602e-05,-6.04546e-05,3.43614e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000779706,1.27774e-05,1.2472e-05,0.000821934,0.135271,0.136026,0.167539,0.260186,0.25691,0.100573,3.56995e-11,3.53362e-11,2.66387e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -31385000,0.714332,0.00257004,0.00415711,0.69979,-1.83961,-0.920965,0.662394,-11.9365,-5.60451,-367.831,-1.26743e-05,-6.04605e-05,3.42837e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000774652,1.28784e-05,1.25827e-05,0.000812832,0.11078,0.111263,0.148256,0.259173,0.255826,0.0961557,3.57742e-11,3.54081e-11,2.66111e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -31485000,0.714231,0.00232922,0.00347272,0.699898,-1.80388,-0.914174,0.659663,-12.1186,-5.69645,-367.77,-1.26744e-05,-6.04623e-05,3.40404e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000771931,1.30359e-05,1.27428e-05,0.000807914,0.135299,0.135993,0.168593,0.270329,0.267028,0.102631,3.58741e-11,3.55068e-11,2.65947e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -31585000,0.714279,0.00210833,0.00300758,0.699852,-1.77201,-0.894144,0.652534,-12.2993,-5.78079,-367.711,-1.26788e-05,-6.04525e-05,3.40889e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000767431,1.31397e-05,1.2855e-05,0.000800012,0.110799,0.111246,0.149067,0.269324,0.265947,0.0980172,3.59472e-11,3.5577e-11,2.65686e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -31685000,0.714307,0.00182564,0.00231412,0.699826,-1.73819,-0.887168,0.660373,-12.4748,-5.86978,-367.647,-1.2679e-05,-6.04517e-05,3.42092e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000764227,1.32991e-05,1.30196e-05,0.000794369,0.13532,0.135954,0.168214,0.280475,0.277147,0.101972,3.60471e-11,3.56755e-11,2.65447e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -31785000,0.714388,0.00145797,0.00152771,0.699747,-1.72938,-0.877698,0.655888,-12.6616,-5.95676,-367.59,-1.26998e-05,-6.04491e-05,3.43065e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000760323,1.34025e-05,1.31358e-05,0.000787505,0.110815,0.111218,0.148778,0.279472,0.276068,0.0974084,3.61185e-11,3.57442e-11,2.65199e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -31885000,0.714427,0.00115404,0.000770085,0.699709,-1.69181,-0.868634,0.654225,-12.8326,-6.04408,-367.528,-1.26999e-05,-6.04492e-05,3.42791e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000757686,1.35653e-05,1.3306e-05,0.000782567,0.135354,0.135941,0.167843,0.290619,0.287271,0.101267,3.62185e-11,3.58429e-11,2.64971e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -31985000,0.71436,0.000895659,0.000197154,0.699778,-1.64826,-0.851647,0.649047,-12.9965,-6.1252,-367.47,-1.26964e-05,-6.04422e-05,3.40876e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000754167,1.36723e-05,1.34224e-05,0.000776572,0.110843,0.111214,0.148497,0.289624,0.286195,0.0967615,3.62881e-11,3.59099e-11,2.64731e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -32085000,0.714269,0.000568509,-0.000574515,0.699871,-1.61221,-0.843481,0.656055,-13.1595,-6.21006,-367.412,-1.26966e-05,-6.04433e-05,3.3913e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.00075176,1.38379e-05,1.35976e-05,0.000772428,0.135388,0.135915,0.167483,0.300763,0.2974,0.10054,3.63881e-11,3.60088e-11,2.64509e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -32185000,0.714186,0.000194576,-0.00150714,0.699955,-1.5975,-0.835816,0.655994,-13.3309,-6.29376,-367.353,-1.27142e-05,-6.04446e-05,3.35222e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000749281,1.39463e-05,1.37206e-05,0.000768069,0.110863,0.111191,0.14926,0.299776,0.29633,0.0984616,3.64561e-11,3.60742e-11,2.64352e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -32285000,0.714164,-9.90294e-05,-0.00232031,0.699975,-1.5597,-0.827463,0.651022,-13.4887,-6.37701,-367.297,-1.27144e-05,-6.04453e-05,3.34083e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.00074721,1.41165e-05,1.3902e-05,0.000764327,0.135429,0.135895,0.168465,0.310906,0.307535,0.102359,3.65561e-11,3.61733e-11,2.64132e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -32385000,0.714186,-0.000366698,-0.0030093,0.69995,-1.51119,-0.816513,0.654977,-13.6377,-6.45792,-367.228,-1.27072e-05,-6.04422e-05,3.359e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000744313,1.42274e-05,1.40235e-05,0.000759591,0.110894,0.11119,0.148972,0.309928,0.306464,0.0977576,3.66224e-11,3.62365e-11,2.63897e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -32485000,0.714118,-0.000536314,-0.00331982,0.700017,-1.47309,-0.806912,0.664551,-13.787,-6.53906,-367.165,-1.27073e-05,-6.04419e-05,3.36613e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.00074233,1.44008e-05,1.42016e-05,0.000756472,0.135467,0.135891,0.168097,0.321051,0.317669,0.10159,3.67224e-11,3.63357e-11,2.63677e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -32585000,0.714018,-0.000615755,-0.00362188,0.700118,-1.45773,-0.803047,0.665398,-13.9442,-6.62212,-367.095,-1.27248e-05,-6.04472e-05,3.34544e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000739647,1.45144e-05,1.43183e-05,0.000752249,0.110917,0.111183,0.148643,0.320083,0.316601,0.0970253,3.67869e-11,3.63971e-11,2.6344e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -32685000,0.713956,-0.000693474,-0.00373649,0.70018,-1.42059,-0.794611,0.66804,-14.0881,-6.70202,-367.026,-1.27248e-05,-6.04473e-05,3.34252e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000737932,1.46918e-05,1.44963e-05,0.000749453,0.135508,0.135884,0.167672,0.331201,0.327807,0.100793,3.68869e-11,3.64964e-11,2.63219e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -32785000,0.713924,-0.000718168,-0.00374626,0.700213,-1.38559,-0.781476,0.66712,-14.229,-6.77837,-366.959,-1.27263e-05,-6.04429e-05,3.3401e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000735981,1.48061e-05,1.46086e-05,0.000746349,0.110944,0.11118,0.14941,0.330237,0.326743,0.0987092,3.69494e-11,3.65557e-11,2.6306e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -32885000,0.713772,-0.000690931,-0.00374245,0.700367,-1.35141,-0.773252,0.67147,-14.3657,-6.85627,-366.895,-1.27263e-05,-6.04442e-05,3.31155e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000734383,1.49882e-05,1.47877e-05,0.000743875,0.135539,0.135871,0.168664,0.341352,0.337949,0.102612,3.70494e-11,3.66551e-11,2.62835e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -32985000,0.713727,-0.000639303,-0.00378092,0.700413,-1.34237,-0.769206,0.668127,-14.5132,-6.93462,-366.833,-1.2749e-05,-6.04459e-05,3.32803e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000732071,1.51046e-05,1.49015e-05,0.000740537,0.110965,0.11117,0.14908,0.34039,0.336885,0.0979609,3.71097e-11,3.6712e-11,2.62591e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -33085000,0.713804,-0.00071351,-0.00383379,0.700335,-1.30857,-0.762181,0.667348,-14.6458,-7.01094,-366.765,-1.2749e-05,-6.0444e-05,3.37453e-06,-0.000215266,0.000531024,-0.00119842,0.205161,0.00194731,0.427215,-0.00348432,-0.000183228,-0.0029757,0,0,0.000730698,1.52883e-05,1.50848e-05,0.000738267,0.135576,0.135866,0.16824,0.351504,0.34809,0.101803,3.72097e-11,3.68115e-11,2.62361e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -33185000,0.710873,0.00185336,-0.00316509,0.703311,-1.27686,-0.745609,0.612861,-14.7827,-7.08266,-366.701,-1.28175e-05,-6.04286e-05,3.42813e-06,-0.000215266,0.000531024,-0.00119842,0.207055,0.00198515,0.430444,-0.0033539,-0.0021093,-0.000416084,0,0,0.000542134,1.53164e-05,1.5065e-05,0.000555421,0.110987,0.111125,0.148757,0.349418,0.34701,0.097226,3.70938e-11,3.67217e-11,2.62136e-10,2.89034e-07,3.65203e-07,5e-08,0.000756393,1.48306e-05,0.000862156,8.44374e-05,0.000770037,0.000749026,0,0 -33285000,0.662509,0.0147941,-0.00194264,0.748906,-1.26616,-0.72852,0.585999,-14.9105,-7.15637,-366.64,-1.28289e-05,-6.04209e-05,3.44315e-06,-0.000215266,0.000531024,-0.00119842,0.207072,0.00199622,0.430978,-0.00329909,-0.00214005,1.36931e-05,0,0,0.000466901,1.5813e-05,1.51353e-05,0.000580256,0.135599,0.135797,0.167828,0.360428,0.358201,0.101011,3.71672e-11,3.66798e-11,2.62048e-10,2.89034e-07,3.65203e-07,5e-08,0.000688138,1.45351e-05,0.000808111,7.5957e-05,0.000695112,0.000715667,0,0 -33385000,0.561815,0.012894,-0.00253915,0.827158,-1.27261,-0.720251,0.784257,-15.0459,-7.23113,-366.573,-1.28588e-05,-6.04244e-05,3.44438e-06,-0.000215266,0.000531024,-0.00119842,0.206435,0.00199273,0.431599,-0.00317384,-0.0015679,0.000445093,0,0,0.00036913,1.58275e-05,1.51956e-05,0.000659432,0.110892,0.111011,0.148447,0.359371,0.357132,0.0965058,3.72097e-11,3.6632e-11,2.62005e-10,2.89034e-07,3.65203e-07,5e-08,0.000636249,1.4338e-05,0.000789592,7.0253e-05,0.000632845,0.000704982,0,0 -33485000,0.425874,0.0063304,0.000277993,0.904761,-1.25034,-0.714014,0.816118,-15.173,-7.30304,-366.491,-1.2858e-05,-6.04483e-05,3.42487e-06,-0.000215266,0.000531024,-0.00119842,0.207561,0.00197629,0.431643,-0.00338356,-0.000431814,0.000503812,0,0,0.000269686,1.57942e-05,1.53495e-05,0.000748436,0.13548,0.135635,0.168778,0.370496,0.368326,0.102812,3.73038e-11,3.6683e-11,2.62048e-10,2.89034e-07,3.65203e-07,5e-08,0.000566632,1.42368e-05,0.000781306,6.78064e-05,0.00054328,0.000700114,0,0 -33585000,0.269508,0.000177452,-0.00184593,0.962996,-1.19736,-0.698993,0.757848,-15.2887,-7.36613,-366.427,-1.28508e-05,-6.0453e-05,3.39245e-06,-0.000215266,0.000531024,-0.00119842,0.207082,0.00194721,0.4317,-0.00324329,-0.000246275,0.000585154,0,0,0.000190615,1.57854e-05,1.54802e-05,0.000811462,0.11099,0.111043,0.149174,0.369451,0.367277,0.0981505,3.73533e-11,3.66973e-11,2.62073e-10,2.89034e-07,3.65203e-07,5e-08,0.000451266,1.41149e-05,0.000773282,6.6159e-05,0.00039147,0.000694389,0,0 -33685000,0.103272,-0.00329472,-0.00478803,0.994636,-1.14041,-0.693761,0.769635,-15.406,-7.43594,-366.35,-1.28544e-05,-6.04585e-05,3.38713e-06,-0.000215266,0.000531024,-0.00119842,0.207193,0.00194183,0.43183,-0.00323616,-1.6242e-05,0.000694,0,0,0.000146811,1.58921e-05,1.56643e-05,0.000843183,0.135707,0.13568,0.168374,0.380523,0.378469,0.102014,3.74489e-11,3.67535e-11,2.62087e-10,2.89034e-07,3.65203e-07,5e-08,0.000355392,1.39644e-05,0.000767744,6.45805e-05,0.000264771,0.000690003,0,0 -33785000,-0.0664753,-0.00498524,-0.00635004,0.997755,-1.10134,-0.670226,0.742119,-15.5308,-7.50079,-366.277,-1.28792e-05,-6.05037e-05,3.29677e-06,-0.000215266,0.000531024,-0.00119842,0.206902,0.00187354,0.4317,-0.00294168,1.44582e-05,0.000738467,0,0,0.000143207,1.58887e-05,1.56995e-05,0.000837721,0.111197,0.111065,0.148872,0.379549,0.377421,0.0974252,3.75009e-11,3.67392e-11,2.62023e-10,2.89034e-07,3.65203e-07,5e-08,0.000291115,1.37712e-05,0.000763741,6.20084e-05,0.00018066,0.000686852,0,0 -33885000,-0.234102,-0.00616023,-0.00682731,0.972169,-1.03239,-0.645082,0.731997,-15.637,-7.56742,-366.206,-1.28817e-05,-6.0568e-05,3.20169e-06,-0.000215266,0.000531024,-0.00119842,0.206471,0.00179094,0.431691,-0.0026314,-0.000201895,0.00088249,0,0,0.00017942,1.58848e-05,1.57442e-05,0.000795968,0.136078,0.135721,0.167926,0.390564,0.388598,0.101197,3.75988e-11,3.67452e-11,2.61917e-10,2.89034e-07,3.65203e-07,5e-08,0.000251374,1.35418e-05,0.000761054,5.83622e-05,0.000129483,0.000684741,0,0 -33985000,-0.381924,-0.00479645,-0.0100227,0.924127,-1.01683,-0.607818,0.704079,-15.7647,-7.63024,-366.136,-1.293e-05,-6.06016e-05,3.13057e-06,-0.000215266,0.000531024,-0.00119842,0.206943,0.00175204,0.431696,-0.00231721,0.000228505,0.000986194,0,0,0.000243431,1.57227e-05,1.57272e-05,0.000726096,0.111442,0.111085,0.148531,0.38968,0.387551,0.0966838,3.76534e-11,3.66836e-11,2.61731e-10,2.89034e-07,3.65203e-07,5e-08,0.000226559,1.32936e-05,0.000758763,5.40711e-05,9.89753e-05,0.000683195,0,0 -34085000,-0.490296,-0.00354761,-0.011572,0.871472,-0.961326,-0.560872,0.711615,-15.8636,-7.68905,-366.063,-1.29326e-05,-6.06267e-05,3.09118e-06,-0.000215266,0.000531024,-0.00119842,0.206899,0.00172052,0.431751,-0.00218495,0.000197131,0.00107724,0,0,0.000309876,1.55803e-05,1.57448e-05,0.000657004,0.136342,0.135728,0.168906,0.400659,0.398722,0.103022,3.77526e-11,3.66953e-11,2.61617e-10,2.89034e-07,3.65203e-07,5e-08,0.000214364,1.31079e-05,0.000757494,5.07851e-05,8.43303e-05,0.000682479,0,0 -34185000,-0.56176,-0.00353144,-0.0100117,0.827232,-0.988334,-0.539959,0.717493,-15.9983,-7.75945,-365.991,-1.30026e-05,-6.06811e-05,3.03567e-06,-0.000215266,0.000531024,-0.00119842,0.207366,0.0016923,0.431867,-0.00195143,0.000318715,0.00123449,0,0,0.000360965,1.53421e-05,1.55573e-05,0.000599989,0.111509,0.111065,0.149284,0.399825,0.397681,0.0983492,3.7809e-11,3.66353e-11,2.61395e-10,2.89034e-07,3.65203e-07,5e-08,0.000202793,1.28743e-05,0.000755843,4.66985e-05,7.13163e-05,0.000681557,0,0 -34285000,-0.606288,-0.00435296,-0.00702399,0.795202,-0.9379,-0.490344,0.72034,-16.0945,-7.81144,-365.92,-1.30037e-05,-6.07193e-05,2.97011e-06,-0.000215266,0.000531024,-0.00119842,0.207533,0.00164731,0.431814,-0.00167361,0.000372279,0.00124167,0,0,0.000396069,1.52e-05,1.54066e-05,0.000561193,0.136384,0.135691,0.168467,0.410796,0.408845,0.102201,3.79084e-11,3.66379e-11,2.61217e-10,2.89034e-07,3.65203e-07,5e-08,0.000195472,1.26652e-05,0.000754887,4.31506e-05,6.27592e-05,0.000680966,0,0 -34385000,-0.633274,-0.00525692,-0.00408324,0.773899,-0.941288,-0.46959,0.714426,-16.2159,-7.87296,-365.855,-1.30565e-05,-6.07637e-05,2.92429e-06,-0.000215266,0.000531024,-0.00119842,0.207895,0.00162573,0.431897,-0.00148309,0.000423959,0.0013172,0,0,0.000417446,1.50146e-05,1.51976e-05,0.00053467,0.11152,0.111039,0.148951,0.409971,0.407811,0.0976034,3.79664e-11,3.661e-11,2.61022e-10,2.89034e-07,3.65203e-07,5e-08,0.000189934,1.2481e-05,0.00075385,4.01709e-05,5.68096e-05,0.000680211,0,0 -34485000,-0.649656,-0.00617595,-0.00180585,0.760201,-0.885869,-0.426098,0.716693,-16.3071,-7.91813,-365.787,-1.30573e-05,-6.07944e-05,2.8663e-06,-0.000215266,0.000531024,-0.00119842,0.207857,0.0015867,0.431899,-0.00135796,0.000277602,0.00134384,0,0,0.000430885,1.49206e-05,1.50844e-05,0.000518411,0.136386,0.135654,0.168041,0.420943,0.418978,0.101397,3.80659e-11,3.66437e-11,2.60882e-10,2.89034e-07,3.65203e-07,5e-08,0.000186344,1.23195e-05,0.000753298,3.76872e-05,5.24693e-05,0.000679655,0,0 -34585000,-0.659651,-0.00676496,-0.000357812,0.751542,-0.904302,-0.432232,0.712929,-16.4332,-7.98588,-365.719,-1.31265e-05,-6.08478e-05,2.84417e-06,-0.000215266,0.000531024,-0.00119842,0.208082,0.00157681,0.432126,-0.00131894,0.00017585,0.00153491,0,0,0.000438214,1.47654e-05,1.49198e-05,0.000506855,0.111516,0.111018,0.14863,0.420121,0.417949,0.0968739,3.81255e-11,3.66453e-11,2.6072e-10,2.89034e-07,3.65203e-07,5e-08,0.000183149,1.21763e-05,0.000752528,3.56152e-05,4.91761e-05,0.000678924,0,0 -34685000,-0.665857,-0.00712059,0.000482262,0.746046,-0.845945,-0.389494,0.715353,-16.5207,-8.02726,-365.644,-1.31297e-05,-6.0868e-05,2.79396e-06,-0.000215266,0.000531024,-0.00119842,0.208293,0.00155191,0.432078,-0.00109158,0.000267691,0.00145095,0,0,0.000442993,1.46861e-05,1.48354e-05,0.000500067,0.136384,0.135632,0.167634,0.431094,0.429117,0.100613,3.82248e-11,3.6702e-11,2.6061e-10,2.89034e-07,3.65203e-07,5e-08,0.000181087,1.2049e-05,0.000752143,3.38738e-05,4.66002e-05,0.000678419,0,0 -34785000,-0.669864,-0.00715009,0.00103713,0.742449,-0.852328,-0.392003,0.715158,-16.6369,-8.08896,-365.572,-1.31901e-05,-6.09316e-05,2.72696e-06,-0.000215266,0.000531024,-0.00119842,0.208648,0.00152132,0.432181,-0.000885301,0.000216016,0.00150734,0,0,0.000445357,1.45476e-05,1.46922e-05,0.000494757,0.111513,0.111008,0.149359,0.430273,0.428094,0.0985283,3.82863e-11,3.67327e-11,2.60517e-10,2.89034e-07,3.65203e-07,5e-08,0.000179309,1.19615e-05,0.000751572,3.2744e-05,4.50087e-05,0.000677882,0,0 -34885000,-0.672395,-0.00717407,0.00116688,0.740157,-0.794972,-0.351984,0.718728,-16.7191,-8.12641,-365.499,-1.31892e-05,-6.09492e-05,2.68318e-06,-0.000215266,0.000531024,-0.00119842,0.20863,0.00149722,0.432155,-0.000819266,0.000107403,0.00150712,0,0,0.000446981,1.44746e-05,1.46199e-05,0.000491661,0.136363,0.135614,0.168575,0.441249,0.439264,0.102402,3.83853e-11,3.6803e-11,2.60422e-10,2.89034e-07,3.65203e-07,5e-08,0.000177917,1.18546e-05,0.000751266,3.14302e-05,4.32308e-05,0.000677466,0,0 -34985000,-0.675731,-0.0143868,-0.000978416,0.737008,0.142453,0.244961,-0.0591168,-16.7726,-8.14712,-365.493,-1.32619e-05,-6.10224e-05,2.60189e-06,-0.000215266,0.000531024,-0.00119842,0.208942,0.00146157,0.432346,-0.000645353,-4.2318e-05,0.00175708,0,0,0.000448633,1.43955e-05,1.46588e-05,0.000486796,0.124863,0.112664,0.14918,0.439858,0.438234,0.0977961,3.84483e-11,3.68391e-11,2.60289e-10,2.89034e-07,3.65203e-07,5e-08,0.000176246,1.17561e-05,0.000750642,3.02952e-05,4.17527e-05,0.000676735,0,0 -35085000,-0.675892,-0.0147572,-0.00137601,0.736852,0.365533,0.268508,-0.153203,-16.7386,-8.12239,-365.498,-1.32586e-05,-6.10397e-05,2.55123e-06,-0.000215266,0.000531024,-0.00119842,0.208914,0.0014358,0.432293,-0.000585869,-0.000175063,0.00181746,0,0,0.000448362,1.43358e-05,1.46086e-05,0.00048596,0.152819,0.138202,0.168345,0.450157,0.449435,0.101619,3.85466e-11,3.69201e-11,2.60202e-10,2.89034e-07,3.65203e-07,5e-08,0.000175274,1.16657e-05,0.00075034,2.93084e-05,4.0509e-05,0.00067618,0,0 -35185000,-0.67589,-0.0144955,-0.00145747,0.736859,0.182611,0.216122,-0.114544,-16.805,-8.14587,-365.49,-1.33656e-05,-6.11067e-05,2.45399e-06,-0.000215266,0.000531024,-0.00119842,0.210982,0.0014509,0.43443,-0.000537083,-0.000258926,0.00357278,0,0,0.000434316,1.4159e-05,1.44622e-05,0.000464496,0.118261,0.112123,0.148797,0.449912,0.448385,0.097049,3.8629e-11,3.69403e-11,2.59885e-10,2.89034e-07,3.65203e-07,5e-08,0.000168166,1.15799e-05,0.000742727,2.84445e-05,3.94496e-05,0.000671239,0,0 -35285000,-0.67595,-0.0144947,-0.00152584,0.736804,0.217223,0.256782,-0.103442,-16.7848,-8.12251,-365.492,-1.3362e-05,-6.11263e-05,2.38452e-06,-0.000215266,0.000531024,-0.00119842,0.210996,0.00142079,0.434346,-0.000447471,-0.000397192,0.00361618,0,0,0.000433987,1.41049e-05,1.44068e-05,0.000463866,0.143345,0.1368,0.167833,0.460504,0.459578,0.100813,3.87266e-11,3.70278e-11,2.59797e-10,2.89034e-07,3.65203e-07,5e-08,0.000167482,1.15021e-05,0.000742525,2.76852e-05,3.85376e-05,0.000670818,0,0 -35385000,-0.675961,-0.0143074,-0.00152856,0.736797,0.0965319,0.205077,-0.074608,-16.8402,-8.14582,-365.484,-1.34537e-05,-6.12046e-05,2.32003e-06,-0.000215266,0.000531024,-0.00119842,0.212096,0.00141429,0.43533,-0.000382142,-0.000546866,0.0044943,0,0,0.000427924,1.39639e-05,1.42806e-05,0.000454534,0.114423,0.111524,0.149509,0.460016,0.458538,0.0987259,3.88055e-11,3.70705e-11,2.5962e-10,2.89034e-07,3.65203e-07,5e-08,0.00016408,1.14459e-05,0.000739264,2.71716e-05,3.79316e-05,0.00066866,0,0 -35485000,-0.676103,-0.0143162,-0.00152755,0.736666,0.131015,0.244168,-0.0658565,-16.8284,-8.1237,-365.483,-1.34491e-05,-6.12252e-05,2.23526e-06,-0.000215266,0.000531024,-0.00119842,0.212129,0.0013811,0.435223,-0.000283391,-0.000705013,0.00453103,0,0,0.000427712,1.39173e-05,1.42308e-05,0.000453938,0.139325,0.136165,0.168768,0.4708,0.469727,0.102627,3.89021e-11,3.7162e-11,2.59528e-10,2.89034e-07,3.65203e-07,5e-08,0.000163554,1.13758e-05,0.000739107,2.65529e-05,3.72122e-05,0.000668314,0,0 -35585000,-0.676053,-0.0141989,-0.00149915,0.736715,0.120105,0.195937,-0.0472256,-16.837,-8.14605,-365.481,-1.34761e-05,-6.131e-05,2.27112e-06,-0.000215266,0.000531024,-0.00119842,0.212324,0.00137056,0.435336,-0.000297669,-0.000889389,0.00471809,0,0,0.000424716,1.37926e-05,1.41143e-05,0.000449247,0.112705,0.11124,0.149144,0.470145,0.46869,0.0979729,3.8977e-11,3.7215e-11,2.59344e-10,2.89034e-07,3.65203e-07,5e-08,0.000161543,1.13081e-05,0.000737528,2.59964e-05,3.65755e-05,0.000667157,0,0 -35685000,-0.676114,-0.0141869,-0.00145282,0.736659,0.154043,0.2355,-0.0417179,-16.8228,-8.12469,-365.484,-1.34758e-05,-6.13241e-05,2.20653e-06,-0.000215266,0.000531024,-0.00119842,0.212383,0.00134837,0.435202,-0.000231319,-0.00100411,0.00469496,0,0,0.000424562,1.37527e-05,1.40691e-05,0.00044884,0.137503,0.135854,0.168307,0.481054,0.479878,0.101815,3.90727e-11,3.73096e-11,2.59247e-10,2.89034e-07,3.65203e-07,5e-08,0.000161128,1.12441e-05,0.000737395,2.5495e-05,3.60099e-05,0.000666877,0,0 -35785000,-0.676084,-0.0141049,-0.00145389,0.736688,0.136158,0.189873,-0.0256979,-16.8338,-8.14616,-365.478,-1.35158e-05,-6.13855e-05,2.20671e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000422331,1.36431e-05,1.39571e-05,0.000446272,0.111897,0.111091,0.148799,0.480286,0.478844,0.0972352,3.91478e-11,3.73699e-11,2.58839e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -35885000,-0.67617,-0.014119,-0.00152814,0.736609,0.170019,0.230269,-0.0179605,-16.8185,-8.12521,-365.476,-1.3516e-05,-6.1379e-05,2.14164e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000421045,1.36082e-05,1.39089e-05,0.0004458,0.136627,0.135679,0.167872,0.491278,0.490035,0.10102,3.92477e-11,3.74632e-11,2.58254e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -35985000,-0.676139,-0.0139558,-0.00151844,0.736641,0.13839,0.18195,-0.0131988,-16.8352,-8.14819,-365.477,-1.35662e-05,-6.14309e-05,2.15322e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000418903,1.3509e-05,1.37984e-05,0.000444145,0.111488,0.111002,0.148475,0.490437,0.489001,0.0965131,3.93251e-11,3.75277e-11,2.57619e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -36085000,-0.676204,-0.0140058,-0.00154003,0.73658,0.17211,0.221886,-0.00621368,-16.8196,-8.128,-365.473,-1.35664e-05,-6.14254e-05,2.09728e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000418086,1.34818e-05,1.37597e-05,0.000443911,0.136172,0.135577,0.168808,0.501483,0.500194,0.10282,3.94251e-11,3.7623e-11,2.57203e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -36185000,-0.676306,-0.0138946,-0.0015672,0.736488,0.139132,0.177352,-0.00154172,-16.8365,-8.15029,-365.47,-1.36166e-05,-6.1459e-05,1.97021e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.00041627,1.33915e-05,1.3658e-05,0.000442796,0.111272,0.110951,0.149193,0.50059,0.499158,0.0981566,3.95032e-11,3.76917e-11,2.56576e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -36285000,-0.676421,-0.0139722,-0.0015633,0.736381,0.172497,0.217294,0.0101506,-16.8209,-8.13064,-365.458,-1.36165e-05,-6.14509e-05,1.88554e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000415168,1.33681e-05,1.36208e-05,0.000442391,0.135925,0.135513,0.168393,0.511673,0.510353,0.10202,3.96031e-11,3.77858e-11,2.55986e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -36385000,-0.6764,-0.0139006,-0.00157771,0.736401,0.143297,0.176192,0.0104691,-16.8361,-8.15047,-365.457,-1.36621e-05,-6.14896e-05,1.87287e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000413605,1.32857e-05,1.35274e-05,0.000441517,0.111149,0.110916,0.148883,0.510746,0.509315,0.0974302,3.96824e-11,3.7858e-11,2.55362e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -36485000,-0.676401,-0.0139602,-0.00163945,0.736399,0.177717,0.215349,0.0151811,-16.82,-8.13089,-365.456,-1.36621e-05,-6.14892e-05,1.86816e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000412574,1.32662e-05,1.34974e-05,0.000441156,0.135781,0.135469,0.167936,0.521854,0.520512,0.101202,3.97823e-11,3.79525e-11,2.54767e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -36585000,-0.67651,-0.0139107,-0.00162684,0.7363,0.145889,0.176814,0.0177023,-16.8357,-8.15057,-365.453,-1.37078e-05,-6.15179e-05,1.77872e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.0004112,1.31911e-05,1.34104e-05,0.00044041,0.111076,0.110891,0.148536,0.520903,0.519472,0.0966879,3.98631e-11,3.80276e-11,2.54142e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -36685000,-0.676632,-0.0139036,-0.0016102,0.736189,0.179313,0.21658,0.024432,-16.8194,-8.13096,-365.448,-1.37084e-05,-6.15101e-05,1.68843e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.00041058,1.31776e-05,1.33856e-05,0.000440233,0.135693,0.135439,0.16891,0.532027,0.530672,0.103026,3.9963e-11,3.81238e-11,2.53718e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -36785000,-0.676744,-0.0138466,-0.00164782,0.736087,0.147372,0.181557,0.0205777,-16.8352,-8.14878,-365.447,-1.37524e-05,-6.15349e-05,1.60008e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000409317,1.31079e-05,1.33061e-05,0.000439573,0.111031,0.110875,0.149286,0.531061,0.52963,0.0983525,4.00455e-11,3.82015e-11,2.53091e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -36885000,-0.6769,-0.0139066,-0.00167466,0.735942,0.180361,0.219679,0.0258535,-16.8188,-8.12881,-365.444,-1.37534e-05,-6.15247e-05,1.47762e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000408435,1.30981e-05,1.32855e-05,0.000439252,0.135634,0.135414,0.168467,0.542195,0.540831,0.102204,4.01454e-11,3.82966e-11,2.52485e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -36985000,-0.676971,-0.0138217,-0.00161839,0.735879,0.14846,0.183083,0.0192416,-16.8348,-8.14692,-365.446,-1.37958e-05,-6.15493e-05,1.40847e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000407256,1.30349e-05,1.321e-05,0.00043867,0.111,0.11086,0.14895,0.541219,0.539787,0.097606,4.02295e-11,3.83767e-11,2.51854e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -37085000,-0.677031,-0.0138523,-0.00161043,0.735823,0.181974,0.221673,0.0264245,-16.8182,-8.12671,-365.442,-1.37963e-05,-6.15444e-05,1.34791e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000406421,1.30297e-05,1.31937e-05,0.000438391,0.135596,0.135394,0.168038,0.552361,0.550991,0.1014,4.03294e-11,3.84721e-11,2.51242e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -37185000,-0.677071,-0.0137881,-0.00160295,0.735787,0.149591,0.18009,0.0251481,-16.8344,-8.14697,-365.445,-1.38369e-05,-6.15723e-05,1.32784e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000405342,1.29717e-05,1.31261e-05,0.00043783,0.110978,0.110847,0.148627,0.551377,0.549944,0.0968758,4.04152e-11,3.85542e-11,2.50606e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -37285000,-0.677165,-0.0138099,-0.00165287,0.7357,0.182747,0.218742,0.0308397,-16.8178,-8.12709,-365.442,-1.38377e-05,-6.1565e-05,1.23313e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.00040456,1.29705e-05,1.3116e-05,0.000437577,0.135568,0.135376,0.167628,0.562524,0.561151,0.100615,4.05152e-11,3.86499e-11,2.49985e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -37385000,-0.677222,-0.0137494,-0.00160452,0.735648,0.148976,0.177308,0.0279545,-16.834,-8.14709,-365.444,-1.38765e-05,-6.15886e-05,1.1985e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000403821,1.29191e-05,1.30557e-05,0.000437201,0.11096,0.110837,0.149354,0.561535,0.560102,0.0985298,4.06026e-11,3.87349e-11,2.49524e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -37485000,-0.677358,-0.0137714,-0.00160899,0.735523,0.18172,0.217394,0.0327342,-16.8174,-8.12741,-365.444,-1.38776e-05,-6.158e-05,1.08376e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000403106,1.29228e-05,1.30496e-05,0.000436947,0.135546,0.135364,0.168569,0.572687,0.57131,0.102403,4.07026e-11,3.88308e-11,2.48896e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -37585000,-0.677419,-0.0137049,-0.00160368,0.735468,0.147701,0.17762,0.0376649,-16.8336,-8.14732,-365.439,-1.39142e-05,-6.15973e-05,1.00279e-06,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000402109,1.28751e-05,1.29934e-05,0.000436488,0.110948,0.11083,0.149039,0.571694,0.570259,0.0977956,4.07916e-11,3.89166e-11,2.48248e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -37685000,-0.677504,-0.0137564,-0.00166321,0.735389,0.179749,0.217763,0.0484005,-16.8172,-8.12759,-365.429,-1.39148e-05,-6.15904e-05,9.09981e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000401419,1.28832e-05,1.29939e-05,0.000436274,0.135529,0.135355,0.16817,0.582849,0.58147,0.101614,4.08915e-11,3.90126e-11,2.47611e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -37785000,-0.677546,-0.0136349,-0.00170518,0.735352,0.146355,0.17797,0.0495964,-16.8331,-8.14748,-365.424,-1.39489e-05,-6.16077e-05,8.6122e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000400489,1.28394e-05,1.29436e-05,0.00043582,0.110939,0.110824,0.148691,0.581853,0.580416,0.097046,4.0982e-11,3.91e-11,2.46955e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -37885000,-0.677618,-0.0136449,-0.00172192,0.735286,0.17824,0.217431,0.052976,-16.8169,-8.12775,-365.425,-1.39496e-05,-6.16031e-05,7.94876e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.00039986,1.28518e-05,1.29478e-05,0.000435609,0.135516,0.135346,0.167724,0.593011,0.591629,0.100806,4.10819e-11,3.91962e-11,2.46309e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -37985000,-0.677616,-0.0135622,-0.00176866,0.735288,0.142263,0.177724,0.0486748,-16.8347,-8.14761,-365.425,-1.39827e-05,-6.16192e-05,7.70906e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000399199,1.28141e-05,1.29054e-05,0.000435328,0.110931,0.110818,0.149442,0.592011,0.590574,0.098721,4.11738e-11,3.92859e-11,2.45833e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -38085000,-0.677675,-0.0135891,-0.00179806,0.735234,0.173303,0.21693,0.060798,-16.8189,-8.12794,-365.414,-1.39834e-05,-6.16126e-05,6.75209e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000398567,1.28311e-05,1.29148e-05,0.000435169,0.135504,0.135338,0.168699,0.603172,0.601789,0.102619,4.12737e-11,3.93823e-11,2.45179e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -38185000,-0.67769,-0.0134859,-0.00177856,0.735222,0.137309,0.176882,0.0523956,-16.8363,-8.14783,-365.417,-1.40139e-05,-6.16252e-05,6.34664e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000397709,1.27977e-05,1.28742e-05,0.000434765,0.110922,0.110813,0.149102,0.60217,0.600731,0.0979671,4.13668e-11,3.94724e-11,2.44508e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -38285000,-0.677753,-0.0135127,-0.00180242,0.735163,0.16928,0.214918,0.0581662,-16.8209,-8.12824,-365.413,-1.40145e-05,-6.1621e-05,5.71379e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000397149,1.28192e-05,1.28885e-05,0.000434587,0.135492,0.13533,0.168264,0.613334,0.611949,0.101807,4.14668e-11,3.95689e-11,2.43844e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -38385000,-0.677752,-0.0134095,-0.00175973,0.735166,0.138726,0.176519,0.0451602,-16.836,-8.14784,-365.415,-1.40412e-05,-6.16325e-05,5.47238e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000396336,1.27905e-05,1.28528e-05,0.000434204,0.110918,0.11081,0.148773,0.612329,0.610889,0.0972293,4.1561e-11,3.96602e-11,2.43164e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -38485000,-0.677821,-0.0134163,-0.00179641,0.735102,0.170731,0.215732,0.0500557,-16.8205,-8.12826,-365.413,-1.40419e-05,-6.1628e-05,4.7825e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000395813,1.2816e-05,1.28719e-05,0.000434039,0.135489,0.135327,0.167845,0.623494,0.622108,0.101013,4.16609e-11,3.97569e-11,2.4249e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -38585000,-0.677802,-0.0133504,-0.00172686,0.735121,0.141137,0.177107,0.0359715,-16.8356,-8.14795,-365.421,-1.40668e-05,-6.16367e-05,4.48712e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000395013,1.27925e-05,1.28411e-05,0.000433686,0.110918,0.110808,0.148458,0.622487,0.621046,0.0965076,4.17562e-11,3.98492e-11,2.418e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -38685000,-0.677883,-0.0134272,-0.0017594,0.735045,0.172167,0.214328,0.0403196,-16.8199,-8.12841,-365.422,-1.40676e-05,-6.16324e-05,3.81363e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000394743,1.28239e-05,1.28672e-05,0.00043365,0.135485,0.135322,0.16879,0.633654,0.632268,0.102813,4.18562e-11,3.99468e-11,2.41313e-10,2.89034e-07,3.65203e-07,5e-08,0,0,0,0,0,0,0,0 -38785000,-0.677886,-0.0133312,-0.00175637,0.735044,0.137967,0.171878,0.0378667,-16.8372,-8.14999,-365.422,-1.40919e-05,-6.16373e-05,3.33583e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.000393981,1.28039e-05,1.28423e-05,0.000433305,0.0894152,0.0893056,0.127716,0.632597,0.631155,0.0981057,4.19524e-11,4.004e-11,2.40615e-10,2.89034e-07,3.65203e-07,5.0009e-08,0,0,0,0,0,0,0,0 -38885000,-0.677941,-0.0135031,-0.00183415,0.73499,0.152687,0.191495,0.490874,-16.8222,-8.13138,-365.405,-1.40925e-05,-6.16335e-05,2.72971e-07,-0.000215266,0.000531024,-0.00119842,0.212632,0.00135173,0.43538,-0.000222243,-0.00105322,0.00485453,0,0,0.00039351,1.28401e-05,1.28735e-05,0.000433166,0.0898248,0.0896914,0.123339,0.643308,0.641922,0.101577,4.20523e-11,4.0137e-11,2.39922e-10,2.89034e-07,3.65203e-07,5.0019e-08,0,0,0,0,0,0,0,0 diff --git a/src/lib/ecl/test/change_indication/iris_gps.csv b/src/lib/ecl/test/change_indication/iris_gps.csv deleted file mode 100644 index 53825b2dcd..0000000000 --- a/src/lib/ecl/test/change_indication/iris_gps.csv +++ /dev/null @@ -1,351 +0,0 @@ -Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] -15000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -85000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 -185000,0.979315,-0.00941534,-0.0138038,0.201649,0.000856322,-0.000411629,-0.0109864,5.47934e-05,-6.84752e-06,-0.0416696,5.00889e-13,-3.73116e-13,-2.04073e-14,0,0,-2.00585e-09,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000204663,0.002482,0.00248157,0.00481116,0.256366,0.256365,0.562563,0.126414,0.126414,1.00079,1e-06,1e-06,1e-06,4e-06,4e-06,4.00001e-06,0,0,0,0,0,0,0,0 -285000,0.979308,-0.00949873,-0.0141086,0.20166,0.002379,-0.00213114,-0.0263621,0.000165842,-0.000101819,-0.0412744,4.72333e-12,-1.36589e-12,-1.42115e-13,0,0,-1.03405e-08,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00020737,0.00254707,0.00254659,0.00487353,0.282172,0.282169,0.562506,0.132888,0.132888,0.576885,1e-06,1e-06,1e-06,4e-06,4e-06,4.00001e-06,0,0,0,0,0,0,0,0 -385000,0.979291,-0.00951138,-0.0143965,0.201721,0.00537783,-0.00315158,-0.0396036,0.000429404,-0.00026618,-0.0244167,-1.0942e-09,-7.23618e-10,8.85773e-12,0,0,-2.11601e-07,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000212229,0.00265868,0.00265816,0.00498376,0.319167,0.319162,0.560114,0.0942198,0.0942198,0.375592,9.99994e-07,9.99994e-07,1e-06,4e-06,4e-06,3.99998e-06,0,0,0,0,0,0,0,0 -485000,0.979278,-0.00952859,-0.0147624,0.201755,0.00880115,-0.00649446,-0.0568877,0.0011663,-0.000751267,-0.0284287,-1.35448e-09,-8.91104e-10,1.09489e-11,0,0,-1.48264e-08,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000219099,0.00282371,0.00282311,0.00514201,0.386741,0.386732,0.553871,0.109438,0.109437,0.287379,9.99994e-07,9.99994e-07,1e-06,4e-06,4e-06,3.99978e-06,0,0,0,0,0,0,0,0 -585000,0.979269,-0.0095287,-0.0149642,0.201785,0.0102124,-0.00954547,-0.0751953,0.00161955,-0.00119412,-0.0361541,-5.53152e-08,-3.52001e-08,4.57828e-10,0,0,2.77562e-07,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00022799,0.00298935,0.00298869,0.00534822,0.435949,0.435934,0.542812,0.0904933,0.0904929,0.242024,9.99625e-07,9.99625e-07,1e-06,4e-06,4e-06,3.99919e-06,0,0,0,0,0,0,0,0 -685000,0.979259,-0.00955857,-0.0153322,0.201804,0.0151134,-0.0119584,-0.0797677,0.00292575,-0.0022634,-0.0326607,-5.19032e-08,-3.35021e-08,4.17757e-10,0,0,-1.69524e-06,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000238947,0.003253,0.00325224,0.00560241,0.547191,0.54717,0.525907,0.117148,0.117146,0.217499,9.99625e-07,9.99625e-07,1e-06,4e-06,4e-06,3.99786e-06,0,0,0,0,0,0,0,0 -785000,0.979257,-0.00947261,-0.0154864,0.201808,0.0173967,-0.0110439,-0.0884127,0.00313515,-0.00236293,-0.0373937,-4.47456e-07,-2.53029e-07,4.57112e-09,0,0,-2.80912e-06,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00025184,0.00335582,0.00335498,0.00590458,0.566853,0.566833,0.503498,0.101251,0.10125,0.204568,9.96263e-07,9.96262e-07,9.99997e-07,4e-06,4e-06,3.99537e-06,0,0,0,0,0,0,0,0 -885000,0.979246,-0.00951692,-0.0158372,0.201831,0.0211409,-0.0115711,-0.104516,0.00503006,-0.00352416,-0.0502256,-4.49494e-07,-2.54198e-07,4.59161e-09,0,0,-1.88445e-06,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00026693,0.00371092,0.00370996,0.00625468,0.718475,0.71845,0.475826,0.141035,0.141033,0.198089,9.96263e-07,9.96263e-07,9.99997e-07,4e-06,4e-06,3.99118e-06,0,0,0,0,0,0,0,0 -985000,0.979255,-0.00927553,-0.0159463,0.201791,0.0211795,-0.00880513,-0.116405,0.00449049,-0.00283133,-0.0592977,-1.6037e-06,-1.01145e-06,1.37953e-08,0,0,-2.95381e-06,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000283718,0.00362002,0.00361894,0.00665284,0.661743,0.661727,0.453916,0.116197,0.116196,0.20526,9.83329e-07,9.83328e-07,9.99986e-07,4e-06,4e-06,3.9866e-06,0,0,0,0,0,0,0,0 -1085000,0.979258,-0.00936203,-0.0161338,0.201755,0.030556,-0.0113142,-0.13449,0.00701773,-0.00376993,-0.0779794,-1.61019e-06,-1.01687e-06,1.38204e-08,0,0,-3.32483e-07,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000302726,0.00404907,0.00404789,0.00709903,0.841032,0.841019,0.420545,0.166803,0.166801,0.203829,9.83329e-07,9.83328e-07,9.99986e-07,4e-06,4e-06,3.97832e-06,0,0,0,0,0,0,0,0 -1185000,0.979274,-0.00904449,-0.0160523,0.201702,0.0297317,-0.00982761,-0.130921,0.00569539,-0.0027183,-0.0734185,-3.63716e-06,-2.74135e-06,2.026e-08,0,0,-9.50728e-06,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000323428,0.00374004,0.00373878,0.00759315,0.698898,0.6989,0.38636,0.126795,0.126794,0.203011,9.53858e-07,9.53857e-07,9.9996e-07,4e-06,4e-06,3.96733e-06,0,0,0,0,0,0,0,0 -1285000,0.979284,-0.00891737,-0.016305,0.201639,0.0388641,-0.0104528,-0.137,0.00917325,-0.00377233,-0.0780551,-3.6203e-06,-2.72268e-06,2.02979e-08,0,0,-1.47572e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000346392,0.00421853,0.0042171,0.0081354,0.892068,0.892084,0.352444,0.183037,0.183036,0.20185,9.53858e-07,9.53857e-07,9.9996e-07,4e-06,4e-06,3.95329e-06,0,0,0,0,0,0,0,0 -1385000,0.979303,-0.00855862,-0.01598,0.201587,0.0364758,-0.00769753,-0.134581,0.00685964,-0.002438,-0.0751093,-6.54748e-06,-5.82778e-06,1.53196e-08,0,0,-2.57585e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000371053,0.0037641,0.00376268,0.0087255,0.697876,0.697903,0.320012,0.130672,0.130672,0.199989,9.05208e-07,9.05207e-07,9.9992e-07,4e-06,4e-06,3.93598e-06,0,0,0,0,0,0,0,0 -1485000,0.979297,-0.0084952,-0.0161468,0.201606,0.0419636,-0.00834532,-0.145852,0.010793,-0.00316663,-0.0873161,-6.54149e-06,-5.81958e-06,1.53685e-08,0,0,-2.72374e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000398344,0.00426767,0.00426608,0.00936342,0.894964,0.895005,0.290205,0.188098,0.188099,0.197529,9.05208e-07,9.05207e-07,9.9992e-07,4e-06,4e-06,3.91566e-06,0,0,0,0,0,0,0,0 -1585000,0.9793,-0.00823196,-0.0158364,0.201624,0.0354209,-0.00538601,-0.156301,0.00739539,-0.00196173,-0.0981812,-1.00478e-05,-1.02836e-05,-6.86652e-09,0,0,-3.07102e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000427319,0.00373392,0.00373239,0.0100492,0.683827,0.683864,0.271779,0.129813,0.129814,0.204443,8.38498e-07,8.38499e-07,9.99868e-07,4e-06,4e-06,3.8983e-06,0,0,0,0,0,0,0,0 -1685000,0.979285,-0.0082739,-0.0160536,0.201679,0.0426854,-0.00452515,-0.161557,0.0113214,-0.00239468,-0.103477,-1.00166e-05,-1.0239e-05,-6.57948e-09,0,0,-3.90924e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000458881,0.00424134,0.00423963,0.0107828,0.881816,0.881877,0.247137,0.186204,0.186207,0.20042,8.38498e-07,8.38498e-07,9.99869e-07,4e-06,4e-06,3.87227e-06,0,0,0,0,0,0,0,0 -1785000,0.979293,-0.00838086,-0.0163109,0.201618,0.0521503,-0.00529812,-0.16245,0.0161426,-0.00290156,-0.106004,-9.96722e-06,-1.01647e-05,-6.03789e-09,0,0,-5.09311e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000491985,0.00479068,0.00478877,0.0115649,1.12394,1.12403,0.22547,0.266836,0.266843,0.195906,8.38497e-07,8.38497e-07,9.99869e-07,4e-06,4e-06,3.84277e-06,0,0,0,0,0,0,0,0 -1885000,0.979303,-0.00795909,-0.0157409,0.201628,0.0423569,0.000449667,-0.163765,0.0114988,-0.00145998,-0.110691,-1.35985e-05,-1.56832e-05,-4.85675e-08,0,0,-6.17675e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000526934,0.00414335,0.00414159,0.0123946,0.865117,0.865191,0.206811,0.181391,0.181395,0.191238,7.56526e-07,7.56529e-07,9.99808e-07,4e-06,4e-06,3.81008e-06,0,0,0,0,0,0,0,0 -1985000,0.979297,-0.00800563,-0.0160619,0.201633,0.0494432,0.00106662,-0.162364,0.0161293,-0.00145303,-0.110024,-1.35317e-05,-1.55685e-05,-4.75172e-08,0,0,-7.87975e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000564404,0.00467373,0.00467174,0.0132723,1.10518,1.10528,0.190781,0.259864,0.259874,0.186401,7.56526e-07,7.56528e-07,9.99808e-07,4e-06,4e-06,3.77376e-06,0,0,0,0,0,0,0,0 -2085000,0.9793,-0.00777906,-0.0155154,0.201668,0.0391,0.00357233,-0.160831,0.0111217,-0.000425663,-0.107737,-1.68535e-05,-2.18021e-05,-1.1309e-07,0,0,-9.9046e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000603579,0.0039611,0.00395932,0.0141977,0.846812,0.846886,0.177231,0.175709,0.175714,0.181659,6.63631e-07,6.6364e-07,9.9974e-07,4e-06,4e-06,3.73407e-06,0,0,0,0,0,0,0,0 -2185000,0.979304,-0.00768114,-0.0158078,0.201628,0.0453426,0.00465532,-0.16201,0.0153611,2.89192e-05,-0.112147,-1.68075e-05,-2.17096e-05,-1.12058e-07,0,0,-0.000112763,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000644819,0.00445572,0.00445368,0.0151716,1.08084,1.08095,0.165769,0.251845,0.251856,0.176968,6.63631e-07,6.63638e-07,9.9974e-07,4e-06,4e-06,3.69045e-06,0,0,0,0,0,0,0,0 -2285000,0.979318,-0.00752596,-0.0152285,0.201614,0.033289,0.00645201,-0.159514,0.0101616,0.000503271,-0.112044,-1.95304e-05,-2.82325e-05,-1.98006e-07,0,0,-0.000132649,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000687724,0.00369111,0.00368934,0.0161932,0.820576,0.82064,0.16073,0.169814,0.16982,0.180294,5.65715e-07,5.65733e-07,9.99668e-07,4e-06,4e-06,3.65504e-06,0,0,0,0,0,0,0,0 -2385000,0.979311,-0.00751644,-0.0153657,0.201636,0.0391041,0.00675995,-0.15905,0.0138168,0.00112758,-0.11056,-1.94714e-05,-2.80988e-05,-1.96335e-07,0,0,-0.000154859,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000733381,0.00413709,0.00413516,0.0172627,1.04502,1.04512,0.152358,0.243306,0.243317,0.175628,5.65715e-07,5.65731e-07,9.99668e-07,4e-06,4e-06,3.6043e-06,0,0,0,0,0,0,0,0 -2485000,0.979304,-0.00729423,-0.0147981,0.201722,0.0266756,0.00750853,-0.159892,0.00886131,0.00107749,-0.113769,-2.14775e-05,-3.42862e-05,-2.90868e-07,0,0,-0.000171804,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000781098,0.0033497,0.003348,0.0183794,0.784741,0.784796,0.145445,0.16374,0.163745,0.171309,4.69477e-07,4.69505e-07,9.99594e-07,4e-06,4e-06,3.54969e-06,0,0,0,0,0,0,0,0 -2585000,0.979319,-0.00734512,-0.0148991,0.20164,0.0287248,0.00731753,-0.161903,0.0116264,0.00184637,-0.117672,-2.14429e-05,-3.41985e-05,-2.89673e-07,0,0,-0.000188952,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000830025,0.00373962,0.0037378,0.0195456,0.994296,0.994375,0.139706,0.234128,0.234138,0.167247,4.69477e-07,4.69504e-07,9.99594e-07,4e-06,4e-06,3.49054e-06,0,0,0,0,0,0,0,0 -2685000,0.979316,-0.00734359,-0.0143827,0.201691,0.0190914,0.00787703,-0.160567,0.00716888,0.00141391,-0.116783,-2.2683e-05,-3.93868e-05,-3.79109e-07,0,0,-0.000215073,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000881601,0.00296709,0.00296553,0.0207584,0.73846,0.738507,0.134935,0.157404,0.157408,0.163452,3.80761e-07,3.80797e-07,9.9952e-07,4e-06,4e-06,3.42669e-06,0,0,0,0,0,0,0,0 -2785000,0.979326,-0.00722315,-0.0145043,0.201638,0.0233698,0.00924434,-0.157127,0.00942057,0.00227068,-0.113278,-2.26376e-05,-3.92563e-05,-3.77165e-07,0,0,-0.000246346,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000934726,0.00329917,0.00329743,0.0220203,0.93011,0.93018,0.131058,0.224139,0.224148,0.160024,3.80761e-07,3.80796e-07,9.9952e-07,4e-06,4e-06,3.35873e-06,0,0,0,0,0,0,0,0 -2885000,0.979346,-0.00724213,-0.014116,0.201567,0.016411,0.00675776,-0.157825,0.00579474,0.0015795,-0.114611,-2.32705e-05,-4.34214e-05,-4.58053e-07,0,0,-0.000270141,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000989255,0.00257656,0.00257499,0.0233301,0.684472,0.684515,0.131137,0.150805,0.150809,0.163352,3.03368e-07,3.0341e-07,9.99448e-07,4e-06,4e-06,3.30485e-06,0,0,0,0,0,0,0,0 -2985000,0.979344,-0.00720378,-0.0141789,0.201576,0.0183022,0.00696817,-0.159607,0.00762676,0.00227207,-0.118318,-2.32496e-05,-4.33556e-05,-4.57027e-07,0,0,-0.000290577,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00104694,0.00285357,0.00285189,0.0246874,0.856405,0.856469,0.128356,0.213433,0.21344,0.160286,3.03368e-07,3.03409e-07,9.99448e-07,4e-06,4e-06,3.22896e-06,0,0,0,0,0,0,0,0 -3085000,0.979305,-0.00720812,-0.0139268,0.201782,0.0146371,0.00394695,-0.162243,0.00476311,0.00141294,-0.122497,-2.36123e-05,-4.65892e-05,-5.2187e-07,0,0,-0.000311834,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00110848,0.00220491,0.00220326,0.0260902,0.626621,0.62666,0.125998,0.144047,0.144051,0.157475,2.38761e-07,2.38806e-07,9.99385e-07,4e-06,4e-06,3.14842e-06,0,0,0,0,0,0,0,0 -3185000,0.979297,-0.00718785,-0.0140278,0.201815,0.0172549,0.00345028,-0.16267,0.00639508,0.00174328,-0.127186,-2.35966e-05,-4.65379e-05,-5.21063e-07,0,0,-0.00033257,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00117065,0.00243267,0.00243089,0.0275429,0.77838,0.778436,0.124033,0.202309,0.202316,0.154989,2.38762e-07,2.38805e-07,9.99385e-07,4e-06,4e-06,3.06414e-06,0,0,0,0,0,0,0,0 -3285000,0.979295,-0.00716318,-0.0136869,0.201847,0.0121836,0.00267534,-0.165375,0.00405541,0.00102137,-0.134892,-2.39891e-05,-4.90469e-05,-5.65202e-07,0,0,-0.000349336,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00123455,0.00186869,0.00186693,0.0290434,0.568054,0.568088,0.12229,0.137283,0.137286,0.152715,1.86562e-07,1.86602e-07,9.99333e-07,4e-06,4e-06,2.97565e-06,0,0,0,0,0,0,0,0 -3385000,0.979295,-0.00695292,-0.0137087,0.201856,0.0125998,0.00430885,-0.163308,0.00526318,0.00136763,-0.132681,-2.39662e-05,-4.89753e-05,-5.64115e-07,0,0,-0.000386465,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00130052,0.00205419,0.00205226,0.0305924,0.701273,0.701324,0.120765,0.191123,0.191129,0.150714,1.86562e-07,1.86602e-07,9.99333e-07,4e-06,4e-06,2.88403e-06,0,0,0,0,0,0,0,0 -3485000,0.979301,-0.0069062,-0.0134589,0.201844,0.0106377,0.00620349,-0.161135,0.00337129,0.000998393,-0.132553,-2.41928e-05,-5.08569e-05,-5.9813e-07,0,0,-0.000419676,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00136801,0.0015751,0.00157308,0.0321892,0.512379,0.512409,0.119318,0.130669,0.130671,0.148875,1.45322e-07,1.45357e-07,9.99288e-07,4e-06,4e-06,2.78892e-06,0,0,0,0,0,0,0,0 -3585000,0.979311,-0.00680119,-0.0133752,0.201802,0.0123648,0.00662421,-0.166155,0.00456212,0.001642,-0.140065,-2.41851e-05,-5.08301e-05,-5.97679e-07,0,0,-0.000437857,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00143732,0.00172541,0.00172333,0.0338348,0.628318,0.62836,0.120755,0.18023,0.180235,0.152881,1.45322e-07,1.45357e-07,9.99288e-07,4e-06,4e-06,2.71559e-06,0,0,0,0,0,0,0,0 -3685000,0.979312,-0.00680956,-0.0131976,0.201812,0.00826204,0.00580457,-0.162073,0.00297874,0.00117173,-0.138301,-2.42198e-05,-5.23878e-05,-6.30765e-07,0,0,-0.000476318,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00150919,0.00132455,0.00132234,0.0355273,0.4606,0.46063,0.119312,0.124324,0.124326,0.151255,1.1319e-07,1.13222e-07,9.99251e-07,4e-06,4e-06,2.61583e-06,0,0,0,0,0,0,0,0 -3785000,0.979309,-0.00671833,-0.0132887,0.201824,0.00771957,0.0099721,-0.163017,0.00379107,0.00204625,-0.143126,-2.4213e-05,-5.23606e-05,-6.30248e-07,0,0,-0.000500103,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00158336,0.00144632,0.00144391,0.0372678,0.560928,0.56097,0.117874,0.169836,0.169841,0.149809,1.1319e-07,1.13222e-07,9.99251e-07,4e-06,4e-06,2.5147e-06,0,0,0,0,0,0,0,0 -3885000,0.979295,-0.00664804,-0.0133283,0.20189,0.0071303,0.0115881,-0.160466,0.00463006,0.00318613,-0.144139,-2.42048e-05,-5.23227e-05,-6.29472e-07,0,0,-0.000531961,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00166045,0.00157369,0.00157114,0.0390555,0.67678,0.676841,0.116345,0.230945,0.230953,0.148436,1.1319e-07,1.13222e-07,9.99251e-07,4e-06,4e-06,2.412e-06,0,0,0,0,0,0,0,0 -3985000,0.97928,-0.00671595,-0.0131745,0.201971,0.00629481,0.0103198,-0.159483,0.0028868,0.00253607,-0.143313,-2.39349e-05,-5.3559e-05,-6.68174e-07,0,0,-0.000568684,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00173974,0.00121273,0.00121004,0.0408903,0.500427,0.500466,0.114703,0.160077,0.160081,0.147113,8.83569e-08,8.83869e-08,9.99216e-07,4e-06,4e-06,2.3083e-06,0,0,0,0,0,0,0,0 -4085000,0.979271,-0.00663722,-0.0130944,0.202021,0.00745585,0.0109685,-0.148011,0.00368646,0.00363053,-0.132286,-2.3928e-05,-5.3506e-05,-6.66815e-07,0,0,-0.000626088,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00182083,0.00131564,0.0013129,0.0427741,0.600302,0.600353,0.112992,0.215727,0.215734,0.145898,8.8357e-08,8.83869e-08,9.99216e-07,4e-06,4e-06,2.20496e-06,0,0,0,0,0,0,0,0 -4185000,0.979278,-0.00681727,-0.0129295,0.201995,0.00515359,0.00849869,-0.149563,0.00240525,0.00267145,-0.138516,-2.35238e-05,-5.45021e-05,-7.069e-07,0,0,-0.000644794,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00190239,0.00101869,0.00101588,0.0447065,0.446318,0.446356,0.113892,0.151008,0.151012,0.150204,6.92261e-08,6.92552e-08,9.99183e-07,4e-06,4e-06,2.12776e-06,0,0,0,0,0,0,0,0 -4285000,0.979272,-0.00684619,-0.0129734,0.202016,0.00736674,0.010294,-0.151848,0.00309424,0.00359677,-0.1443,-2.35228e-05,-5.44877e-05,-7.06482e-07,0,0,-0.000664953,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00198711,0.00110224,0.00109931,0.0466863,0.532677,0.53272,0.111906,0.201708,0.201715,0.148982,6.92262e-08,6.92553e-08,9.99183e-07,4e-06,4e-06,2.02548e-06,0,0,0,0,0,0,0,0 -4385000,0.97928,-0.00684161,-0.0129089,0.201985,0.00685068,0.00687378,-0.14312,0.00225649,0.00253016,-0.134677,-2.3123e-05,-5.52734e-05,-7.41769e-07,0,0,-0.00071727,0.202688,0.0101969,0.433398,0,0,0,0,0,0.0020726,0.000858479,0.000855246,0.0487148,0.398816,0.398844,0.109778,0.142641,0.142644,0.14774,5.44924e-08,5.45198e-08,9.99156e-07,4e-06,4e-06,1.92433e-06,0,0,0,0,0,0,0,0 -4485000,0.97927,-0.00687264,-0.0128567,0.202034,0.00763556,0.0101264,-0.139694,0.00305042,0.00343589,-0.133233,-2.31227e-05,-5.52546e-05,-7.41181e-07,0,0,-0.000750459,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00216202,0.000926372,0.000923119,0.05079,0.47343,0.473465,0.107571,0.188896,0.188901,0.146543,5.44925e-08,5.45198e-08,9.99156e-07,4e-06,4e-06,1.82549e-06,0,0,0,0,0,0,0,0 -4585000,0.979255,-0.00693674,-0.0128062,0.202106,0.00658649,0.00680756,-0.139156,0.00220076,0.002516,-0.135953,-2.27794e-05,-5.59659e-05,-7.71834e-07,0,0,-0.000774414,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00225386,0.000726121,0.000722586,0.0529121,0.356965,0.356989,0.105237,0.134949,0.134952,0.145303,4.31223e-08,4.31473e-08,9.99134e-07,4e-06,4e-06,1.72872e-06,0,0,0,0,0,0,0,0 -4685000,0.979267,-0.00687777,-0.0127564,0.202057,0.00616056,0.00770458,-0.130694,0.00292885,0.00331909,-0.129896,-2.27802e-05,-5.59469e-05,-7.7118e-07,0,0,-0.000815646,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00234526,0.000781593,0.000777952,0.0550854,0.421535,0.421569,0.102843,0.177221,0.177226,0.144087,4.31224e-08,4.31474e-08,9.99134e-07,4e-06,4e-06,1.63502e-06,0,0,0,0,0,0,0,0 -4785000,0.979251,-0.00679985,-0.0127388,0.202135,-0.000862814,0.00647328,-0.129287,0.00175576,0.00239712,-0.131268,-2.24764e-05,-5.65517e-05,-7.97218e-07,0,0,-0.000839925,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00244151,0.000616826,0.00061272,0.0573032,0.320162,0.320208,0.100346,0.127885,0.127888,0.142816,3.43201e-08,3.43421e-08,9.99118e-07,4e-06,4e-06,1.5441e-06,0,0,0,0,0,0,0,0 -4885000,0.97924,-0.00672651,-0.0127614,0.202188,-0.000164653,0.00502557,-0.125785,0.00171915,0.00296393,-0.131602,-2.24775e-05,-5.65429e-05,-7.96838e-07,0,0,-0.000865244,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00253949,0.00066246,0.000658122,0.0595697,0.376327,0.376376,0.100234,0.1666,0.166605,0.14675,3.43202e-08,3.43422e-08,9.99118e-07,4e-06,4e-06,1.47795e-06,0,0,0,0,0,0,0,0 -4985000,0.979243,-0.00673665,-0.0127047,0.202178,5.80292e-05,0.00480318,-0.118957,0.000976788,0.00204936,-0.127489,-2.21883e-05,-5.68937e-05,-8.19302e-07,0,0,-0.000898055,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00263775,0.000526476,0.00052176,0.0618852,0.287836,0.287869,0.0975532,0.121403,0.121406,0.145332,2.7481e-08,2.74968e-08,9.99098e-07,4e-06,4e-06,1.3928e-06,0,0,0,0,0,0,0,0 -5085000,0.979229,-0.0065953,-0.012632,0.202256,0.000454212,0.00570448,-0.114668,0.00103788,0.00254555,-0.123521,-2.219e-05,-5.68858e-05,-8.18852e-07,0,0,-0.000928831,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00274064,0.000564003,0.000559104,0.064247,0.336914,0.336952,0.094863,0.156942,0.156947,0.143922,2.74811e-08,2.74969e-08,9.99098e-07,4e-06,4e-06,1.31154e-06,0,0,0,0,0,0,0,0 -5185000,0.979218,-0.00648252,-0.0126381,0.202312,-0.00265282,0.0070653,-0.111608,0.000498689,0.00192633,-0.121206,-2.19282e-05,-5.71121e-05,-8.38835e-07,0,0,-0.000955391,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00284489,0.000451525,0.000445997,0.0666563,0.259644,0.259687,0.0921298,0.115458,0.115462,0.14245,2.21416e-08,2.21499e-08,9.99078e-07,4e-06,4e-06,1.23377e-06,0,0,0,0,0,0,0,0 -5285000,0.979209,-0.00636711,-0.0126132,0.202361,-0.0022369,0.0088154,-0.101069,0.000278826,0.00273218,-0.114803,-2.19305e-05,-5.71058e-05,-8.38313e-07,0,0,-0.000988044,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00295131,0.000482707,0.000476928,0.0691144,0.302394,0.302442,0.0893715,0.148163,0.148169,0.140918,2.21417e-08,2.215e-08,9.99078e-07,4e-06,4e-06,1.15959e-06,0,0,0,0,0,0,0,0 -5385000,0.979212,-0.00631379,-0.0126012,0.202351,-0.00509109,0.00989163,-0.0966152,-7.58475e-05,0.00222194,-0.109622,-2.16174e-05,-5.72396e-05,-8.63242e-07,0,0,-0.00101625,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00305781,0.000389251,0.000382915,0.0716211,0.234681,0.234732,0.0866424,0.109994,0.109997,0.139397,1.79527e-08,1.79541e-08,9.99055e-07,4e-06,4e-06,1.08941e-06,0,0,0,0,0,0,0,0 -5485000,0.97921,-0.00631379,-0.0126669,0.202356,-0.00498517,0.0134521,-0.0935514,-0.000608166,0.00337077,-0.110032,-2.1619e-05,-5.72372e-05,-8.6293e-07,0,0,-0.0010331,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00316707,0.000415413,0.000408766,0.074176,0.272329,0.272383,0.0860335,0.140161,0.140168,0.142808,1.79528e-08,1.79542e-08,9.99055e-07,4e-06,4e-06,1.03924e-06,0,0,0,0,0,0,0,0 -5585000,0.979218,-0.00639376,-0.0126974,0.202312,-0.00539784,0.0148553,-0.085782,-0.000659618,0.00294847,-0.1024,-2.12012e-05,-5.73143e-05,-8.98896e-07,0,0,-0.00106268,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00327644,0.000337577,0.000330443,0.0767791,0.212723,0.212759,0.083268,0.104968,0.104972,0.141135,1.46494e-08,1.46465e-08,9.99028e-07,4e-06,4e-06,9.75474e-07,0,0,0,0,0,0,0,0 -5685000,0.981896,-0.00652952,-0.012503,0.188895,-0.00557599,0.0177653,-0.0859193,-0.00126253,0.00450961,-0.101837,-2.1192e-05,-5.73234e-05,-3.9023e-07,0,0,-0.00107856,0.20342,0.0019756,0.434785,0,0,0,0,0,0.0002153,0.000329109,0.000328702,0.00505963,0.217419,0.217462,0.0805253,0.132177,0.132184,0.139416,1.46493e-08,1.46464e-08,9.98606e-07,4e-06,4e-06,9.15198e-07,0,0,0,0,0,0,0,0 -5785000,0.982427,-0.00642289,-0.0124533,0.186121,-0.00504225,0.0177966,-0.0801795,-0.00108789,0.00387237,-0.0958455,-2.06262e-05,-5.74408e-05,2.00235e-06,0,0,-0.00110298,0.20342,0.0019756,0.434785,0,0,0,0,0,0.000112118,0.000329372,0.000329185,0.00263465,0.153017,0.153043,0.0778503,0.0989639,0.0989681,0.137718,1.21173e-08,1.2113e-08,9.9565e-07,4e-06,4e-06,8.58622e-07,0,0,0,0,0,0,0,0 -5885000,0.982401,-0.006349,-0.0125093,0.186258,-0.00315199,0.0194272,-0.0768537,-0.00147657,0.00577277,-0.0972845,-2.06304e-05,-5.74371e-05,1.87357e-06,0,0,-0.00111362,0.20342,0.0019756,0.434785,0,0,0,0,0,7.69552e-05,0.00033062,0.000330507,0.0018129,0.160754,0.160781,0.0752151,0.121055,0.121062,0.135986,1.21137e-08,1.21095e-08,9.8777e-07,4e-06,4e-06,8.05326e-07,0,0,0,0,0,0,0,0 -5985000,0.982233,-0.00627637,-0.012627,0.187135,-0.00290272,0.0214237,-0.0703361,-0.00176602,0.00779216,-0.0915208,-2.07551e-05,-5.73153e-05,-3.69302e-06,0,0,-0.00113513,0.20342,0.0019756,0.434785,0,0,0,0,0,5.97929e-05,0.000332516,0.000332439,0.00141957,0.17176,0.171787,0.0726587,0.146573,0.146583,0.134281,1.21068e-08,1.21028e-08,9.73208e-07,4e-06,4e-06,7.55447e-07,0,0,0,0,0,0,0,0 -6085000,0.982058,-0.00626863,-0.0125729,0.188055,-0.00342744,0.0203061,-0.067169,-0.00141265,0.00676171,-0.0897615,-2.04081e-05,-5.72192e-05,-1.28395e-05,0,0,-0.00114883,0.20342,0.0019756,0.434785,0,0,0,0,0,5.00653e-05,0.000331894,0.000331844,0.00120495,0.136561,0.136578,0.070154,0.110262,0.110268,0.132549,1.02483e-08,1.02443e-08,9.50007e-07,4e-06,4e-06,7.08585e-07,0,0,0,0,0,0,0,0 -6185000,0.982015,-0.00628007,-0.0125286,0.188282,-0.00458645,0.0229405,-0.0658624,-0.00177156,0.00894771,-0.0892255,-2.04398e-05,-5.71884e-05,-1.42144e-05,0,0,-0.00116029,0.20342,0.0019756,0.434785,0,0,0,0,0,4.66298e-05,0.000334193,0.000334159,0.00113993,0.15255,0.152568,0.0693564,0.131874,0.131881,0.135275,1.0237e-08,1.02333e-08,9.26409e-07,4e-06,4e-06,6.75355e-07,0,0,0,0,0,0,0,0 -6285000,0.982013,-0.00627142,-0.0125538,0.188291,-0.00597455,0.0225917,-0.0669628,-0.00162214,0.00780038,-0.0929807,-1.987e-05,-5.73224e-05,-1.34939e-05,0,0,-0.0011647,0.20342,0.0019756,0.434785,0,0,0,0,0,4.27564e-05,0.000329475,0.000329451,0.00106315,0.132479,0.13249,0.066919,0.101719,0.101723,0.133441,8.87397e-09,8.87093e-09,8.86814e-07,4e-06,4e-06,6.33558e-07,0,0,0,0,0,0,0,0 -6385000,0.982118,-0.00621575,-0.0124862,0.18775,-0.00525502,0.0253149,-0.0663674,-0.00222117,0.0102037,-0.0943801,-1.96809e-05,-5.75095e-05,-4.89202e-06,0,0,-0.00117254,0.20342,0.0019756,0.434785,0,0,0,0,0,4.03345e-05,0.000331718,0.000331705,0.00102171,0.152529,0.152541,0.064573,0.121363,0.121369,0.131646,8.85083e-09,8.84831e-09,8.39139e-07,4e-06,4e-06,5.94583e-07,0,0,0,0,0,0,0,0 -6485000,0.982098,-0.00621581,-0.0124855,0.187856,-0.00723607,0.0214734,-0.0627554,-0.00201732,0.00872198,-0.0913298,-1.9196e-05,-5.75433e-05,-8.25206e-06,0,0,-0.00118633,0.20342,0.0019756,0.434785,0,0,0,0,0,3.87254e-05,0.000320332,0.000320323,0.000999984,0.139657,0.139664,0.0622933,0.0959077,0.095911,0.129843,7.84702e-09,7.84506e-09,7.84381e-07,4e-06,4e-06,5.58086e-07,0,0,0,0,0,0,0,0 -6585000,0.982037,-0.00616262,-0.012444,0.188179,-0.00832063,0.0238437,-0.0640819,-0.00278395,0.0109337,-0.0932065,-1.93263e-05,-5.74141e-05,-1.41143e-05,0,0,-0.00119272,0.20342,0.0019756,0.434785,0,0,0,0,0,3.76512e-05,0.000322226,0.000322224,0.000988297,0.162849,0.162856,0.0600824,0.115047,0.115051,0.128036,7.81786e-09,7.8165e-09,7.2478e-07,4e-06,4e-06,5.23936e-07,0,0,0,0,0,0,0,0 -6685000,0.98197,-0.00614578,-0.012425,0.188527,-0.0111204,0.0236449,-0.0656668,-0.00275724,0.00933894,-0.0931239,-1.89415e-05,-5.73479e-05,-2.05868e-05,0,0,-0.00120193,0.20342,0.0019756,0.434785,0,0,0,0,0,3.68498e-05,0.000302311,0.000302308,0.000981293,0.151603,0.151607,0.0579631,0.0926533,0.0926556,0.126274,7.09027e-09,7.0892e-09,6.63331e-07,4e-06,4e-06,4.9214e-07,0,0,0,0,0,0,0,0 -6785000,0.98193,-0.00617046,-0.0123615,0.188739,-0.0103987,0.0262103,-0.062571,-0.00388787,0.0117941,-0.0925204,-1.89999e-05,-5.72892e-05,-2.31994e-05,0,0,-0.00121135,0.20342,0.0019756,0.434785,0,0,0,0,0,3.78843e-05,0.000303697,0.000303699,0.00102092,0.176676,0.17668,0.0572193,0.112245,0.112248,0.128562,7.0676e-09,7.06698e-09,6.17197e-07,4e-06,4e-06,4.69699e-07,0,0,0,0,0,0,0,0 -6885000,0.9819,-0.00609233,-0.0122915,0.188904,-0.00942212,0.0221579,-0.0593796,-0.00342762,0.00983231,-0.0914365,-1.85525e-05,-5.72832e-05,-2.51605e-05,0,0,-0.0012208,0.20342,0.0019756,0.434785,0,0,0,0,0,3.72109e-05,0.000274968,0.000274963,0.00101176,0.162662,0.162663,0.0551931,0.0913766,0.0913781,0.126737,6.56268e-09,6.56215e-09,5.57006e-07,4e-06,4e-06,4.41494e-07,0,0,0,0,0,0,0,0 -6985000,0.981933,-0.00603974,-0.0122515,0.188735,-0.0106331,0.023923,-0.0558395,-0.00448804,0.0121387,-0.0887999,-1.8458e-05,-5.73749e-05,-2.09188e-05,0,0,-0.0012316,0.20342,0.0019756,0.434785,0,0,0,0,0,3.64954e-05,0.000275803,0.000275802,0.000999225,0.188338,0.188338,0.0532374,0.111854,0.111855,0.124921,6.53438e-09,6.53443e-09,4.9969e-07,4e-06,4e-06,4.15134e-07,0,0,0,0,0,0,0,0 -7085000,0.981903,-0.00607039,-0.0121767,0.188894,-0.0100253,0.0246571,-0.055854,-0.00383763,0.0100993,-0.0898541,-1.8045e-05,-5.73898e-05,-2.09885e-05,0,0,-0.00123729,0.20342,0.0019756,0.434785,0,0,0,0,0,3.57668e-05,0.000240136,0.000240129,0.000983843,0.169111,0.169112,0.0513691,0.0912439,0.0912448,0.123157,6.20827e-09,6.20833e-09,4.46653e-07,4e-06,4e-06,3.90605e-07,0,0,0,0,0,0,0,0 -7185000,0.981862,-0.00599972,-0.0122436,0.189106,-0.0113276,0.0271231,-0.0545323,-0.0049591,0.0127436,-0.0917013,-1.80942e-05,-5.734e-05,-2.32079e-05,0,0,-0.00124189,0.20342,0.0019756,0.434785,0,0,0,0,0,3.49478e-05,0.000240541,0.000240534,0.000965197,0.194009,0.19401,0.0495685,0.112563,0.112564,0.121406,6.18424e-09,6.18484e-09,3.98058e-07,4e-06,4e-06,3.67682e-07,0,0,0,0,0,0,0,0 -7285000,0.981886,-0.00613074,-0.0122782,0.188975,-0.00917033,0.0253157,-0.0506932,-0.00411908,0.0104157,-0.0873216,-1.76878e-05,-5.74148e-05,-2.00399e-05,0,0,-0.00125345,0.20342,0.0019756,0.434785,0,0,0,0,0,3.40852e-05,0.00020161,0.000201596,0.000944478,0.168872,0.168874,0.0478499,0.0913843,0.0913849,0.119707,5.99255e-09,5.99321e-09,3.54381e-07,4e-06,4e-06,3.46347e-07,0,0,0,0,0,0,0,0 -7385000,0.981931,-0.00605755,-0.0122607,0.188744,-0.0114159,0.0283361,-0.0476121,-0.00513873,0.0131894,-0.084075,-1.76007e-05,-5.74978e-05,-1.61786e-05,0,0,-0.00126307,0.20342,0.0019756,0.434785,0,0,0,0,0,3.3156e-05,0.000201784,0.000201771,0.000921671,0.191865,0.191868,0.0461955,0.113139,0.113139,0.118022,5.9732e-09,5.97434e-09,3.15262e-07,4e-06,4e-06,3.26405e-07,0,0,0,0,0,0,0,0 -7485000,0.982011,-0.00617799,-0.0123179,0.18832,-0.0073983,0.0257612,-0.0433781,-0.00406048,0.0106483,-0.0805811,-1.71903e-05,-5.76616e-05,-8.90482e-06,0,0,-0.00127233,0.20342,0.0019756,0.434785,0,0,0,0,0,3.35823e-05,0.000163785,0.000163762,0.000936579,0.162073,0.162076,0.0455781,0.0911172,0.0911176,0.119877,5.87602e-09,5.87718e-09,2.88801e-07,4e-06,4e-06,3.12313e-07,0,0,0,0,0,0,0,0 -7585000,0.982071,-0.00626467,-0.0122796,0.188008,-0.00694957,0.0279156,-0.0393176,-0.00480074,0.0132869,-0.074562,-1.70888e-05,-5.77573e-05,-4.43123e-06,0,0,-0.00128368,0.20342,0.0019756,0.434785,0,0,0,0,0,3.25322e-05,0.000163968,0.000163951,0.000909725,0.182405,0.182409,0.044013,0.112736,0.112736,0.118163,5.86038e-09,5.86197e-09,2.57157e-07,4e-06,4e-06,2.94624e-07,0,0,0,0,0,0,0,0 -7685000,0.982081,-0.00643825,-0.0123618,0.187945,-0.00562819,0.0256366,-0.0377519,-0.00359733,0.0106171,-0.0681839,-1.69127e-05,-5.77764e-05,-3.81229e-06,0,0,-0.00129485,0.20342,0.0019756,0.434785,0,0,0,0,0,3.14895e-05,0.000130195,0.000130172,0.000882896,0.15041,0.150413,0.0425212,0.0900899,0.0900903,0.116504,5.81176e-09,5.81354e-09,2.29368e-07,4e-06,4e-06,2.78148e-07,0,0,0,0,0,0,0,0 -7785000,0.982078,-0.00632317,-0.0123645,0.187965,-0.00425925,0.0269735,-0.0394257,-0.00410649,0.0131864,-0.0722225,-1.69148e-05,-5.77745e-05,-3.90444e-06,0,0,-0.00129457,0.20342,0.0019756,0.434785,0,0,0,0,0,3.04815e-05,0.000130605,0.000130583,0.000855967,0.167809,0.167814,0.0410875,0.111025,0.111025,0.114864,5.79969e-09,5.80182e-09,2.04893e-07,4e-06,4e-06,2.62735e-07,0,0,0,0,0,0,0,0 -7885000,0.982072,-0.00648194,-0.0124491,0.187982,-0.00425326,0.0250931,-0.039086,-0.0030457,0.010392,-0.0749485,-1.68066e-05,-5.77978e-05,-3.11583e-06,0,0,-0.0012958,0.20342,0.0019756,0.434785,0,0,0,0,0,2.95089e-05,0.00010281,0.000102783,0.000829253,0.135919,0.135923,0.0397097,0.0882577,0.0882581,0.113245,5.77775e-09,5.78009e-09,1.83363e-07,4e-06,4e-06,2.48314e-07,0,0,0,0,0,0,0,0 -7985000,0.982106,-0.00642213,-0.0123596,0.187815,-0.00418535,0.0264586,-0.0351745,-0.00351239,0.0129236,-0.0713219,-1.67435e-05,-5.78561e-05,-3.65312e-07,0,0,-0.00130339,0.20342,0.0019756,0.434785,0,0,0,0,0,2.85694e-05,0.000103609,0.000103586,0.000803427,0.150442,0.150445,0.0383974,0.10809,0.108091,0.11168,5.76847e-09,5.7711e-09,1.64507e-07,4e-06,4e-06,2.34867e-07,0,0,0,0,0,0,0,0 -8085000,0.982043,-0.00629908,-0.0123586,0.188148,-0.00335662,0.0298771,-0.0354649,-0.00384367,0.0157294,-0.0737426,-1.68388e-05,-5.77618e-05,-4.64842e-06,0,0,-0.00130453,0.20342,0.0019756,0.434785,0,0,0,0,0,2.86512e-05,0.0001047,0.000104677,0.000807474,0.165739,0.165744,0.0379038,0.131906,0.131907,0.113286,5.76229e-09,5.76512e-09,1.51882e-07,4e-06,4e-06,2.25364e-07,0,0,0,0,0,0,0,0 -8185000,0.982021,-0.00647212,-0.012292,0.18826,-0.00174599,0.0292669,-0.0319319,-0.00268973,0.0128935,-0.0692171,-1.68153e-05,-5.77416e-05,-5.54926e-06,0,0,-0.00131237,0.20342,0.0019756,0.434785,0,0,0,0,0,2.77154e-05,8.34018e-05,8.33788e-05,0.000781495,0.132617,0.132621,0.0366664,0.104242,0.104243,0.111706,5.75243e-09,5.75545e-09,1.36814e-07,4e-06,4e-06,2.13398e-07,0,0,0,0,0,0,0,0 -8285000,0.982032,-0.00644951,-0.0122764,0.188203,0.000397881,0.032119,-0.0293551,-0.00277249,0.0159438,-0.0678704,-1.68115e-05,-5.77432e-05,-5.42374e-06,0,0,-0.00131648,0.20342,0.0019756,0.434785,0,0,0,0,0,2.68052e-05,8.49817e-05,8.49617e-05,0.00075646,0.145222,0.145228,0.0354785,0.126224,0.126225,0.11015,5.74592e-09,5.74915e-09,1.23523e-07,4e-06,4e-06,2.02185e-07,0,0,0,0,0,0,0,0 -8385000,0.982048,-0.00652031,-0.0122682,0.188121,-0.00129426,0.0279218,-0.0276533,-0.00183004,0.0130707,-0.0643388,-1.67669e-05,-5.77682e-05,-4.07191e-06,0,0,-0.00132242,0.20342,0.0019756,0.434785,0,0,0,0,0,2.59611e-05,6.94372e-05,6.94149e-05,0.000732631,0.115822,0.115825,0.0343466,0.099845,0.0998458,0.108647,5.73996e-09,5.74338e-09,1.11819e-07,4e-06,4e-06,1.91714e-07,0,0,0,0,0,0,0,0 -8485000,0.982126,-0.00642234,-0.0122604,0.187718,-0.00182419,0.0310097,-0.0281648,-0.00197141,0.0159665,-0.0683778,-1.66669e-05,-5.78673e-05,4.27485e-07,0,0,-0.00132125,0.20342,0.0019756,0.434785,0,0,0,0,0,2.5153e-05,7.15682e-05,7.15472e-05,0.000709771,0.126255,0.126259,0.0332599,0.119927,0.119928,0.107166,5.73491e-09,5.73849e-09,1.01456e-07,4e-06,4e-06,1.81893e-07,0,0,0,0,0,0,0,0 -8585000,0.982139,-0.00647232,-0.0123588,0.187637,-0.0004561,0.027715,-0.0229869,-0.00142084,0.0131444,-0.0632075,-1.66616e-05,-5.78619e-05,6.02564e-07,0,0,-0.00132813,0.20342,0.0019756,0.434785,0,0,0,0,0,2.43567e-05,6.07682e-05,6.07437e-05,0.000688116,0.100903,0.100905,0.0322244,0.0952197,0.0952204,0.105736,5.73039e-09,5.73413e-09,9.22908e-08,4e-06,4e-06,1.72712e-07,0,0,0,0,0,0,0,0 -8685000,0.982192,-0.00650564,-0.0124431,0.187357,-0.000630147,0.0289149,-0.0241965,-0.00151816,0.0159574,-0.0649191,-1.66192e-05,-5.79034e-05,2.49902e-06,0,0,-0.00132863,0.20342,0.0019756,0.434785,0,0,0,0,0,2.35966e-05,6.34726e-05,6.34506e-05,0.000667393,0.109678,0.109679,0.0312299,0.113467,0.113468,0.104327,5.72644e-09,5.73031e-09,8.41388e-08,4e-06,4e-06,1.64093e-07,0,0,0,0,0,0,0,0 -8785000,0.982176,-0.00654546,-0.0123997,0.187438,0.000633593,0.0256801,-0.0231786,-0.00107484,0.0130318,-0.0615658,-1.66429e-05,-5.78697e-05,1.40318e-06,0,0,-0.00133353,0.20342,0.0019756,0.434785,0,0,0,0,0,2.3567e-05,5.63779e-05,5.63546e-05,0.000667625,0.0883107,0.0883111,0.0308552,0.0906082,0.0906088,0.105686,5.72371e-09,5.72768e-09,7.86137e-08,4e-06,4e-06,1.57979e-07,0,0,0,0,0,0,0,0 -8885000,0.98225,-0.00659785,-0.0123912,0.18705,0.000852273,0.0280891,-0.0198414,-0.000982812,0.0157351,-0.0559502,-1.65725e-05,-5.79348e-05,4.47786e-06,0,0,-0.00134008,0.20342,0.0019756,0.434785,0,0,0,0,0,2.2849e-05,5.96528e-05,5.96339e-05,0.000647689,0.095872,0.095872,0.0299187,0.107175,0.107175,0.104275,5.7205e-09,5.72458e-09,7.19491e-08,4e-06,4e-06,1.50268e-07,0,0,0,0,0,0,0,0 -8985000,0.982337,-0.00659232,-0.0123072,0.186601,3.26901e-05,0.02649,-0.0178767,-0.000705687,0.012964,-0.0576124,-1.64759e-05,-5.80143e-05,8.33141e-06,0,0,-0.00134022,0.20342,0.0019756,0.434785,0,0,0,0,0,2.21731e-05,5.53468e-05,5.53281e-05,0.000628826,0.0780653,0.0780645,0.0290259,0.0861796,0.0861799,0.102911,5.71746e-09,5.72164e-09,6.60018e-08,4e-06,4e-06,1.43045e-07,0,0,0,0,0,0,0,0 -9085000,0.982435,-0.00660708,-0.0123723,0.186079,0.000299583,0.0298128,-0.0192221,-0.000704992,0.0157213,-0.0573178,-1.63948e-05,-5.80929e-05,1.19494e-05,0,0,-0.00134193,0.20342,0.0019756,0.434785,0,0,0,0,0,2.15078e-05,5.91838e-05,5.91673e-05,0.000610846,0.0848525,0.0848514,0.0281683,0.101257,0.101257,0.10157,5.71491e-09,5.71918e-09,6.06666e-08,4e-06,4e-06,1.36252e-07,0,0,0,0,0,0,0,0 -9185000,0.982504,-0.00666188,-0.012403,0.185709,0.00331793,0.0263748,-0.0173314,-0.000350281,0.0132335,-0.0571572,-1.63015e-05,-5.8154e-05,1.46677e-05,0,0,-0.00134353,0.20342,0.0019756,0.434785,0,0,0,0,0,2.08845e-05,5.69332e-05,5.69163e-05,0.000593672,0.0701693,0.0701678,0.0273444,0.0820442,0.0820444,0.100252,5.71139e-09,5.71573e-09,5.58701e-08,4e-06,4e-06,1.2986e-07,0,0,0,0,0,0,0,0 -9285000,0.98254,-0.00651206,-0.0122259,0.185535,0.0053658,0.0284813,-0.0156373,0.000141733,0.0159522,-0.0544668,-1.62805e-05,-5.81723e-05,1.55663e-05,0,0,-0.00134688,0.20342,0.0019756,0.434785,0,0,0,0,0,2.02895e-05,6.13085e-05,6.12958e-05,0.000577423,0.0765141,0.0765122,0.0265586,0.0958495,0.0958496,0.0989779,5.70935e-09,5.71376e-09,5.15604e-08,4e-06,4e-06,1.23864e-07,0,0,0,0,0,0,0,0 -9385000,0.982504,-0.00646949,-0.0122512,0.185725,0.00523315,0.0258833,-0.0140999,0.000551745,0.0133954,-0.0542571,-1.62667e-05,-5.81405e-05,1.33532e-05,0,0,-0.00134813,0.20342,0.0019756,0.434785,0,0,0,0,0,2.02277e-05,6.05267e-05,6.05114e-05,0.000576909,0.0644651,0.0644625,0.0262699,0.0782754,0.0782754,0.100194,5.70331e-09,5.70773e-09,4.8608e-08,4e-06,4e-06,1.19605e-07,0,0,0,0,0,0,0,0 -9485000,0.982541,-0.00649987,-0.0123228,0.185526,0.00468681,0.0261841,-0.0118387,0.00101778,0.0159738,-0.0503257,-1.62521e-05,-5.81521e-05,1.39583e-05,0,0,-0.00135201,0.20342,0.0019756,0.434785,0,0,0,0,0,1.96556e-05,6.54246e-05,6.54119e-05,0.0005614,0.0706862,0.0706822,0.0255293,0.0910322,0.091032,0.0989221,5.70162e-09,5.7061e-09,4.50021e-08,4e-06,4e-06,1.14211e-07,0,0,0,0,0,0,0,0 -9585000,0.982471,-0.00658491,-0.0122843,0.185895,0.00371453,0.0223046,-0.0124202,0.00099815,0.0132583,-0.0532586,-1.62175e-05,-5.81267e-05,1.10523e-05,0,0,-0.0013507,0.20342,0.0019756,0.434785,0,0,0,0,0,1.91311e-05,6.56287e-05,6.56175e-05,0.000546568,0.0608141,0.0608093,0.0248174,0.0749227,0.0749224,0.0976718,5.68788e-09,5.69235e-09,4.17338e-08,4e-06,4e-06,1.09127e-07,0,0,0,0,0,0,0,0 -9685000,0.982466,-0.00657674,-0.0122385,0.185923,0.0033519,0.0236989,-0.00924116,0.00144044,0.0156645,-0.0508359,-1.62411e-05,-5.81016e-05,9.95634e-06,0,0,-0.00135322,0.20342,0.0019756,0.434785,0,0,0,0,0,1.86179e-05,7.10152e-05,7.10081e-05,0.000532516,0.0671607,0.0671546,0.0241379,0.0868553,0.0868546,0.0964633,5.68652e-09,5.69104e-09,3.87731e-08,4e-06,4e-06,1.04347e-07,0,0,0,0,0,0,0,0 -9785000,0.982404,-0.00660661,-0.0121731,0.186252,0.00407497,0.0224435,-0.00980077,0.00134651,0.0130623,-0.0512005,-1.61703e-05,-5.80946e-05,6.77893e-06,0,0,-0.00135366,0.20342,0.0019756,0.434785,0,0,0,0,0,1.81301e-05,7.18012e-05,7.17948e-05,0.000519074,0.0590416,0.0590357,0.0234845,0.0720195,0.0720189,0.0952758,5.6596e-09,5.66407e-09,3.60785e-08,4e-06,4e-06,9.98359e-08,0,0,0,0,0,0,0,0 -9885000,0.982435,-0.00657,-0.0121148,0.186098,0.00602639,0.0227847,-0.00814747,0.00181734,0.0152048,-0.0513286,-1.61485e-05,-5.81157e-05,7.75711e-06,0,0,-0.00135419,0.20342,0.0019756,0.434785,0,0,0,0,0,1.76874e-05,7.76427e-05,7.76397e-05,0.000506281,0.0657425,0.0657355,0.0228605,0.0833479,0.0833468,0.0941276,5.6585e-09,5.66301e-09,3.36275e-08,4e-06,4e-06,9.559e-08,0,0,0,0,0,0,0,0 -9985000,0.982367,-0.0066144,-0.0121693,0.186447,0.00686715,0.0196901,-0.00709096,0.00178742,0.0125992,-0.0523749,-1.6024e-05,-5.81521e-05,5.14676e-06,0,0,-0.00135402,0.20342,0.0019756,0.434785,0,0,0,0,0,1.72612e-05,7.86315e-05,7.86272e-05,0.000494029,0.0589566,0.0589497,0.0222601,0.0695875,0.0695865,0.0929992,5.61074e-09,5.61514e-09,3.13882e-08,4e-06,4e-06,9.15787e-08,0,0,0,0,0,0,0,0 -10085000,0.982334,-0.00655214,-0.0123275,0.186617,0.00566913,0.0180012,-0.00594373,0.00244009,0.0144482,-0.0508065,-1.60604e-05,-5.81153e-05,3.48472e-06,0,0,-0.00135547,0.20342,0.0019756,0.434785,0,0,0,0,0,1.72175e-05,8.48864e-05,8.48814e-05,0.0004933,0.0661907,0.0661814,0.0220469,0.0805227,0.080521,0.094069,5.61007e-09,5.61451e-09,2.98349e-08,4e-06,4e-06,8.87184e-08,0,0,0,0,0,0,0,0 -10185000,0.982246,-0.00650968,-0.0122472,0.187086,0.003333,0.0193462,-0.00430147,0.00288544,0.0163446,-0.0508615,-1.61301e-05,-5.80468e-05,3.37061e-07,0,0,-0.00135577,0.20342,0.0019756,0.434785,0,0,0,0,0,1.68217e-05,9.14159e-05,9.1415e-05,0.000481602,0.0742724,0.0742611,0.0214802,0.0932301,0.0932275,0.0929451,5.60923e-09,5.6137e-09,2.79176e-08,4e-06,4e-06,8.50884e-08,0,0,0,0,0,0,0,0 -10285000,0.982297,-0.00660805,-0.0121446,0.186819,0.00281594,0.0170482,-0.00538176,0.00232278,0.013438,-0.0507841,-1.58795e-05,-5.8202e-05,1.80461e-06,0,0,-0.00135611,0.20342,0.0019756,0.434785,0,0,0,0,0,1.64376e-05,9.22894e-05,9.22893e-05,0.000470458,0.0682568,0.0682461,0.0209387,0.0783775,0.0783752,0.0918582,5.53177e-09,5.53607e-09,2.61613e-08,4e-06,4e-06,8.16647e-08,0,0,0,0,0,0,0,0 -10385000,0.982335,-0.00660808,-0.0120416,0.186626,0.00699285,0.00287798,-0.00294913,0.000765827,6.88046e-05,-0.0491379,-1.58573e-05,-5.82227e-05,2.79528e-06,0,0,-0.00135725,0.20342,0.0019756,0.434785,0,0,0,0,0,1.6071e-05,9.91637e-05,9.9168e-05,0.000459771,0.0349289,0.0349289,0.0374558,0.12528,0.12528,0.0850656,5.53108e-09,5.53542e-09,2.45464e-08,4e-06,4e-06,7.85881e-08,0,0,0,0,0,0,0,0 -10485000,0.982295,-0.00650675,-0.0119909,0.186843,0.00706091,0.00321875,-0.00187173,0.00146081,0.000370722,-0.0446964,-1.58956e-05,-5.81831e-05,1.03011e-06,0,0,-0.00136017,0.20342,0.0019756,0.434785,0,0,0,0,0,1.57154e-05,0.000106315,0.000106322,0.000449517,0.0361708,0.0361706,0.0375587,0.126259,0.126259,0.0794293,5.53045e-09,5.53482e-09,2.30592e-08,4e-06,4e-06,7.59896e-08,0,0,0,0,0,0,0,0 -10585000,0.982335,-0.00644578,-0.0119173,0.186642,0.00544058,0.00323387,-0.000553102,0.0011007,-0.00317636,-0.0438585,-1.58896e-05,-5.83916e-05,2.50761e-06,0,0,-0.00136059,0.20342,0.0019756,0.434785,0,0,0,0,0,1.5393e-05,0.000113132,0.000113141,0.000439706,0.0333783,0.0333778,0.0352684,0.0848775,0.0848775,0.0750998,5.5036e-09,5.50796e-09,2.16902e-08,4e-06,4e-06,7.37646e-08,0,0,0,0,0,0,0,0 -10685000,0.982341,-0.00639246,-0.0119496,0.186607,0.00566659,0.00191043,-0.000423849,0.00164901,-0.00292372,-0.0430392,-1.58965e-05,-5.83845e-05,2.19155e-06,0,0,-0.00136111,0.20342,0.0019756,0.434785,0,0,0,0,0,1.53537e-05,0.000120798,0.000120808,0.000439024,0.0362188,0.0362177,0.0353114,0.08665,0.08665,0.0733583,5.50324e-09,5.50761e-09,2.07333e-08,4e-06,4e-06,7.23007e-08,0,0,0,0,0,0,0,0 -10785000,0.982341,-0.00640472,-0.0120404,0.186601,0.006196,0.00110546,0.000466317,0.00153195,-0.00252646,-0.0402185,-1.57404e-05,-5.85626e-05,1.83383e-06,0,0,-0.00136274,0.20342,0.0019756,0.434785,0,0,0,0,0,1.50285e-05,0.000126114,0.000126124,0.00042965,0.0347413,0.03474,0.0331825,0.0658046,0.0658045,0.0707296,5.40257e-09,5.40681e-09,1.95416e-08,4e-06,4e-06,7.05669e-08,0,0,0,0,0,0,0,0 -10885000,0.982394,-0.00637544,-0.0120832,0.186323,0.00641841,0.00210116,0.000682741,0.00216344,-0.00242339,-0.0396666,-1.57002e-05,-5.86016e-05,3.65397e-06,0,0,-0.001363,0.20342,0.0019756,0.434785,0,0,0,0,0,1.47321e-05,0.000134163,0.000134175,0.000420621,0.0392497,0.0392477,0.0330565,0.0682754,0.0682752,0.0691991,5.40213e-09,5.40639e-09,1.84381e-08,4e-06,4e-06,6.90547e-08,0,0,0,0,0,0,0,0 -10985000,0.9824,-0.00637406,-0.0121729,0.186281,0.00449295,0.00789017,0.00269413,0.00189284,-0.00157927,-0.0369252,-1.57114e-05,-5.87667e-05,3.39601e-06,0,0,-0.00136405,0.20342,0.0019756,0.434785,0,0,0,0,0,1.44268e-05,0.000136303,0.000136314,0.000411994,0.0382734,0.0382717,0.0310419,0.0554723,0.0554721,0.0676382,5.19105e-09,5.19502e-09,1.74165e-08,4e-06,4e-06,6.77251e-08,0,0,0,0,0,0,0,0 -11085000,0.982328,-0.00649111,-0.0121548,0.186662,0.00500588,0.0112018,0.00457871,0.00234247,-0.000684389,-0.0343449,-1.57544e-05,-5.87244e-05,1.43413e-06,0,0,-0.00136519,0.20342,0.0019756,0.434785,0,0,0,0,0,1.41524e-05,0.000144525,0.000144541,0.00040367,0.044399,0.0443969,0.0307745,0.0586838,0.0586836,0.0671414,5.19069e-09,5.19469e-09,1.6468e-08,4e-06,4e-06,6.65589e-08,0,0,0,0,0,0,0,0 -11185000,0.982312,-0.00655742,-0.0121189,0.186746,0.00485234,0.0127055,0.00781423,0.0028122,-0.000195631,-0.0297565,-1.53797e-05,-5.87061e-05,4.12787e-07,0,0,-0.0013667,0.20342,0.0019756,0.434785,0,0,0,0,0,1.3869e-05,0.00014204,0.000142055,0.000395705,0.0430439,0.0430419,0.0288705,0.0496911,0.0496909,0.0661792,4.85454e-09,4.85817e-09,1.55875e-08,4e-06,4e-06,6.55294e-08,0,0,0,0,0,0,0,0 -11285000,0.982292,-0.00655502,-0.0121507,0.186848,0.00369015,0.0132448,0.00888695,0.00319762,0.00115811,-0.0299901,-1.53909e-05,-5.86956e-05,-9.83051e-08,0,0,-0.00136622,0.20342,0.0019756,0.434785,0,0,0,0,0,1.36146e-05,0.000150165,0.000150183,0.000388009,0.0505897,0.0505867,0.0284808,0.0537098,0.0537095,0.0663138,4.85425e-09,4.85791e-09,1.47678e-08,4e-06,4e-06,6.46246e-08,0,0,0,0,0,0,0,0 -11385000,0.982288,-0.00653776,-0.01211,0.186871,0.00228902,0.0130158,0.0079881,0.00257712,0.00113125,-0.0318609,-1.49892e-05,-5.90432e-05,-3.43818e-07,0,0,-0.00136502,0.20342,0.0019756,0.434785,0,0,0,0,0,1.35876e-05,0.000142423,0.000142435,0.000387392,0.0480242,0.0480215,0.0268409,0.0466039,0.0466036,0.0667595,4.40845e-09,4.41162e-09,1.41898e-08,4e-06,4e-06,6.40172e-08,0,0,0,0,0,0,0,0 -11485000,0.982318,-0.00644575,-0.0120838,0.186718,0.000503172,0.0132156,0.00966921,0.00266776,0.00246418,-0.0287011,-1.49815e-05,-5.90502e-05,1.45953e-08,0,0,-0.00136594,0.20342,0.0019756,0.434785,0,0,0,0,0,1.33303e-05,0.000150175,0.000150189,0.000380018,0.0566505,0.0566466,0.0263737,0.0514569,0.0514563,0.0672672,4.40821e-09,4.4114e-09,1.34652e-08,4e-06,4e-06,6.3292e-08,0,0,0,0,0,0,0,0 -11585000,0.982315,-0.00662151,-0.0120382,0.186732,0.00209561,0.0118651,0.0101795,0.00227694,0.00196543,-0.0273955,-1.44785e-05,-5.93091e-05,-1.72816e-07,0,0,-0.00136667,0.20342,0.0019756,0.434785,0,0,0,0,0,1.30866e-05,0.000137638,0.000137648,0.000372917,0.0522695,0.0522666,0.0247175,0.045179,0.0451786,0.0667352,3.89306e-09,3.89569e-09,1.27893e-08,4e-06,4e-06,6.26507e-08,0,0,0,0,0,0,0,0 -11685000,0.982328,-0.0065787,-0.0119823,0.18667,0.00211573,0.0149623,0.0119291,0.00249597,0.00330364,-0.0271928,-1.44735e-05,-5.9314e-05,5.9731e-08,0,0,-0.00136632,0.20342,0.0019756,0.434785,0,0,0,0,0,1.28577e-05,0.000144789,0.000144801,0.00036606,0.0615258,0.0615225,0.024186,0.0508216,0.050821,0.067416,3.89286e-09,3.89552e-09,1.21575e-08,4e-06,4e-06,6.20878e-08,0,0,0,0,0,0,0,0 -11785000,0.982369,-0.00681329,-0.0119198,0.186445,0.000694143,0.0130597,0.0127516,0.00194678,0.00127703,-0.0244623,-1.34996e-05,-5.98214e-05,1.25983e-06,0,0,-0.00136687,0.20342,0.0019756,0.434785,0,0,0,0,0,1.26347e-05,0.000128873,0.000128879,0.000359426,0.055213,0.0552108,0.0226622,0.0447469,0.0447465,0.0669062,3.35983e-09,3.36197e-09,1.15659e-08,4e-06,4e-06,6.15899e-08,0,0,0,0,0,0,0,0 -11885000,0.982356,-0.00689199,-0.0118163,0.186519,0.00302487,0.0138809,0.0117942,0.00206227,0.00258004,-0.0231633,-1.35119e-05,-5.98098e-05,6.87081e-07,0,0,-0.00136687,0.20342,0.0019756,0.434785,0,0,0,0,0,1.24161e-05,0.000135285,0.000135296,0.000353051,0.0647189,0.0647164,0.0220972,0.0510703,0.0510696,0.0676279,3.35968e-09,3.36184e-09,1.10126e-08,4e-06,4e-06,6.11534e-08,0,0,0,0,0,0,0,0 -11985000,0.982376,-0.00704632,-0.0118835,0.186404,0.00465468,0.0139369,0.0109299,0.00290217,0.00117096,-0.0257133,-1.30855e-05,-5.97289e-05,9.25264e-07,0,0,-0.00136602,0.20342,0.0019756,0.434785,0,0,0,0,0,1.23843e-05,0.00011771,0.000117715,0.000352523,0.0567055,0.056704,0.020893,0.0448537,0.0448533,0.068242,2.85241e-09,2.85411e-09,1.06204e-08,4e-06,4e-06,6.08604e-08,0,0,0,0,0,0,0,0 -12085000,0.982358,-0.00696309,-0.0119355,0.186501,0.00596929,0.014132,0.013531,0.00344022,0.00253644,-0.0189922,-1.30931e-05,-5.97217e-05,5.9322e-07,0,0,-0.00136757,0.20342,0.0019756,0.434785,0,0,0,0,0,1.2184e-05,0.00012334,0.000123345,0.000346375,0.0660689,0.0660669,0.0203272,0.0517097,0.0517091,0.0689439,2.85228e-09,2.85401e-09,1.01259e-08,4e-06,4e-06,6.05111e-08,0,0,0,0,0,0,0,0 -12185000,0.982343,-0.0068962,-0.0118901,0.186581,0.00551656,0.0127081,0.0128793,0.00265474,0.00295234,-0.0173716,-1.30623e-05,-6.00089e-05,-2.60925e-07,0,0,-0.00136768,0.20342,0.0019756,0.434785,0,0,0,0,0,1.19678e-05,0.000105658,0.000105658,0.000340436,0.056885,0.0568835,0.0190781,0.0452053,0.045205,0.0683251,2.39885e-09,2.40017e-09,9.66103e-09,4e-06,4e-06,6.01993e-08,0,0,0,0,0,0,0,0 -12285000,0.982328,-0.00694716,-0.0118756,0.18666,0.00287936,0.0117278,0.0113019,0.00308631,0.00416777,-0.0167748,-1.30708e-05,-6.00009e-05,-6.66158e-07,0,0,-0.00136752,0.20342,0.0019756,0.434785,0,0,0,0,0,1.1777e-05,0.00011053,0.000110532,0.000334699,0.065894,0.0658917,0.0185251,0.0524374,0.0524368,0.0689309,2.39875e-09,2.40009e-09,9.22468e-09,4e-06,4e-06,5.99275e-08,0,0,0,0,0,0,0,0 -12385000,0.982338,-0.00705821,-0.0117947,0.186607,0.00175778,0.00864211,0.0118034,0.00247544,0.00288117,-0.0196681,-1.27122e-05,-6.02607e-05,-8.72711e-07,0,0,-0.00136666,0.20342,0.0019756,0.434785,0,0,0,0,0,1.15757e-05,9.37938e-05,9.37907e-05,0.000329146,0.0560318,0.0560301,0.0174138,0.0456228,0.0456224,0.0682426,2.01038e-09,2.01136e-09,8.81378e-09,4e-06,4e-06,5.96819e-08,0,0,0,0,0,0,0,0 -12485000,0.982316,-0.00705973,-0.0117994,0.186723,0.00188832,0.00963648,0.0156822,0.00266592,0.00377806,-0.0176384,-1.27174e-05,-6.02559e-05,-1.11891e-06,0,0,-0.0013668,0.20342,0.0019756,0.434785,0,0,0,0,0,1.14058e-05,9.79772e-05,9.79752e-05,0.000323769,0.0644794,0.0644776,0.0168907,0.053087,0.0530864,0.068727,2.01031e-09,2.01131e-09,8.42736e-09,4e-06,4e-06,5.94689e-08,0,0,0,0,0,0,0,0 -12585000,0.982292,-0.00720988,-0.011759,0.18685,0.00498375,0.00358917,0.017356,0.00377046,0.0010134,-0.0163509,-1.20533e-05,-6.02492e-05,-1.50173e-06,0,0,-0.00136669,0.20342,0.0019756,0.434785,0,0,0,0,0,1.12336e-05,8.27889e-05,8.27832e-05,0.000318552,0.0544597,0.0544584,0.0159113,0.0460115,0.0460112,0.0679731,1.68719e-09,1.68791e-09,8.06283e-09,4e-06,4e-06,5.92719e-08,0,0,0,0,0,0,0,0 -12685000,0.982296,-0.00718598,-0.0117703,0.186828,0.0049456,0.00184828,0.0175079,0.00421142,0.00128482,-0.0134291,-1.20557e-05,-6.02471e-05,-1.60749e-06,0,0,-0.00136692,0.20342,0.0019756,0.434785,0,0,0,0,0,1.12143e-05,8.63727e-05,8.63672e-05,0.000318101,0.0623603,0.0623585,0.0155921,0.0535917,0.0535913,0.0695162,1.68718e-09,1.68791e-09,7.80312e-09,4e-06,4e-06,5.9146e-08,0,0,0,0,0,0,0,0 -12785000,0.982374,-0.00741171,-0.0116578,0.186415,0.00627013,-0.00113143,0.018711,0.0043744,-0.00204704,-0.0118536,-1.13815e-05,-6.02778e-05,-1.294e-07,0,0,-0.00136687,0.20342,0.0019756,0.434785,0,0,0,0,0,1.10358e-05,7.29241e-05,7.29165e-05,0.000313075,0.0525002,0.0524992,0.0147265,0.0463271,0.0463268,0.0686789,1.42245e-09,1.42294e-09,7.47377e-09,4e-06,4e-06,5.89789e-08,0,0,0,0,0,0,0,0 -12885000,0.982427,-0.0073993,-0.0115878,0.186139,0.00583742,-0.00253951,0.019567,0.00501564,-0.00223137,-0.00850925,-1.1365e-05,-6.02929e-05,6.62825e-07,0,0,-0.00136713,0.20342,0.0019756,0.434785,0,0,0,0,0,1.08646e-05,7.59954e-05,7.5989e-05,0.00030822,0.0598047,0.0598034,0.0142917,0.0539345,0.0539341,0.0689184,1.42241e-09,1.42293e-09,7.16305e-09,4e-06,4e-06,5.88393e-08,0,0,0,0,0,0,0,0 -12985000,0.982478,-0.00740638,-0.0115651,0.185873,0.0044277,-0.00093761,0.019962,0.00381947,-0.00169961,-0.00698182,-1.14912e-05,-6.04543e-05,1.32848e-06,0,0,-0.00136707,0.20342,0.0019756,0.434785,0,0,0,0,0,1.06922e-05,6.42758e-05,6.42661e-05,0.000303503,0.0503242,0.0503235,0.0135404,0.0465561,0.0465559,0.0680383,1.20729e-09,1.20763e-09,6.86905e-09,4e-06,4e-06,5.8696e-08,0,0,0,0,0,0,0,0 -13085000,0.982506,-0.00741934,-0.0114843,0.185727,0.00524014,-0.000840708,0.0184055,0.00429806,-0.00174386,-0.00697542,-1.14724e-05,-6.04713e-05,2.22204e-06,0,0,-0.00136674,0.20342,0.0019756,0.434785,0,0,0,0,0,1.05473e-05,6.69182e-05,6.69099e-05,0.000298904,0.0570662,0.0570655,0.0131557,0.0541255,0.0541251,0.068153,1.20727e-09,1.20763e-09,6.59086e-09,4e-06,4e-06,5.85809e-08,0,0,0,0,0,0,0,0 -13185000,0.982526,-0.00744209,-0.0114343,0.185627,0.00156631,-0.00265724,0.0175502,0.00134522,-0.00296034,-0.00598542,-1.14004e-05,-6.08002e-05,2.73099e-06,0,0,-0.00136663,0.20342,0.0019756,0.434785,0,0,0,0,0,1.03984e-05,5.67887e-05,5.67775e-05,0.000294453,0.0480844,0.048084,0.0125086,0.0466987,0.0466985,0.0672452,1.0328e-09,1.03303e-09,6.32763e-09,4e-06,4e-06,5.84518e-08,0,0,0,0,0,0,0,0 -13285000,0.982532,-0.00745756,-0.0114128,0.185594,0.000413542,-0.00361527,0.0158046,0.00137666,-0.00325862,-0.0053302,-1.14007e-05,-6.07999e-05,2.71094e-06,0,0,-0.00136646,0.20342,0.0019756,0.434785,0,0,0,0,0,1.03799e-05,5.9075e-05,5.90644e-05,0.000294066,0.054296,0.0542954,0.0123113,0.0541856,0.0541853,0.068418,1.03282e-09,1.03306e-09,6.13942e-09,4e-06,4e-06,5.83805e-08,0,0,0,0,0,0,0,0 -13385000,0.982523,-0.00741097,-0.0115238,0.185636,-0.000182001,-0.00230827,0.0148917,0.00109753,-0.00241428,-0.00540195,-1.15112e-05,-6.07752e-05,2.37793e-06,0,0,-0.0013662,0.20342,0.0019756,0.434785,0,0,0,0,0,1.02288e-05,5.03544e-05,5.03406e-05,0.000289763,0.045858,0.0458577,0.0117497,0.046763,0.0467629,0.0674648,8.91095e-10,8.9122e-10,5.89975e-09,4e-06,4e-06,5.82555e-08,0,0,0,0,0,0,0,0 -13485000,0.982525,-0.0073859,-0.0114797,0.185629,0.000313297,-0.000562598,0.0156779,0.00110296,-0.00251014,-0.00659982,-1.15105e-05,-6.07757e-05,2.40655e-06,0,0,-0.0013658,0.20342,0.0019756,0.434785,0,0,0,0,0,1.00893e-05,5.23437e-05,5.23305e-05,0.000285575,0.0515609,0.0515608,0.0114679,0.0541361,0.0541359,0.0673942,8.91097e-10,8.91241e-10,5.67234e-09,4e-06,4e-06,5.81687e-08,0,0,0,0,0,0,0,0 -13585000,0.982499,-0.00739711,-0.0115655,0.185761,0.00436685,-0.00104597,0.0170805,0.00401041,-0.00207592,-0.00838528,-1.14205e-05,-6.0437e-05,2.09486e-06,0,0,-0.00136526,0.20342,0.0019756,0.434785,0,0,0,0,0,9.95673e-06,4.48446e-05,4.483e-05,0.000281506,0.0436749,0.0436749,0.0109909,0.0467593,0.0467591,0.0664404,7.75518e-10,7.75583e-10,5.4566e-09,4e-06,4e-06,5.80434e-08,0,0,0,0,0,0,0,0 -13685000,0.982539,-0.00733697,-0.0114756,0.185557,0.00363629,-0.00257605,0.016705,0.00440199,-0.00225866,-0.00593285,-1.14119e-05,-6.04447e-05,2.51021e-06,0,0,-0.00136536,0.20342,0.0019756,0.434785,0,0,0,0,0,9.8151e-06,4.65877e-05,4.65738e-05,0.000277562,0.0489458,0.0489456,0.0107595,0.0539977,0.0539975,0.0663025,7.75529e-10,7.75612e-10,5.25162e-09,4e-06,4e-06,5.79645e-08,0,0,0,0,0,0,0,0 -13785000,0.982524,-0.00729645,-0.0115954,0.185633,0.0104705,0.000419796,0.0168509,0.00803207,-0.000197111,-0.00632278,-1.14884e-05,-6.00097e-05,2.18047e-06,0,0,-0.00136494,0.20342,0.0019756,0.434785,0,0,0,0,0,9.68371e-06,4.0131e-05,4.01157e-05,0.000273724,0.0416202,0.0416203,0.0103574,0.0466982,0.0466981,0.0653593,6.8071e-10,6.80727e-10,5.05689e-09,4e-06,4e-06,5.7833e-08,0,0,0,0,0,0,0,0 -13885000,0.982562,-0.00722279,-0.0115606,0.185435,0.0114501,0.00130085,0.0181317,0.00909869,-8.48051e-05,-0.0039334,-1.14732e-05,-6.00233e-05,2.91339e-06,0,0,-0.00136504,0.20342,0.0019756,0.434785,0,0,0,0,0,9.55932e-06,4.16699e-05,4.16549e-05,0.000269984,0.046483,0.0464832,0.0101736,0.053792,0.0537919,0.0651711,6.8073e-10,6.80763e-10,4.87164e-09,4e-06,4e-06,5.77583e-08,0,0,0,0,0,0,0,0 -13985000,0.98258,-0.0072827,-0.0113241,0.185351,0.0117292,0.00220549,0.0171677,0.00711715,-0.00154341,-0.00356592,-1.13849e-05,-6.03076e-05,3.38523e-06,0,0,-0.00136486,0.20342,0.0019756,0.434785,0,0,0,0,0,9.54961e-06,3.60937e-05,3.60787e-05,0.000269644,0.0396853,0.0396859,0.0099378,0.0465904,0.0465904,0.0652967,6.02391e-10,6.02376e-10,4.73856e-09,4e-06,4e-06,5.76357e-08,0,0,0,0,0,0,0,0 -14085000,0.982508,-0.007274,-0.0112572,0.185736,0.00894342,-0.00218561,0.019003,0.00824242,-0.00156214,-0.00504211,-1.14128e-05,-6.02826e-05,2.03042e-06,0,0,-0.0013644,0.20342,0.0019756,0.434785,0,0,0,0,0,9.42919e-06,3.74617e-05,3.74475e-05,0.000266014,0.0441831,0.0441833,0.00979591,0.0535337,0.0535337,0.0650665,6.02418e-10,6.02418e-10,4.56859e-09,4e-06,4e-06,5.75627e-08,0,0,0,0,0,0,0,0 -14185000,0.982461,-0.00726121,-0.0112001,0.185989,0.00688369,-0.00091874,0.0179842,0.00772832,-0.00111431,-0.00726196,-1.14907e-05,-6.02877e-05,1.15349e-06,0,0,-0.00136354,0.20342,0.0019756,0.434785,0,0,0,0,0,9.31125e-06,3.26303e-05,3.26156e-05,0.000262485,0.0378677,0.0378679,0.00951239,0.0464449,0.0464449,0.0641414,5.37183e-10,5.37144e-10,4.40676e-09,4e-06,4e-06,5.74032e-08,0,0,0,0,0,0,0,0 -14285000,0.982459,-0.00718851,-0.0111882,0.186004,0.00782396,-0.00147497,0.0168476,0.0083296,-0.00129371,-0.00354284,-1.14903e-05,-6.02881e-05,1.1765e-06,0,0,-0.00136381,0.20342,0.0019756,0.434785,0,0,0,0,0,9.19927e-06,3.38556e-05,3.38408e-05,0.000259042,0.0420652,0.0420653,0.00941132,0.0532361,0.053236,0.0638899,5.37217e-10,5.37192e-10,4.25245e-09,4e-06,4e-06,5.7329e-08,0,0,0,0,0,0,0,0 -14385000,0.982471,-0.00726866,-0.0111395,0.185939,0.00876771,-0.0041767,0.016909,0.00802451,-0.00251292,2.86906e-05,-1.14051e-05,-6.03552e-05,1.51995e-06,0,0,-0.00136395,0.20342,0.0019756,0.434785,0,0,0,0,0,9.0898e-06,2.96497e-05,2.96346e-05,0.000255682,0.036195,0.0361951,0.0091779,0.0462688,0.0462688,0.0629937,4.82444e-10,4.8239e-10,4.1052e-09,4e-06,4e-06,5.71494e-08,0,0,0,0,0,0,0,0 -14485000,0.98244,-0.00737315,-0.0111035,0.186101,0.00671263,-0.00404317,0.0206691,0.00872216,-0.00293303,0.00230591,-1.142e-05,-6.0342e-05,7.97016e-07,0,0,-0.001364,0.20342,0.0019756,0.434785,0,0,0,0,0,8.97679e-06,3.07541e-05,3.074e-05,0.000252421,0.0400854,0.0400855,0.00911386,0.0529092,0.0529092,0.0627333,4.82484e-10,4.82443e-10,3.9648e-09,4e-06,4e-06,5.70714e-08,0,0,0,0,0,0,0,0 -14585000,0.982427,-0.00744463,-0.0109684,0.186177,0.00529494,-0.003848,0.019321,0.00563127,-0.00365041,0.000178416,-1.14619e-05,-6.05779e-05,5.90124e-07,0,0,-0.00136336,0.20342,0.0019756,0.434785,0,0,0,0,0,8.96739e-06,2.70796e-05,2.70653e-05,0.000252125,0.0346248,0.034625,0.00900835,0.0460696,0.0460695,0.0628549,4.36173e-10,4.36105e-10,3.8637e-09,4e-06,4e-06,5.68909e-08,0,0,0,0,0,0,0,0 -14685000,0.98245,-0.0074211,-0.0110224,0.186052,0.00457837,-0.00396971,0.0190935,0.00611742,-0.00402324,0.0006808,-1.14559e-05,-6.05831e-05,8.76539e-07,0,0,-0.00136315,0.20342,0.0019756,0.434785,0,0,0,0,0,8.85853e-06,2.80823e-05,2.80677e-05,0.000248954,0.038273,0.0382733,0.00897627,0.052562,0.0525619,0.0625879,4.36218e-10,4.36162e-10,3.73415e-09,4e-06,4e-06,5.68084e-08,0,0,0,0,0,0,0,0 -14785000,0.982494,-0.00743043,-0.0110094,0.185819,0.00624802,0.00186055,0.0188398,0.0050154,0.000890594,0.00263909,-1.1814e-05,-6.05319e-05,1.42491e-06,0,0,-0.00136339,0.20342,0.0019756,0.434785,0,0,0,0,0,8.74854e-06,2.48554e-05,2.48408e-05,0.000245859,0.0331829,0.0331833,0.0088212,0.0458522,0.0458522,0.0617489,3.96704e-10,3.96631e-10,3.61028e-09,4e-06,4e-06,5.65782e-08,0,0,0,0,0,0,0,0 -14885000,0.982538,-0.00736083,-0.0109331,0.185596,0.00485696,-0.000294644,0.0224416,0.0055591,0.000972259,0.00360763,-1.18019e-05,-6.05426e-05,2.00832e-06,0,0,-0.00136321,0.20342,0.0019756,0.434785,0,0,0,0,0,8.6442e-06,2.57703e-05,2.5756e-05,0.000242844,0.0365904,0.0365906,0.00881907,0.0522008,0.0522008,0.0614928,3.96753e-10,3.96691e-10,3.49193e-09,4e-06,4e-06,5.64878e-08,0,0,0,0,0,0,0,0 -14985000,0.982546,-0.00748901,-0.0108292,0.185552,0.00436028,-0.00171632,0.0252411,0.00448116,-0.000490976,0.00502839,-1.17408e-05,-6.06546e-05,2.27634e-06,0,0,-0.00136252,0.20342,0.0019756,0.434785,0,0,0,0,0,8.54851e-06,2.29244e-05,2.29099e-05,0.000239891,0.0318285,0.0318288,0.00869664,0.0456212,0.0456212,0.0607007,3.62804e-10,3.62716e-10,3.37866e-09,4e-06,4e-06,5.62278e-08,0,0,0,0,0,0,0,0 -15085000,0.982547,-0.00743367,-0.0109134,0.185548,0.00432257,-0.00108866,0.0291266,0.0049245,-0.000663707,0.00748319,-1.17418e-05,-6.06539e-05,2.23098e-06,0,0,-0.00136247,0.20342,0.0019756,0.434785,0,0,0,0,0,8.45121e-06,2.37657e-05,2.37503e-05,0.000237018,0.035031,0.0350314,0.00872095,0.0518296,0.0518296,0.060463,3.62861e-10,3.62777e-10,3.27034e-09,4e-06,4e-06,5.61274e-08,0,0,0,0,0,0,0,0 -15185000,0.982542,-0.00756333,-0.0109732,0.185564,0.00304789,-0.00211072,0.0295306,0.00396794,-0.000623816,0.00807687,-1.17753e-05,-6.07043e-05,2.10215e-06,0,0,-0.00136181,0.20342,0.0019756,0.434785,0,0,0,0,0,8.35491e-06,2.12452e-05,2.12291e-05,0.000234209,0.0305859,0.0305863,0.00862591,0.04538,0.04538,0.0597189,3.33468e-10,3.33364e-10,3.16657e-09,4e-06,4e-06,5.58349e-08,0,0,0,0,0,0,0,0 -15285000,0.982565,-0.00766614,-0.0110022,0.185435,0.0028963,-0.00289004,0.029371,0.00428572,-0.00082809,0.00795658,-1.17663e-05,-6.07135e-05,2.57054e-06,0,0,-0.00136126,0.20342,0.0019756,0.434785,0,0,0,0,0,8.34747e-06,2.20222e-05,2.20058e-05,0.000233953,0.0336156,0.033616,0.0087454,0.0514546,0.0514548,0.0604041,3.33541e-10,3.33435e-10,3.09162e-09,4e-06,4e-06,5.57536e-08,0,0,0,0,0,0,0,0 -15385000,0.982532,-0.00774029,-0.0110208,0.185608,0.00397882,-0.000513298,0.0290396,0.00350354,-0.000534122,0.00722103,-1.18175e-05,-6.07421e-05,2.20891e-06,0,0,-0.00136016,0.20342,0.0019756,0.434785,0,0,0,0,0,8.26059e-06,1.97776e-05,1.97607e-05,0.00023121,0.0294484,0.0294489,0.00867053,0.0451323,0.0451325,0.0596871,3.07893e-10,3.07772e-10,2.99532e-09,4e-06,4e-06,5.54269e-08,0,0,0,0,0,0,0,0 -15485000,0.98253,-0.00778175,-0.010981,0.185617,0.00299037,-0.00298153,0.0290753,0.00384224,-0.000672234,0.00814623,-1.18153e-05,-6.07443e-05,2.32344e-06,0,0,-0.00135977,0.20342,0.0019756,0.434785,0,0,0,0,0,8.1754e-06,2.04982e-05,2.04813e-05,0.000228537,0.0323145,0.032315,0.00873759,0.0510796,0.0510797,0.0594972,3.07959e-10,3.07837e-10,2.90305e-09,4e-06,4e-06,5.53029e-08,0,0,0,0,0,0,0,0 -15585000,0.982533,-0.0078596,-0.0109739,0.185599,0.00624614,-0.00526543,0.028687,0.00572256,-0.00416431,0.00716199,-1.15807e-05,-6.07216e-05,2.59652e-06,0,0,-0.00135871,0.20342,0.0019756,0.434785,0,0,0,0,0,8.09361e-06,1.84894e-05,1.84722e-05,0.00022592,0.0283982,0.0283987,0.00868132,0.0448812,0.0448813,0.0588295,2.85416e-10,2.85285e-10,2.81452e-09,4e-06,4e-06,5.49397e-08,0,0,0,0,0,0,0,0 -15685000,0.982566,-0.0078281,-0.0109651,0.185427,0.00795021,-0.00852247,0.0290989,0.00642142,-0.00485629,0.00830979,-1.15734e-05,-6.07288e-05,2.96869e-06,0,0,-0.00135834,0.20342,0.0019756,0.434785,0,0,0,0,0,8.00414e-06,1.91617e-05,1.9144e-05,0.000223368,0.0311161,0.0311167,0.00876472,0.0507067,0.0507069,0.058668,2.85485e-10,2.85353e-10,2.72954e-09,4e-06,4e-06,5.47992e-08,0,0,0,0,0,0,0,0 -15785000,0.982606,-0.00785657,-0.0108766,0.185217,0.0053229,-0.0087541,0.0285071,0.00510668,-0.00393846,0.00954482,-1.16712e-05,-6.07867e-05,3.50719e-06,0,0,-0.00135754,0.20342,0.0019756,0.434785,0,0,0,0,0,7.91772e-06,1.73559e-05,1.73386e-05,0.000220877,0.0274297,0.0274302,0.00872301,0.0446286,0.0446288,0.0580486,2.65539e-10,2.65403e-10,2.64801e-09,4e-06,4e-06,5.4398e-08,0,0,0,0,0,0,0,0 -15885000,0.982575,-0.00790412,-0.0109237,0.185379,0.00395706,-0.00686662,0.0296714,0.00550304,-0.00472135,0.00966296,-1.16784e-05,-6.07794e-05,3.12907e-06,0,0,-0.00135692,0.20342,0.0019756,0.434785,0,0,0,0,0,7.91208e-06,1.7986e-05,1.79682e-05,0.000220651,0.0300123,0.0300128,0.00888931,0.0503384,0.0503386,0.0587789,2.65617e-10,2.65482e-10,2.58902e-09,4e-06,4e-06,5.42836e-08,0,0,0,0,0,0,0,0 -15985000,0.982581,-0.00773361,-0.0108854,0.185355,0.0026808,-0.00546333,0.0262088,0.00449357,-0.00373595,0.00746483,-1.17588e-05,-6.07989e-05,3.02382e-06,0,0,-0.00135488,0.20342,0.0019756,0.434785,0,0,0,0,0,7.82541e-06,1.63558e-05,1.63375e-05,0.000218223,0.0265368,0.0265372,0.00885689,0.0443764,0.0443766,0.0581888,2.47857e-10,2.4772e-10,2.51304e-09,4e-06,4e-06,5.38445e-08,0,0,0,0,0,0,0,0 -16085000,0.982583,-0.00769934,-0.0108741,0.185348,0.00115493,-0.0067497,0.0247665,0.00462049,-0.00436409,0.00899128,-1.17653e-05,-6.07925e-05,2.6876e-06,0,0,-0.00135464,0.20342,0.0019756,0.434785,0,0,0,0,0,7.73617e-06,1.69479e-05,1.69292e-05,0.00021585,0.0290077,0.0290082,0.00896639,0.0499767,0.0499769,0.0580975,2.4793e-10,2.47794e-10,2.43998e-09,4e-06,4e-06,5.36707e-08,0,0,0,0,0,0,0,0 -16185000,0.982569,-0.00762683,-0.0108045,0.185429,-0.00205517,-0.00511598,0.0236577,0.00258404,-0.00341767,0.00586622,-1.18672e-05,-6.08458e-05,2.29184e-06,0,0,-0.00135292,0.20342,0.0019756,0.434785,0,0,0,0,0,7.65393e-06,1.54686e-05,1.54499e-05,0.000213527,0.0257128,0.0257132,0.00894177,0.0441262,0.0441264,0.0575529,2.32015e-10,2.31879e-10,2.36979e-09,4e-06,4e-06,5.31924e-08,0,0,0,0,0,0,0,0 -16285000,0.982567,-0.00768078,-0.0107357,0.185441,-0.00167563,-0.00670988,0.0232212,0.00237889,-0.00402297,0.00726465,-1.18651e-05,-6.08478e-05,2.40038e-06,0,0,-0.0013527,0.20342,0.0019756,0.434785,0,0,0,0,0,7.58209e-06,1.6027e-05,1.60086e-05,0.000211242,0.0280734,0.0280739,0.00906028,0.0496222,0.0496225,0.0575,2.32089e-10,2.31954e-10,2.30226e-09,4e-06,4e-06,5.29983e-08,0,0,0,0,0,0,0,0 -16385000,0.982582,-0.00763769,-0.0107214,0.185365,0.000300856,-0.00600728,0.0238527,0.00323131,-0.00322661,0.00719838,-1.18882e-05,-6.07775e-05,2.72359e-06,0,0,-0.00135171,0.20342,0.0019756,0.434785,0,0,0,0,0,7.51044e-06,1.46795e-05,1.46612e-05,0.00020901,0.024948,0.0249485,0.00904046,0.0438789,0.0438791,0.0569979,2.17753e-10,2.17619e-10,2.23732e-09,4e-06,4e-06,5.24812e-08,0,0,0,0,0,0,0,0 -16485000,0.98258,-0.00774217,-0.010705,0.18537,0.00270007,-0.00761763,0.0257142,0.00337604,-0.00397305,0.010608,-1.18906e-05,-6.07753e-05,2.60342e-06,0,0,-0.00135195,0.20342,0.0019756,0.434785,0,0,0,0,0,7.43488e-06,1.52085e-05,1.51904e-05,0.000206827,0.0272069,0.0272075,0.00916556,0.0492758,0.0492761,0.056983,2.17829e-10,2.17696e-10,2.1748e-09,4e-06,4e-06,5.22657e-08,0,0,0,0,0,0,0,0 -16585000,0.982579,-0.00773803,-0.0107144,0.185377,0.00681905,-0.00845536,0.0291536,0.00304068,-0.0032492,0.01132,-1.19585e-05,-6.07744e-05,2.53947e-06,0,0,-0.00135117,0.20342,0.0019756,0.434785,0,0,0,0,0,7.42619e-06,1.39764e-05,1.39581e-05,0.000206633,0.0242333,0.024234,0.00921464,0.0436353,0.0436354,0.0573301,2.04851e-10,2.04721e-10,2.12945e-09,4e-06,4e-06,5.17688e-08,0,0,0,0,0,0,0,0 -16685000,0.982594,-0.00779942,-0.0106491,0.185296,0.00804522,-0.0123887,0.0294557,0.00378451,-0.00427085,0.0127296,-1.19541e-05,-6.07785e-05,2.75988e-06,0,0,-0.00135076,0.20342,0.0019756,0.434785,0,0,0,0,0,7.35518e-06,1.44784e-05,1.44605e-05,0.000204499,0.0264052,0.0264059,0.00934514,0.0489379,0.0489381,0.0573525,2.04929e-10,2.048e-10,2.07092e-09,4e-06,4e-06,5.15351e-08,0,0,0,0,0,0,0,0 -16785000,0.982617,-0.00766988,-0.010557,0.185187,0.00964729,-0.0124472,0.0282299,0.00317177,-0.00345662,0.0119002,-1.20556e-05,-6.08024e-05,2.89006e-06,0,0,-0.00134922,0.20342,0.0019756,0.434785,0,0,0,0,0,7.28081e-06,1.33461e-05,1.33283e-05,0.000202416,0.0235835,0.0235842,0.00932604,0.0433962,0.0433964,0.0569127,1.93115e-10,1.92989e-10,2.01456e-09,4e-06,4e-06,5.0944e-08,0,0,0,0,0,0,0,0 -16885000,0.982662,-0.00764231,-0.01065,0.184944,0.00846297,-0.0127109,0.0295165,0.0040743,-0.0046986,0.0111231,-1.20469e-05,-6.08104e-05,3.32146e-06,0,0,-0.00134816,0.20342,0.0019756,0.434785,0,0,0,0,0,7.20649e-06,1.3825e-05,1.38064e-05,0.000200374,0.0256718,0.0256726,0.00945884,0.0486101,0.0486103,0.0569709,1.93194e-10,1.9307e-10,1.96022e-09,4e-06,4e-06,5.06879e-08,0,0,0,0,0,0,0,0 -16985000,0.982664,-0.00767585,-0.0106615,0.184932,0.00821488,-0.0130722,0.0296508,0.00365517,-0.00385038,0.0101535,-1.21205e-05,-6.0772e-05,3.41168e-06,0,0,-0.00134683,0.20342,0.0019756,0.434785,0,0,0,0,0,7.14089e-06,1.27807e-05,1.27625e-05,0.000198363,0.0229777,0.0229783,0.0094366,0.0431625,0.0431627,0.0565591,1.82393e-10,1.82272e-10,1.90782e-09,4e-06,4e-06,5.00609e-08,0,0,0,0,0,0,0,0 -17085000,0.982657,-0.00778148,-0.0105942,0.184968,0.00913851,-0.015779,0.0298423,0.00452907,-0.00530889,0.0100005,-1.21226e-05,-6.07698e-05,3.29852e-06,0,0,-0.00134589,0.20342,0.0019756,0.434785,0,0,0,0,0,7.07494e-06,1.32369e-05,1.32192e-05,0.000196398,0.0249955,0.0249961,0.00956979,0.0482925,0.0482927,0.0566505,1.82473e-10,1.82355e-10,1.85731e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -17185000,0.982612,-0.00786103,-0.0105082,0.185208,0.00868766,-0.0197858,0.0309835,0.00301476,-0.00833224,0.0126726,-1.21125e-05,-6.08202e-05,2.87894e-06,0,0,-0.00134531,0.20342,0.0019756,0.434785,0,0,0,0,0,7.07406e-06,1.22695e-05,1.22523e-05,0.000196219,0.0224198,0.0224204,0.00961399,0.0429346,0.0429348,0.0570748,1.72561e-10,1.72445e-10,1.82063e-09,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -17285000,0.982582,-0.00781884,-0.0105039,0.185368,0.00912814,-0.0206036,0.0304826,0.00389041,-0.0103202,0.0132144,-1.21204e-05,-6.08126e-05,2.47356e-06,0,0,-0.00134454,0.20342,0.0019756,0.434785,0,0,0,0,0,7.01066e-06,1.27062e-05,1.26887e-05,0.000194295,0.0243726,0.0243732,0.00974756,0.0479858,0.047986,0.0572,1.72643e-10,1.72529e-10,1.77318e-09,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -17385000,0.982625,-0.00777451,-0.0104758,0.185142,0.00593434,-0.0217932,0.0305007,0.00513464,-0.00755212,0.013818,-1.22699e-05,-6.07162e-05,2.78663e-06,0,0,-0.00134329,0.20342,0.0019756,0.434785,0,0,0,0,0,6.94021e-06,1.18065e-05,1.17895e-05,0.000192415,0.0219061,0.0219064,0.00971511,0.0427135,0.0427137,0.0568307,1.63503e-10,1.63392e-10,1.72736e-09,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -17485000,0.982615,-0.0077787,-0.0105286,0.185191,0.0036407,-0.0229889,0.0299832,0.0055468,-0.00976327,0.0143396,-1.22728e-05,-6.07134e-05,2.63781e-06,0,0,-0.0013425,0.20342,0.0019756,0.434785,0,0,0,0,0,6.87828e-06,1.22254e-05,1.22079e-05,0.000190567,0.0237982,0.0237985,0.0098464,0.0476903,0.0476905,0.0569836,1.63586e-10,1.63477e-10,1.68315e-09,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -17585000,0.982618,-0.00775615,-0.0104641,0.185182,0.00126416,-0.0196678,0.0290029,0.00254584,-0.00798578,0.0125095,-1.24442e-05,-6.07794e-05,2.63833e-06,0,0,-0.00134064,0.20342,0.0019756,0.434785,0,0,0,0,0,6.81725e-06,1.13858e-05,1.13686e-05,0.000188752,0.0214309,0.0214312,0.0098079,0.0424994,0.0424995,0.0566351,1.55134e-10,1.55026e-10,1.64044e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -17685000,0.982648,-0.00785746,-0.0103835,0.185025,0.000303671,-0.0206761,0.030298,0.00264513,-0.0100253,0.0148794,-1.24428e-05,-6.07806e-05,2.70679e-06,0,0,-0.00134043,0.20342,0.0019756,0.434785,0,0,0,0,0,6.74943e-06,1.17872e-05,1.17705e-05,0.000186983,0.0232652,0.0232655,0.00993595,0.047406,0.0474062,0.056812,1.55218e-10,1.55112e-10,1.59919e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -17785000,0.982694,-0.00786184,-0.0103376,0.184782,0.00221934,-0.0193875,0.0300819,0.00327548,-0.00907598,0.0185111,-1.25509e-05,-6.06997e-05,2.8305e-06,0,0,-0.00134046,0.20342,0.0019756,0.434785,0,0,0,0,0,6.67821e-06,1.10006e-05,1.09844e-05,0.000185249,0.02099,0.0209904,0.00989081,0.0422923,0.0422925,0.0564803,1.47376e-10,1.47273e-10,1.55931e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -17885000,0.982704,-0.00781602,-0.0104442,0.184726,0.00450613,-0.0221861,0.0295666,0.00366699,-0.0111721,0.0235294,-1.25497e-05,-6.07009e-05,2.89347e-06,0,0,-0.00134112,0.20342,0.0019756,0.434785,0,0,0,0,0,6.67055e-06,1.13877e-05,1.13705e-05,0.000185098,0.0227778,0.0227782,0.0100905,0.0471331,0.0471333,0.057492,1.47465e-10,1.47363e-10,1.5303e-09,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -17985000,0.982713,-0.00771312,-0.0104232,0.18468,0.00367387,-0.01735,0.0292931,0.00305483,-0.00617511,0.0236537,-1.27992e-05,-6.06352e-05,2.8649e-06,0,0,-0.00134018,0.20342,0.0019756,0.434785,0,0,0,0,0,6.60988e-06,1.06483e-05,1.06313e-05,0.000183391,0.0205832,0.0205836,0.0100374,0.0420928,0.0420929,0.0571639,1.40167e-10,1.40068e-10,1.49271e-09,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -18085000,0.982716,-0.00780592,-0.0103859,0.184664,0.00391364,-0.0185286,0.0289534,0.00350895,-0.0079985,0.0231011,-1.27987e-05,-6.06356e-05,2.88816e-06,0,0,-0.001339,0.20342,0.0019756,0.434785,0,0,0,0,0,6.55406e-06,1.10201e-05,1.10034e-05,0.000181714,0.0223209,0.0223213,0.0101585,0.0468717,0.0468719,0.0573837,1.40253e-10,1.40156e-10,1.45637e-09,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -18185000,0.98276,-0.00782285,-0.0104163,0.184424,0.00348197,-0.0171192,0.0296824,0.0038824,-0.00670711,0.0214714,-1.28755e-05,-6.0592e-05,3.35612e-06,0,0,-0.00133711,0.20342,0.0019756,0.434785,0,0,0,0,0,6.4963e-06,1.03231e-05,1.03065e-05,0.000180069,0.0201997,0.0202001,0.0100983,0.0419006,0.0419007,0.0570652,1.33447e-10,1.33352e-10,1.4212e-09,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -18285000,0.982762,-0.00786677,-0.0103895,0.184418,0.00432219,-0.0185138,0.0289834,0.00421431,-0.00847509,0.0205648,-1.28744e-05,-6.05928e-05,3.4075e-06,0,0,-0.00133576,0.20342,0.0019756,0.434785,0,0,0,0,0,6.44375e-06,1.06816e-05,1.06651e-05,0.000178448,0.0218941,0.0218946,0.0102134,0.0466206,0.0466207,0.0572933,1.33534e-10,1.33441e-10,1.38716e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -18385000,0.982744,-0.00778995,-0.0103891,0.184517,0.0043604,-0.0173248,0.0287601,0.0054797,-0.00713594,0.0201822,-1.29481e-05,-6.05088e-05,3.28497e-06,0,0,-0.00133448,0.20342,0.0019756,0.434785,0,0,0,0,0,6.3941e-06,1.00221e-05,1.00058e-05,0.000176857,0.0198452,0.0198455,0.0101461,0.0417155,0.0417157,0.056981,1.27171e-10,1.27082e-10,1.35423e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -18485000,0.982754,-0.00783213,-0.0104018,0.184461,0.00724385,-0.0176984,0.0284705,0.00614361,-0.00889459,0.0228513,-1.29447e-05,-6.05119e-05,3.45718e-06,0,0,-0.00133445,0.20342,0.0019756,0.434785,0,0,0,0,0,6.39007e-06,1.03685e-05,1.0352e-05,0.000176719,0.0215005,0.021501,0.0103369,0.0463806,0.0463808,0.0580544,1.27262e-10,1.27174e-10,1.33024e-09,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -18585000,0.982732,-0.00767249,-0.010297,0.184587,0.00630977,-0.0167963,0.028138,0.00517282,-0.00754308,0.0245126,-1.30493e-05,-6.05173e-05,3.33686e-06,0,0,-0.00133361,0.20342,0.0019756,0.434785,0,0,0,0,0,6.34314e-06,9.74264e-06,9.72637e-06,0.000175157,0.0195163,0.0195167,0.0102617,0.041538,0.0415381,0.0577365,1.21303e-10,1.21217e-10,1.29911e-09,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -18685000,0.982749,-0.00766315,-0.0102465,0.1845,0.00594197,-0.0165,0.0266789,0.00579191,-0.00920903,0.0239845,-1.30472e-05,-6.05191e-05,3.44179e-06,0,0,-0.00133245,0.20342,0.0019756,0.434785,0,0,0,0,0,6.28982e-06,1.00768e-05,1.00606e-05,0.000173629,0.0211344,0.0211349,0.0103677,0.0461511,0.0461513,0.0579879,1.21391e-10,1.21308e-10,1.26894e-09,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -18785000,0.982754,-0.00759845,-0.0101434,0.184482,0.00482603,-0.0158804,0.0260221,0.00577651,-0.00785403,0.0207082,-1.31268e-05,-6.04889e-05,3.46461e-06,0,0,-0.00132948,0.20342,0.0019756,0.434785,0,0,0,0,0,6.23937e-06,9.48147e-06,9.46581e-06,0.000172127,0.019207,0.0192074,0.010286,0.0413676,0.0413678,0.0576709,1.158e-10,1.15719e-10,1.23973e-09,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -18885000,0.982751,-0.0075621,-0.010157,0.184503,0.00390693,-0.0162525,0.0245573,0.00618808,-0.0095213,0.0177418,-1.31291e-05,-6.04865e-05,3.34306e-06,0,0,-0.00132746,0.20342,0.0019756,0.434785,0,0,0,0,0,6.18845e-06,9.80489e-06,9.78895e-06,0.000170651,0.020789,0.0207894,0.0103865,0.0459315,0.0459317,0.0579258,1.15889e-10,1.1581e-10,1.21141e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -18985000,0.982732,-0.00754448,-0.0102081,0.184597,0.00257784,-0.0158445,0.025063,0.005231,-0.00809927,0.0205575,-1.32172e-05,-6.04826e-05,3.33646e-06,0,0,-0.00132704,0.20342,0.0019756,0.434785,0,0,0,0,0,6.146e-06,9.23803e-06,9.22206e-06,0.000169195,0.0189175,0.0189179,0.0102988,0.0412042,0.0412043,0.0576076,1.10637e-10,1.10561e-10,1.18397e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -19085000,0.98274,-0.00762776,-0.0102171,0.184553,0.000610754,-0.0166425,0.0255961,0.00543371,-0.00968704,0.0167955,-1.32147e-05,-6.04846e-05,3.45836e-06,0,0,-0.00132476,0.20342,0.0019756,0.434785,0,0,0,0,0,6.09942e-06,9.55097e-06,9.53504e-06,0.000167766,0.0204636,0.0204639,0.010394,0.0457218,0.045722,0.0578634,1.10726e-10,1.10652e-10,1.15736e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -19185000,0.982718,-0.00752068,-0.0103503,0.184665,-0.000690114,-0.0160442,0.0256131,0.00457402,-0.00831909,0.0168368,-1.33024e-05,-6.04629e-05,3.20549e-06,0,0,-0.00132376,0.20342,0.0019756,0.434785,0,0,0,0,0,6.09473e-06,9.00994e-06,8.99337e-06,0.000167644,0.0186427,0.0186429,0.0103835,0.0410475,0.0410476,0.0583821,1.05789e-10,1.05718e-10,1.13795e-09,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -19285000,0.982719,-0.00746918,-0.010302,0.184664,-0.00176602,-0.0167059,0.0259673,0.00448704,-0.00995921,0.0169236,-1.33038e-05,-6.04615e-05,3.13127e-06,0,0,-0.00132286,0.20342,0.0019756,0.434785,0,0,0,0,0,6.04643e-06,9.31281e-06,9.29623e-06,0.000166246,0.0201598,0.02016,0.0104753,0.045521,0.0455212,0.0586438,1.05879e-10,1.05809e-10,1.11272e-09,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -19385000,0.982719,-0.00756026,-0.0101911,0.184667,-0.00178253,-0.0129852,0.0276271,0.00383643,-0.0074171,0.0157028,-1.34133e-05,-6.04225e-05,3.00776e-06,0,0,-0.00132102,0.20342,0.0019756,0.434785,0,0,0,0,0,5.99775e-06,8.79377e-06,8.77813e-06,0.000164874,0.0183827,0.0183829,0.0103759,0.040897,0.0408971,0.058309,1.01228e-10,1.01161e-10,1.08825e-09,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -19485000,0.982679,-0.00761981,-0.0100935,0.184885,-0.002689,-0.0136869,0.026908,0.0035784,-0.00874981,0.0154546,-1.34181e-05,-6.0418e-05,2.758e-06,0,0,-0.00131991,0.20342,0.0019756,0.434785,0,0,0,0,0,5.95942e-06,9.08711e-06,9.0719e-06,0.000163514,0.0198719,0.0198721,0.0104628,0.0453286,0.0453287,0.0585671,1.01319e-10,1.01253e-10,1.0645e-09,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -19585000,0.98266,-0.00753745,-0.0101954,0.184984,-0.00485333,-0.0154363,0.0283292,0.00384541,-0.00849338,0.015599,-1.34377e-05,-6.03709e-05,2.68916e-06,0,0,-0.00131858,0.20342,0.0019756,0.434785,0,0,0,0,0,5.91938e-06,8.59013e-06,8.57458e-06,0.000162176,0.0181393,0.0181395,0.0103583,0.0407525,0.0407526,0.0582216,9.69359e-11,9.68728e-11,1.04144e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -19685000,0.982676,-0.00756514,-0.0102093,0.184895,-0.00620855,-0.0149292,0.02758,0.00332797,-0.0100166,0.0154732,-1.34347e-05,-6.03735e-05,2.84178e-06,0,0,-0.00131746,0.20342,0.0019756,0.434785,0,0,0,0,0,5.87515e-06,8.87504e-06,8.85941e-06,0.000160868,0.0196011,0.0196012,0.0104407,0.0451445,0.0451447,0.0584744,9.70273e-11,9.69656e-11,1.01906e-09,4e-06,4e-06,5e-08,0,0,0,0,0,0,0,0 -19785000,0.982665,-0.00763243,-0.010199,0.18495,-0.00704209,-0.0128948,0.0263814,0.00535546,-0.00854123,0.0124724,-1.3476e-05,-6.02812e-05,2.73525e-06,0,0,-0.001315,0.20342,0.0019756,0.434785,0,0,0,0,0,5.87141e-06,8.39729e-06,8.38209e-06,0.000160758,0.017911,0.0179111,0.010419,0.040614,0.0406141,0.0589858,9.28957e-11,9.28361e-11,1.00272e-09,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -19885000,0.982645,-0.00764835,-0.0102883,0.185054,-0.00679977,-0.0129936,0.0261272,0.00461221,-0.00979365,0.0112915,-1.34798e-05,-6.02776e-05,2.53941e-06,0,0,-0.00131361,0.20342,0.0019756,0.434785,0,0,0,0,0,5.82983e-06,8.67406e-06,8.65846e-06,0.000159471,0.0193458,0.0193459,0.0104988,0.0449687,0.0449688,0.0592393,9.29875e-11,9.29293e-11,9.81459e-10,4e-06,4e-06,5.0002e-08,0,0,0,0,0,0,0,0 -19985000,0.982667,-0.00766579,-0.0104105,0.184928,-0.00719878,-0.0124454,0.0235764,0.00476755,-0.00748917,0.00765027,-1.35503e-05,-6.02042e-05,2.60476e-06,0,0,-0.00131052,0.20342,0.0019756,0.434785,0,0,0,0,0,5.78257e-06,8.21485e-06,8.19913e-06,0.000158209,0.0176946,0.0176947,0.0103864,0.0404813,0.0404814,0.0588716,8.90867e-11,8.90308e-11,9.60796e-10,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -20085000,0.98268,-0.00767908,-0.01042,0.18486,-0.00673247,-0.0155683,0.0236544,0.00404734,-0.00891611,0.0108347,-1.35505e-05,-6.0204e-05,2.59446e-06,0,0,-0.00131082,0.20342,0.0019756,0.434785,0,0,0,0,0,5.73746e-06,8.4833e-06,8.4675e-06,0.000156968,0.0191062,0.0191063,0.0104625,0.0448005,0.0448006,0.0591173,8.9179e-11,8.91243e-11,9.40728e-10,4e-06,4e-06,5.0001e-08,0,0,0,0,0,0,0,0 -20185000,0.982664,-0.00767039,-0.0105171,0.184937,-0.00585331,-0.0130902,0.0244401,0.00505089,-0.00763288,0.0104005,-1.36041e-05,-6.01426e-05,2.38923e-06,-5.71978e-11,6.08943e-11,-0.00130944,0.20342,0.0019756,0.434785,0,0,0,0,0,5.69586e-06,8.04071e-06,8.02481e-06,0.000155743,0.017711,0.0177112,0.0103482,0.0403543,0.0403543,0.0587434,8.54951e-11,8.54424e-11,9.21219e-10,4.00001e-06,4.00001e-06,5e-08,0,0,0,0,0,0,0,0 -20285000,0.982678,-0.0076699,-0.0105449,0.18486,-0.00897817,-0.0140361,0.0247472,0.00434191,-0.00891404,0.0111065,-1.36053e-05,-6.01414e-05,2.32744e-06,3.47917e-09,-3.70081e-09,-0.00130879,0.20342,0.0019756,0.434785,0,0,0,0,0,5.65034e-06,8.3016e-06,8.28552e-06,0.000154543,0.020097,0.0200976,0.0104216,0.0446478,0.0446478,0.0589806,8.55878e-11,8.55363e-11,9.02265e-10,4.00002e-06,4.00002e-06,5e-08,0,0,0,0,0,0,0,0 -20385000,0.982675,-0.00760779,-0.0105321,0.184882,-0.00982081,-0.0122549,0.0237558,0.00522843,-0.00761246,0.0105516,-1.36439e-05,-6.00837e-05,2.48963e-06,-3.77339e-06,-3.01392e-06,-0.00130693,0.20342,0.0019756,0.434785,0,0,0,0,0,5.61695e-06,7.87642e-06,7.86052e-06,0.00015335,0.0200049,0.0200061,0.0103068,0.0402472,0.0402472,0.0586009,8.21196e-11,8.207e-11,8.83831e-10,3.97867e-06,3.97867e-06,5e-08,0,0,0,0,0,0,0,0 -20485000,0.982694,-0.00762745,-0.0105023,0.184782,-0.0141974,-0.0137991,0.0243692,0.00400361,-0.00889168,0.0101918,-1.36453e-05,-6.00823e-05,2.41712e-06,-3.75588e-06,-3.03244e-06,-0.00130589,0.20342,0.0019756,0.434785,0,0,0,0,0,5.60599e-06,8.13e-06,8.11414e-06,0.000153259,0.0238295,0.0238317,0.0104667,0.0445855,0.0445856,0.0597074,8.22144e-11,8.21656e-11,8.70363e-10,3.97868e-06,3.97868e-06,5.0002e-08,0,0,0,0,0,0,0,0 -20585000,0.982731,-0.00758576,-0.0105026,0.184587,-0.0136541,-0.0135848,0.0240034,0.00496139,-0.0076401,0.00857013,-1.36719e-05,-6.00145e-05,2.71637e-06,-1.43333e-05,-7.53529e-06,-0.00130392,0.20342,0.0019756,0.434785,0,0,0,0,0,5.56497e-06,7.73467e-06,7.71895e-06,0.000152094,0.0243652,0.0243682,0.0103498,0.0402271,0.0402272,0.0593109,7.90181e-11,7.8971e-11,8.52805e-10,3.89698e-06,3.89698e-06,5.0001e-08,0,0,0,0,0,0,0,0 -20685000,0.982724,-0.00751818,-0.0104954,0.184626,-0.0157193,-0.0130916,0.024952,0.00354043,-0.00893399,0.00895249,-1.36762e-05,-6.00105e-05,2.49631e-06,-1.4309e-05,-7.56285e-06,-0.00130317,0.20342,0.0019756,0.434785,0,0,0,0,0,5.52347e-06,7.98169e-06,7.96581e-06,0.00015095,0.0294,0.0294046,0.0104213,0.0447378,0.0447379,0.0595369,7.91116e-11,7.90654e-11,8.35734e-10,3.89699e-06,3.89699e-06,5.0001e-08,0,0,0,0,0,0,0,0 -20785000,0.982749,-0.00704484,-0.0104304,0.184515,-0.0168674,-0.00942404,0.0126098,0.00283969,-0.00756874,0.00755711,-1.37106e-05,-5.99642e-05,2.57598e-06,-2.8563e-05,-1.35879e-05,-0.00130148,0.20342,0.0019756,0.434785,0,0,0,0,0,5.48237e-06,7.63829e-06,7.62186e-06,0.000149823,0.0297474,0.0297527,0.0103044,0.0403813,0.0403814,0.0591356,7.62885e-11,7.62438e-11,8.19119e-10,3.73399e-06,3.73399e-06,5.0001e-08,0,0,0,0,0,0,0,0 -20885000,0.982813,0.00181049,-0.00675651,0.184473,-0.0231451,0.00178984,-0.100859,0.000771729,-0.00792153,0.00198812,-1.37104e-05,-5.99642e-05,2.58376e-06,-2.85094e-05,-1.36409e-05,-0.00130073,0.20342,0.0019756,0.434785,0,0,0,0,0,5.44335e-06,7.87024e-06,7.85969e-06,0.000148725,0.0357917,0.0357985,0.0103726,0.0452034,0.0452038,0.0593471,7.63815e-11,7.63389e-11,8.02946e-10,3.734e-06,3.734e-06,5e-08,0,0,0,0,0,0,0,0 -20985000,0.982815,0.00556131,-0.00302686,0.184483,-0.0320875,0.0202272,-0.242091,0.00037795,-0.00600236,-0.0114643,-1.37015e-05,-5.99136e-05,2.55484e-06,-4.90445e-05,-3.54576e-06,-0.00130379,0.20342,0.0019756,0.434785,0,0,0,0,0,5.40734e-06,7.59233e-06,7.59351e-06,0.000147628,0.0352272,0.0352326,0.0102525,0.0407676,0.0407679,0.0589416,7.40071e-11,7.39669e-11,7.87211e-10,3.49195e-06,3.49196e-06,5e-08,0,0,0,0,0,0,0,0 -21085000,0.982756,0.00412997,-0.00326736,0.184835,-0.0453994,0.0359985,-0.359781,-0.00349296,-0.00313693,-0.0408188,-1.37026e-05,-5.99126e-05,2.5006e-06,-4.90651e-05,-3.52664e-06,-0.00130404,0.20342,0.0019756,0.434785,0,0,0,0,0,5.4217e-06,7.83095e-06,7.82892e-06,0.000147523,0.0417718,0.0417771,0.0104065,0.0460138,0.0460144,0.0600375,7.41024e-11,7.40631e-11,7.75712e-10,3.49196e-06,3.49196e-06,5.0002e-08,0,0,0,0,0,0,0,0 -21185000,0.982703,0.00136568,-0.00485123,0.185118,-0.0459847,0.0394569,-0.484772,-0.00249959,-0.00293285,-0.0746254,-1.36092e-05,-5.98532e-05,2.58339e-06,-8.23897e-05,4.97905e-05,-0.00131189,0.20342,0.0019756,0.434785,0,0,0,0,0,5.40363e-06,7.64917e-06,7.64159e-06,0.000146424,0.0396017,0.0396058,0.0102852,0.04137,0.0413705,0.0596162,7.2216e-11,7.21801e-11,7.60692e-10,3.19348e-06,3.1935e-06,5.0002e-08,0,0,0,0,0,0,0,0 -21285000,0.982654,-0.000853683,-0.00622339,0.185342,-0.0457812,0.0423186,-0.614829,-0.00711754,0.00117077,-0.130766,-1.36132e-05,-5.98496e-05,2.38329e-06,-8.23576e-05,4.97505e-05,-0.00131148,0.20342,0.0019756,0.434785,0,0,0,0,0,5.37508e-06,7.88836e-06,7.87746e-06,0.00014535,0.0462646,0.0462693,0.0103504,0.0470555,0.0470562,0.059816,7.23097e-11,7.22754e-11,7.46068e-10,3.19348e-06,3.1935e-06,5.0001e-08,0,0,0,0,0,0,0,0 -21385000,0.98261,-0.00231886,-0.00688092,0.185541,-0.0389307,0.0391179,-0.739083,-0.00544531,0.00477143,-0.192473,-1.3586e-05,-5.97879e-05,2.32238e-06,-0.000112362,6.47072e-05,-0.00131757,0.20342,0.0019756,0.434785,0,0,0,0,0,5.34955e-06,7.79694e-06,7.78521e-06,0.00014429,0.0424263,0.0424307,0.0102306,0.0421015,0.0421021,0.0593919,7.09032e-11,7.08722e-11,7.31826e-10,2.87004e-06,2.87006e-06,5.0001e-08,0,0,0,0,0,0,0,0 -21485000,0.982584,-0.00316843,-0.00732204,0.185648,-0.033965,0.0356997,-0.874484,-0.0091612,0.00854695,-0.277065,-1.35837e-05,-5.97893e-05,2.41881e-06,-0.000112169,6.45649e-05,-0.00131612,0.20342,0.0019756,0.434785,0,0,0,0,0,5.32383e-06,8.03441e-06,8.02225e-06,0.000143246,0.0488914,0.048897,0.0102953,0.0481774,0.0481784,0.0595834,7.09972e-11,7.09678e-11,7.17955e-10,2.87004e-06,2.87007e-06,5e-08,0,0,0,0,0,0,0,0 -21585000,0.982587,-0.00359918,-0.00730709,0.185625,-0.0252692,0.0325276,-0.997699,-0.00787388,0.0106493,-0.362394,-1.35587e-05,-5.97626e-05,2.50404e-06,-0.000119976,5.83672e-05,-0.00132407,0.20342,0.0019756,0.434785,0,0,0,0,0,5.29134e-06,8.02597e-06,8.01439e-06,0.000142227,0.0436732,0.0436783,0.0101764,0.0428619,0.0428627,0.0591575,7.00061e-11,6.99793e-11,7.04444e-10,2.55045e-06,2.55048e-06,5e-08,0,0,0,0,0,0,0,0 -21685000,0.982577,-0.00395346,-0.00715842,0.185674,-0.0222833,0.0282756,-1.13109,-0.0102458,0.0137349,-0.476509,-1.35551e-05,-5.97645e-05,2.64961e-06,-0.000119565,5.80814e-05,-0.00132125,0.20342,0.0019756,0.434785,0,0,0,0,0,5.26466e-06,8.2638e-06,8.25306e-06,0.000141217,0.0497307,0.0497369,0.0102404,0.0492379,0.0492391,0.0593412,7.01005e-11,7.00752e-11,6.91277e-10,2.55045e-06,2.55048e-06,5e-08,0,0,0,0,0,0,0,0 -21785000,0.982595,-0.00431568,-0.00726168,0.185567,-0.0125715,0.0244035,-1.25878,-0.00290246,0.0129399,-0.589423,-1.34927e-05,-5.97155e-05,2.88187e-06,-0.000144758,5.05706e-05,-0.00132815,0.20342,0.0019756,0.434785,0,0,0,0,0,5.26273e-06,8.32645e-06,8.31591e-06,0.000141135,0.0435922,0.0435975,0.0102094,0.0435685,0.0435694,0.0597949,6.94375e-11,6.94138e-11,6.81644e-10,2.25443e-06,2.25447e-06,5.0002e-08,0,0,0,0,0,0,0,0 -21885000,0.982588,-0.00460807,-0.00737799,0.185594,-0.00895604,0.0200262,-1.37994,-0.00400181,0.0152052,-0.728965,-1.34958e-05,-5.97116e-05,2.70502e-06,-0.000144449,5.03152e-05,-0.00132557,0.20342,0.0019756,0.434785,0,0,0,0,0,5.22655e-06,8.56826e-06,8.55782e-06,0.000140151,0.0491313,0.0491377,0.010274,0.0501397,0.0501411,0.0599768,6.95321e-11,6.95099e-11,6.69054e-10,2.25443e-06,2.25447e-06,5.0001e-08,0,0,0,0,0,0,0,0 -21985000,0.982606,-0.00529228,-0.00767235,0.185471,-0.00779453,0.0168705,-1.36793,-2.05677e-06,0.0127166,-0.864083,-1.34346e-05,-5.96842e-05,2.7728e-06,-0.000129616,2.58454e-05,-0.00133025,0.20342,0.0019756,0.434785,0,0,0,0,0,5.18999e-06,8.68667e-06,8.67653e-06,0.000139181,0.0425096,0.042515,0.0101557,0.0441649,0.0441659,0.0595366,6.91072e-11,6.90866e-11,6.56784e-10,1.99192e-06,1.99196e-06,5.0001e-08,0,0,0,0,0,0,0,0 -22085000,0.982599,-0.00603717,-0.00846323,0.185449,-0.00468422,0.0132382,-1.34861,-0.000692342,0.0141794,-1.00589,-1.34308e-05,-5.96862e-05,2.93212e-06,-0.000129251,2.56151e-05,-0.00132789,0.20342,0.0019756,0.434785,0,0,0,0,0,5.16161e-06,8.93471e-06,8.92349e-06,0.000138215,0.0474788,0.0474853,0.0102202,0.0508169,0.0508185,0.0597118,6.92026e-11,6.91825e-11,6.44818e-10,1.99192e-06,1.99197e-06,5.0001e-08,0,0,0,0,0,0,0,0 -22185000,0.982615,-0.00648161,-0.0087607,0.185333,0.00128142,0.00994086,-1.36351,0.00588682,0.0102279,-1.14714,-1.33528e-05,-5.9647e-05,3.05485e-06,-0.000122781,4.18159e-06,-0.0013256,0.20342,0.0019756,0.434785,0,0,0,0,0,5.12773e-06,9.09603e-06,9.08468e-06,0.000137269,0.0408162,0.0408218,0.0101028,0.0446228,0.044624,0.0592667,6.89519e-11,6.89322e-11,6.33145e-10,1.76376e-06,1.76381e-06,5e-08,0,0,0,0,0,0,0,0 -22285000,0.982603,-0.0072091,-0.00900052,0.185359,0.0072397,0.00484104,-1.36153,0.00629481,0.0110066,-1.28967,-1.3354e-05,-5.96443e-05,2.95912e-06,-0.000122476,3.94772e-06,-0.00132339,0.20342,0.0019756,0.434785,0,0,0,0,0,5.09559e-06,9.34761e-06,9.33697e-06,0.000136336,0.0452663,0.045273,0.0101673,0.0512763,0.0512782,0.0594357,6.90475e-11,6.90282e-11,6.21766e-10,1.76376e-06,1.76381e-06,5e-08,0,0,0,0,0,0,0,0 -22385000,0.982747,-0.00758551,-0.0091905,0.184569,0.00907535,-0.00405208,-1.36343,0.0117062,0.00186289,-1.43403,-1.32713e-05,-5.96057e-05,2.88905e-06,-9.60501e-05,-2.32973e-06,-0.00131942,0.204279,0.00198394,0.434362,0,0,0,0,0,8.01054e-05,9.68679e-06,9.61711e-06,0.00228386,0.0387997,0.0388054,0.010139,0.0449394,0.0449407,0.0598806,6.89111e-11,6.88919e-11,6.1623e-10,1.56905e-06,1.5691e-06,5.0002e-08,0,0,0,0,0,0,0,0 -22485000,0.982441,-0.00774548,-0.00963449,0.186165,0.0135755,-0.0105417,-1.36817,0.012821,0.00111907,-1.57535,-1.32708e-05,-5.96049e-05,2.88818e-06,-9.58064e-05,-2.5044e-06,-0.00131771,0.204279,0.00198394,0.434362,0,0,0,0,0,5.65858e-05,9.69906e-06,9.63932e-06,0.00160817,0.0429237,0.0429303,0.0102049,0.0515041,0.0515061,0.0600492,6.9011e-11,6.89918e-11,6.16329e-10,1.56905e-06,1.56911e-06,5.0002e-08,0,0,0,0,0,0,0,0 -22585000,0.982544,-0.00760745,-0.0102186,0.185592,0.0222062,-0.0167529,-1.36793,0.0246019,-0.00654359,-1.7182,-1.31806e-05,-5.95614e-05,2.88922e-06,-0.000101836,-1.38589e-05,-0.00131491,0.204279,0.00198394,0.434362,0,0,0,0,0,4.38602e-05,9.73885e-06,9.67337e-06,0.00124099,0.0371174,0.0371232,0.0100892,0.0451014,0.0451029,0.0595941,6.89344e-11,6.89151e-11,6.16424e-10,1.3967e-06,1.39677e-06,5.0001e-08,0,0,0,0,0,0,0,0 -22685000,0.982489,-0.00754074,-0.0104169,0.185878,0.0245009,-0.0216086,-1.37138,0.0269293,-0.00850902,-1.86207,-1.31797e-05,-5.95601e-05,2.88739e-06,-0.000101482,-1.41146e-05,-0.00131245,0.204279,0.00198394,0.434362,0,0,0,0,0,3.58578e-05,9.78354e-06,9.72379e-06,0.00101036,0.0411488,0.0411556,0.0101553,0.0515089,0.0515111,0.0597578,6.90344e-11,6.9015e-11,6.16517e-10,1.39671e-06,1.39678e-06,5.0001e-08,0,0,0,0,0,0,0,0 -22785000,0.98244,-0.00748917,-0.0108058,0.186117,0.0277659,-0.0274767,-1.37549,0.0357066,-0.0174404,-2.01001,-1.30702e-05,-5.94932e-05,2.88432e-06,-8.39867e-05,-3.37758e-05,-0.00130777,0.204279,0.00198394,0.434362,0,0,0,0,0,3.0261e-05,9.83171e-06,9.77229e-06,0.000852146,0.0358537,0.0358598,0.0100414,0.0451264,0.0451281,0.0593054,6.89388e-11,6.89195e-11,6.16604e-10,1.24104e-06,1.24111e-06,5e-08,0,0,0,0,0,0,0,0 -22885000,0.982599,-0.00768141,-0.0111331,0.185249,0.0308915,-0.0322484,-1.37736,0.0385993,-0.0203469,-2.15431,-1.30691e-05,-5.94921e-05,2.89153e-06,-8.36701e-05,-3.40368e-05,-0.00130538,0.204279,0.00198394,0.434362,0,0,0,0,0,2.61546e-05,9.89596e-06,9.84021e-06,0.000736863,0.0397591,0.0397665,0.0101078,0.0513938,0.0513963,0.0594648,6.90387e-11,6.90194e-11,6.16687e-10,1.24105e-06,1.24112e-06,5e-08,0,0,0,0,0,0,0,0 -22985000,0.98273,-0.00761778,-0.0115008,0.184531,0.0324072,-0.0357193,-1.38172,0.0472186,-0.0300641,-2.30652,-1.29499e-05,-5.94142e-05,2.89923e-06,-6.43415e-05,-5.39968e-05,-0.00129937,0.204279,0.00198394,0.434362,0,0,0,0,0,2.30316e-05,9.94424e-06,9.88851e-06,0.000649108,0.0348138,0.0348205,0.00999578,0.0450633,0.0450652,0.0590158,6.88806e-11,6.88614e-11,6.16761e-10,1.10176e-06,1.10183e-06,5e-08,0,0,0,0,0,0,0,0 -23085000,0.982786,-0.00763212,-0.011819,0.184211,0.0361628,-0.0406397,-1.37904,0.0506314,-0.0339113,-2.44582,-1.29498e-05,-5.9414e-05,2.8984e-06,-6.42792e-05,-5.40407e-05,-0.00129893,0.204279,0.00198394,0.434362,0,0,0,0,0,2.11136e-05,1.00215e-05,9.96575e-06,0.000595999,0.0385619,0.03857,0.0101493,0.0512081,0.0512109,0.0600599,6.89805e-11,6.89613e-11,6.16838e-10,1.10176e-06,1.10183e-06,5.0002e-08,0,0,0,0,0,0,0,0 -23185000,0.982777,-0.00759405,-0.0120085,0.184247,0.0408877,-0.0404275,-1.38236,0.0616846,-0.0436876,-2.59313,-1.28513e-05,-5.93399e-05,2.89093e-06,-5.33169e-05,-6.46139e-05,-0.00129449,0.204279,0.00198394,0.434362,0,0,0,0,0,1.90356e-05,1.00647e-05,1.00115e-05,0.000537352,0.0338661,0.0338741,0.0100371,0.0449472,0.0449493,0.0596012,6.87456e-11,6.87267e-11,6.16899e-10,9.78441e-07,9.78505e-07,5.0001e-08,0,0,0,0,0,0,0,0 -23285000,0.982825,-0.00807045,-0.0121359,0.183962,0.0447246,-0.0451372,-1.37831,0.0658953,-0.0480089,-2.7374,-1.28502e-05,-5.93386e-05,2.89407e-06,-5.30269e-05,-6.48548e-05,-0.00129226,0.204279,0.00198394,0.434362,0,0,0,0,0,1.73519e-05,1.01467e-05,1.01006e-05,0.00048925,0.0374315,0.0374409,0.0101051,0.050984,0.0509871,0.0597583,6.88455e-11,6.88265e-11,6.16952e-10,9.78442e-07,9.7851e-07,5.0001e-08,0,0,0,0,0,0,0,0 -23385000,0.98279,-0.0080461,-0.012244,0.184143,0.0487945,-0.0439975,-1.37972,0.0768003,-0.0516836,-2.87817,-1.27269e-05,-5.92969e-05,2.87778e-06,-5.44984e-05,-9.38173e-05,-0.00129077,0.204279,0.00198394,0.434362,0,0,0,0,0,1.59414e-05,1.01877e-05,1.01441e-05,0.000449105,0.0329291,0.0329374,0.00999477,0.0448011,0.0448035,0.0593038,6.85382e-11,6.85195e-11,6.16994e-10,8.70426e-07,8.70483e-07,5.0001e-08,0,0,0,0,0,0,0,0 -23485000,0.982839,-0.00814087,-0.0125102,0.18386,0.0522386,-0.0454592,-1.38141,0.0818121,-0.0561871,-3.02191,-1.27256e-05,-5.92958e-05,2.88845e-06,-5.42657e-05,-9.40486e-05,-0.00128872,0.204279,0.00198394,0.434362,0,0,0,0,0,1.47734e-05,1.02812e-05,1.02387e-05,0.000415073,0.0362981,0.036308,0.0100622,0.0507402,0.0507437,0.0594527,6.86381e-11,6.86193e-11,6.17025e-10,8.70427e-07,8.70488e-07,5e-08,0,0,0,0,0,0,0,0 -23585000,0.982866,-0.00839486,-0.0124511,0.18371,0.0523636,-0.0478608,-1.38089,0.0886692,-0.0665896,-3.1678,-1.26527e-05,-5.92167e-05,2.8947e-06,-3.51127e-05,-0.00010036,-0.00128579,0.204279,0.00198394,0.434362,0,0,0,0,0,1.37677e-05,1.03205e-05,1.02832e-05,0.000385882,0.0319584,0.0319672,0.00995369,0.0446389,0.0446415,0.0590029,6.82734e-11,6.8255e-11,6.17044e-10,7.76793e-07,7.76843e-07,5e-08,0,0,0,0,0,0,0,0 -23685000,0.982874,-0.00902859,-0.0129431,0.183601,0.0501613,-0.0499757,-1.28495,0.0938091,-0.0715471,-3.3058,-1.2652e-05,-5.92162e-05,2.90207e-06,-3.49988e-05,-0.00010048,-0.00128468,0.204279,0.00198394,0.434362,0,0,0,0,0,1.31138e-05,1.04266e-05,1.03903e-05,0.000366635,0.035068,0.0350778,0.0101087,0.0504857,0.0504894,0.060043,6.83733e-11,6.83548e-11,6.17076e-10,7.76797e-07,7.76849e-07,5.0002e-08,0,0,0,0,0,0,0,0 -23785000,0.982864,-0.0108157,-0.0156214,0.183348,0.0459138,-0.0447613,-0.967719,0.103965,-0.0754507,-3.42874,-1.25548e-05,-5.91928e-05,2.91936e-06,-3.85172e-05,-0.000118768,-0.0012801,0.204279,0.00198394,0.434362,0,0,0,0,0,1.23367e-05,1.04973e-05,1.04478e-05,0.00034371,0.0307412,0.0307495,0.0100004,0.0444659,0.0444687,0.0595846,6.79676e-11,6.79495e-11,6.17072e-10,6.96257e-07,6.963e-07,5.0002e-08,0,0,0,0,0,0,0,0 -23885000,0.982773,-0.0141658,-0.0197476,0.18321,0.04072,-0.0439238,-0.537188,0.108263,-0.0798371,-3.50717,-1.25542e-05,-5.9192e-05,2.91879e-06,-3.83759e-05,-0.000118883,-0.00127898,0.204279,0.00198394,0.434362,0,0,0,0,0,1.16347e-05,1.0653e-05,1.05843e-05,0.000323507,0.0334523,0.0334623,0.0100705,0.0502113,0.0502153,0.059734,6.80675e-11,6.80493e-11,6.17054e-10,6.96259e-07,6.96305e-07,5.0001e-08,0,0,0,0,0,0,0,0 -23985000,0.982712,-0.0164349,-0.0222246,0.183067,0.0424945,-0.0407328,-0.153095,0.117026,-0.0817609,-3.57572,-1.24702e-05,-5.91684e-05,2.91531e-06,-4.19541e-05,-0.000134679,-0.0012553,0.204279,0.00198394,0.434362,0,0,0,0,0,1.1007e-05,1.07423e-05,1.06653e-05,0.000305607,0.0293238,0.0293333,0.00996488,0.0442785,0.0442816,0.059281,6.76202e-11,6.76023e-11,6.1702e-10,6.26714e-07,6.26753e-07,5.0001e-08,0,0,0,0,0,0,0,0 -24085000,0.982741,-0.0160776,-0.0212974,0.183055,0.0481128,-0.0481906,0.0912157,0.1215,-0.0861634,-3.57915,-1.247e-05,-5.91675e-05,2.90137e-06,-4.18139e-05,-0.000134757,-0.00125449,0.204279,0.00198394,0.434362,0,0,0,0,0,1.04477e-05,1.08441e-05,1.0779e-05,0.000289689,0.0318918,0.0319037,0.0100359,0.0499153,0.0499199,0.0594291,6.772e-11,6.7702e-11,6.1697e-10,6.26715e-07,6.26758e-07,5e-08,0,0,0,0,0,0,0,0 -24185000,0.982863,-0.0132924,-0.0176353,0.183008,0.0591525,-0.052975,0.0835181,0.129613,-0.0908524,-3.59556,-1.24218e-05,-5.91364e-05,2.91248e-06,-4.01547e-05,-0.000141846,-0.00123543,0.204279,0.00198394,0.434362,0,0,0,0,0,9.96451e-06,1.08765e-05,1.08317e-05,0.000275423,0.0281489,0.0281594,0.00993122,0.0440767,0.0440802,0.0589817,6.72533e-11,6.72357e-11,6.16903e-10,5.67009e-07,5.67045e-07,5e-08,0,0,0,0,0,0,0,0 -24285000,0.98296,-0.0108529,-0.0141548,0.18295,0.0621482,-0.0563155,0.0583063,0.135723,-0.0963714,-3.59181,-1.24212e-05,-5.91359e-05,2.91671e-06,-4.00499e-05,-0.000141948,-0.00123447,0.204279,0.00198394,0.434362,0,0,0,0,0,9.52167e-06,1.09731e-05,1.09446e-05,0.000262537,0.0306403,0.0306522,0.0100015,0.0496137,0.0496187,0.0591287,6.73531e-11,6.73354e-11,6.16818e-10,5.67011e-07,5.6705e-07,5e-08,0,0,0,0,0,0,0,0 -24385000,0.983025,-0.00993861,-0.013067,0.182734,0.056483,-0.0499662,0.0747228,0.143498,-0.0969292,-3.58808,-1.23581e-05,-5.91482e-05,2.93621e-06,-4.59944e-05,-0.000156559,-0.00123334,0.204279,0.00198394,0.434362,0,0,0,0,0,9.21656e-06,1.10444e-05,1.10196e-05,0.000253747,0.0270636,0.0270731,0.00998166,0.0438667,0.0438705,0.0595607,6.69078e-11,6.68905e-11,6.16767e-10,5.16697e-07,5.1673e-07,5.0002e-08,0,0,0,0,0,0,0,0 -24485000,0.983066,-0.0101604,-0.0131301,0.1825,0.0507392,-0.0455621,0.0728391,0.14884,-0.101694,-3.58026,-1.23575e-05,-5.91492e-05,2.97261e-06,-4.60979e-05,-0.000156572,-0.00123346,0.204279,0.00198394,0.434362,0,0,0,0,0,8.84876e-06,1.11811e-05,1.11576e-05,0.000242813,0.0293654,0.0293758,0.010053,0.0493027,0.049308,0.0597112,6.70076e-11,6.69902e-11,6.16648e-10,5.16699e-07,5.16735e-07,5.0001e-08,0,0,0,0,0,0,0,0 -24585000,0.983026,-0.0108637,-0.0132322,0.182667,0.0484158,-0.040246,0.0681856,0.153948,-0.0986999,-3.57462,-1.23003e-05,-5.91815e-05,2.97084e-06,-5.40868e-05,-0.000172362,-0.0012323,0.204279,0.00198394,0.434362,0,0,0,0,0,8.5245e-06,1.12643e-05,1.12444e-05,0.000232812,0.0259738,0.0259822,0.00994882,0.0436483,0.0436523,0.0592619,6.65945e-11,6.65774e-11,6.16509e-10,4.74508e-07,4.7454e-07,5.0001e-08,0,0,0,0,0,0,0,0 -24685000,0.983011,-0.01138,-0.0130617,0.182729,0.0450222,-0.0389583,0.0673197,0.158669,-0.102595,-3.56786,-1.23003e-05,-5.91814e-05,2.96816e-06,-5.40765e-05,-0.000172366,-0.00123227,0.204279,0.00198394,0.434362,0,0,0,0,0,8.21802e-06,1.14081e-05,1.13922e-05,0.000223656,0.0281064,0.0281156,0.0100204,0.0489808,0.0489863,0.0594117,6.66942e-11,6.6677e-11,6.16349e-10,4.74511e-07,4.74545e-07,5.0001e-08,0,0,0,0,0,0,0,0 -24785000,0.983037,-0.0115302,-0.0124229,0.182623,0.0424337,-0.0359464,0.0595996,0.162004,-0.0990311,-3.56543,-1.22546e-05,-5.91905e-05,2.97375e-06,-5.69365e-05,-0.00018584,-0.00123134,0.204279,0.00198394,0.434362,0,0,0,0,0,7.92588e-06,1.14913e-05,1.14802e-05,0.000215251,0.0248918,0.024899,0.00991681,0.0434201,0.0434242,0.0589628,6.63233e-11,6.63064e-11,6.16166e-10,4.39348e-07,4.39379e-07,5e-08,0,0,0,0,0,0,0,0 -24885000,0.983041,-0.0113743,-0.0119124,0.182647,0.0394775,-0.0388044,0.0492711,0.166122,-0.102775,-3.56231,-1.22538e-05,-5.91902e-05,2.98667e-06,-5.68645e-05,-0.000185933,-0.00123051,0.204279,0.00198394,0.434362,0,0,0,0,0,7.6695e-06,1.16423e-05,1.16333e-05,0.000207486,0.0268721,0.0268799,0.00998839,0.0486464,0.0486519,0.059112,6.6423e-11,6.6406e-11,6.1596e-10,4.3935e-07,4.39384e-07,5e-08,0,0,0,0,0,0,0,0 -24985000,0.983024,-0.0111809,-0.0116767,0.182766,0.0320931,-0.0334784,0.0417936,0.167287,-0.0945839,-3.55985,-1.21937e-05,-5.92162e-05,2.98735e-06,-6.22381e-05,-0.000204639,-0.00123003,0.204279,0.00198394,0.434362,0,0,0,0,0,7.4979e-06,1.17324e-05,1.17236e-05,0.000202163,0.023832,0.0238382,0.00997098,0.0431809,0.043185,0.0595479,6.61011e-11,6.60843e-11,6.15815e-10,4.10217e-07,4.10248e-07,5.0002e-08,0,0,0,0,0,0,0,0 -25085000,0.983022,-0.0115204,-0.0117322,0.182747,0.0279278,-0.0323749,0.0386714,0.170215,-0.0979214,-3.56169,-1.21924e-05,-5.92145e-05,2.98086e-06,-6.19883e-05,-0.000204853,-0.00122796,0.204279,0.00198394,0.434362,0,0,0,0,0,7.26412e-06,1.18947e-05,1.18872e-05,0.000195388,0.0256638,0.0256705,0.0100438,0.0482987,0.048304,0.0597012,6.62007e-11,6.61838e-11,6.15567e-10,4.1022e-07,4.10253e-07,5.0002e-08,0,0,0,0,0,0,0,0 -25185000,0.982975,-0.0117695,-0.0115782,0.182997,0.0245671,-0.0262608,0.0387007,0.172059,-0.0909426,-3.55944,-1.21651e-05,-5.92482e-05,2.96112e-06,-6.88093e-05,-0.000216102,-0.00122672,0.204279,0.00198394,0.434362,0,0,0,0,0,7.06191e-06,1.19887e-05,1.19829e-05,0.000189082,0.0227925,0.0227978,0.00994115,0.0429299,0.0429339,0.0592509,6.59301e-11,6.59134e-11,6.15293e-10,3.86196e-07,3.86227e-07,5.0001e-08,0,0,0,0,0,0,0,0 -25285000,0.982929,-0.0119194,-0.0109339,0.183275,0.0185127,-0.0271415,0.0334811,0.174178,-0.0935905,-3.55689,-1.21656e-05,-5.92469e-05,2.91926e-06,-6.87072e-05,-0.000216121,-0.00122637,0.204279,0.00198394,0.434362,0,0,0,0,0,6.87001e-06,1.21564e-05,1.21541e-05,0.000183219,0.0244938,0.0244997,0.010014,0.047937,0.0479421,0.059404,6.60297e-11,6.60129e-11,6.14994e-10,3.86199e-07,3.86232e-07,5.0001e-08,0,0,0,0,0,0,0,0 -25385000,0.982931,-0.0120779,-0.0107447,0.183265,0.0115587,-0.0200357,0.03177,0.171366,-0.0835225,-3.55779,-1.21136e-05,-5.92663e-05,2.92161e-06,-7.15143e-05,-0.000232353,-0.00122425,0.204279,0.00198394,0.434362,0,0,0,0,0,6.68349e-06,1.22541e-05,1.22529e-05,0.000177756,0.0217923,0.021797,0.00991274,0.0426666,0.0426706,0.0589597,6.58114e-11,6.57948e-11,6.14666e-10,3.66491e-07,3.66523e-07,5e-08,0,0,0,0,0,0,0,0 -25485000,0.982923,-0.0121235,-0.0104433,0.183322,0.00527909,-0.018835,0.0308575,0.172145,-0.0854621,-3.55648,-1.21134e-05,-5.92654e-05,2.90486e-06,-7.14202e-05,-0.000232415,-0.00122361,0.204279,0.00198394,0.434362,0,0,0,0,0,6.50951e-06,1.24317e-05,1.24316e-05,0.000172653,0.0233715,0.0233767,0.0099857,0.047562,0.0475668,0.0591125,6.5911e-11,6.58943e-11,6.14313e-10,3.66495e-07,3.66527e-07,5e-08,0,0,0,0,0,0,0,0 -25585000,0.98291,-0.0123591,-0.0102623,0.183385,0.00156795,-0.0164647,0.0326254,0.169803,-0.079268,-3.55487,-1.21059e-05,-5.92795e-05,2.88308e-06,-7.35018e-05,-0.000238955,-0.00122293,0.204279,0.00198394,0.434362,0,0,0,0,0,6.34611e-06,1.25328e-05,1.25338e-05,0.000167875,0.0208331,0.0208372,0.00988551,0.0423915,0.0423952,0.0586741,6.57436e-11,6.57271e-11,6.13929e-10,3.50412e-07,3.50443e-07,5e-08,0,0,0,0,0,0,0,0 -25685000,0.982923,-0.0118402,-0.00995921,0.183365,0.000109554,-0.015805,0.0217363,0.169884,-0.0809147,-3.55498,-1.2105e-05,-5.92789e-05,2.89082e-06,-7.33951e-05,-0.000239068,-0.00122192,0.204279,0.00198394,0.434362,0,0,0,0,0,6.23597e-06,1.2719e-05,1.27187e-05,0.000164635,0.0223102,0.0223144,0.010043,0.0471748,0.0471792,0.0597049,6.58433e-11,6.58267e-11,6.13647e-10,3.50417e-07,3.50449e-07,5.0002e-08,0,0,0,0,0,0,0,0 -25785000,0.982942,-0.0116474,-0.00926268,0.183312,-0.00966199,-0.00901111,0.0204885,0.164171,-0.0732803,-3.5579,-1.20812e-05,-5.92884e-05,2.89131e-06,-7.35172e-05,-0.000248105,-0.00121984,0.204279,0.00198394,0.434362,0,0,0,0,0,6.08712e-06,1.28208e-05,1.28218e-05,0.000160373,0.01993,0.0199335,0.00994218,0.0421053,0.0421087,0.0592592,6.5725e-11,6.57084e-11,6.13211e-10,3.37377e-07,3.37408e-07,5.0001e-08,0,0,0,0,0,0,0,0 -25885000,0.982912,-0.011712,-0.00930589,0.183467,-0.016694,-0.00681346,0.0228856,0.162787,-0.0740465,-3.5567,-1.20822e-05,-5.92866e-05,2.82612e-06,-7.34087e-05,-0.00024813,-0.00121948,0.204279,0.00198394,0.434362,0,0,0,0,0,5.94893e-06,1.30159e-05,1.30166e-05,0.000156364,0.0213042,0.0213081,0.0100161,0.046777,0.0467811,0.0594163,6.58245e-11,6.58079e-11,6.12747e-10,3.3738e-07,3.37413e-07,5.0001e-08,0,0,0,0,0,0,0,0 -25985000,0.982906,-0.0118448,-0.00947622,0.183483,-0.0246309,-0.00205005,0.0160916,0.152625,-0.0669289,-3.55701,-1.20609e-05,-5.92726e-05,2.81203e-06,-6.9035e-05,-0.000256219,-0.00121819,0.204279,0.00198394,0.434362,0,0,0,0,0,5.81939e-06,1.31224e-05,1.31224e-05,0.000152589,0.0190781,0.0190812,0.00991618,0.0418092,0.0418123,0.0589764,6.57509e-11,6.57343e-11,6.12249e-10,3.26869e-07,3.26901e-07,5.0001e-08,0,0,0,0,0,0,0,0 -26085000,0.982939,-0.0115498,-0.00942874,0.183329,-0.0300375,-0.00143222,0.0144367,0.149868,-0.0670929,-3.55745,-1.20597e-05,-5.92729e-05,2.84774e-06,-6.89882e-05,-0.000256305,-0.00121749,0.204279,0.00198394,0.434362,0,0,0,0,0,5.69519e-06,1.33251e-05,1.33238e-05,0.000149038,0.0203698,0.0203732,0.00998904,0.0463709,0.0463746,0.059128,6.58504e-11,6.58338e-11,6.11719e-10,3.26873e-07,3.26905e-07,5e-08,0,0,0,0,0,0,0,0 -26185000,0.982935,-0.0115252,-0.00995081,0.183322,-0.0357502,0.00227117,0.00997051,0.141145,-0.0628799,-3.56084,-1.20571e-05,-5.92712e-05,2.8724e-06,-6.70587e-05,-0.000259355,-0.00121564,0.204279,0.00198394,0.434362,0,0,0,0,0,5.58442e-06,1.34333e-05,1.34296e-05,0.000145678,0.0182839,0.0182867,0.00989012,0.0415048,0.0415076,0.0586937,6.58173e-11,6.58007e-11,6.11156e-10,3.18469e-07,3.185e-07,5e-08,0,0,0,0,0,0,0,0 -26285000,0.982934,-0.0115947,-0.0102618,0.183305,-0.0375392,0.00340916,0.00400276,0.137465,-0.0626303,-3.56199,-1.20571e-05,-5.927e-05,2.83889e-06,-6.69576e-05,-0.000259429,-0.00121498,0.204279,0.00198394,0.434362,0,0,0,0,0,5.50401e-06,1.36447e-05,1.36399e-05,0.000143456,0.0195042,0.0195069,0.0100485,0.0459588,0.0459621,0.0597293,6.59169e-11,6.59003e-11,6.10739e-10,3.18474e-07,3.18506e-07,5.0002e-08,0,0,0,0,0,0,0,0 -26385000,0.982966,-0.0110832,-0.0102364,0.183165,-0.0430253,0.00820928,0.00708121,0.125155,-0.0572855,-3.56205,-1.20454e-05,-5.92535e-05,2.81745e-06,-6.23232e-05,-0.000263988,-0.00121481,0.204279,0.00198394,0.434362,0,0,0,0,0,5.39129e-06,1.37508e-05,1.37438e-05,0.000140435,0.0175479,0.0175499,0.00994853,0.041194,0.0411964,0.0592876,6.59188e-11,6.59022e-11,6.10116e-10,3.11815e-07,3.11844e-07,5.0002e-08,0,0,0,0,0,0,0,0 -26485000,0.982976,-0.0108398,-0.0101245,0.183135,-0.0465112,0.0110403,0.0161678,0.120681,-0.0563445,-3.56097,-1.20459e-05,-5.92529e-05,2.79347e-06,-6.23027e-05,-0.000263991,-0.00121479,0.204279,0.00198394,0.434362,0,0,0,0,0,5.2901e-06,1.39684e-05,1.39608e-05,0.000137574,0.0186942,0.0186961,0.0100222,0.045543,0.0455458,0.0594435,6.60183e-11,6.60016e-11,6.09461e-10,3.11819e-07,3.11848e-07,5.0001e-08,0,0,0,0,0,0,0,0 -26585000,0.982964,-0.0103444,-0.0103951,0.183213,-0.0471429,0.0164247,0.0165265,0.112008,-0.0518987,-3.56128,-1.20374e-05,-5.92463e-05,2.76087e-06,-6.07762e-05,-0.00026635,-0.00121317,0.204279,0.00198394,0.434362,0,0,0,0,0,5.19888e-06,1.40741e-05,1.40637e-05,0.00013486,0.0168651,0.0168662,0.00992294,0.0408785,0.0408807,0.0590073,6.60487e-11,6.6032e-11,6.08768e-10,3.06583e-07,3.0661e-07,5.0001e-08,0,0,0,0,0,0,0,0 -26685000,0.982958,-0.0102257,-0.0101026,0.183267,-0.0492305,0.0210182,0.0156607,0.107175,-0.0500258,-3.55981,-1.20384e-05,-5.92449e-05,2.7004e-06,-6.07301e-05,-0.000266359,-0.0012131,0.204279,0.00198394,0.434362,0,0,0,0,0,5.1088e-06,1.42985e-05,1.42885e-05,0.000132295,0.0179618,0.0179626,0.00999637,0.0451261,0.0451286,0.0591629,6.61481e-11,6.61314e-11,6.08042e-10,3.06587e-07,3.06614e-07,5e-08,0,0,0,0,0,0,0,0 -26785000,0.98298,-0.0100583,-0.00959147,0.183185,-0.0546366,0.0225181,0.0143044,0.0960066,-0.047368,-3.56255,-1.20267e-05,-5.92289e-05,2.67678e-06,-5.70449e-05,-0.000267869,-0.00121116,0.204279,0.00198394,0.434362,0,0,0,0,0,5.02047e-06,1.43988e-05,1.43895e-05,0.000129866,0.0162497,0.0162502,0.00989793,0.0405608,0.0405627,0.058732,6.62006e-11,6.6184e-11,6.07278e-10,3.02522e-07,3.02546e-07,5e-08,0,0,0,0,0,0,0,0 -26885000,0.98301,-0.00945814,-0.0096789,0.183052,-0.0605689,0.0249336,0.00992319,0.0902101,-0.045,-3.56188,-1.20257e-05,-5.92296e-05,2.72168e-06,-5.70465e-05,-0.000267893,-0.00121095,0.204279,0.00198394,0.434362,0,0,0,0,0,4.94025e-06,1.46317e-05,1.46204e-05,0.00012756,0.0173014,0.0173019,0.0099712,0.0447116,0.0447136,0.0588873,6.62999e-11,6.62833e-11,6.06478e-10,3.02526e-07,3.02549e-07,5e-08,0,0,0,0,0,0,0,0 -26985000,0.983005,-0.00897064,-0.0101642,0.183077,-0.0664564,0.0289188,0.00795369,0.0788624,-0.041153,-3.56638,-1.20065e-05,-5.92137e-05,2.69368e-06,-5.41856e-05,-0.000270162,-0.00120854,0.204279,0.00198394,0.434362,0,0,0,0,0,4.89007e-06,1.47303e-05,1.47161e-05,0.000126094,0.015697,0.0156972,0.00995662,0.0402436,0.0402451,0.0593287,6.63677e-11,6.63512e-11,6.05876e-10,2.99412e-07,2.99432e-07,5.0002e-08,0,0,0,0,0,0,0,0 -27085000,0.983006,-0.00880188,-0.0104949,0.183062,-0.0688343,0.0358369,0.0117786,0.072024,-0.0378974,-3.56979,-1.20053e-05,-5.92121e-05,2.67938e-06,-5.40001e-05,-0.000270364,-0.00120693,0.204279,0.00198394,0.434362,0,0,0,0,0,4.8176e-06,1.49707e-05,1.49549e-05,0.00012399,0.0167028,0.0167025,0.0100307,0.0443025,0.0443041,0.0594883,6.6467e-11,6.64505e-11,6.0501e-10,2.99416e-07,2.99435e-07,5.0001e-08,0,0,0,0,0,0,0,0 -27185000,0.983014,-0.00886302,-0.0104,0.183023,-0.073825,0.0392384,0.0130277,0.0625141,-0.0339946,-3.57229,-1.19839e-05,-5.91997e-05,2.66708e-06,-5.23828e-05,-0.000271827,-0.00120545,0.204279,0.00198394,0.434362,0,0,0,0,0,4.7478e-06,1.50614e-05,1.50458e-05,0.000121991,0.0151961,0.0151956,0.00993183,0.0399291,0.0399302,0.0590549,6.65422e-11,6.6526e-11,6.04104e-10,2.9706e-07,2.97074e-07,5.0001e-08,0,0,0,0,0,0,0,0 -27285000,0.983022,-0.00903178,-0.0113195,0.182918,-0.0805622,0.0449477,0.115868,0.0548336,-0.0297999,-3.57045,-1.19829e-05,-5.91989e-05,2.66661e-06,-5.22713e-05,-0.000271955,-0.00120444,0.204279,0.00198394,0.434362,0,0,0,0,0,4.67975e-06,1.53102e-05,1.52918e-05,0.000120093,0.0160954,0.0160947,0.0100059,0.0439002,0.0439014,0.0592142,6.66415e-11,6.66252e-11,6.03161e-10,2.97064e-07,2.97077e-07,5.0001e-08,0,0,0,0,0,0,0,0 -27385000,0.982983,-0.0103861,-0.0137866,0.182884,-0.0840409,0.0501301,0.431741,0.0468616,-0.0244058,-3.55223,-1.19538e-05,-5.91732e-05,2.66845e-06,-5.09567e-05,-0.000274021,-0.00119947,0.204279,0.00198394,0.434362,0,0,0,0,0,4.61897e-06,1.5406e-05,1.53817e-05,0.000118275,0.0144659,0.0144651,0.00990694,0.0396134,0.0396142,0.0587804,6.67183e-11,6.67024e-11,6.02174e-10,2.95289e-07,2.95297e-07,5e-08,0,0,0,0,0,0,0,0 -27485000,0.982929,-0.01183,-0.0157551,0.182928,-0.0870663,0.0556456,0.750816,0.0382606,-0.0190985,-3.49461,-1.19539e-05,-5.91712e-05,2.60488e-06,-5.08269e-05,-0.000274162,-0.00119852,0.204279,0.00198394,0.434362,0,0,0,0,0,4.56066e-06,1.56652e-05,1.56364e-05,0.00011655,0.015168,0.0151668,0.0099809,0.0434776,0.0434785,0.0589392,6.68176e-11,6.68016e-11,6.01153e-10,2.95294e-07,2.95299e-07,5e-08,0,0,0,0,0,0,0,0 -27585000,0.982953,-0.0118253,-0.0147595,0.182883,-0.0803061,0.0568046,0.855468,0.0311684,-0.0166449,-3.4338,-1.19114e-05,-5.91439e-05,2.60175e-06,-4.8729e-05,-0.000275938,-0.00118329,0.204279,0.00198394,0.434362,0,0,0,0,0,4.52408e-06,1.57674e-05,1.57427e-05,0.000115529,0.0138082,0.0138065,0.00996655,0.0392818,0.0392824,0.0593844,6.68985e-11,6.68828e-11,6.00382e-10,2.93889e-07,2.9389e-07,5.0002e-08,0,0,0,0,0,0,0,0 -27685000,0.983022,-0.0106774,-0.0118656,0.182794,-0.0768822,0.0524406,0.762495,0.023346,-0.011119,-3.3557,-1.19098e-05,-5.91432e-05,2.61834e-06,-4.85947e-05,-0.000276104,-0.001182,0.204279,0.00198394,0.434362,0,0,0,0,0,4.4676e-06,1.60173e-05,1.60003e-05,0.000113973,0.0147644,0.0147625,0.0100405,0.0430555,0.043056,0.0595475,6.69978e-11,6.6982e-11,5.9929e-10,2.93894e-07,2.93892e-07,5.0002e-08,0,0,0,0,0,0,0,0 -27785000,0.983057,-0.00933575,-0.0102765,0.182775,-0.0750524,0.0479459,0.749894,0.0184369,-0.0102124,-3.28191,-1.18792e-05,-5.91283e-05,2.64737e-06,-4.84146e-05,-0.000275596,-0.00118311,0.204279,0.00198394,0.434362,0,0,0,0,0,4.41779e-06,1.61083e-05,1.60932e-05,0.00011248,0.0135703,0.0135687,0.00994032,0.0389574,0.0389578,0.0591105,6.70663e-11,6.70511e-11,5.98152e-10,2.92857e-07,2.92849e-07,5.0001e-08,0,0,0,0,0,0,0,0 -27885000,0.983055,-0.00895002,-0.0103524,0.182802,-0.0816646,0.0535451,0.791549,0.0106121,-0.00518753,-3.20727,-1.18781e-05,-5.91275e-05,2.64836e-06,-4.82995e-05,-0.000275739,-0.00118204,0.204279,0.00198394,0.434362,0,0,0,0,0,4.37156e-06,1.63741e-05,1.63577e-05,0.000111056,0.0144224,0.0144206,0.0100145,0.0426608,0.042661,0.0592729,6.71654e-11,6.71503e-11,5.96979e-10,2.92862e-07,2.92851e-07,5.0001e-08,0,0,0,0,0,0,0,0 -27985000,0.983054,-0.00939698,-0.010728,0.182759,-0.0815672,0.0540484,0.778886,0.00639563,-0.00473013,-3.13688,-1.1828e-05,-5.90976e-05,2.65328e-06,-4.72525e-05,-0.000276508,-0.00117731,0.204279,0.00198394,0.434362,0,0,0,0,0,4.32509e-06,1.6458e-05,1.64414e-05,0.000109697,0.013298,0.0132961,0.00991511,0.0386505,0.0386506,0.0588406,6.72149e-11,6.72004e-11,5.95759e-10,2.92106e-07,2.92089e-07,5e-08,0,0,0,0,0,0,0,0 -28085000,0.983076,-0.00973108,-0.0107316,0.182626,-0.0852029,0.0538909,0.785106,-0.00190444,0.000701941,-3.05916,-1.18266e-05,-5.90991e-05,2.72952e-06,-4.72613e-05,-0.000276519,-0.00117718,0.204279,0.00198394,0.434362,0,0,0,0,0,4.28088e-06,1.67293e-05,1.67131e-05,0.000108407,0.0141694,0.0141676,0.00998867,0.0422892,0.0422891,0.0590023,6.73139e-11,6.72995e-11,5.94504e-10,2.92111e-07,2.92091e-07,5e-08,0,0,0,0,0,0,0,0 -28185000,0.98308,-0.00922106,-0.0110264,0.182612,-0.0846522,0.0491438,0.790947,-0.00758273,0.000119893,-2.98494,-1.17713e-05,-5.90735e-05,2.73024e-06,-4.60531e-05,-0.000277538,-0.00117463,0.204279,0.00198394,0.434362,0,0,0,0,0,4.23946e-06,1.67968e-05,1.67787e-05,0.000107174,0.013093,0.0130915,0.00988966,0.0383617,0.0383616,0.0585745,6.7334e-11,6.73204e-11,5.932e-10,2.91555e-07,2.91529e-07,5e-08,0,0,0,0,0,0,0,0 -28285000,0.9831,-0.00871027,-0.0113159,0.18251,-0.0898403,0.0515222,0.791506,-0.0162648,0.00519982,-2.9083,-1.17693e-05,-5.90739e-05,2.78743e-06,-4.59714e-05,-0.000277657,-0.00117371,0.204279,0.00198394,0.434362,0,0,0,0,0,4.21694e-06,1.70749e-05,1.70547e-05,0.000106523,0.0139661,0.0139646,0.0100476,0.0419437,0.0419433,0.0596107,6.74333e-11,6.74197e-11,5.92223e-10,2.91561e-07,2.91532e-07,5.0002e-08,0,0,0,0,0,0,0,0 -28385000,0.98309,-0.00874073,-0.0119405,0.182527,-0.0897976,0.0534365,0.792515,-0.0201013,0.0074155,-2.83551,-1.17099e-05,-5.90248e-05,2.85695e-06,-4.43245e-05,-0.000279499,-0.001171,0.204279,0.00198394,0.434362,0,0,0,0,0,4.18354e-06,1.71242e-05,1.71021e-05,0.000105387,0.0129474,0.0129459,0.00994761,0.0380936,0.0380932,0.0591748,6.74155e-11,6.74028e-11,5.90845e-10,2.91133e-07,2.91097e-07,5.0001e-08,0,0,0,0,0,0,0,0 -28485000,0.983087,-0.00906534,-0.0124393,0.18249,-0.0912356,0.0556302,0.793631,-0.0291234,0.0128452,-2.76087,-1.17083e-05,-5.90234e-05,2.85425e-06,-4.41515e-05,-0.000279722,-0.00116936,0.204279,0.00198394,0.434362,0,0,0,0,0,4.14674e-06,1.74077e-05,1.73845e-05,0.000104313,0.0138213,0.0138196,0.0100216,0.0416275,0.0416269,0.0593396,6.75146e-11,6.75018e-11,5.89432e-10,2.91138e-07,2.91099e-07,5.0001e-08,0,0,0,0,0,0,0,0 -28585000,0.983122,-0.00914847,-0.0124121,0.182303,-0.0845042,0.0504101,0.790973,-0.0317059,0.00999707,-2.68532,-1.16156e-05,-5.89825e-05,2.90745e-06,-4.2701e-05,-0.000281974,-0.00116762,0.204279,0.00198394,0.434362,0,0,0,0,0,4.10792e-06,1.74333e-05,1.74103e-05,0.000103292,0.0128521,0.0128506,0.00992172,0.0378487,0.0378482,0.0589081,6.74497e-11,6.7438e-11,5.8797e-10,2.90774e-07,2.90728e-07,5.0001e-08,0,0,0,0,0,0,0,0 -28685000,0.983118,-0.0089468,-0.0118004,0.182371,-0.0843465,0.0501905,0.791808,-0.0401388,0.0150544,-2.61027,-1.16143e-05,-5.89811e-05,2.89452e-06,-4.25425e-05,-0.000282181,-0.00116612,0.204279,0.00198394,0.434362,0,0,0,0,0,4.07759e-06,1.77186e-05,1.7697e-05,0.000102317,0.0137316,0.01373,0.00999428,0.041343,0.0413422,0.0590665,6.75487e-11,6.7537e-11,5.8647e-10,2.90779e-07,2.90729e-07,5e-08,0,0,0,0,0,0,0,0 -28785000,0.983139,-0.00831807,-0.0116114,0.182299,-0.079895,0.0494444,0.790399,-0.04201,0.016466,-2.53806,-1.15447e-05,-5.89157e-05,2.97313e-06,-4.00712e-05,-0.000284627,-0.00116255,0.204279,0.00198394,0.434362,0,0,0,0,0,4.04706e-06,1.77188e-05,1.76969e-05,0.000101387,0.0127982,0.0127968,0.00989509,0.0376287,0.0376281,0.0586394,6.74276e-11,6.74171e-11,5.84923e-10,2.90423e-07,2.90366e-07,5e-08,0,0,0,0,0,0,0,0 -28885000,0.983167,-0.00814114,-0.0113482,0.182175,-0.083926,0.0501727,0.789699,-0.050176,0.0214385,-2.46194,-1.15427e-05,-5.8916e-05,3.02328e-06,-3.99762e-05,-0.000284764,-0.00116152,0.204279,0.00198394,0.434362,0,0,0,0,0,4.03093e-06,1.80096e-05,1.7988e-05,0.000100972,0.0136877,0.0136863,0.0100532,0.0410915,0.0410906,0.0596796,6.75268e-11,6.75163e-11,5.83764e-10,2.90429e-07,2.9037e-07,5.0002e-08,0,0,0,0,0,0,0,0 -28985000,0.983155,-0.00792188,-0.0115739,0.182235,-0.0794639,0.0462508,0.78883,-0.0490932,0.0203889,-2.39073,-1.14436e-05,-5.88442e-05,3.0527e-06,-3.75354e-05,-0.000288188,-0.00115773,0.204279,0.00198394,0.434362,0,0,0,0,0,4.00617e-06,1.7983e-05,1.79605e-05,0.000100115,0.0127843,0.0127832,0.00995269,0.0374352,0.0374344,0.059244,6.73414e-11,6.73322e-11,5.82142e-10,2.90032e-07,2.89966e-07,5.0002e-08,0,0,0,0,0,0,0,0 -29085000,0.983156,-0.00781025,-0.0116154,0.182231,-0.0824372,0.0474254,0.788533,-0.057252,0.0250449,-2.31385,-1.14426e-05,-5.88439e-05,3.0635e-06,-3.74624e-05,-0.000288287,-0.00115702,0.204279,0.00198394,0.434362,0,0,0,0,0,3.97982e-06,1.82781e-05,1.82554e-05,9.93042e-05,0.013684,0.013683,0.0100258,0.0408743,0.0408733,0.0594052,6.744e-11,6.74314e-11,5.80482e-10,2.90038e-07,2.89968e-07,5.0001e-08,0,0,0,0,0,0,0,0 -29185000,0.983184,-0.00776392,-0.0118429,0.18207,-0.0780364,0.044963,0.782766,-0.0545177,0.024313,-2.24538,-1.13384e-05,-5.87491e-05,3.15052e-06,-3.39466e-05,-0.000292124,-0.00115216,0.204279,0.00198394,0.434362,0,0,0,0,0,3.95167e-06,1.8221e-05,1.8198e-05,9.85326e-05,0.0128086,0.0128079,0.00992593,0.037269,0.0372683,0.058974,6.71824e-11,6.71759e-11,5.78775e-10,2.8956e-07,2.89484e-07,5.0001e-08,0,0,0,0,0,0,0,0 -29285000,0.983168,-0.00801099,-0.0118763,0.182144,-0.0796982,0.0498362,0.785161,-0.0623677,0.0290963,-2.16847,-1.13369e-05,-5.87494e-05,3.19167e-06,-3.3888e-05,-0.000292206,-0.00115163,0.204279,0.00198394,0.434362,0,0,0,0,0,3.93182e-06,1.85192e-05,1.84966e-05,9.77925e-05,0.0137183,0.0137174,0.00999874,0.0406921,0.0406911,0.0591342,6.7281e-11,6.72751e-11,5.77031e-10,2.89566e-07,2.89485e-07,5e-08,0,0,0,0,0,0,0,0 -29385000,0.983177,-0.00846187,-0.0113807,0.182103,-0.0750967,0.0482569,0.787374,-0.0602274,0.0301167,-2.09333,-1.12462e-05,-5.86667e-05,3.2543e-06,-3.1012e-05,-0.000295558,-0.00114979,0.204279,0.00198394,0.434362,0,0,0,0,0,3.90928e-06,1.84278e-05,1.84077e-05,9.7091e-05,0.0128545,0.0128538,0.00989946,0.0371307,0.0371299,0.0587073,6.69456e-11,6.69411e-11,5.7524e-10,2.88974e-07,2.88887e-07,5e-08,0,0,0,0,0,0,0,0 -29485000,0.983189,-0.00851289,-0.0112446,0.182045,-0.0773965,0.0480148,0.788628,-0.0678087,0.0349533,-2.01661,-1.12433e-05,-5.86687e-05,3.37194e-06,-3.09671e-05,-0.000295645,-0.00114906,0.204279,0.00198394,0.434362,0,0,0,0,0,3.88932e-06,1.87285e-05,1.87087e-05,9.64227e-05,0.0137781,0.0137775,0.00997183,0.0405444,0.0405434,0.0588664,6.70445e-11,6.70399e-11,5.73413e-10,2.88979e-07,2.8889e-07,5e-08,0,0,0,0,0,0,0,0 -29585000,0.983206,-0.00842603,-0.011248,0.181958,-0.0726347,0.0454999,0.790456,-0.0648485,0.0343831,-1.93855,-1.11348e-05,-5.85844e-05,3.45292e-06,-2.80065e-05,-0.000299585,-0.00114883,0.204279,0.00198394,0.434362,0,0,0,0,0,3.8823e-06,1.86046e-05,1.85849e-05,9.62109e-05,0.0129275,0.0129271,0.0099563,0.0370199,0.0370191,0.0593102,6.66261e-11,6.66231e-11,5.72032e-10,2.88249e-07,2.88155e-07,5.0002e-08,0,0,0,0,0,0,0,0 -29685000,0.98323,-0.0084944,-0.0110389,0.181835,-0.0770057,0.0435612,0.786239,-0.0723054,0.0388729,-1.86376,-1.11316e-05,-5.85857e-05,3.55485e-06,-2.78914e-05,-0.000299766,-0.00114738,0.204279,0.00198394,0.434362,0,0,0,0,0,3.86124e-06,1.89071e-05,1.88879e-05,9.56033e-05,0.0138708,0.0138708,0.0100295,0.0404308,0.0404298,0.059473,6.67251e-11,6.67219e-11,5.70132e-10,2.88255e-07,2.88157e-07,5.0001e-08,0,0,0,0,0,0,0,0 -29785000,0.983239,-0.00835383,-0.0115624,0.181762,-0.0725361,0.0358832,0.782578,-0.0672431,0.0366122,-1.79159,-1.10203e-05,-5.84814e-05,3.67516e-06,-2.39124e-05,-0.00030386,-0.00114435,0.204279,0.00198394,0.434362,0,0,0,0,0,3.84351e-06,1.87485e-05,1.87279e-05,9.50204e-05,0.013029,0.0130293,0.00992946,0.0369366,0.0369359,0.0590419,6.62188e-11,6.62172e-11,5.68185e-10,2.87362e-07,2.8726e-07,5.0001e-08,0,0,0,0,0,0,0,0 -29885000,0.983244,-0.00785565,-0.011951,0.181733,-0.0727631,0.0354254,0.7789,-0.0744133,0.040142,-1.71957,-1.10165e-05,-5.84819e-05,3.7708e-06,-2.37254e-05,-0.000304133,-0.0011422,0.204279,0.00198394,0.434362,0,0,0,0,0,3.82752e-06,1.9054e-05,1.90314e-05,9.44667e-05,0.0139864,0.0139869,0.0100022,0.0403511,0.0403503,0.0592035,6.63176e-11,6.63162e-11,5.66202e-10,2.87368e-07,2.87262e-07,5.0001e-08,0,0,0,0,0,0,0,0 -29985000,0.983241,-0.00796699,-0.0120183,0.181738,-0.0673759,0.0307223,0.775883,-0.0696377,0.0361633,-1.64993,-1.08851e-05,-5.83928e-05,3.81135e-06,-2.02724e-05,-0.000309339,-0.0011382,0.204279,0.00198394,0.434362,0,0,0,0,0,3.81168e-06,1.88572e-05,1.88351e-05,9.39393e-05,0.013143,0.0131436,0.00990196,0.03688,0.0368794,0.0587712,6.57209e-11,6.57217e-11,5.6417e-10,2.86301e-07,2.86191e-07,5e-08,0,0,0,0,0,0,0,0 -30085000,0.983242,-0.00812513,-0.0121592,0.181719,-0.0674516,0.0303673,0.773907,-0.0763786,0.0392446,-1.57607,-1.0886e-05,-5.83903e-05,3.71651e-06,-2.01653e-05,-0.000309477,-0.00113687,0.204279,0.00198394,0.434362,0,0,0,0,0,3.79201e-06,1.91626e-05,1.91404e-05,9.34438e-05,0.0141143,0.0141151,0.00997439,0.0403029,0.0403023,0.0589316,6.58194e-11,6.58208e-11,5.62107e-10,2.86307e-07,2.86194e-07,5e-08,0,0,0,0,0,0,0,0 -30185000,0.98322,-0.00810698,-0.0121695,0.181839,-0.0609628,0.026985,0.773833,-0.0695517,0.0381357,-1.50417,-1.08166e-05,-5.82672e-05,3.64542e-06,-1.54834e-05,-0.000312089,-0.00113429,0.204279,0.00198394,0.434362,0,0,0,0,0,3.79203e-06,1.89286e-05,1.8907e-05,9.33662e-05,0.0132639,0.0132648,0.00995903,0.0368481,0.0368477,0.0593774,6.51327e-11,6.51361e-11,5.60551e-10,2.85061e-07,2.84946e-07,5.0002e-08,0,0,0,0,0,0,0,0 -30285000,0.983208,-0.00814337,-0.0121691,0.181899,-0.0601944,0.0258988,0.774076,-0.0755584,0.0407966,-1.43185,-1.08144e-05,-5.82666e-05,3.67318e-06,-1.53188e-05,-0.000312315,-0.00113248,0.204279,0.00198394,0.434362,0,0,0,0,0,3.7802e-06,1.92338e-05,1.92123e-05,9.29092e-05,0.0142464,0.0142476,0.0100322,0.0402837,0.0402833,0.0595415,6.52313e-11,6.52352e-11,5.58418e-10,2.85068e-07,2.84949e-07,5.0002e-08,0,0,0,0,0,0,0,0 -30385000,0.983199,-0.00812356,-0.012093,0.181955,-0.052288,0.0202996,0.771679,-0.067163,0.0385514,-1.36388,-1.0717e-05,-5.81257e-05,3.83179e-06,-9.45095e-06,-0.00031618,-0.00112816,0.204279,0.00198394,0.434362,0,0,0,0,0,3.77237e-06,1.89632e-05,1.89426e-05,9.24708e-05,0.0133888,0.01339,0.00993136,0.0368389,0.0368388,0.059105,6.44559e-11,6.44618e-11,5.56237e-10,2.83645e-07,2.83524e-07,5.0001e-08,0,0,0,0,0,0,0,0 -30485000,0.983228,-0.00814605,-0.0122317,0.181789,-0.0549856,0.0192951,0.772645,-0.0724856,0.04058,-1.29211,-1.0713e-05,-5.81264e-05,3.93627e-06,-9.27041e-06,-0.000316435,-0.0011262,0.204279,0.00198394,0.434362,0,0,0,0,0,3.75641e-06,1.92681e-05,1.92472e-05,9.20637e-05,0.014384,0.0143855,0.0100044,0.0402905,0.0402905,0.0592678,6.45544e-11,6.45609e-11,5.54026e-10,2.83651e-07,2.83527e-07,5.0001e-08,0,0,0,0,0,0,0,0 -30585000,0.983244,-0.00844959,-0.0125198,0.181668,-0.0497587,0.0167418,0.772287,-0.0651675,0.0376289,-1.22038,-1.06172e-05,-5.8007e-05,4.06243e-06,-4.33654e-06,-0.000320213,-0.00112353,0.204279,0.00198394,0.434362,0,0,0,0,0,3.7431e-06,1.89631e-05,1.89425e-05,9.16738e-05,0.0135138,0.0135152,0.00990431,0.0368499,0.03685,0.0588356,6.36936e-11,6.37018e-11,5.51769e-10,2.82057e-07,2.81932e-07,5e-08,0,0,0,0,0,0,0,0 -30685000,0.983262,-0.00882907,-0.0127546,0.181536,-0.0481581,0.0142174,0.771181,-0.0701293,0.0392223,-1.14932,-1.06149e-05,-5.80064e-05,4.0929e-06,-4.15893e-06,-0.000320456,-0.00112133,0.204279,0.00198394,0.434362,0,0,0,0,0,3.72767e-06,1.9267e-05,1.92464e-05,9.13076e-05,0.0145242,0.0145259,0.0099769,0.0403202,0.0403205,0.0589973,6.37922e-11,6.38008e-11,5.49482e-10,2.82064e-07,2.81936e-07,5e-08,0,0,0,0,0,0,0,0 -30785000,0.98329,-0.00853664,-0.0124744,0.181417,-0.0404798,0.00914845,0.76974,-0.0627323,0.039045,-1.07937,-1.06048e-05,-5.78859e-05,4.10596e-06,7.64025e-07,-0.000320709,-0.00111802,0.204279,0.00198394,0.434362,0,0,0,0,0,3.71223e-06,1.89268e-05,1.89072e-05,9.09619e-05,0.0136399,0.0136416,0.00987737,0.0368786,0.0368789,0.0585694,6.28503e-11,6.28606e-11,5.47151e-10,2.8031e-07,2.8018e-07,5e-08,0,0,0,0,0,0,0,0 -30885000,0.983282,-0.00790745,-0.0123355,0.181498,-0.0402755,0.00477637,0.767396,-0.0667007,0.0397951,-1.00705,-1.06042e-05,-5.78846e-05,4.08081e-06,8.90694e-07,-0.000320873,-0.00111642,0.204279,0.00198394,0.434362,0,0,0,0,0,3.71631e-06,1.92283e-05,1.9208e-05,9.10083e-05,0.0146645,0.0146664,0.0100343,0.0403701,0.0403706,0.059605,6.29492e-11,6.29599e-11,5.45408e-10,2.80317e-07,2.80186e-07,5.0002e-08,0,0,0,0,0,0,0,0 -30985000,0.983283,-0.00806774,-0.0122902,0.181491,-0.0327631,0.000181983,0.768864,-0.0565784,0.0341541,-0.93795,-1.05032e-05,-5.77607e-05,4.09576e-06,5.97806e-06,-0.000325,-0.00111317,0.204279,0.00198394,0.434362,0,0,0,0,0,3.70604e-06,1.88565e-05,1.88372e-05,9.06906e-05,0.0137593,0.0137611,0.00993361,0.0369225,0.036923,0.0591686,6.19319e-11,6.19439e-11,5.43013e-10,2.78416e-07,2.78285e-07,5.0001e-08,0,0,0,0,0,0,0,0 -31085000,0.983245,-0.00821644,-0.0123964,0.181682,-0.031191,-0.00291402,0.767852,-0.0597322,0.0339521,-0.863881,-1.05034e-05,-5.77595e-05,4.05764e-06,6.05154e-06,-0.000325089,-0.00111219,0.204279,0.00198394,0.434362,0,0,0,0,0,3.70193e-06,1.91559e-05,1.91366e-05,9.03842e-05,0.0147932,0.0147952,0.0100067,0.0404359,0.0404368,0.0593326,6.20305e-11,6.20429e-11,5.40589e-10,2.78423e-07,2.7829e-07,5.0001e-08,0,0,0,0,0,0,0,0 -31185000,0.983259,-0.00835003,-0.0125464,0.181591,-0.0265487,-0.00613051,0.769344,-0.0511618,0.0305004,-0.794042,-1.04606e-05,-5.76533e-05,4.22203e-06,1.05695e-05,-0.00032668,-0.00110956,0.204279,0.00198394,0.434362,0,0,0,0,0,3.69381e-06,1.87552e-05,1.87364e-05,9.00976e-05,0.0138703,0.0138722,0.00990683,0.0369785,0.0369792,0.0589006,6.09455e-11,6.09591e-11,5.38125e-10,2.76394e-07,2.76262e-07,5.0001e-08,0,0,0,0,0,0,0,0 -31285000,0.983277,-0.00861763,-0.0126236,0.181475,-0.0236362,-0.00967535,0.773236,-0.0536287,0.0297547,-0.72242,-1.04573e-05,-5.76542e-05,4.31569e-06,1.07257e-05,-0.000326891,-0.00110759,0.204279,0.00198394,0.434362,0,0,0,0,0,3.68373e-06,1.90516e-05,1.90331e-05,8.98285e-05,0.0149051,0.0149072,0.00997874,0.0405141,0.0405152,0.0590581,6.10441e-11,6.10581e-11,5.3563e-10,2.76402e-07,2.76268e-07,5e-08,0,0,0,0,0,0,0,0 -31385000,0.983289,-0.00839327,-0.012434,0.181432,-0.0175885,-0.0152143,0.772563,-0.0448134,0.025855,-0.649569,-1.04285e-05,-5.75644e-05,4.25707e-06,1.43233e-05,-0.000328047,-0.00110505,0.204279,0.00198394,0.434362,0,0,0,0,0,3.67229e-06,1.86245e-05,1.86067e-05,8.95769e-05,0.0139675,0.0139694,0.00987948,0.0370433,0.0370443,0.0586304,5.99007e-11,5.99156e-11,5.33098e-10,2.74271e-07,2.74138e-07,5e-08,0,0,0,0,0,0,0,0 -31485000,0.983273,-0.008143,-0.0127421,0.18151,-0.0176058,-0.0197688,0.769401,-0.0466232,0.0240665,-0.574423,-1.04284e-05,-5.75639e-05,4.24587e-06,1.43713e-05,-0.000328106,-0.00110438,0.204279,0.00198394,0.434362,0,0,0,0,0,3.67958e-06,1.89183e-05,1.88991e-05,8.97011e-05,0.0150208,0.0150228,0.0100368,0.0406016,0.0406029,0.0596691,5.99996e-11,6.00148e-11,5.31207e-10,2.74279e-07,2.74145e-07,5.0002e-08,0,0,0,0,0,0,0,0 -31585000,0.983297,-0.00795374,-0.0132189,0.181353,-0.01307,-0.0204022,0.773012,-0.0356807,0.0216508,-0.503008,-1.0423e-05,-5.74321e-05,4.35597e-06,1.99357e-05,-0.000328229,-0.00110162,0.204279,0.00198394,0.434362,0,0,0,0,0,3.66959e-06,1.8469e-05,1.84489e-05,8.94725e-05,0.0140571,0.0140589,0.00993648,0.0371149,0.0371159,0.059233,5.88048e-11,5.88206e-11,5.28618e-10,2.7206e-07,2.71929e-07,5.0002e-08,0,0,0,0,0,0,0,0 -31685000,0.983322,-0.00795289,-0.0136905,0.181185,-0.015037,-0.0227805,0.769333,-0.0371057,0.0194198,-0.433518,-1.04188e-05,-5.74334e-05,4.48411e-06,2.01364e-05,-0.000328494,-0.00109885,0.204279,0.00198394,0.434362,0,0,0,0,0,3.66039e-06,1.87592e-05,1.87377e-05,8.92557e-05,0.0151144,0.0151162,0.0100091,0.0406946,0.040696,0.059393,5.89034e-11,5.89194e-11,5.26001e-10,2.72068e-07,2.71935e-07,5.0001e-08,0,0,0,0,0,0,0,0 -31785000,0.983334,-0.00812462,-0.0143582,0.181056,-0.00598659,-0.0242308,0.769176,-0.0256238,0.019853,-0.36209,-1.0476e-05,-5.72765e-05,4.59558e-06,2.67672e-05,-0.000326023,-0.00109627,0.204279,0.00198394,0.434362,0,0,0,0,0,3.65226e-06,1.82907e-05,1.82683e-05,8.90496e-05,0.0141371,0.0141387,0.00990935,0.0371903,0.0371915,0.0589613,5.76675e-11,5.76839e-11,5.2335e-10,2.69789e-07,2.69658e-07,5.0001e-08,0,0,0,0,0,0,0,0 -31885000,0.983344,-0.00789873,-0.0141567,0.18103,-0.00222832,-0.0278092,0.767894,-0.0260112,0.0171904,-0.292842,-1.04732e-05,-5.72769e-05,4.66987e-06,2.69547e-05,-0.000326255,-0.00109355,0.204279,0.00198394,0.434362,0,0,0,0,0,3.64684e-06,1.8575e-05,1.85529e-05,8.88548e-05,0.0151954,0.0151971,0.00998161,0.040791,0.0407926,0.0591201,5.7766e-11,5.77828e-11,5.20672e-10,2.69797e-07,2.69665e-07,5e-08,0,0,0,0,0,0,0,0 -31985000,0.983335,-0.0080833,-0.0137372,0.1811,0.00580248,-0.0269993,0.764546,-0.0142095,0.0163743,-0.226457,-1.05169e-05,-5.71455e-05,4.63527e-06,3.24786e-05,-0.000324603,-0.00108915,0.204279,0.00198394,0.434362,0,0,0,0,0,3.64201e-06,1.80874e-05,1.80675e-05,8.86705e-05,0.0142019,0.0142033,0.00988258,0.0372675,0.0372688,0.0586928,5.64979e-11,5.65147e-11,5.17963e-10,2.67477e-07,2.67349e-07,5e-08,0,0,0,0,0,0,0,0 -32085000,0.983352,-0.00846482,-0.0133637,0.181021,0.00596814,-0.0316402,0.766928,-0.0136029,0.0135068,-0.155557,-1.05158e-05,-5.7145e-05,4.64758e-06,3.26115e-05,-0.000324756,-0.00108709,0.204279,0.00198394,0.434362,0,0,0,0,0,3.63408e-06,1.83667e-05,1.83486e-05,8.84994e-05,0.0152585,0.0152601,0.00995464,0.0408875,0.0408891,0.0588505,5.65965e-11,5.66136e-11,5.15228e-10,2.67486e-07,2.67356e-07,5e-08,0,0,0,0,0,0,0,0 -32185000,0.983344,-0.00863623,-0.0136453,0.181035,0.0106012,-0.0329276,0.766962,-0.00268935,0.0146067,-0.0864206,-1.06172e-05,-5.70268e-05,4.63559e-06,3.75742e-05,-0.000320685,-0.00108347,0.204279,0.00198394,0.434362,0,0,0,0,0,3.64122e-06,1.78682e-05,1.78502e-05,8.86945e-05,0.0142447,0.0142459,0.00993935,0.037344,0.0373453,0.0592936,5.53061e-11,5.53231e-11,5.1318e-10,2.65149e-07,2.65023e-07,5.0002e-08,0,0,0,0,0,0,0,0 -32285000,0.98336,-0.00855919,-0.0138982,0.180933,0.0124168,-0.0374801,0.765474,-0.0015267,0.0110549,-0.017388,-1.06146e-05,-5.70274e-05,4.71409e-06,3.77501e-05,-0.000320889,-0.00108073,0.204279,0.00198394,0.434362,0,0,0,0,0,3.63486e-06,1.81443e-05,1.81255e-05,8.85393e-05,0.0153067,0.015308,0.0100122,0.0409808,0.0409825,0.059455,5.54047e-11,5.5422e-11,5.10396e-10,2.65158e-07,2.65031e-07,5.0001e-08,0,0,0,0,0,0,0,0 -32385000,0.983342,-0.00857346,-0.0140175,0.181023,0.0190487,-0.0365901,0.764125,0.00941382,0.0110139,0.0553429,-1.06985e-05,-5.69309e-05,4.68151e-06,4.17412e-05,-0.000317534,-0.00107808,0.204279,0.00198394,0.434362,0,0,0,0,0,3.63217e-06,1.76361e-05,1.76175e-05,8.83895e-05,0.0142804,0.0142814,0.00991272,0.0374177,0.037419,0.0590237,5.41004e-11,5.41174e-11,5.07585e-10,2.62824e-07,2.62701e-07,5.0001e-08,0,0,0,0,0,0,0,0 -32485000,0.983357,-0.0114764,-0.0119474,0.18093,0.0451941,-0.104451,-0.108486,0.013077,0.0021654,0.0638751,-1.0699e-05,-5.69293e-05,4.62809e-06,4.17645e-05,-0.000317554,-0.00107765,0.204279,0.00198394,0.434362,0,0,0,0,0,3.62347e-06,1.79013e-05,1.78943e-05,8.8256e-05,0.0169454,0.0169445,0.00978613,0.0411527,0.0411543,0.0591751,5.41993e-11,5.42159e-11,5.04751e-10,2.62826e-07,2.62702e-07,5e-08,0,0,0,0,0,0,0,0 -32585000,0.983368,-0.0114057,-0.0119113,0.180877,0.0447604,-0.10333,-0.109892,0.0246569,0.00143205,0.045944,-1.09297e-05,-5.68331e-05,4.73734e-06,4.17645e-05,-0.000317554,-0.00107765,0.204279,0.00198394,0.434362,0,0,0,0,0,3.61954e-06,1.72637e-05,1.72566e-05,8.81226e-05,0.0161885,0.0161877,0.00941854,0.0375979,0.0375992,0.0587073,5.2703e-11,5.27168e-11,5.01888e-10,2.62826e-07,2.62702e-07,5e-08,0,0,0,0,0,0,0,0 -32685000,0.983372,-0.0113941,-0.0117747,0.180862,0.0412877,-0.1101,-0.111692,0.0290053,-0.00924481,0.0311782,-1.09297e-05,-5.68324e-05,4.72359e-06,4.17645e-05,-0.000317554,-0.00107765,0.204279,0.00198394,0.434362,0,0,0,0,0,3.61474e-06,1.75275e-05,1.75203e-05,8.79996e-05,0.01789,0.0178897,0.0092221,0.0414576,0.0414592,0.0587818,5.2802e-11,5.28152e-11,4.99006e-10,2.62826e-07,2.62702e-07,5e-08,0,0,0,0,0,0,0,0 -32785000,0.983375,-0.0111893,-0.0118556,0.180851,0.0392107,-0.10575,-0.112326,0.0381662,-0.00810884,0.0162689,-1.11997e-05,-5.67363e-05,4.82837e-06,4.17645e-05,-0.000317554,-0.00107765,0.204279,0.00198394,0.434362,0,0,0,0,0,3.62467e-06,1.67858e-05,1.67779e-05,8.8236e-05,0.0170504,0.0170503,0.00896611,0.037847,0.0378483,0.0591409,5.11984e-11,5.12086e-11,4.96853e-10,2.62826e-07,2.62702e-07,5e-08,0,0,0,0,0,0,0,0 -32885000,0.983395,-0.0111645,-0.0119172,0.180742,0.0396953,-0.113634,-0.113647,0.0421634,-0.0190981,0.00260113,-1.11987e-05,-5.67371e-05,4.87525e-06,4.17645e-05,-0.000317554,-0.00107765,0.204279,0.00198394,0.434362,0,0,0,0,0,3.61863e-06,1.7042e-05,1.70337e-05,8.81268e-05,0.0188427,0.018843,0.00878586,0.041805,0.0418066,0.0591471,5.12973e-11,5.13071e-11,4.93931e-10,2.62829e-07,2.62705e-07,5.0003e-08,0,0,0,0,0,0,0,0 -32985000,0.983406,-0.0110099,-0.0118841,0.180691,0.036885,-0.109295,-0.112651,0.0493599,-0.0196096,-0.0100572,-1.14439e-05,-5.66675e-05,5.00651e-06,4.17567e-05,-0.000318021,-0.00107769,0.204279,0.00198394,0.434362,0,0,0,0,0,3.61598e-06,1.62062e-05,1.61974e-05,8.80189e-05,0.0179236,0.0179243,0.00848981,0.0381265,0.0381278,0.0585942,4.96162e-11,4.96225e-11,4.90985e-10,2.62835e-07,2.62711e-07,5.00129e-08,0,0,0,0,0,0,0,0 -33085000,0.98341,-0.0109785,-0.0119006,0.180675,0.0338246,-0.114517,-0.110424,0.0529277,-0.0307611,-0.0185871,-1.14441e-05,-5.66675e-05,4.99805e-06,4.17562e-05,-0.000318021,-0.00107769,0.204279,0.00198394,0.434362,0,0,0,0,0,3.61207e-06,1.64534e-05,1.64443e-05,8.792e-05,0.019866,0.0198673,0.00834368,0.0421865,0.0421883,0.0585412,4.9715e-11,4.97211e-11,4.88023e-10,2.62845e-07,2.62721e-07,5.00229e-08,0,0,0,0,0,0,0,0 -33185000,0.983418,-0.0107862,-0.0118245,0.180644,0.0298069,-0.110592,-0.10885,0.0584394,-0.03017,-0.0247485,-1.16923e-05,-5.65957e-05,4.96135e-06,4.15614e-05,-0.000320533,-0.00107794,0.204279,0.00198394,0.434362,0,0,0,0,0,3.60662e-06,1.5541e-05,1.55316e-05,8.78266e-05,0.0188842,0.0188856,0.0080967,0.0384297,0.0384311,0.0579684,4.79927e-11,4.79954e-11,4.85038e-10,2.62711e-07,2.62588e-07,5.00304e-08,0,0,0,0,0,0,0,0 -33285000,0.983441,-0.0108595,-0.011834,0.180515,0.0274337,-0.114111,-0.108677,0.0612421,-0.0414122,-0.0332604,-1.16895e-05,-5.65989e-05,5.10616e-06,4.15594e-05,-0.000320531,-0.00107795,0.204279,0.00198394,0.434362,0,0,0,0,0,3.6028e-06,1.57786e-05,1.5769e-05,8.77381e-05,0.0209649,0.0209671,0.00798636,0.0425973,0.0425991,0.0578683,4.80916e-11,4.8094e-11,4.82039e-10,2.62721e-07,2.62598e-07,5.00403e-08,0,0,0,0,0,0,0,0 -33385000,0.983455,-0.0106313,-0.0118913,0.180448,0.0227873,-0.103197,-0.106345,0.0637463,-0.0345886,-0.0417188,-1.20259e-05,-5.65074e-05,5.16472e-06,4.15594e-05,-0.000320531,-0.00107824,0.204279,0.00198394,0.434362,0,0,0,0,0,3.59856e-06,1.48125e-05,1.48024e-05,8.76534e-05,0.0196594,0.0196617,0.00778378,0.0387517,0.0387532,0.0572856,4.63667e-11,4.6366e-11,4.79019e-10,2.62721e-07,2.62598e-07,5.00418e-08,0,0,0,0,0,0,0,0 -33485000,0.983459,-0.0106185,-0.0118457,0.18043,0.0187276,-0.107062,-0.106271,0.0657791,-0.0450709,-0.0524613,-1.20257e-05,-5.65076e-05,5.17633e-06,4.15594e-05,-0.000320531,-0.00107824,0.204279,0.00198394,0.434362,0,0,0,0,0,3.60767e-06,1.504e-05,1.50297e-05,8.79273e-05,0.0215695,0.0215725,0.00777044,0.0430227,0.0430247,0.0579788,4.64658e-11,4.6465e-11,4.76769e-10,2.62721e-07,2.62598e-07,5.00515e-08,0,0,0,0,0,0,0,0 -33585000,0.983487,-0.0103512,-0.0118151,0.180296,0.0148061,-0.100036,-0.102538,0.0675522,-0.0392893,-0.0583093,-1.23025e-05,-5.64273e-05,5.30767e-06,4.15594e-05,-0.000320531,-0.00107888,0.204279,0.00198394,0.434362,0,0,0,0,0,3.60307e-06,1.40426e-05,1.40319e-05,8.78512e-05,0.0200903,0.0200932,0.00760535,0.0390796,0.0390811,0.0573781,4.47724e-11,4.47686e-11,4.7372e-10,2.62721e-07,2.62598e-07,5.00437e-08,0,0,0,0,0,0,0,0 -33685000,0.983496,-0.0103467,-0.0118041,0.180246,0.0108664,-0.10398,-0.104144,0.0688756,-0.0495311,-0.0667976,-1.23017e-05,-5.64282e-05,5.34918e-06,4.15594e-05,-0.000320531,-0.00107891,0.204279,0.00198394,0.434362,0,0,0,0,0,3.59997e-06,1.42599e-05,1.42489e-05,8.77788e-05,0.0220002,0.0220038,0.00755978,0.0434405,0.0434426,0.057215,4.48712e-11,4.48673e-11,4.7066e-10,2.62721e-07,2.62598e-07,5.00524e-08,0,0,0,0,0,0,0,0 -33785000,0.983509,-0.0101496,-0.0118012,0.180189,0.00641581,-0.0963475,-0.0983857,0.0717219,-0.0427707,-0.0728109,-1.25666e-05,-5.63194e-05,5.32166e-06,4.15594e-05,-0.000320531,-0.00107964,0.204279,0.00198394,0.434362,0,0,0,0,0,3.59464e-06,1.32529e-05,1.32417e-05,8.77109e-05,0.0203776,0.0203808,0.00743089,0.0393971,0.0393987,0.0566217,4.32373e-11,4.32309e-11,4.67583e-10,2.62721e-07,2.62598e-07,5.00318e-08,0,0,0,0,0,0,0,0 -33885000,0.983525,-0.0101898,-0.0117586,0.180104,0.00292411,-0.0973977,-0.0979857,0.0721371,-0.0525046,-0.0800861,-1.25644e-05,-5.63217e-05,5.43048e-06,4.15594e-05,-0.000320531,-0.00107972,0.204279,0.00198394,0.434362,0,0,0,0,0,3.59206e-06,1.346e-05,1.34487e-05,8.76441e-05,0.0222622,0.0222663,0.00741446,0.0438329,0.043835,0.0564415,4.33361e-11,4.33296e-11,4.64494e-10,2.62721e-07,2.62598e-07,5.00388e-08,0,0,0,0,0,0,0,0 -33985000,0.983518,-0.00993798,-0.011894,0.180145,0.000498625,-0.0868494,-0.0943615,0.073799,-0.0431352,-0.0833155,-1.2846e-05,-5.61888e-05,5.37944e-06,4.15594e-05,-0.000320531,-0.00108066,0.204279,0.00198394,0.434362,0,0,0,0,0,3.58959e-06,1.24636e-05,1.24517e-05,8.75794e-05,0.0205251,0.0205287,0.00731757,0.0396918,0.0396935,0.0558629,4.17843e-11,4.17755e-11,4.61393e-10,2.62721e-07,2.62598e-07,5.0005e-08,0,0,0,0,0,0,0,0 -34085000,0.983523,-0.00987527,-0.0118975,0.180118,-0.00306447,-0.0913964,-0.0934497,0.0737167,-0.0520798,-0.0900178,-1.28459e-05,-5.6189e-05,5.38106e-06,4.15594e-05,-0.000320531,-0.00108077,0.204279,0.00198394,0.434362,0,0,0,0,0,3.59875e-06,1.2661e-05,1.26488e-05,8.78724e-05,0.0223731,0.0223773,0.00738417,0.0441863,0.0441886,0.0564705,4.18833e-11,4.18746e-11,4.59086e-10,2.62721e-07,2.62598e-07,5.00108e-08,0,0,0,0,0,0,0,0 -34185000,0.983525,-0.00970373,-0.0119365,0.180119,-0.00668622,-0.0814299,-0.091119,0.0757973,-0.0435222,-0.0918185,-1.30842e-05,-5.60687e-05,5.42709e-06,4.15594e-05,-0.000320531,-0.00108154,0.204279,0.00198394,0.434362,0,0,0,0,0,3.59728e-06,1.16907e-05,1.16783e-05,8.78114e-05,0.0205416,0.0205454,0.00731336,0.0399541,0.0399559,0.0558966,4.04285e-11,4.04178e-11,4.55965e-10,2.62721e-07,2.62598e-07,5.00037e-08,0,0,0,0,0,0,0,0 -34285000,0.983528,-0.00959658,-0.0119969,0.1801,-0.00680031,-0.0849691,-0.0900857,0.0751546,-0.0518838,-0.0990843,-1.3083e-05,-5.60698e-05,5.48315e-06,4.15594e-05,-0.000320531,-0.00108164,0.204279,0.00198394,0.434362,0,0,0,0,0,3.59594e-06,1.18788e-05,1.18659e-05,8.7753e-05,0.022342,0.0223463,0.00734865,0.0444904,0.0444927,0.0557153,4.05271e-11,4.05166e-11,4.52836e-10,2.62721e-07,2.62598e-07,5.0004e-08,0,0,0,0,0,0,0,0 -34385000,0.983552,-0.00938221,-0.0120066,0.179981,-0.00964968,-0.0740477,-0.0850889,0.0754486,-0.0430849,-0.102274,-1.33065e-05,-5.59668e-05,5.49651e-06,4.15594e-05,-0.000320531,-0.00108311,0.204279,0.00198394,0.434362,0,0,0,0,0,3.58998e-06,1.09476e-05,1.09344e-05,8.77008e-05,0.0204348,0.0204386,0.00730222,0.0401771,0.0401789,0.0551677,3.91783e-11,3.91661e-11,4.49697e-10,2.62721e-07,2.62598e-07,5.0001e-08,0,0,0,0,0,0,0,0 -34485000,0.983556,-0.00946709,-0.0119364,0.17996,-0.0126689,-0.077798,-0.0836043,0.0743368,-0.0507469,-0.105781,-1.33051e-05,-5.59681e-05,5.55591e-06,4.15594e-05,-0.000320531,-0.00108347,0.204279,0.00198394,0.434362,0,0,0,0,0,3.58878e-06,1.11266e-05,1.11136e-05,8.76459e-05,0.0221805,0.0221847,0.00735996,0.0447379,0.0447403,0.0550007,3.92769e-11,3.92649e-11,4.46552e-10,2.62721e-07,2.62598e-07,5e-08,0,0,0,0,0,0,0,0 -34585000,0.983562,-0.00926919,-0.0117599,0.179949,-0.0128818,-0.0663435,0.662289,0.0747899,-0.0430201,-0.0806858,-1.34861e-05,-5.58695e-05,5.54379e-06,4.15594e-05,-0.000320531,-0.00108484,0.204279,0.00198394,0.434362,0,0,0,0,0,3.58591e-06,1.02432e-05,1.02304e-05,8.75942e-05,0.0191072,0.0191105,0.00733423,0.0403258,0.0403276,0.0544833,3.8038e-11,3.80247e-11,4.434e-10,2.62721e-07,2.62598e-07,5e-08,0,0,0,0,0,0,0,0 -34685000,0.983568,-0.00925611,-0.0114729,0.179933,-0.0146815,-0.063338,1.65295,0.0734175,-0.0495005,0.0321606,-1.34866e-05,-5.5869e-05,5.52527e-06,4.15594e-05,-0.000320531,-0.00108457,0.204279,0.00198394,0.434362,0,0,0,0,0,3.58321e-06,1.04137e-05,1.04015e-05,8.7544e-05,0.0192163,0.0192196,0.00741185,0.0447213,0.0447236,0.0543372,3.81366e-11,3.81235e-11,4.40242e-10,2.62721e-07,2.62598e-07,5e-08,0,0,0,0,0,0,0,0 -34785000,0.983576,-0.00909799,-0.0112412,0.179916,-0.0148925,-0.0519221,2.6195,0.0740976,-0.0418724,0.194292,-1.36331e-05,-5.57803e-05,5.51322e-06,4.15594e-05,-0.000320531,-0.00105859,0.204279,0.00198394,0.434362,0,0,0,0,0,3.59227e-06,9.68481e-06,9.67298e-06,8.7848e-05,0.0163819,0.0163845,0.00745318,0.0402591,0.0402609,0.0545875,3.71288e-11,3.71149e-11,4.37894e-10,2.62721e-07,2.62598e-07,5.0002e-08,0,0,0,0,0,0,0,0 -34885000,0.983581,-0.00908347,-0.0109551,0.179903,-0.0166451,-0.048899,3.60507,0.0725539,-0.0468836,0.484156,-1.36343e-05,-5.57793e-05,5.48955e-06,4.15594e-05,-0.000320531,-0.00105635,0.204279,0.00198394,0.434362,0,0,0,0,0,3.58962e-06,9.84911e-06,9.83783e-06,8.77992e-05,0.0164934,0.016496,0.0075485,0.0443771,0.0443793,0.0544643,3.72274e-11,3.72137e-11,4.34728e-10,2.62721e-07,2.62598e-07,5.0001e-08,0,0,0,0,0,0,0,0 diff --git a/src/lib/ecl/test/gtest.cmake b/src/lib/ecl/test/gtest.cmake deleted file mode 100644 index 94c4103ce5..0000000000 --- a/src/lib/ecl/test/gtest.cmake +++ /dev/null @@ -1,43 +0,0 @@ -############################################################################ -# -# Copyright (c) 2019 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. -# -############################################################################ - -# Download and unpack googletest at configure time -configure_file(${CMAKE_CURRENT_LIST_DIR}/CMakeLists.txt.in googletest-download/CMakeLists.txt) -execute_process(COMMAND ${CMAKE_COMMAND} -G "${CMAKE_GENERATOR}" . RESULT_VARIABLE result1 WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/googletest-download) -execute_process(COMMAND ${CMAKE_COMMAND} --build . RESULT_VARIABLE result2 WORKING_DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/googletest-download) -if(result1 OR result2) - message(FATAL_ERROR "Preparing googletest failed: ${result1} ${result2}") -endif() - -# Add googletest, defines gtest and gtest_main targets -add_subdirectory(${CMAKE_CURRENT_BINARY_DIR}/googletest-src ${CMAKE_CURRENT_BINARY_DIR}/googletest-build EXCLUDE_FROM_ALL) diff --git a/src/lib/ecl/test/main.cpp b/src/lib/ecl/test/main.cpp deleted file mode 100644 index 02539d2e7b..0000000000 --- a/src/lib/ecl/test/main.cpp +++ /dev/null @@ -1,7 +0,0 @@ -#include - -int main(int argc, char **argv) { - testing::InitGoogleTest(&argc, argv); - std::cout << "Run ECL gtests" << std::endl; - return RUN_ALL_TESTS(); -} diff --git a/src/lib/ecl/tools/format.sh b/src/lib/ecl/tools/format.sh deleted file mode 100755 index da4c7620e4..0000000000 --- a/src/lib/ecl/tools/format.sh +++ /dev/null @@ -1,38 +0,0 @@ -#!/bin/bash -do_format=$1 -files_to_format=""" -EKF/AlphaFilter.hpp -EKF/RingBuffer.h -EKF/vel_pos_fusion.cpp -EKF/imu_down_sampler.*pp -mathlib/*.cpp -mathlib/*.h -""" -RED='\033[0;31m' -GREEN='\033[0;32m' -YELLOW='\033[1;33m' -NC='\033[0m' # No Color - -if ! hash clang-format-6.0 -then - echo -e ${RED}Error: No clang-format-6.0 installed${NC} - exit 1 -fi - -if [[ $do_format -eq 1 ]] -then - # formatting - clang-format-6.0 -i -style=file ${files_to_format} - echo -e ${GREEN}Formatting finished${NC} -else - # checking format... - clang-format-6.0 -style=file -output-replacements-xml ${files_to_format} | grep -c " /dev/null - if [[ $? -eq 0 ]] - then - echo -e ${RED}Error: need to format${NC} - echo -e ${YELLOW}From cmake build directory run: 'make format'${NC} - exit 1 - fi - echo -e ${GREEN}no formatting needed${NC} - exit 0 -fi diff --git a/src/lib/geo/CMakeLists.txt b/src/lib/geo/CMakeLists.txt index 149af1f80a..9f353d92f2 100644 --- a/src/lib/geo/CMakeLists.txt +++ b/src/lib/geo/CMakeLists.txt @@ -39,6 +39,4 @@ add_dependencies(geo prebuild_targets) target_compile_options(geo PRIVATE ${MAX_CUSTOM_OPT_LEVEL}) target_link_libraries(geo PRIVATE m) -if(CMAKE_PROJECT_NAME MATCHES "px4") # temporary - px4_add_unit_gtest(SRC test_geo.cpp LINKLIBS geo) -endif() +px4_add_unit_gtest(SRC test_geo.cpp LINKLIBS geo) diff --git a/src/lib/world_magnetic_model/CMakeLists.txt b/src/lib/world_magnetic_model/CMakeLists.txt index 07d56ecc98..1295d42b01 100644 --- a/src/lib/world_magnetic_model/CMakeLists.txt +++ b/src/lib/world_magnetic_model/CMakeLists.txt @@ -39,7 +39,5 @@ add_library(world_magnetic_model add_dependencies(world_magnetic_model prebuild_targets) target_compile_options(world_magnetic_model PRIVATE ${MAX_CUSTOM_OPT_LEVEL}) -if(CMAKE_PROJECT_NAME MATCHES "px4") # temporary - add_compile_options(-Wno-double-promotion) - px4_add_unit_gtest(SRC test_geo_lookup.cpp LINKLIBS world_magnetic_model) -endif() +add_compile_options(-Wno-double-promotion) +px4_add_unit_gtest(SRC test_geo_lookup.cpp LINKLIBS world_magnetic_model) diff --git a/src/modules/ekf2/CMakeLists.txt b/src/modules/ekf2/CMakeLists.txt index b778949948..9a54b1cbc2 100644 --- a/src/modules/ekf2/CMakeLists.txt +++ b/src/modules/ekf2/CMakeLists.txt @@ -38,15 +38,47 @@ px4_add_module( MAIN ekf2 COMPILE_FLAGS ${MAX_CUSTOM_OPT_LEVEL} + -fno-associative-math + INCLUDES + EKF + STACK_MAX + 3500 SRCS + EKF/airspeed_fusion.cpp + EKF/control.cpp + EKF/covariance.cpp + EKF/drag_fusion.cpp + EKF/ekf.cpp + EKF/ekf_helper.cpp + EKF/EKFGSF_yaw.cpp + EKF/estimator_interface.cpp + EKF/gps_checks.cpp + EKF/gps_yaw_fusion.cpp + EKF/imu_down_sampler.cpp + EKF/mag_control.cpp + EKF/mag_fusion.cpp + EKF/optflow_fusion.cpp + EKF/sensor_range_finder.cpp + EKF/sideslip_fusion.cpp + EKF/terrain_estimator.cpp + EKF/utils.cpp + EKF/vel_pos_fusion.cpp + EKF2.cpp EKF2.hpp EKF2Selector.cpp EKF2Selector.hpp + DEPENDS - ecl_EKF geo perf EKF2Utility px4_work_queue + world_magnetic_model + UNITY_BUILD ) + +if(BUILD_TESTING) + add_subdirectory(EKF) + add_subdirectory(test) +endif() diff --git a/src/lib/ecl/EKF/CMakeLists.txt b/src/modules/ekf2/EKF/CMakeLists.txt similarity index 91% rename from src/lib/ecl/EKF/CMakeLists.txt rename to src/modules/ekf2/EKF/CMakeLists.txt index 99bcf3b791..4a47e3d3a0 100644 --- a/src/lib/ecl/EKF/CMakeLists.txt +++ b/src/modules/ekf2/EKF/CMakeLists.txt @@ -34,30 +34,25 @@ add_library(ecl_EKF airspeed_fusion.cpp control.cpp - mag_control.cpp covariance.cpp drag_fusion.cpp ekf.cpp ekf_helper.cpp + EKFGSF_yaw.cpp estimator_interface.cpp gps_checks.cpp - mag_fusion.cpp - optflow_fusion.cpp - sideslip_fusion.cpp - terrain_estimator.cpp - vel_pos_fusion.cpp gps_yaw_fusion.cpp imu_down_sampler.cpp - EKFGSF_yaw.cpp + mag_control.cpp + mag_fusion.cpp + optflow_fusion.cpp sensor_range_finder.cpp + sideslip_fusion.cpp + terrain_estimator.cpp utils.cpp + vel_pos_fusion.cpp ) add_dependencies(ecl_EKF prebuild_targets) -target_compile_definitions(ecl_EKF PRIVATE -DMODULE_NAME="ecl/EKF") -target_include_directories(ecl_EKF PUBLIC ${ECL_SOURCE_DIR}) target_link_libraries(ecl_EKF PRIVATE geo world_magnetic_model) - -set_target_properties(ecl_EKF PROPERTIES PUBLIC_HEADER "ekf.h") - target_compile_options(ecl_EKF PRIVATE -fno-associative-math) diff --git a/src/lib/ecl/EKF/EKFGSF_yaw.cpp b/src/modules/ekf2/EKF/EKFGSF_yaw.cpp similarity index 100% rename from src/lib/ecl/EKF/EKFGSF_yaw.cpp rename to src/modules/ekf2/EKF/EKFGSF_yaw.cpp diff --git a/src/lib/ecl/EKF/EKFGSF_yaw.h b/src/modules/ekf2/EKF/EKFGSF_yaw.h similarity index 98% rename from src/lib/ecl/EKF/EKFGSF_yaw.h rename to src/modules/ekf2/EKF/EKFGSF_yaw.h index ea9e8ca136..60d5556953 100644 --- a/src/lib/ecl/EKF/EKFGSF_yaw.h +++ b/src/modules/ekf2/EKF/EKFGSF_yaw.h @@ -1,4 +1,5 @@ -#pragma once +#ifndef EKF_EKFGSF_YAW_H +#define EKF_EKFGSF_YAW_H #include #include @@ -133,3 +134,4 @@ private: // return the probability of the state estimate for the specified EKF assuming a gaussian error distribution float gaussianDensity(const uint8_t model_index) const; }; +#endif // !EKF_EKFGSF_YAW_H diff --git a/src/lib/ecl/EKF/RingBuffer.h b/src/modules/ekf2/EKF/RingBuffer.h similarity index 99% rename from src/lib/ecl/EKF/RingBuffer.h rename to src/modules/ekf2/EKF/RingBuffer.h index bc36fcb120..512b3a6b6a 100644 --- a/src/lib/ecl/EKF/RingBuffer.h +++ b/src/modules/ekf2/EKF/RingBuffer.h @@ -70,7 +70,7 @@ public: delete[] _buffer; } - _buffer = new data_type[size]{}; + _buffer = new data_type[size] {}; if (_buffer == nullptr) { return false; diff --git a/src/lib/ecl/EKF/Sensor.hpp b/src/modules/ekf2/EKF/Sensor.hpp similarity index 96% rename from src/lib/ecl/EKF/Sensor.hpp rename to src/modules/ekf2/EKF/Sensor.hpp index a3fe91c8fe..5f18340c77 100644 --- a/src/lib/ecl/EKF/Sensor.hpp +++ b/src/modules/ekf2/EKF/Sensor.hpp @@ -39,7 +39,8 @@ * */ -#pragma once +#ifndef EKF_SENSOR_HPP +#define EKF_SENSOR_HPP #include "common.h" @@ -58,7 +59,7 @@ public: * this has to be called immediately after * setting new data */ - virtual void runChecks(){}; + virtual void runChecks() {}; /* * return true if the sensor is healthy @@ -80,3 +81,4 @@ public: } // namespace sensor } // namespace estimator +#endif // !EKF_SENSOR_HPP diff --git a/src/lib/ecl/EKF/airspeed_fusion.cpp b/src/modules/ekf2/EKF/airspeed_fusion.cpp similarity index 99% rename from src/lib/ecl/EKF/airspeed_fusion.cpp rename to src/modules/ekf2/EKF/airspeed_fusion.cpp index 129dcf0970..d9bad18211 100644 --- a/src/lib/ecl/EKF/airspeed_fusion.cpp +++ b/src/modules/ekf2/EKF/airspeed_fusion.cpp @@ -41,7 +41,7 @@ * @author Paul Riseborough * */ -#include "../ecl.h" + #include "ekf.h" #include diff --git a/src/lib/ecl/EKF/common.h b/src/modules/ekf2/EKF/common.h similarity index 99% rename from src/lib/ecl/EKF/common.h rename to src/modules/ekf2/EKF/common.h index 893dda0299..933a0004bb 100644 --- a/src/lib/ecl/EKF/common.h +++ b/src/modules/ekf2/EKF/common.h @@ -39,7 +39,8 @@ * @author Siddharth Bharat Purohit * */ -#pragma once +#ifndef EKF_COMMON_H +#define EKF_COMMON_H #include @@ -552,3 +553,4 @@ union warning_event_status_u { }; } +#endif // !EKF_COMMON_H diff --git a/src/lib/ecl/EKF/control.cpp b/src/modules/ekf2/EKF/control.cpp similarity index 99% rename from src/lib/ecl/EKF/control.cpp rename to src/modules/ekf2/EKF/control.cpp index 528391b8e0..5eb8796c26 100644 --- a/src/lib/ecl/EKF/control.cpp +++ b/src/modules/ekf2/EKF/control.cpp @@ -39,7 +39,7 @@ * */ -#include "../ecl.h" + #include "ekf.h" #include @@ -100,7 +100,7 @@ void Ekf::controlFusionModes() // if enabled, use knowledge of theoretical magnetic field vector to calculate a synthetic magnetomter Z component value. // this is useful if there is a lot of interference on the sensor measurement. - if (_params.synthesize_mag_z && (_params.mag_declination_source & MASK_USE_GEO_DECL) && (_NED_origin_initialised || ISFINITE(_mag_declination_gps))) { + if (_params.synthesize_mag_z && (_params.mag_declination_source & MASK_USE_GEO_DECL) && (_NED_origin_initialised || PX4_ISFINITE(_mag_declination_gps))) { const Vector3f mag_earth_pred = Dcmf(Eulerf(0, -_mag_inclination_gps, _mag_declination_gps)) * Vector3f(_mag_strength_gps, 0, 0); _mag_sample_delayed.mag(2) = calculate_synthetic_mag_z_measurement(_mag_sample_delayed.mag, mag_earth_pred); _control_status.flags.synthetic_mag_z = true; @@ -738,7 +738,7 @@ void Ekf::controlGpsYawFusion(bool gps_checks_passing, bool gps_checks_failing) return; } - const bool is_new_data_available = ISFINITE(_gps_sample_delayed.yaw); + const bool is_new_data_available = PX4_ISFINITE(_gps_sample_delayed.yaw); if (is_new_data_available) { diff --git a/src/lib/ecl/EKF/covariance.cpp b/src/modules/ekf2/EKF/covariance.cpp similarity index 99% rename from src/lib/ecl/EKF/covariance.cpp rename to src/modules/ekf2/EKF/covariance.cpp index b44b09e556..c73471ebcd 100644 --- a/src/lib/ecl/EKF/covariance.cpp +++ b/src/modules/ekf2/EKF/covariance.cpp @@ -44,7 +44,6 @@ #include "ekf.h" #include "utils.hpp" -#include #include #include diff --git a/src/lib/ecl/EKF/documentation/Output Predictor.pdf b/src/modules/ekf2/EKF/documentation/Output Predictor.pdf similarity index 100% rename from src/lib/ecl/EKF/documentation/Output Predictor.pdf rename to src/modules/ekf2/EKF/documentation/Output Predictor.pdf diff --git a/src/lib/ecl/EKF/documentation/Process and Observation Models.pdf b/src/modules/ekf2/EKF/documentation/Process and Observation Models.pdf similarity index 100% rename from src/lib/ecl/EKF/documentation/Process and Observation Models.pdf rename to src/modules/ekf2/EKF/documentation/Process and Observation Models.pdf diff --git a/src/lib/ecl/EKF/documentation/Reference List.pdf b/src/modules/ekf2/EKF/documentation/Reference List.pdf similarity index 100% rename from src/lib/ecl/EKF/documentation/Reference List.pdf rename to src/modules/ekf2/EKF/documentation/Reference List.pdf diff --git a/src/lib/ecl/EKF/documentation/readme.txt b/src/modules/ekf2/EKF/documentation/readme.txt similarity index 100% rename from src/lib/ecl/EKF/documentation/readme.txt rename to src/modules/ekf2/EKF/documentation/readme.txt diff --git a/src/lib/ecl/EKF/drag_fusion.cpp b/src/modules/ekf2/EKF/drag_fusion.cpp similarity index 99% rename from src/lib/ecl/EKF/drag_fusion.cpp rename to src/modules/ekf2/EKF/drag_fusion.cpp index 89d1c4a380..754a81e794 100644 --- a/src/lib/ecl/EKF/drag_fusion.cpp +++ b/src/modules/ekf2/EKF/drag_fusion.cpp @@ -41,7 +41,7 @@ */ #include "ekf.h" -#include + #include void Ekf::fuseDrag() diff --git a/src/lib/ecl/EKF/ekf.cpp b/src/modules/ekf2/EKF/ekf.cpp similarity index 99% rename from src/lib/ecl/EKF/ekf.cpp rename to src/modules/ekf2/EKF/ekf.cpp index 72b705da7e..6db8ebb4f7 100644 --- a/src/lib/ecl/EKF/ekf.cpp +++ b/src/modules/ekf2/EKF/ekf.cpp @@ -41,7 +41,6 @@ #include "ekf.h" -#include #include bool Ekf::init(uint64_t timestamp) diff --git a/src/lib/ecl/EKF/ekf.h b/src/modules/ekf2/EKF/ekf.h similarity index 99% rename from src/lib/ecl/EKF/ekf.h rename to src/modules/ekf2/EKF/ekf.h index 1f08c143d2..c6bf119f06 100644 --- a/src/lib/ecl/EKF/ekf.h +++ b/src/modules/ekf2/EKF/ekf.h @@ -40,7 +40,8 @@ * */ -#pragma once +#ifndef EKF_EKF_H +#define EKF_EKF_H #include "estimator_interface.h" @@ -993,3 +994,4 @@ private: void resetGpsDriftCheckFilters(); }; +#endif // !EKF_EKF_H diff --git a/src/lib/ecl/EKF/ekf_helper.cpp b/src/modules/ekf2/EKF/ekf_helper.cpp similarity index 99% rename from src/lib/ecl/EKF/ekf_helper.cpp rename to src/modules/ekf2/EKF/ekf_helper.cpp index 03ef4d51b6..5449bf611c 100644 --- a/src/lib/ecl/EKF/ekf_helper.cpp +++ b/src/modules/ekf2/EKF/ekf_helper.cpp @@ -41,11 +41,9 @@ #include "ekf.h" -#include #include #include - void Ekf::resetVelocity() { if (_control_status.flags.gps && isTimedOut(_last_gps_fail_us, (uint64_t)_min_gps_health_time_us)) { @@ -547,7 +545,7 @@ float Ekf::getMagDeclination() } else if (_params.mag_declination_source & MASK_USE_GEO_DECL) { // use parameter value until GPS is available, then use value returned by geo library - if (_NED_origin_initialised || ISFINITE(_mag_declination_gps)) { + if (_NED_origin_initialised || PX4_ISFINITE(_mag_declination_gps)) { return _mag_declination_gps; } else { @@ -1691,7 +1689,7 @@ void Ekf::runYawEKFGSF() // basic sanity check on GPS velocity data if (_gps_data_ready && _gps_sample_delayed.vacc > FLT_EPSILON && - ISFINITE(_gps_sample_delayed.vel(0)) && ISFINITE(_gps_sample_delayed.vel(1))) { + PX4_ISFINITE(_gps_sample_delayed.vel(0)) && PX4_ISFINITE(_gps_sample_delayed.vel(1))) { _yawEstimator.setVelocity(_gps_sample_delayed.vel.xy(), _gps_sample_delayed.vacc); } } diff --git a/src/lib/ecl/EKF/estimator_interface.cpp b/src/modules/ekf2/EKF/estimator_interface.cpp similarity index 99% rename from src/lib/ecl/EKF/estimator_interface.cpp rename to src/modules/ekf2/EKF/estimator_interface.cpp index 4736569ac3..6562d9a73b 100644 --- a/src/lib/ecl/EKF/estimator_interface.cpp +++ b/src/modules/ekf2/EKF/estimator_interface.cpp @@ -42,7 +42,6 @@ #include "estimator_interface.h" -#include #include // Accumulate imu data and store to buffer at desired rate @@ -206,7 +205,7 @@ void EstimatorInterface::setGpsData(const gps_message &gps) gps_sample_new.yaw = gps.yaw; - if (ISFINITE(gps.yaw_offset)) { + if (PX4_ISFINITE(gps.yaw_offset)) { _gps_yaw_offset = gps.yaw_offset; } else { diff --git a/src/lib/ecl/EKF/estimator_interface.h b/src/modules/ekf2/EKF/estimator_interface.h similarity index 97% rename from src/lib/ecl/EKF/estimator_interface.h rename to src/modules/ekf2/EKF/estimator_interface.h index a6dc866606..d9ba423043 100644 --- a/src/lib/ecl/EKF/estimator_interface.h +++ b/src/modules/ekf2/EKF/estimator_interface.h @@ -39,9 +39,20 @@ * */ -#pragma once +#ifndef EKF_ESTIMATOR_INTERFACE_H +#define EKF_ESTIMATOR_INTERFACE_H + +#if defined(MODULE_NAME) +# define ECL_INFO PX4_DEBUG +# define ECL_WARN PX4_DEBUG +# define ECL_ERR PX4_DEBUG +#else +# define ECL_INFO(X, ...) printf(X "\n", ##__VA_ARGS__) +# define ECL_WARN(X, ...) fprintf(stderr, X "\n", ##__VA_ARGS__) +# define ECL_ERR(X, ...) fprintf(stderr, X "\n", ##__VA_ARGS__) + +#endif -#include #include "common.h" #include "RingBuffer.h" #include "imu_down_sampler.hpp" @@ -106,7 +117,7 @@ public: } // return true if the attitude is usable - bool attitude_valid() const { return ISFINITE(_output_new.quat_nominal(0)) && _control_status.flags.tilt_align; } + bool attitude_valid() const { return PX4_ISFINITE(_output_new.quat_nominal(0)) && _control_status.flags.tilt_align; } // get vehicle landed status data bool get_in_air_status() const { return _control_status.flags.in_air; } @@ -441,3 +452,4 @@ private: bool _auxvel_buffer_fail{false}; }; +#endif // !EKF_ESTIMATOR_INTERFACE_H diff --git a/src/lib/ecl/EKF/gps_checks.cpp b/src/modules/ekf2/EKF/gps_checks.cpp similarity index 98% rename from src/lib/ecl/EKF/gps_checks.cpp rename to src/modules/ekf2/EKF/gps_checks.cpp index a709a54c3d..35c4454361 100644 --- a/src/lib/ecl/EKF/gps_checks.cpp +++ b/src/modules/ekf2/EKF/gps_checks.cpp @@ -41,7 +41,6 @@ #include "ekf.h" -#include #include #include @@ -84,7 +83,7 @@ bool Ekf::collect_gps(const gps_message &gps) _earth_rate_NED = calcEarthRateNED((float)_pos_ref.lat_rad); _last_gps_origin_time_us = _time_last_imu; - const bool declination_was_valid = ISFINITE(_mag_declination_gps); + const bool declination_was_valid = PX4_ISFINITE(_mag_declination_gps); // set the magnetic field data returned by the geo library using the current GPS position _mag_declination_gps = get_mag_declination_radians(lat, lon); @@ -119,7 +118,7 @@ bool Ekf::collect_gps(const gps_message &gps) // a rough 2D fix is still sufficient to lookup declination if ((gps.fix_type >= 2) && (gps.eph < 1000)) { - const bool declination_was_valid = ISFINITE(_mag_declination_gps); + const bool declination_was_valid = PX4_ISFINITE(_mag_declination_gps); // If we have good GPS data set the origin's WGS-84 position to the last gps fix const double lat = gps.lat * 1.0e-7; @@ -132,7 +131,7 @@ bool Ekf::collect_gps(const gps_message &gps) // request mag yaw reset if there's a mag declination for the first time if (_params.mag_fusion_type != MAG_FUSE_TYPE_NONE) { - if (!declination_was_valid && ISFINITE(_mag_declination_gps)) { + if (!declination_was_valid && PX4_ISFINITE(_mag_declination_gps)) { _mag_yaw_reset_req = true; } } diff --git a/src/lib/ecl/EKF/gps_yaw_fusion.cpp b/src/modules/ekf2/EKF/gps_yaw_fusion.cpp similarity index 99% rename from src/lib/ecl/EKF/gps_yaw_fusion.cpp rename to src/modules/ekf2/EKF/gps_yaw_fusion.cpp index dbf3205318..dd18df4c1a 100644 --- a/src/lib/ecl/EKF/gps_yaw_fusion.cpp +++ b/src/modules/ekf2/EKF/gps_yaw_fusion.cpp @@ -42,7 +42,6 @@ #include "ekf.h" -#include #include #include diff --git a/src/lib/ecl/EKF/imu_down_sampler.cpp b/src/modules/ekf2/EKF/imu_down_sampler.cpp similarity index 98% rename from src/lib/ecl/EKF/imu_down_sampler.cpp rename to src/modules/ekf2/EKF/imu_down_sampler.cpp index 265671e3b4..c1f6817040 100644 --- a/src/lib/ecl/EKF/imu_down_sampler.cpp +++ b/src/modules/ekf2/EKF/imu_down_sampler.cpp @@ -39,7 +39,7 @@ bool ImuDownSampler::update(const imuSample &imu_sample_new) // average EKF update rate requirement _imu_collection_time_adj += 0.01f * (_imu_down_sampled.delta_ang_dt - _target_dt); _imu_collection_time_adj = math::constrain(_imu_collection_time_adj, -0.5f * _target_dt, - 0.5f * _target_dt); + 0.5f * _target_dt); _imu_down_sampled.delta_ang = AxisAnglef(_delta_angle_accumulated); diff --git a/src/lib/ecl/EKF/imu_down_sampler.hpp b/src/modules/ekf2/EKF/imu_down_sampler.hpp similarity index 96% rename from src/lib/ecl/EKF/imu_down_sampler.hpp rename to src/modules/ekf2/EKF/imu_down_sampler.hpp index 17cdaf27d4..e9944718dd 100644 --- a/src/lib/ecl/EKF/imu_down_sampler.hpp +++ b/src/modules/ekf2/EKF/imu_down_sampler.hpp @@ -35,7 +35,8 @@ * Downsamples IMU data to a lower rate such that EKF predicition can happen less frequent * @author Kamil Ritz */ -#pragma once +#ifndef EKF_IMU_DOWN_SAMPLER_HPP +#define EKF_IMU_DOWN_SAMPLER_HPP #include #include @@ -67,3 +68,4 @@ private: float _imu_collection_time_adj{0.f}; bool _do_reset{true}; }; +#endif // !EKF_IMU_DOWN_SAMPLER_HPP diff --git a/src/lib/ecl/EKF/mag_control.cpp b/src/modules/ekf2/EKF/mag_control.cpp similarity index 100% rename from src/lib/ecl/EKF/mag_control.cpp rename to src/modules/ekf2/EKF/mag_control.cpp diff --git a/src/lib/ecl/EKF/mag_fusion.cpp b/src/modules/ekf2/EKF/mag_fusion.cpp similarity index 99% rename from src/lib/ecl/EKF/mag_fusion.cpp rename to src/modules/ekf2/EKF/mag_fusion.cpp index 5a799f8119..36eefd6c04 100644 --- a/src/lib/ecl/EKF/mag_fusion.cpp +++ b/src/modules/ekf2/EKF/mag_fusion.cpp @@ -42,7 +42,7 @@ */ #include "ekf.h" -#include + #include void Ekf::fuseMag() @@ -905,7 +905,7 @@ void Ekf::limitDeclination() float h_field_min = 0.001f; if (_params.mag_declination_source & MASK_USE_GEO_DECL) { // use parameter value until GPS is available, then use value returned by geo library - if (_NED_origin_initialised || ISFINITE(_mag_declination_gps)) { + if (_NED_origin_initialised || PX4_ISFINITE(_mag_declination_gps)) { decl_reference = _mag_declination_gps; h_field_min = fmaxf(h_field_min , 0.5f * _mag_strength_gps * cosf(_mag_inclination_gps)); diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/AlignTilt.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/AlignTilt.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/AlignTilt.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/AlignTilt.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/ConvertToC.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/ConvertToC.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/ConvertToC.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/ConvertToC.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/ConvertToM.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/ConvertToM.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/ConvertToM.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/ConvertToM.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/EulToQuat.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/EulToQuat.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/EulToQuat.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/EulToQuat.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/LLH2NED.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/LLH2NED.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/LLH2NED.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/LLH2NED.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/NormQuat.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/NormQuat.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/NormQuat.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/NormQuat.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/OptimiseAlgebra.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/OptimiseAlgebra.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/OptimiseAlgebra.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/OptimiseAlgebra.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/Quat2Tbn.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/Quat2Tbn.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/Quat2Tbn.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/Quat2Tbn.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/QuatDivide.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/QuatDivide.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/QuatDivide.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/QuatDivide.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/QuatMult.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/QuatMult.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/QuatMult.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/QuatMult.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/QuatToEul.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/QuatToEul.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/QuatToEul.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/QuatToEul.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/RotToQuat.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/RotToQuat.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/RotToQuat.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/RotToQuat.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_apm_data.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_apm_data.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_apm_data.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_apm_data.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_actuators_csv_data.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_actuators_csv_data.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_actuators_csv_data.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_actuators_csv_data.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_distance_sensor_csv_data.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_distance_sensor_csv_data.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_distance_sensor_csv_data.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_distance_sensor_csv_data.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_groundtruth_csv_data.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_groundtruth_csv_data.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_groundtruth_csv_data.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_groundtruth_csv_data.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_optical_flow_csv_data.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_optical_flow_csv_data.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_optical_flow_csv_data.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_optical_flow_csv_data.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_sensor_combined_csv_data.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_sensor_combined_csv_data.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_sensor_combined_csv_data.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_sensor_combined_csv_data.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_vehicle_gps_position_csv.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_vehicle_gps_position_csv.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Common/convert_px4_vehicle_gps_position_csv.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Common/convert_px4_vehicle_gps_position_csv.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/AlignHeading.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/AlignHeading.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/AlignHeading.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/AlignHeading.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/ConstrainStates.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/ConstrainStates.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/ConstrainStates.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/ConstrainStates.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseBaroHeight.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseBaroHeight.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseBaroHeight.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseBaroHeight.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseBodyVel.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseBodyVel.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseBodyVel.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseBodyVel.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseMagDeclination.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseMagDeclination.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseMagDeclination.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseMagDeclination.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseMagHeading.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseMagHeading.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseMagHeading.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseMagHeading.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseMagnetometer.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseMagnetometer.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseMagnetometer.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseMagnetometer.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseOpticalFlow.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseOpticalFlow.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseOpticalFlow.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseOpticalFlow.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/FusePosition.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FusePosition.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/FusePosition.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FusePosition.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseVelocity.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseVelocity.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/FuseVelocity.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/FuseVelocity.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/GenerateEquations24.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/GenerateEquations24.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/GenerateEquations24.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/GenerateEquations24.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/InitCovariance.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/InitCovariance.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/InitCovariance.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/InitCovariance.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/InitStates.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/InitStates.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/InitStates.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/InitStates.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/PlotData.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/PlotData.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/PlotData.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/PlotData.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/PredictCovariance.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/PredictCovariance.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/PredictCovariance.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/PredictCovariance.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/PredictStates.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/PredictStates.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/PredictStates.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/PredictStates.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/RunFilter.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/RunFilter.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/RunFilter.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/RunFilter.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/SetParameterDefaults.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/SetParameterDefaults.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/SetParameterDefaults.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/SetParameterDefaults.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/SetParameters.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/SetParameters.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/SetParameters.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/SetParameters.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcF24.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcF24.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcF24.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcF24.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_HDG.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_HDG.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_HDG.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_HDG.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_LOSX.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_LOSX.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_LOSX.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_LOSX.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_LOSY.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_LOSY.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_LOSY.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_LOSY.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_MAGD.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_MAGD.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_MAGD.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_MAGD.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_MAGX.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_MAGX.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_MAGX.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_MAGX.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_MAGY.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_MAGY.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_MAGY.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_MAGY.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_MAGZ.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_MAGZ.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_MAGZ.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_MAGZ.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_VELX.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_VELX.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_VELX.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_VELX.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_VELY.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_VELY.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_VELY.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_VELY.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_VELZ.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_VELZ.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcH_VELZ.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcH_VELZ.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcQ24.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcQ24.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/calcQ24.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/calcQ24.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/find_best_gps_delay.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/find_best_gps_delay.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/find_best_gps_delay.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/find_best_gps_delay.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/quat_to_euler_error_transfer_matrix.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/quat_to_euler_error_transfer_matrix.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/quat_to_euler_error_transfer_matrix.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/quat_to_euler_error_transfer_matrix.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/replay_apm_data.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/replay_apm_data.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/replay_apm_data.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/replay_apm_data.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/replay_px4_data.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/replay_px4_data.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/replay_px4_data.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/replay_px4_data.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/replay_px4_optflow_data.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/replay_px4_optflow_data.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/replay_px4_optflow_data.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/replay_px4_optflow_data.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/Filter/transfer_matrix.m b/src/modules/ekf2/EKF/matlab/EKF_replay/Filter/transfer_matrix.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/Filter/transfer_matrix.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/Filter/transfer_matrix.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/SensorCalibration/allan.m b/src/modules/ekf2/EKF/matlab/EKF_replay/SensorCalibration/allan.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/SensorCalibration/allan.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/SensorCalibration/allan.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/SensorCalibration/compare_mag_calibration.m b/src/modules/ekf2/EKF/matlab/EKF_replay/SensorCalibration/compare_mag_calibration.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/SensorCalibration/compare_mag_calibration.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/SensorCalibration/compare_mag_calibration.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/SensorCalibration/ellipsoid_fit.m b/src/modules/ekf2/EKF/matlab/EKF_replay/SensorCalibration/ellipsoid_fit.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/SensorCalibration/ellipsoid_fit.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/SensorCalibration/ellipsoid_fit.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/px4_replay_import.m b/src/modules/ekf2/EKF/matlab/EKF_replay/px4_replay_import.m similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/px4_replay_import.m rename to src/modules/ekf2/EKF/matlab/EKF_replay/px4_replay_import.m diff --git a/src/lib/ecl/EKF/matlab/EKF_replay/readme.txt b/src/modules/ekf2/EKF/matlab/EKF_replay/readme.txt similarity index 100% rename from src/lib/ecl/EKF/matlab/EKF_replay/readme.txt rename to src/modules/ekf2/EKF/matlab/EKF_replay/readme.txt diff --git a/src/lib/ecl/EKF/matlab/README.md b/src/modules/ekf2/EKF/matlab/README.md similarity index 100% rename from src/lib/ecl/EKF/matlab/README.md rename to src/modules/ekf2/EKF/matlab/README.md diff --git a/src/lib/ecl/EKF/matlab/analysis/estimatorLogViewerPX4.m b/src/modules/ekf2/EKF/matlab/analysis/estimatorLogViewerPX4.m similarity index 100% rename from src/lib/ecl/EKF/matlab/analysis/estimatorLogViewerPX4.m rename to src/modules/ekf2/EKF/matlab/analysis/estimatorLogViewerPX4.m diff --git a/src/lib/ecl/EKF/matlab/analysis/importPX4log.m b/src/modules/ekf2/EKF/matlab/analysis/importPX4log.m similarity index 100% rename from src/lib/ecl/EKF/matlab/analysis/importPX4log.m rename to src/modules/ekf2/EKF/matlab/analysis/importPX4log.m diff --git a/src/lib/ecl/EKF/matlab/analysis/usageSamples.m b/src/modules/ekf2/EKF/matlab/analysis/usageSamples.m similarity index 100% rename from src/lib/ecl/EKF/matlab/analysis/usageSamples.m rename to src/modules/ekf2/EKF/matlab/analysis/usageSamples.m diff --git a/src/lib/ecl/EKF/matlab/scripts/Terrain Estimator/GenerateEquationsTerrainEstimator.m b/src/modules/ekf2/EKF/matlab/scripts/Terrain Estimator/GenerateEquationsTerrainEstimator.m similarity index 100% rename from src/lib/ecl/EKF/matlab/scripts/Terrain Estimator/GenerateEquationsTerrainEstimator.m rename to src/modules/ekf2/EKF/matlab/scripts/Terrain Estimator/GenerateEquationsTerrainEstimator.m diff --git a/src/lib/ecl/EKF/matlab/scripts/Terrain Estimator/H_OPT.c b/src/modules/ekf2/EKF/matlab/scripts/Terrain Estimator/H_OPT.c similarity index 100% rename from src/lib/ecl/EKF/matlab/scripts/Terrain Estimator/H_OPT.c rename to src/modules/ekf2/EKF/matlab/scripts/Terrain Estimator/H_OPT.c diff --git a/src/lib/ecl/EKF/matlab/scripts/Terrain Estimator/H_RNG.c b/src/modules/ekf2/EKF/matlab/scripts/Terrain Estimator/H_RNG.c similarity index 100% rename from src/lib/ecl/EKF/matlab/scripts/Terrain Estimator/H_RNG.c rename to src/modules/ekf2/EKF/matlab/scripts/Terrain Estimator/H_RNG.c diff --git a/src/lib/ecl/EKF/optflow_fusion.cpp b/src/modules/ekf2/EKF/optflow_fusion.cpp similarity index 98% rename from src/lib/ecl/EKF/optflow_fusion.cpp rename to src/modules/ekf2/EKF/optflow_fusion.cpp index a5b5415c28..109d3f2a01 100644 --- a/src/lib/ecl/EKF/optflow_fusion.cpp +++ b/src/modules/ekf2/EKF/optflow_fusion.cpp @@ -42,7 +42,7 @@ */ #include "ekf.h" -#include + #include #include #include "utils.hpp" @@ -339,7 +339,7 @@ bool Ekf::calcOptFlowBodyRateComp() return false; } - const bool use_flow_sensor_gyro = ISFINITE(_flow_sample_delayed.gyro_xyz(0)) && ISFINITE(_flow_sample_delayed.gyro_xyz(1)) && ISFINITE(_flow_sample_delayed.gyro_xyz(2)); + const bool use_flow_sensor_gyro = PX4_ISFINITE(_flow_sample_delayed.gyro_xyz(0)) && PX4_ISFINITE(_flow_sample_delayed.gyro_xyz(1)) && PX4_ISFINITE(_flow_sample_delayed.gyro_xyz(2)); if (use_flow_sensor_gyro) { diff --git a/src/lib/ecl/EKF/python/ekf_derivation/.gitignore b/src/modules/ekf2/EKF/python/ekf_derivation/.gitignore similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/.gitignore rename to src/modules/ekf2/EKF/python/ekf_derivation/.gitignore diff --git a/src/lib/ecl/EKF/python/ekf_derivation/__init__.py b/src/modules/ekf2/EKF/python/ekf_derivation/__init__.py similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/__init__.py rename to src/modules/ekf2/EKF/python/ekf_derivation/__init__.py diff --git a/src/lib/ecl/EKF/python/ekf_derivation/code_gen.py b/src/modules/ekf2/EKF/python/ekf_derivation/code_gen.py similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/code_gen.py rename to src/modules/ekf2/EKF/python/ekf_derivation/code_gen.py diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/3Dmag_fusion_generated_compare.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/3Dmag_fusion_generated_compare.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/3Dmag_fusion_generated_compare.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/3Dmag_fusion_generated_compare.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/3Dmag_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/3Dmag_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/3Dmag_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/3Dmag_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/3Dmag_generated_alt.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/3Dmag_generated_alt.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/3Dmag_generated_alt.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/3Dmag_generated_alt.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/3Dmag_innov_var_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/3Dmag_innov_var_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/3Dmag_innov_var_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/3Dmag_innov_var_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/acc_bf_fusion_generated_compare.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/acc_bf_fusion_generated_compare.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/acc_bf_fusion_generated_compare.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/acc_bf_fusion_generated_compare.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/acc_bf_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/acc_bf_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/acc_bf_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/acc_bf_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/acc_bf_generated_alt.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/acc_bf_generated_alt.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/acc_bf_generated_alt.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/acc_bf_generated_alt.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/beta_fusion_generated_compare.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/beta_fusion_generated_compare.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/beta_fusion_generated_compare.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/beta_fusion_generated_compare.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/beta_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/beta_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/beta_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/beta_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/covariance_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/covariance_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/covariance_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/covariance_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/covariance_generated_compare.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/covariance_generated_compare.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/covariance_generated_compare.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/covariance_generated_compare.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/flow_fusion_generated_compare.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/flow_fusion_generated_compare.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/flow_fusion_generated_compare.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/flow_fusion_generated_compare.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/flow_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/flow_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/flow_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/flow_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/flow_generated_alt.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/flow_generated_alt.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/flow_generated_alt.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/flow_generated_alt.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/gps_yaw_fusion_generated_compare.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/gps_yaw_fusion_generated_compare.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/gps_yaw_fusion_generated_compare.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/gps_yaw_fusion_generated_compare.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/gps_yaw_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/gps_yaw_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/gps_yaw_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/gps_yaw_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/mag_decl_fusion_generated_compare.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/mag_decl_fusion_generated_compare.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/mag_decl_fusion_generated_compare.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/mag_decl_fusion_generated_compare.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/mag_decl_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/mag_decl_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/mag_decl_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/mag_decl_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/tas_fusion_generated_compare.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/tas_fusion_generated_compare.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/tas_fusion_generated_compare.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/tas_fusion_generated_compare.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/tas_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/tas_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/tas_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/tas_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/util.h b/src/modules/ekf2/EKF/python/ekf_derivation/generated/util.h similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/util.h rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/util.h diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/vel_bf_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/vel_bf_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/vel_bf_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/vel_bf_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/vel_bf_generated_alt.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/vel_bf_generated_alt.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/vel_bf_generated_alt.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/vel_bf_generated_alt.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/yaw_estimator_covariance_prediction_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_estimator_covariance_prediction_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/yaw_estimator_covariance_prediction_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_estimator_covariance_prediction_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/yaw_estimator_measurement_update_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_estimator_measurement_update_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/yaw_estimator_measurement_update_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_estimator_measurement_update_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/yaw_fusion_generated_compare.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_fusion_generated_compare.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/yaw_fusion_generated_compare.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_fusion_generated_compare.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/generated/yaw_generated.cpp b/src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_generated.cpp similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/generated/yaw_generated.cpp rename to src/modules/ekf2/EKF/python/ekf_derivation/generated/yaw_generated.cpp diff --git a/src/lib/ecl/EKF/python/ekf_derivation/main.py b/src/modules/ekf2/EKF/python/ekf_derivation/main.py similarity index 100% rename from src/lib/ecl/EKF/python/ekf_derivation/main.py rename to src/modules/ekf2/EKF/python/ekf_derivation/main.py diff --git a/src/lib/ecl/EKF/python/terrain_flow_derivation/derive_terrain_flow.py b/src/modules/ekf2/EKF/python/terrain_flow_derivation/derive_terrain_flow.py similarity index 100% rename from src/lib/ecl/EKF/python/terrain_flow_derivation/derive_terrain_flow.py rename to src/modules/ekf2/EKF/python/terrain_flow_derivation/derive_terrain_flow.py diff --git a/src/lib/ecl/EKF/python/wind_cov_init/derivation.py b/src/modules/ekf2/EKF/python/wind_cov_init/derivation.py similarity index 100% rename from src/lib/ecl/EKF/python/wind_cov_init/derivation.py rename to src/modules/ekf2/EKF/python/wind_cov_init/derivation.py diff --git a/src/lib/ecl/EKF/sensor_range_finder.cpp b/src/modules/ekf2/EKF/sensor_range_finder.cpp similarity index 100% rename from src/lib/ecl/EKF/sensor_range_finder.cpp rename to src/modules/ekf2/EKF/sensor_range_finder.cpp diff --git a/src/lib/ecl/EKF/sensor_range_finder.hpp b/src/modules/ekf2/EKF/sensor_range_finder.hpp similarity index 94% rename from src/lib/ecl/EKF/sensor_range_finder.hpp rename to src/modules/ekf2/EKF/sensor_range_finder.hpp index d0aa23e046..ea123805df 100644 --- a/src/lib/ecl/EKF/sensor_range_finder.hpp +++ b/src/modules/ekf2/EKF/sensor_range_finder.hpp @@ -38,7 +38,8 @@ * @author Mathieu Bresciani * */ -#pragma once +#ifndef EKF_SENSOR_RANGE_FINDER_HPP +#define EKF_SENSOR_RANGE_FINDER_HPP #include "Sensor.hpp" #include @@ -59,14 +60,15 @@ public: bool isDataHealthy() const override { return _is_sample_ready && _is_sample_valid; } bool isRegularlySendingData() const override { return _is_regularly_sending_data; } - void setSample(const rangeSample &sample) { + void setSample(const rangeSample &sample) + { _sample = sample; _is_sample_ready = true; } // This is required because of the ring buffer // TODO: move the ring buffer here - rangeSample* getSampleAddress() { return &_sample; } + rangeSample *getSampleAddress() { return &_sample; } void setPitchOffset(float new_pitch_offset) { @@ -79,12 +81,14 @@ public: void setCosMaxTilt(float cos_max_tilt) { _range_cos_max_tilt = cos_max_tilt; } - void setLimits(float min_distance, float max_distance) { + void setLimits(float min_distance, float max_distance) + { _rng_valid_min_val = min_distance; _rng_valid_max_val = max_distance; } - void setQualityHysteresis(float valid_quality_threshold_s){ + void setQualityHysteresis(float valid_quality_threshold_s) + { _quality_hyst_us = uint64_t(valid_quality_threshold_s * 1e6f); } @@ -157,3 +161,4 @@ private: } // namespace sensor } // namespace estimator +#endif // !EKF_SENSOR_RANGE_FINDER_HPP diff --git a/src/lib/ecl/EKF/sideslip_fusion.cpp b/src/modules/ekf2/EKF/sideslip_fusion.cpp similarity index 99% rename from src/lib/ecl/EKF/sideslip_fusion.cpp rename to src/modules/ekf2/EKF/sideslip_fusion.cpp index 2b966a1b72..d63ace44ba 100644 --- a/src/lib/ecl/EKF/sideslip_fusion.cpp +++ b/src/modules/ekf2/EKF/sideslip_fusion.cpp @@ -42,7 +42,7 @@ */ #include "ekf.h" -#include + #include void Ekf::fuseSideslip() diff --git a/src/lib/ecl/EKF/terrain_estimator.cpp b/src/modules/ekf2/EKF/terrain_estimator.cpp similarity index 99% rename from src/lib/ecl/EKF/terrain_estimator.cpp rename to src/modules/ekf2/EKF/terrain_estimator.cpp index 2657d8cd08..872e707299 100644 --- a/src/lib/ecl/EKF/terrain_estimator.cpp +++ b/src/modules/ekf2/EKF/terrain_estimator.cpp @@ -40,7 +40,7 @@ */ #include "ekf.h" -#include + #include bool Ekf::initHagl() diff --git a/src/lib/ecl/EKF/utils.cpp b/src/modules/ekf2/EKF/utils.cpp similarity index 64% rename from src/lib/ecl/EKF/utils.cpp rename to src/modules/ekf2/EKF/utils.cpp index e87566f391..c09f3b000d 100644 --- a/src/lib/ecl/EKF/utils.cpp +++ b/src/modules/ekf2/EKF/utils.cpp @@ -2,26 +2,26 @@ matrix::Dcmf taitBryan312ToRotMat(const matrix::Vector3f &rot312) { - // Calculate the frame2 to frame 1 rotation matrix from a 312 Tait-Bryan rotation sequence - const float c2 = cosf(rot312(2)); // third rotation is pitch - const float s2 = sinf(rot312(2)); - const float s1 = sinf(rot312(1)); // second rotation is roll - const float c1 = cosf(rot312(1)); - const float s0 = sinf(rot312(0)); // first rotation is yaw - const float c0 = cosf(rot312(0)); + // Calculate the frame2 to frame 1 rotation matrix from a 312 Tait-Bryan rotation sequence + const float c2 = cosf(rot312(2)); // third rotation is pitch + const float s2 = sinf(rot312(2)); + const float s1 = sinf(rot312(1)); // second rotation is roll + const float c1 = cosf(rot312(1)); + const float s0 = sinf(rot312(0)); // first rotation is yaw + const float c0 = cosf(rot312(0)); - matrix::Dcmf R; - R(0, 0) = c0 * c2 - s0 * s1 * s2; - R(1, 1) = c0 * c1; - R(2, 2) = c2 * c1; - R(0, 1) = -c1 * s0; - R(0, 2) = s2 * c0 + c2 * s1 * s0; - R(1, 0) = c2 * s0 + s2 * s1 * c0; - R(1, 2) = s0 * s2 - s1 * c0 * c2; - R(2, 0) = -s2 * c1; - R(2, 1) = s1; + matrix::Dcmf R; + R(0, 0) = c0 * c2 - s0 * s1 * s2; + R(1, 1) = c0 * c1; + R(2, 2) = c2 * c1; + R(0, 1) = -c1 * s0; + R(0, 2) = s2 * c0 + c2 * s1 * s0; + R(1, 0) = c2 * s0 + s2 * s1 * c0; + R(1, 2) = s0 * s2 - s1 * c0 * c2; + R(2, 0) = -s2 * c1; + R(2, 1) = s1; - return R; + return R; } float kahanSummation(float sum_previous, float input, float &accumulator) @@ -59,11 +59,13 @@ matrix::Dcmf quatToInverseRotMat(const matrix::Quatf &quat) return dcm; } -bool shouldUse321RotationSequence(const matrix::Dcmf& R) { +bool shouldUse321RotationSequence(const matrix::Dcmf &R) +{ return fabsf(R(2, 0)) < fabsf(R(2, 1)); } -float getEuler321Yaw(const matrix::Quatf& q) { +float getEuler321Yaw(const matrix::Quatf &q) +{ // Values from yaw_input_321.c file produced by // https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/quat2yaw321.m const float a = 2.f * (q(0) * q(3) + q(1) * q(2)); @@ -71,11 +73,13 @@ float getEuler321Yaw(const matrix::Quatf& q) { return atan2f(a, b); } -float getEuler321Yaw(const matrix::Dcmf& R) { +float getEuler321Yaw(const matrix::Dcmf &R) +{ return atan2f(R(1, 0), R(0, 0)); } -float getEuler312Yaw(const matrix::Quatf& q) { +float getEuler312Yaw(const matrix::Quatf &q) +{ // Values from yaw_input_312.c file produced by // https://github.com/PX4/ecl/blob/master/matlab/scripts/Inertial%20Nav%20EKF/quat2yaw312.m const float a = 2.f * (q(0) * q(3) - q(1) * q(2)); @@ -83,25 +87,29 @@ float getEuler312Yaw(const matrix::Quatf& q) { return atan2f(a, b); } -float getEuler312Yaw(const matrix::Dcmf& R) { +float getEuler312Yaw(const matrix::Dcmf &R) +{ return atan2f(-R(0, 1), R(1, 1)); } -matrix::Dcmf updateEuler321YawInRotMat(float yaw, const matrix::Dcmf& rot_in) { +matrix::Dcmf updateEuler321YawInRotMat(float yaw, const matrix::Dcmf &rot_in) +{ matrix::Eulerf euler321(rot_in); euler321(2) = yaw; return matrix::Dcmf(euler321); } -matrix::Dcmf updateEuler312YawInRotMat(float yaw, const matrix::Dcmf& rot_in) { +matrix::Dcmf updateEuler312YawInRotMat(float yaw, const matrix::Dcmf &rot_in) +{ const matrix::Vector3f rotVec312(yaw, // yaw - asinf(rot_in(2, 1)), // roll - atan2f(-rot_in(2, 0), rot_in(2, 2))); // pitch + asinf(rot_in(2, 1)), // roll + atan2f(-rot_in(2, 0), rot_in(2, 2))); // pitch return taitBryan312ToRotMat(rotVec312); } -matrix::Dcmf updateYawInRotMat(float yaw, const matrix::Dcmf& rot_in) { +matrix::Dcmf updateYawInRotMat(float yaw, const matrix::Dcmf &rot_in) +{ return shouldUse321RotationSequence(rot_in) ? - updateEuler321YawInRotMat(yaw, rot_in) : - updateEuler312YawInRotMat(yaw, rot_in); + updateEuler321YawInRotMat(yaw, rot_in) : + updateEuler312YawInRotMat(yaw, rot_in); } diff --git a/src/lib/ecl/EKF/utils.hpp b/src/modules/ekf2/EKF/utils.hpp similarity index 72% rename from src/lib/ecl/EKF/utils.hpp rename to src/modules/ekf2/EKF/utils.hpp index 23b10516bb..b2e86484c1 100644 --- a/src/lib/ecl/EKF/utils.hpp +++ b/src/modules/ekf2/EKF/utils.hpp @@ -1,6 +1,7 @@ #include -#pragma once +#ifndef EKF_UTILS_HPP +#define EKF_UTILS_HPP // return the square of two floating point numbers - used in auto coded sections static constexpr float sq(float var) { return var * var; } @@ -26,33 +27,40 @@ matrix::Dcmf quatToInverseRotMat(const matrix::Quatf &quat); // We should use a 3-2-1 Tait-Bryan (yaw-pitch-roll) rotation sequence // when there is more roll than pitch tilt and a 3-1-2 rotation sequence // when there is more pitch than roll tilt to avoid gimbal lock. -bool shouldUse321RotationSequence(const matrix::Dcmf& R); +bool shouldUse321RotationSequence(const matrix::Dcmf &R); -float getEuler321Yaw(const matrix::Quatf& q); -float getEuler321Yaw(const matrix::Dcmf& R); +float getEuler321Yaw(const matrix::Quatf &q); +float getEuler321Yaw(const matrix::Dcmf &R); -float getEuler312Yaw(const matrix::Quatf& q); -float getEuler312Yaw(const matrix::Dcmf& R); +float getEuler312Yaw(const matrix::Quatf &q); +float getEuler312Yaw(const matrix::Dcmf &R); -matrix::Dcmf updateEuler321YawInRotMat(float yaw, const matrix::Dcmf& rot_in); -matrix::Dcmf updateEuler312YawInRotMat(float yaw, const matrix::Dcmf& rot_in); +matrix::Dcmf updateEuler321YawInRotMat(float yaw, const matrix::Dcmf &rot_in); +matrix::Dcmf updateEuler312YawInRotMat(float yaw, const matrix::Dcmf &rot_in); // Checks which euler rotation sequence to use and update yaw in rotation matrix -matrix::Dcmf updateYawInRotMat(float yaw, const matrix::Dcmf& rot_in); +matrix::Dcmf updateYawInRotMat(float yaw, const matrix::Dcmf &rot_in); -namespace ecl{ - inline float powf(float x, int exp) - { - float ret; - if (exp > 0) { - ret = x; - for (int count = 1; count < exp; count++) { - ret *= x; - } - return ret; - } else if (exp < 0) { - return 1.0f / ecl::powf(x, -exp); +namespace ecl +{ +inline float powf(float x, int exp) +{ + float ret; + + if (exp > 0) { + ret = x; + + for (int count = 1; count < exp; count++) { + ret *= x; } - return 1.0f; + + return ret; + + } else if (exp < 0) { + return 1.0f / ecl::powf(x, -exp); } + + return 1.0f; } +} +#endif // EKF_UTILS_HPP diff --git a/src/lib/ecl/EKF/vel_pos_fusion.cpp b/src/modules/ekf2/EKF/vel_pos_fusion.cpp similarity index 99% rename from src/lib/ecl/EKF/vel_pos_fusion.cpp rename to src/modules/ekf2/EKF/vel_pos_fusion.cpp index 9631304e51..3df12d7b2e 100644 --- a/src/lib/ecl/EKF/vel_pos_fusion.cpp +++ b/src/modules/ekf2/EKF/vel_pos_fusion.cpp @@ -41,7 +41,6 @@ * */ -#include #include #include "ekf.h" @@ -86,10 +85,12 @@ bool Ekf::fuseVerticalVelocity(const Vector3f &innov, const Vector2f &innov_gate // if there is bad vertical acceleration data, then don't reject measurement, // but limit innovation to prevent spikes that could destabilise the filter float innovation; + if (_bad_vert_accel_detected && !innov_check_pass) { const float innov_limit = innov_gate(1) * sqrtf(innov_var(2)); innovation = math::constrain(innov(2), -innov_limit, innov_limit); innov_check_pass = true; + } else { innovation = innov(2); } @@ -124,6 +125,7 @@ bool Ekf::fuseHorizontalPosition(const Vector3f &innov, const Vector2f &innov_ga // always protect against extreme values that could result in a NaN return false; } + if (!_fuse_hpos_as_odom) { _time_last_hor_pos_fuse = _time_last_imu; @@ -157,10 +159,12 @@ bool Ekf::fuseVerticalPosition(const Vector3f &innov, const Vector2f &innov_gate // if there is bad vertical acceleration data, then don't reject measurement, // but limit innovation to prevent spikes that could destabilise the filter float innovation; + if (_bad_vert_accel_detected && !innov_check_pass) { const float innov_limit = innov_gate(1) * sqrtf(innov_var(2)); innovation = math::constrain(innov(2), -innov_limit, innov_limit); innov_check_pass = true; + } else { innovation = innov(2); } diff --git a/src/modules/ekf2/EKF2.hpp b/src/modules/ekf2/EKF2.hpp index 51206c648b..8859c2d830 100644 --- a/src/modules/ekf2/EKF2.hpp +++ b/src/modules/ekf2/EKF2.hpp @@ -38,7 +38,8 @@ * @author Roman Bapst */ -#pragma once +#ifndef EKF2_HPP +#define EKF2_HPP #include "EKF2Selector.hpp" @@ -46,7 +47,7 @@ #include #include -#include +#include "EKF/ekf.h" #include #include #include @@ -521,3 +522,4 @@ private: ) }; +#endif // !EKF2_HPP diff --git a/src/modules/ekf2/EKF2Selector.hpp b/src/modules/ekf2/EKF2Selector.hpp index a37f5e592c..992762a182 100644 --- a/src/modules/ekf2/EKF2Selector.hpp +++ b/src/modules/ekf2/EKF2Selector.hpp @@ -31,7 +31,8 @@ * ****************************************************************************/ -#pragma once +#ifndef EKF2SELECTOR_HPP +#define EKF2SELECTOR_HPP #include #include @@ -240,3 +241,4 @@ private: (ParamFloat) _param_ekf2_sel_imu_velocity ) }; +#endif // !EKF2SELECTOR_HPP diff --git a/src/modules/ekf2/Utility/PreFlightChecker.hpp b/src/modules/ekf2/Utility/PreFlightChecker.hpp index 07e62489c5..9b6bc21c54 100644 --- a/src/modules/ekf2/Utility/PreFlightChecker.hpp +++ b/src/modules/ekf2/Utility/PreFlightChecker.hpp @@ -39,7 +39,8 @@ * using the hasXxxFailed() getters */ -#pragma once +#ifndef EKF2_PREFLIGHTCHECKER_HPP +#define EKF2_PREFLIGHTCHECKER_HPP #include #include @@ -176,3 +177,4 @@ private: // Preflight flow innovation spike limit (rad) static constexpr float _flow_innov_spike_lim = 2.0f * _flow_innov_test_lim; }; +#endif // !EKF2_PREFLIGHTCHECKER_HPP diff --git a/src/lib/ecl/test/CMakeLists.txt b/src/modules/ekf2/test/CMakeLists.txt similarity index 51% rename from src/lib/ecl/test/CMakeLists.txt rename to src/modules/ekf2/test/CMakeLists.txt index bb19ff85ee..b2cfac70b0 100644 --- a/src/lib/ecl/test/CMakeLists.txt +++ b/src/modules/ekf2/test/CMakeLists.txt @@ -1,6 +1,6 @@ ############################################################################ # -# Copyright (c) 2019 ECL Development Team. All rights reserved. +# Copyright (c) 2019-2021 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 @@ -12,7 +12,7 @@ # notice, this list of conditions and the following disclaimer in # the documentation and/or other materials provided with the # distribution. -# 3. Neither the name ECL nor the names of its contributors may be +# 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. # @@ -30,32 +30,24 @@ # POSSIBILITY OF SUCH DAMAGE. # ############################################################################ +add_compile_definitions(TEST_DATA_PATH="${CMAKE_CURRENT_SOURCE_DIR}") -include(gtest.cmake) - +include_directories(${CMAKE_CURRENT_SOURCE_DIR}/..) add_subdirectory(sensor_simulator) add_subdirectory(test_helper) -set(SRCS - main.cpp - test_EKF_basics.cpp - test_EKF_ringbuffer.cpp - test_EKF_measurementSampling.cpp - test_EKF_imuSampling.cpp - test_EKF_fusionLogic.cpp - test_EKF_initialization.cpp - test_EKF_gps_yaw.cpp - test_EKF_gps.cpp - test_EKF_externalVision.cpp - test_EKF_airspeed.cpp - test_EKF_withReplayData.cpp - test_EKF_flow.cpp - test_EKF_terrain_estimator.cpp - test_SensorRangeFinder.cpp - test_EKF_utils.cpp - ) -add_executable(ECL_GTESTS ${SRCS}) - -target_link_libraries(ECL_GTESTS gtest_main ecl_EKF ecl_sensor_sim ecl_test_helper) - -add_test(NAME ECL_GTESTS COMMAND ECL_GTESTS) +px4_add_unit_gtest(SRC test_EKF_airspeed.cpp LINKLIBS ecl_EKF ecl_sensor_sim) +px4_add_unit_gtest(SRC test_EKF_basics.cpp LINKLIBS ecl_EKF ecl_sensor_sim) +px4_add_unit_gtest(SRC test_EKF_externalVision.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) +px4_add_unit_gtest(SRC test_EKF_flow.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) +px4_add_unit_gtest(SRC test_EKF_fusionLogic.cpp LINKLIBS ecl_EKF ecl_sensor_sim) +px4_add_unit_gtest(SRC test_EKF_gps.cpp LINKLIBS ecl_EKF ecl_sensor_sim ecl_test_helper) +px4_add_unit_gtest(SRC test_EKF_gps_yaw.cpp LINKLIBS ecl_EKF ecl_sensor_sim) +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_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_terrain_estimator.cpp LINKLIBS ecl_EKF ecl_sensor_sim) +px4_add_unit_gtest(SRC test_EKF_utils.cpp LINKLIBS ecl_EKF ecl_sensor_sim) +px4_add_unit_gtest(SRC test_EKF_withReplayData.cpp LINKLIBS ecl_EKF ecl_sensor_sim) +px4_add_unit_gtest(SRC test_SensorRangeFinder.cpp LINKLIBS ecl_EKF ecl_sensor_sim) diff --git a/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv new file mode 100644 index 0000000000..96941a41c0 --- /dev/null +++ b/src/modules/ekf2/test/change_indication/ekf_gsf_reset.csv @@ -0,0 +1,391 @@ +Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] +15000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +85000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +185000,0.999749,-0.0104069,-0.0107853,-0.0166343,0.000120003,-0.000106777,-0.0115085,1.36672e-05,-4.60598e-06,-0.000265304,1.72362e-15,-3.18881e-15,-1.02506e-16,0,0,-7.93589e-11,0.191514,0.00185997,0.404127,0,0,0,0,0,1.95304e-06,0.00251574,0.0025157,0.00501391,0.256461,0.256461,0.562563,0.126414,0.126414,1.00079,1e-06,1e-06,1e-06,4e-06,4e-06,4.00001e-06,0,0,0,0,0,0,0,0 +285000,0.999745,-0.010498,-0.0111248,-0.0166139,0.00135604,0.000386777,-0.0252008,7.07068e-05,-1.58746e-05,-0.00161356,2.51669e-14,2.38317e-14,-5.59251e-17,0,0,-1.75435e-09,0.191514,0.00185997,0.404127,0,0,0,0,0,2.00622e-06,0.0025808,0.00258074,0.00507893,0.282565,0.282564,0.562506,0.132891,0.132891,0.576885,1e-06,1e-06,1e-06,4e-06,4e-06,4.00001e-06,0,0,0,0,0,0,0,0 +385000,0.999742,-0.0105086,-0.0114167,-0.0165992,0.00279367,0.000841279,-0.0397786,0.000234117,6.61504e-05,-0.00379265,3.97567e-11,-5.70702e-10,-1.26583e-11,0,0,-1.90055e-08,0.191514,0.00185997,0.404127,0,0,0,0,0,2.07976e-06,0.00269232,0.00269222,0.00519394,0.320083,0.320083,0.560114,0.0942307,0.0942307,0.375592,9.99994e-07,9.99994e-07,1e-06,4e-06,4e-06,3.99998e-06,0,0,0,0,0,0,0,0 +485000,0.999736,-0.0105821,-0.0117682,-0.0166396,0.00565568,1.37732e-05,-0.0548207,0.00067319,9.33786e-05,-0.00682881,3.12871e-11,-5.37575e-10,-1.17921e-11,-1.59477e-11,1.40041e-11,-9.60387e-08,0.191514,0.00185997,0.404127,0,0,0,0,0,2.19976e-06,0.00285733,0.00285719,0.00535892,0.388532,0.388532,0.553871,0.109483,0.109483,0.287379,9.99994e-07,9.99994e-07,1e-06,4.00001e-06,4.00001e-06,3.99978e-06,0,0,0,0,0,0,0,0 +585000,0.999733,-0.0105813,-0.0120572,-0.0166371,0.00777804,0.000772897,-0.0669065,0.00103104,9.86178e-05,-0.0105822,4.48797e-09,-3.17219e-08,-7.49169e-10,5.38242e-09,1.29507e-09,-3.1415e-07,0.191514,0.00185997,0.404127,0,0,0,0,0,2.32138e-06,0.00302178,0.0030216,0.00557389,0.438935,0.438935,0.542813,0.090563,0.090563,0.242024,9.99626e-07,9.99626e-07,1e-06,4e-06,4e-06,3.99919e-06,0,0,0,0,0,0,0,0 +685000,0.999729,-0.0107148,-0.0123314,-0.0165748,0.0105357,-6.93436e-05,-0.079897,0.00191777,0.00010604,-0.0148862,4.46058e-09,-3.1237e-08,-7.38591e-10,2.83433e-09,3.49819e-09,-8.02325e-07,0.191514,0.00185997,0.404127,0,0,0,0,0,2.48169e-06,0.00328539,0.00328518,0.00583886,0.553298,0.553299,0.525909,0.117361,0.117361,0.217499,9.99626e-07,9.99626e-07,1e-06,4.00001e-06,4.00001e-06,3.99786e-06,0,0,0,0,0,0,0,0 +785000,0.999725,-0.0108223,-0.0126169,-0.0165619,0.011653,0.000228674,-0.0924465,0.00210434,5.69068e-05,-0.0206973,2.09411e-08,-2.7006e-07,-6.00103e-09,1.23859e-07,1.62066e-08,-1.43884e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.62842e-06,0.00338385,0.00338359,0.00615375,0.575255,0.575257,0.510952,0.101501,0.101501,0.215594,9.96274e-07,9.96274e-07,9.99998e-07,3.9991e-06,3.9991e-06,3.99614e-06,0,0,0,0,0,0,0,0 +885000,0.999721,-0.0109303,-0.0128766,-0.0165376,0.0162409,-0.000779467,-0.107111,0.00348454,-7.9107e-06,-0.0306738,2.09411e-08,-2.7006e-07,-6.00103e-09,1.23859e-07,1.62066e-08,-1.43884e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.85509e-06,0.00373883,0.00373854,0.00651869,0.731496,0.731501,0.516593,0.1417,0.1417,0.256222,9.96274e-07,9.96275e-07,9.99998e-07,3.99911e-06,3.99911e-06,3.99615e-06,0,0,0,0,0,0,0,0 +985000,0.999718,-0.0109899,-0.0130373,-0.0165258,0.0171559,-0.00211764,-0.122002,0.00323188,-0.000105528,-0.0421161,3.37173e-08,-1.08563e-06,-2.30415e-08,6.15439e-07,2.41428e-08,-1.46225e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.97198e-06,0.00364015,0.00363984,0.0069335,0.674065,0.674073,0.523032,0.116725,0.116725,0.307346,9.83396e-07,9.83397e-07,9.99987e-07,3.99444e-06,3.99444e-06,3.99614e-06,0,0,0,0,0,0,0,0 +1085000,0.999713,-0.0110851,-0.0133106,-0.0165349,0.0212779,-0.00357539,-0.137286,0.00513551,-0.000395778,-0.0550937,3.37173e-08,-1.08563e-06,-2.30415e-08,6.15439e-07,2.41428e-08,-1.46225e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,3.26497e-06,0.00406897,0.0040686,0.00739839,0.858708,0.85872,0.530272,0.168025,0.168026,0.369158,9.83396e-07,9.83397e-07,9.99987e-07,3.99445e-06,3.99445e-06,3.99615e-06,0,0,0,0,0,0,0,0 +1185000,0.999713,-0.0111283,-0.0133046,-0.0165468,0.0193515,-0.00451356,-0.15178,0.00403561,-0.000466117,-0.0695939,-8.87907e-08,-2.81426e-06,-5.57012e-08,1.61822e-06,-4.64795e-08,-1.50185e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,3.34458e-06,0.00375476,0.00375441,0.00791312,0.7116,0.711611,0.53831,0.127498,0.127499,0.441871,9.54183e-07,9.54184e-07,9.99964e-07,3.98463e-06,3.98463e-06,3.99613e-06,0,0,0,0,0,0,0,0 +1285000,0.999709,-0.0111616,-0.0135984,-0.016503,0.0236315,-0.00550994,-0.165307,0.0061878,-0.000985373,-0.0854348,-8.87907e-08,-2.81426e-06,-5.57012e-08,1.61822e-06,-4.64795e-08,-1.50185e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,3.67101e-06,0.00423307,0.00423264,0.00847798,0.908346,0.908365,0.547149,0.184507,0.184508,0.525726,9.54183e-07,9.54184e-07,9.99964e-07,3.98464e-06,3.98464e-06,3.99614e-06,0,0,0,0,0,0,0,0 +1385000,0.99971,-0.0111913,-0.0134991,-0.0164803,0.0213128,-0.00580919,-0.17788,0.00443861,-0.000813139,-0.102584,-4.73387e-07,-5.46242e-06,-1.0124e-07,2.98419e-06,-2.44295e-07,-1.54925e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,3.7196e-06,0.00378423,0.00378385,0.00909265,0.707062,0.707079,0.556787,0.131338,0.131338,0.620983,9.06289e-07,9.06291e-07,9.99925e-07,3.97191e-06,3.9719e-06,3.99613e-06,0,0,0,0,0,0,0,0 +1485000,0.999706,-0.0112799,-0.0137371,-0.0164988,0.0259617,-0.00693717,-0.1922,0.00681617,-0.00143728,-0.121069,-4.73387e-07,-5.46242e-06,-1.0124e-07,2.98419e-06,-2.44295e-07,-1.54925e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,4.10372e-06,0.0042884,0.00428796,0.00975745,0.906687,0.906713,0.567226,0.189386,0.189387,0.727931,9.06289e-07,9.06291e-07,9.99926e-07,3.97192e-06,3.97191e-06,3.99614e-06,0,0,0,0,0,0,0,0 +1585000,0.999709,-0.0112305,-0.0135598,-0.0165046,0.0223256,-0.00584253,-0.205889,0.00462646,-0.00104432,-0.140993,-1.13198e-06,-8.9048e-06,-1.57017e-07,4.47455e-06,-5.28853e-07,-1.59489e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,4.1503e-06,0.00377329,0.00377293,0.0104721,0.689365,0.689386,0.57846,0.130326,0.130326,0.846878,8.40946e-07,8.40949e-07,9.99874e-07,3.95968e-06,3.95967e-06,3.99614e-06,0,0,0,0,0,0,0,0 +1685000,0.999704,-0.0113428,-0.0137814,-0.0165318,0.0285961,-0.00912939,-0.21802,0.00719274,-0.00180493,-0.162168,-1.13198e-06,-8.9048e-06,-1.57017e-07,4.47455e-06,-5.28853e-07,-1.59489e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,4.57273e-06,0.00428303,0.00428261,0.0112368,0.887771,0.887806,0.590501,0.187115,0.187117,0.978162,8.40946e-07,8.40949e-07,9.99874e-07,3.95969e-06,3.95968e-06,3.99615e-06,0,0,0,0,0,0,0,0 +1785000,0.999699,-0.0113794,-0.0140697,-0.016552,0.0353444,-0.0120225,-0.232811,0.010363,-0.00285392,-0.184712,-1.13198e-06,-8.9048e-06,-1.57017e-07,4.47455e-06,-5.28853e-07,-1.59489e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,5.03198e-06,0.00483482,0.00483431,0.0120516,1.13127,1.13132,0.603345,0.268301,0.268305,1.12214,8.40946e-07,8.40949e-07,9.99874e-07,3.9597e-06,3.95969e-06,3.99616e-06,0,0,0,0,0,0,0,0 +1885000,0.999705,-0.0112608,-0.013766,-0.0165747,0.0320045,-0.0114902,-0.246975,0.00769122,-0.00235687,-0.20872,-2.15343e-06,-1.31187e-05,-2.20289e-07,5.9229e-06,-8.79418e-07,-1.63416e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,5.06568e-06,0.00421849,0.00421809,0.0129161,0.868332,0.868376,0.616976,0.181925,0.181928,1.27919,7.60777e-07,7.60782e-07,9.99813e-07,3.95023e-06,3.95022e-06,3.99616e-06,0,0,0,0,0,0,0,0 +1985000,0.999702,-0.0112939,-0.0139347,-0.0165672,0.0382237,-0.0134647,-0.260906,0.0112195,-0.00361986,-0.234128,-2.15343e-06,-1.31187e-05,-2.20289e-07,5.9229e-06,-8.79418e-07,-1.63416e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,5.5202e-06,0.00475384,0.00475337,0.0138308,1.1089,1.10896,0.631418,0.260699,0.260704,1.44973,7.60777e-07,7.60782e-07,9.99814e-07,3.95024e-06,3.95023e-06,3.99617e-06,0,0,0,0,0,0,0,0 +2085000,0.999708,-0.0111374,-0.0135517,-0.0165982,0.0316816,-0.0123854,-0.274766,0.00803968,-0.00274782,-0.260935,-3.6043e-06,-1.81452e-05,-2.90129e-07,7.20372e-06,-1.24866e-06,-1.66367e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,5.55666e-06,0.00407573,0.00407541,0.0147954,0.848045,0.84809,0.646642,0.175983,0.175986,1.63418,6.69622e-07,6.6963e-07,9.99748e-07,3.94433e-06,3.94432e-06,3.99618e-06,0,0,0,0,0,0,0,0 +2185000,0.999705,-0.0112272,-0.013749,-0.0166012,0.037971,-0.0140438,-0.289343,0.0115207,-0.00409433,-0.289166,-3.6043e-06,-1.81452e-05,-2.90129e-07,7.20372e-06,-1.24866e-06,-1.66367e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,6.04072e-06,0.00457804,0.00457768,0.01581,1.08304,1.08311,0.662683,0.252251,0.252257,1.833,6.69622e-07,6.6963e-07,9.99748e-07,3.94434e-06,3.94433e-06,3.99619e-06,0,0,0,0,0,0,0,0 +2285000,0.999712,-0.0111074,-0.0132922,-0.0166164,0.0317523,-0.0122047,-0.303927,0.00803738,-0.00289867,-0.318882,-5.35309e-06,-2.36208e-05,-3.62059e-07,8.13033e-06,-1.5442e-06,-1.67889e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,6.07299e-06,0.00384454,0.00384436,0.0168746,0.822584,0.822629,0.679504,0.169958,0.169961,2.04666,5.72945e-07,5.72955e-07,9.99682e-07,3.94158e-06,3.94157e-06,3.9962e-06,0,0,0,0,0,0,0,0 +2385000,0.999709,-0.0111603,-0.0134537,-0.0166089,0.0369492,-0.0143926,-0.317241,0.0114777,-0.00424827,-0.349922,-5.35309e-06,-2.36208e-05,-3.62059e-07,8.13033e-06,-1.5442e-06,-1.67889e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,6.55221e-06,0.0043006,0.00430038,0.0179892,1.04751,1.04757,0.697142,0.243554,0.24356,2.27567,5.72945e-07,5.72955e-07,9.99682e-07,3.94159e-06,3.94158e-06,3.99621e-06,0,0,0,0,0,0,0,0 +2485000,0.999717,-0.0109769,-0.012982,-0.0166206,0.0291867,-0.0113974,-0.329436,0.0078136,-0.00290781,-0.382296,-7.2178e-06,-2.92093e-05,-4.33515e-07,8.61813e-06,-1.70664e-06,-1.67886e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,6.59045e-06,0.00353518,0.00353514,0.0191537,0.786966,0.787004,0.715557,0.16384,0.163843,2.52055,4.77167e-07,4.77179e-07,9.99618e-07,3.94087e-06,3.94086e-06,3.99622e-06,0,0,0,0,0,0,0,0 +2585000,0.999715,-0.0110489,-0.0131364,-0.0166044,0.0337442,-0.0124973,-0.34315,0.0109677,-0.00409769,-0.415916,-7.2178e-06,-2.92093e-05,-4.33515e-07,8.61813e-06,-1.70664e-06,-1.67886e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,7.06887e-06,0.00393669,0.00393663,0.0203682,0.997819,0.997873,0.734791,0.234337,0.234342,2.78187,4.77167e-07,4.77179e-07,9.99618e-07,3.94088e-06,3.94087e-06,3.99623e-06,0,0,0,0,0,0,0,0 +2685000,0.999722,-0.0108786,-0.0127108,-0.0166077,0.0257278,-0.00912951,-0.356255,0.00724502,-0.00269781,-0.450983,-8.99037e-06,-3.44839e-05,-5.00746e-07,8.66134e-06,-1.72091e-06,-1.66537e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,7.13196e-06,0.00317506,0.00317514,0.0216327,0.741633,0.741666,0.754804,0.157512,0.157515,3.06017,3.88198e-07,3.88211e-07,9.99559e-07,3.94089e-06,3.94088e-06,3.99623e-06,0,0,0,0,0,0,0,0 +2785000,0.999719,-0.0108866,-0.0129088,-0.0166129,0.0295308,-0.0106143,-0.368427,0.0100112,-0.00370057,-0.487222,-8.99037e-06,-3.44839e-05,-5.00746e-07,8.66134e-06,-1.72091e-06,-1.66537e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,7.62882e-06,0.00351929,0.00351932,0.0229472,0.934632,0.934677,0.775635,0.224399,0.224404,3.35609,3.88198e-07,3.88211e-07,9.9956e-07,3.9409e-06,3.94089e-06,3.99624e-06,0,0,0,0,0,0,0,0 +2885000,0.999725,-0.0107699,-0.0124866,-0.0166577,0.0220333,-0.0079416,-0.380662,0.00648833,-0.00236194,-0.52474,-1.05125e-05,-3.91026e-05,-5.60491e-07,8.34044e-06,-1.61502e-06,-1.64254e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,7.76516e-06,0.00279698,0.00279716,0.0243115,0.688198,0.688225,0.797247,0.150942,0.150944,3.67021,3.1005e-07,3.10063e-07,9.99506e-07,3.94053e-06,3.94052e-06,3.99625e-06,0,0,0,0,0,0,0,0 +2985000,0.999725,-0.0107731,-0.012595,-0.0166144,0.0261323,-0.00874592,-0.394433,0.00891381,-0.00320855,-0.563497,-1.05125e-05,-3.91026e-05,-5.60491e-07,8.34044e-06,-1.61502e-06,-1.64254e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,8.22002e-06,0.0030859,0.00308607,0.0257261,0.862046,0.862084,0.819675,0.213766,0.21377,4.00321,3.1005e-07,3.10063e-07,9.99506e-07,3.94054e-06,3.94053e-06,3.99626e-06,0,0,0,0,0,0,0,0 +3085000,0.999731,-0.0106514,-0.012233,-0.0166075,0.018936,-0.00625715,-0.40689,0.0057414,-0.00202656,-0.603623,-1.17517e-05,-4.29789e-05,-6.11779e-07,7.77051e-06,-1.43279e-06,-1.61449e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,8.36767e-06,0.00242921,0.00242949,0.0271904,0.630999,0.631024,0.842887,0.144224,0.144226,4.35574,2.44438e-07,2.4445e-07,9.99458e-07,3.93913e-06,3.93912e-06,3.99627e-06,0,0,0,0,0,0,0,0 +3185000,0.999728,-0.0107144,-0.0122893,-0.0166737,0.0217518,-0.00621667,-0.420959,0.00775231,-0.00266335,-0.645007,-1.17517e-05,-4.29789e-05,-6.11779e-07,7.77051e-06,-1.43279e-06,-1.61449e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,8.92825e-06,0.00266804,0.00266836,0.0287048,0.785099,0.785132,0.866911,0.202731,0.202735,4.7285,2.44438e-07,2.4445e-07,9.99458e-07,3.93914e-06,3.93913e-06,3.99628e-06,0,0,0,0,0,0,0,0 +3285000,0.999734,-0.0106199,-0.0119733,-0.0166229,0.0166503,-0.00427433,-0.433557,0.00497628,-0.00162487,-0.687776,-1.26721e-05,-4.60924e-05,-6.55547e-07,7.06779e-06,-1.22512e-06,-1.58514e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,9.09422e-06,0.00209049,0.00209091,0.0302691,0.573242,0.573264,0.891724,0.137503,0.137504,5.12221,1.91177e-07,1.91188e-07,9.99415e-07,3.93644e-06,3.93642e-06,3.99628e-06,0,0,0,0,0,0,0,0 +3385000,0.999733,-0.0105818,-0.0120527,-0.0166526,0.0184431,-0.00511684,-0.447001,0.0067524,-0.00209045,-0.731791,-1.26721e-05,-4.60924e-05,-6.55547e-07,7.06779e-06,-1.22512e-06,-1.58514e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,9.63231e-06,0.00228599,0.00228639,0.0318835,0.708271,0.708302,0.917346,0.191634,0.191637,5.53762,1.91177e-07,1.91188e-07,9.99415e-07,3.93645e-06,3.93643e-06,3.99629e-06,0,0,0,0,0,0,0,0 +3485000,0.999736,-0.0105176,-0.0118252,-0.0166631,0.0142424,-0.00448979,-0.459939,0.00434417,-0.00133391,-0.777188,-1.33457e-05,-4.85765e-05,-6.92758e-07,6.30677e-06,-1.01889e-06,-1.55632e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,9.92566e-06,0.00179031,0.00179077,0.0335477,0.517494,0.517515,0.94376,0.13092,0.130921,5.97547,1.4895e-07,1.48959e-07,9.99377e-07,3.93249e-06,3.93247e-06,3.9963e-06,0,0,0,0,0,0,0,0 +3585000,0.999736,-0.0105157,-0.0118571,-0.0166392,0.0151615,-0.00597498,-0.473445,0.00581417,-0.00185821,-0.823864,-1.33457e-05,-4.85765e-05,-6.92758e-07,6.30677e-06,-1.01889e-06,-1.55632e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.04204e-05,0.00194943,0.0019499,0.035262,0.635107,0.635139,0.97098,0.180784,0.180787,6.43659,1.4895e-07,1.48959e-07,9.99377e-07,3.9325e-06,3.93248e-06,3.99631e-06,0,0,0,0,0,0,0,0 +3685000,0.999741,-0.0104625,-0.0116704,-0.0165236,0.0115185,-0.00578292,-0.487245,0.00374262,-0.00127954,-0.871905,-1.39384e-05,-5.05164e-05,-7.18855e-07,5.55092e-06,-7.88117e-07,-1.52858e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.06192e-05,0.00153101,0.00153151,0.0370263,0.465554,0.465577,0.998993,0.124588,0.124589,6.92175,1.15979e-07,1.15984e-07,9.99344e-07,3.9275e-06,3.92748e-06,3.99631e-06,0,0,0,0,0,0,0,0 +3785000,0.99974,-0.0105069,-0.0117138,-0.0164736,0.0127967,-0.00783632,-0.500261,0.00494761,-0.00195326,-0.921294,-1.39384e-05,-5.05164e-05,-7.18855e-07,5.55092e-06,-7.88117e-07,-1.52858e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.10897e-05,0.00166025,0.0016608,0.0388406,0.567584,0.567616,1.02781,0.170412,0.170414,7.43183,1.15979e-07,1.15984e-07,9.99344e-07,3.92751e-06,3.92749e-06,3.99632e-06,0,0,0,0,0,0,0,0 +3885000,0.999741,-0.0104342,-0.0117374,-0.0164972,0.013431,-0.00793084,-0.514225,0.00625355,-0.00274558,-0.97199,-1.39384e-05,-5.05164e-05,-7.18855e-07,5.55092e-06,-7.88117e-07,-1.52858e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.16633e-05,0.00179526,0.00179579,0.0407049,0.685737,0.685784,1.05743,0.232023,0.232028,7.96767,1.15979e-07,1.15984e-07,9.99344e-07,3.92752e-06,3.9275e-06,3.99633e-06,0,0,0,0,0,0,0,0 +3985000,0.999745,-0.0102698,-0.011566,-0.0164851,0.0108771,-0.00633744,-0.528084,0.00415007,-0.00200694,-1.02411,-1.45351e-05,-5.19968e-05,-7.31676e-07,4.84621e-06,-5.04128e-07,-1.50227e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.20337e-05,0.00141569,0.00141611,0.042619,0.506627,0.506662,1.08784,0.160653,0.160655,8.53014,9.04599e-08,9.04586e-08,9.99315e-07,3.92174e-06,3.92172e-06,3.99633e-06,0,0,0,0,0,0,0,0 +4085000,0.999745,-0.0102723,-0.0115383,-0.0164952,0.0126127,-0.00735162,-0.541273,0.00533596,-0.00267349,-1.07757,-1.45351e-05,-5.19968e-05,-7.31676e-07,4.84621e-06,-5.04128e-07,-1.50227e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.26104e-05,0.00152516,0.00152564,0.0445833,0.608491,0.608536,1.11906,0.216785,0.21679,9.12019,9.046e-08,9.04587e-08,9.99315e-07,3.92175e-06,3.92173e-06,3.99634e-06,0,0,0,0,0,0,0,0 +4185000,0.999747,-0.0101644,-0.0113666,-0.0165275,0.0104954,-0.00667159,-0.555755,0.00370637,-0.00195849,-1.13246,-1.50694e-05,-5.31483e-05,-7.37439e-07,4.19458e-06,-2.01866e-07,-1.47791e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.31018e-05,0.00121078,0.00121119,0.0465971,0.452228,0.452261,1.15107,0.151575,0.151578,9.73872,7.07903e-08,7.07811e-08,9.9929e-07,3.91545e-06,3.91543e-06,3.99635e-06,0,0,0,0,0,0,0,0 +4285000,0.999746,-0.0101649,-0.0114195,-0.0165642,0.0119422,-0.00541664,-0.568915,0.00481794,-0.0025885,-1.18874,-1.50694e-05,-5.31483e-05,-7.37439e-07,4.19458e-06,-2.01866e-07,-1.47791e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.37495e-05,0.0012998,0.00130021,0.0486612,0.540171,0.540213,1.18389,0.202736,0.202741,10.3867,7.07904e-08,7.07812e-08,9.9929e-07,3.91546e-06,3.91544e-06,3.99636e-06,0,0,0,0,0,0,0,0 +4385000,0.999749,-0.0100637,-0.0112958,-0.0165521,0.00927968,-0.00326362,-0.583247,0.00337823,-0.00169993,-1.24638,-1.55322e-05,-5.40936e-05,-7.39977e-07,3.571e-06,1.03238e-07,-1.4549e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.42249e-05,0.00104006,0.00104034,0.050775,0.404088,0.40412,1.2175,0.143187,0.14319,11.0651,5.56407e-08,5.56238e-08,9.99267e-07,3.90887e-06,3.90885e-06,3.99636e-06,0,0,0,0,0,0,0,0 +4485000,0.99975,-0.0100325,-0.0113163,-0.0164872,0.0098036,-0.00324034,-0.598106,0.00432623,-0.00200104,-1.30542,-1.55322e-05,-5.40936e-05,-7.39977e-07,3.571e-06,1.03238e-07,-1.4549e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.47225e-05,0.00111262,0.00111289,0.0529392,0.480287,0.48033,1.25191,0.18987,0.189875,11.775,5.56408e-08,5.56239e-08,9.99267e-07,3.90888e-06,3.90886e-06,3.99637e-06,0,0,0,0,0,0,0,0 +4585000,0.999752,-0.0100081,-0.0111996,-0.0164578,0.00887698,-0.00242209,-0.61261,0.00306795,-0.0012888,-1.36598,-1.58477e-05,-5.48588e-05,-7.45032e-07,2.99145e-06,3.41778e-07,-1.43483e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.52052e-05,0.000898026,0.000898251,0.0551528,0.361819,0.361848,1.28712,0.135471,0.135474,12.5173,4.39565e-08,4.39332e-08,9.99245e-07,3.90218e-06,3.90215e-06,3.99637e-06,0,0,0,0,0,0,0,0 +4685000,0.999752,-0.00999543,-0.0111936,-0.0164577,0.00958709,-0.00347593,-0.626621,0.00399935,-0.00156526,-1.42795,-1.58477e-05,-5.48588e-05,-7.45032e-07,2.99145e-06,3.41778e-07,-1.43483e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.58327e-05,0.000957393,0.000957645,0.0574169,0.427827,0.427865,1.32314,0.178148,0.178153,13.2931,4.39566e-08,4.39333e-08,9.99245e-07,3.90219e-06,3.90216e-06,3.99638e-06,0,0,0,0,0,0,0,0 +4785000,0.999753,-0.0100039,-0.0110657,-0.0164627,0.00772613,-0.00297109,-0.641414,0.00283601,-0.00108953,-1.49137,-1.60712e-05,-5.54987e-05,-7.51591e-07,2.4417e-06,5.33317e-07,-1.41683e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.64176e-05,0.000779816,0.000780076,0.0597302,0.324624,0.324652,1.35995,0.128386,0.128389,14.1036,3.49183e-08,3.48895e-08,9.99224e-07,3.89553e-06,3.89549e-06,3.99638e-06,0,0,0,0,0,0,0,0 +4885000,0.999753,-0.0100248,-0.0110843,-0.0164718,0.00843594,-0.00400386,-0.656213,0.00366957,-0.0014251,-1.55623,-1.60712e-05,-5.54987e-05,-7.51591e-07,2.4417e-06,5.33317e-07,-1.41683e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.70899e-05,0.000828644,0.000828935,0.0620941,0.382066,0.382103,1.39756,0.16748,0.167485,14.9497,3.49184e-08,3.48896e-08,9.99224e-07,3.89554e-06,3.8955e-06,3.99639e-06,0,0,0,0,0,0,0,0 +4985000,0.999754,-0.00992862,-0.0110101,-0.0164964,0.00776266,-0.00292988,-0.670999,0.00266017,-0.00105966,-1.62257,-1.62635e-05,-5.60341e-05,-7.56255e-07,1.92522e-06,7.18363e-07,-1.40023e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.77554e-05,0.000681418,0.000681535,0.0645074,0.291982,0.292006,1.43597,0.121884,0.121887,15.8327,2.79003e-08,2.78661e-08,9.99205e-07,3.88901e-06,3.88897e-06,3.9964e-06,0,0,0,0,0,0,0,0 +5085000,0.999754,-0.00996187,-0.0110366,-0.0164582,0.00812157,-0.00294223,-0.685772,0.00346107,-0.00134774,-1.69037,-1.62635e-05,-5.60341e-05,-7.56255e-07,1.92522e-06,7.18363e-07,-1.40023e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.83524e-05,0.000721756,0.000721905,0.0669713,0.342084,0.342115,1.47518,0.157776,0.157781,16.7537,2.79004e-08,2.78662e-08,9.99206e-07,3.88902e-06,3.88898e-06,3.99641e-06,0,0,0,0,0,0,0,0 +5185000,0.999756,-0.0099099,-0.0109486,-0.0164287,0.00681734,-0.00284974,-0.699389,0.00249657,-0.000990924,-1.75964,-1.6426e-05,-5.64909e-05,-7.59922e-07,1.43437e-06,8.92497e-07,-1.38487e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.89327e-05,0.000599265,0.000599307,0.0694845,0.263224,0.263247,1.51518,0.115914,0.115916,17.7138,2.24267e-08,2.23876e-08,9.99189e-07,3.8827e-06,3.88266e-06,3.99641e-06,0,0,0,0,0,0,0,0 +5285000,0.999756,-0.00987037,-0.0109675,-0.0164401,0.00593007,-0.0023007,-0.713733,0.00313909,-0.00127719,-1.83026,-1.6426e-05,-5.64909e-05,-7.59922e-07,1.43437e-06,8.92497e-07,-1.38487e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,1.966e-05,0.000632736,0.000632718,0.0720483,0.307039,0.307074,1.55599,0.148941,0.148945,18.7142,2.24268e-08,2.23877e-08,9.99189e-07,3.88271e-06,3.88267e-06,3.99642e-06,0,0,0,0,0,0,0,0 +5385000,0.999758,-0.00977307,-0.0109828,-0.0163796,0.00310295,-0.00177024,-0.727921,0.00212369,-0.000878171,-1.90236,-1.65591e-05,-5.68499e-05,-7.61841e-07,1.00786e-06,1.05016e-06,-1.37181e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.01922e-05,0.000530653,0.000530313,0.0746613,0.237918,0.237952,1.5976,0.110424,0.110426,19.7563,1.81384e-08,1.8094e-08,9.99171e-07,3.87666e-06,3.87662e-06,3.99643e-06,0,0,0,0,0,0,0,0 +5485000,0.999758,-0.00971397,-0.0109937,-0.0163627,0.00319091,-0.0018772,-0.741209,0.00242271,-0.00107756,-1.97581,-1.65591e-05,-5.68499e-05,-7.61841e-07,1.00786e-06,1.05016e-06,-1.37181e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.08708e-05,0.000558556,0.00055813,0.0773252,0.276334,0.276376,1.64,0.140885,0.14089,20.8411,1.81385e-08,1.80941e-08,9.99172e-07,3.87667e-06,3.87663e-06,3.99644e-06,0,0,0,0,0,0,0,0 +5585000,0.999759,-0.00965821,-0.0109383,-0.0163845,0.00204198,-0.000961146,-0.755562,0.00161013,-0.000719977,-2.05064,-1.66588e-05,-5.70945e-05,-7.61766e-07,6.88579e-07,1.17996e-06,-1.36217e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.16328e-05,0.000473002,0.000472394,0.0800375,0.215576,0.215609,1.68321,0.105368,0.105371,21.9701,1.47632e-08,1.4713e-08,9.99151e-07,3.87091e-06,3.87087e-06,3.99644e-06,0,0,0,0,0,0,0,0 +5685000,0.999761,-0.00956941,-0.010936,-0.0163147,0.00199248,0.000164443,-0.770744,0.00182181,-0.000778932,-2.12694,-1.66588e-05,-5.70945e-05,-7.61766e-07,6.88579e-07,1.17996e-06,-1.36217e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.21909e-05,0.000496367,0.000495634,0.0828015,0.249478,0.249517,1.72721,0.133528,0.133534,23.1444,1.47633e-08,1.47131e-08,9.99151e-07,3.87092e-06,3.87088e-06,3.99645e-06,0,0,0,0,0,0,0,0 +5785000,0.999762,-0.00948799,-0.0109298,-0.0163223,0.0011335,0.00207845,-0.00303896,0.00119404,-0.000412015,-365.429,-1.67087e-05,-5.72561e-05,-7.63252e-07,4.5797e-07,1.25074e-06,-1.35585e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.29451e-05,0.000424553,0.000423513,0.0856134,0.195858,0.195885,9.99879,0.100708,0.100711,2.00225,1.20935e-08,1.20376e-08,9.99128e-07,3.86549e-06,3.86545e-06,3.99646e-06,0,0,0,0,0,0,0,0 +5885000,0.999762,-0.00945627,-0.0109186,-0.0163272,0.00187587,0.00268089,-0.00580534,0.00135554,-0.000208334,-365.42,-1.67087e-05,-5.72561e-05,-7.63252e-07,4.57368e-07,1.25128e-06,-1.38435e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.3727e-05,0.000444213,0.000443141,0.088477,0.225752,0.225778,9.73938,0.1268,0.126805,0.709951,1.20936e-08,1.20378e-08,9.99128e-07,3.8655e-06,3.86546e-06,3.99647e-06,0,0,0,0,0,0,0,0 +5985000,0.999763,-0.00942066,-0.0109538,-0.0163104,0.00197416,0.00489238,0.00379513,0.00154404,0.000204529,-365.403,-1.67087e-05,-5.72562e-05,-7.63251e-07,4.55151e-07,1.25332e-06,-1.48747e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.44592e-05,0.000464542,0.000463349,0.0913906,0.258977,0.258998,8.83902,0.159171,0.159179,0.518921,1.20937e-08,1.20378e-08,9.99128e-07,3.86551e-06,3.86547e-06,3.99646e-06,0,0,0,0,0,0,0,0 +6085000,0.999763,-0.00938274,-0.0109256,-0.0163149,0.00232173,0.00611017,-0.012662,0.00111572,0.000656594,-365.405,-1.6687e-05,-5.73678e-05,-7.71392e-07,2.82432e-07,1.21866e-06,-1.45797e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.52539e-05,0.000400346,0.00039895,0.0943517,0.204883,0.204883,7.28749,0.120631,0.120635,0.482341,9.97142e-09,9.91119e-09,9.991e-07,3.86039e-06,3.86036e-06,3.99637e-06,0,0,0,0,0,0,0,0 +6185000,0.999762,-0.00939313,-0.0108734,-0.0163949,0.00217478,0.00833913,-0.0131216,0.00135222,0.00138569,-365.401,-1.6687e-05,-5.73678e-05,-7.71389e-07,2.79036e-07,1.22183e-06,-1.6142e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.63153e-05,0.000417381,0.000416099,0.0973649,0.23423,0.23422,5.96609,0.150548,0.150553,0.537941,9.97152e-09,9.91129e-09,9.991e-07,3.8604e-06,3.86037e-06,3.99623e-06,0,0,0,0,0,0,0,0 +6285000,0.999762,-0.00941322,-0.0108587,-0.0164061,0.00272503,0.00789365,-0.0110544,0.00105451,0.00156662,-365.395,-1.65844e-05,-5.74547e-05,-7.89955e-07,1.28046e-07,1.05345e-06,-1.84368e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.71821e-05,0.000363165,0.000361788,0.100425,0.186437,0.18642,4.37463,0.114964,0.114966,0.516967,8.27591e-09,8.21334e-09,9.99068e-07,3.85562e-06,3.85559e-06,3.99587e-06,0,0,0,0,0,0,0,0 +6385000,0.999764,-0.00929271,-0.0108478,-0.0163972,0.00311182,0.00920725,-0.0439392,0.00134817,0.00243143,-365.407,-1.65844e-05,-5.74546e-05,-7.89961e-07,1.37053e-07,1.04509e-06,-1.42984e-06,0.191514,0.00185997,0.404127,0,0,0,0,0,2.7994e-05,0.000377704,0.000376114,0.103539,0.212451,0.212425,3.15615,0.14268,0.142682,0.485838,8.27601e-09,8.21344e-09,9.99068e-07,3.85563e-06,3.8556e-06,3.99533e-06,0,0,0,0,0,0,0,0 +6485000,0.705512,0.0013646,-0.0142836,0.708553,0.00292335,0.00806528,-0.0487372,0.00111263,0.00225598,-365.407,-1.64486e-05,-5.75106e-05,-1.95614e-06,-1.19103e-08,7.62844e-07,-1.73723e-06,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00127756,0.000315159,0.000315335,0.0141568,0.157871,0.157843,2.27835,0.109551,0.109551,0.448309,6.91436e-09,6.85136e-09,9.98862e-07,3.85116e-06,3.85113e-06,3.99454e-06,0,0,0,0,0,0,0,0 +6585000,0.703782,0.00140582,-0.0142777,0.710271,0.00233225,0.00803551,-0.0894707,0.00142314,0.00305961,-365.429,-1.64346e-05,-5.75232e-05,-1.31916e-06,1.32864e-08,7.37857e-07,-5.65236e-07,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00130429,0.000314824,0.000315181,0.0072757,0.161622,0.161585,1.66651,0.133661,0.13366,0.410362,6.91339e-09,6.85054e-09,9.96557e-07,3.85117e-06,3.85114e-06,3.99345e-06,0,0,0,0,0,0,0,0 +6685000,0.703731,0.00143267,-0.0142575,0.710322,0.0023277,0.00862944,-0.0732754,0.00164384,0.00387485,-365.418,-1.64664e-05,-5.7494e-05,-2.81236e-06,-2.87742e-08,7.78556e-07,-2.51122e-06,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00135563,0.000315336,0.000315743,0.00518654,0.168424,0.168369,1.24586,0.160815,0.160811,0.376165,6.90623e-09,6.84384e-09,9.8995e-07,3.85116e-06,3.85113e-06,3.99199e-06,0,0,0,0,0,0,0,0 +6785000,0.704646,0.00142027,-0.0142206,0.709415,0.000917115,0.00846734,-0.109164,0.00180606,0.00478335,-365.443,-1.63295e-05,-5.76199e-05,3.52538e-06,4.61512e-09,7.29337e-07,-8.53302e-07,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00143031,0.000316314,0.000316732,0.00438056,0.178633,0.178557,1.01664,0.191634,0.191625,0.378799,6.9021e-09,6.84034e-09,9.80854e-07,3.85117e-06,3.85114e-06,3.99058e-06,0,0,0,0,0,0,0,0 +6885000,0.704455,0.00143407,-0.0141442,0.709606,-0.00160834,0.00848904,-0.117702,0.00175182,0.00561416,-365.449,-1.6343e-05,-5.76068e-05,2.8405e-06,-6.8556e-09,7.38915e-07,-1.42586e-06,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00152499,0.000317622,0.000318049,0.00371101,0.191774,0.191681,0.788006,0.225755,0.225738,0.346717,6.88634e-09,6.82591e-09,9.61678e-07,3.85114e-06,3.85111e-06,3.98817e-06,0,0,0,0,0,0,0,0 +6985000,0.704145,0.00150085,-0.0141057,0.709915,-0.0019145,0.00908375,-0.125676,0.00155374,0.00648232,-365.456,-1.64645e-05,-5.74949e-05,-2.78713e-06,-2.49359e-08,7.71842e-07,-2.364e-06,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00163569,0.000319289,0.000319716,0.00327938,0.208446,0.208317,0.622738,0.264434,0.264406,0.318726,6.87322e-09,6.81474e-09,9.33249e-07,3.85115e-06,3.85112e-06,3.98495e-06,0,0,0,0,0,0,0,0 +7085000,0.703293,0.00150763,-0.0140761,0.710759,-0.00263145,0.00812464,-0.12409,0.00129697,0.00720618,-365.455,-1.67731e-05,-5.7209e-05,-1.71892e-05,-7.4097e-08,8.56387e-07,-5.08396e-06,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0017564,0.000321268,0.000321695,0.00297988,0.227886,0.227719,0.502267,0.306875,0.306831,0.294865,6.84548e-09,6.78963e-09,8.95719e-07,3.85106e-06,3.85103e-06,3.9808e-06,0,0,0,0,0,0,0,0 +7185000,0.70317,0.00152003,-0.0140162,0.710883,-0.00478849,0.00779559,-0.144671,0.000924184,0.00800329,-365.473,-1.68255e-05,-5.71603e-05,-1.96225e-05,-4.59869e-08,8.39782e-07,-3.85827e-06,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00188053,0.000323598,0.000324021,0.0027596,0.251062,0.250864,0.412293,0.355308,0.355242,0.273975,6.82394e-09,6.77129e-09,8.49174e-07,3.85106e-06,3.85104e-06,3.97542e-06,0,0,0,0,0,0,0,0 +7285000,0.7033,0.00154025,-0.0139524,0.710755,-0.00653669,0.007855,-0.145921,0.000381946,0.00875415,-365.474,-1.67256e-05,-5.72507e-05,-1.51201e-05,-1.20728e-07,8.91173e-07,-7.64087e-06,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00200172,0.000326186,0.000326603,0.00259073,0.276717,0.276485,0.344695,0.408054,0.407961,0.25599,6.78474e-09,6.73585e-09,7.95782e-07,3.85083e-06,3.85081e-06,3.96864e-06,0,0,0,0,0,0,0,0 +7385000,0.703236,0.00155665,-0.0139077,0.710819,-0.00704846,0.00889811,-0.156439,-0.000328574,0.00960464,-365.486,-1.67455e-05,-5.72326e-05,-1.6036e-05,-1.52893e-07,9.21037e-07,-9.11668e-06,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00211398,0.000329162,0.000329573,0.00245657,0.306399,0.306119,0.292905,0.468865,0.468737,0.24012,6.75755e-09,6.71269e-09,7.37103e-07,3.85084e-06,3.85082e-06,3.96003e-06,0,0,0,0,0,0,0,0 +7485000,0.703604,0.00161748,-0.0138318,0.710455,-0.00907267,0.00898598,-0.162759,-0.00108218,0.0104961,-365.494,-1.65479e-05,-5.74113e-05,-7.06311e-06,-2.04947e-07,9.47896e-07,-1.22815e-05,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00223479,0.000332312,0.000332702,0.00237354,0.338107,0.337796,0.263757,0.534439,0.534271,0.23989,6.7171e-09,6.67555e-09,6.91079e-07,3.85034e-06,3.85032e-06,3.95217e-06,0,0,0,0,0,0,0,0 +7585000,0.704097,0.0016152,-0.0137455,0.709969,-0.0110886,0.00981686,-0.167186,-0.0019568,0.0114861,-365.5,-1.6281e-05,-5.76592e-05,5.342e-06,-3.26423e-07,1.01117e-06,-1.75199e-05,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00232186,0.000335919,0.000336301,0.00227846,0.374372,0.374029,0.230804,0.610951,0.610733,0.226158,6.68843e-09,6.65111e-09,6.29236e-07,3.85035e-06,3.85033e-06,3.93957e-06,0,0,0,0,0,0,0,0 +7685000,0.704056,0.00169544,-0.0136695,0.710011,-0.0134655,0.0100971,-0.164442,-0.00317881,0.0123954,-365.496,-1.63e-05,-5.76375e-05,4.24494e-06,-5.40167e-07,1.22099e-06,-2.90042e-05,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00239195,0.00033953,0.000339902,0.00219865,0.411968,0.4116,0.205241,0.692281,0.692011,0.214204,6.63609e-09,6.60314e-09,5.68868e-07,3.84938e-06,3.84936e-06,3.9243e-06,0,0,0,0,0,0,0,0 +7785000,0.703506,0.00172083,-0.0136734,0.710556,-0.0152117,0.0109524,-0.164214,-0.00477158,0.0134301,-365.496,-1.65973e-05,-5.73657e-05,-9.48137e-06,-7.78249e-07,1.4613e-06,-4.00935e-05,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00244426,0.000343763,0.000344133,0.00213081,0.454862,0.454455,0.185186,0.78848,0.788149,0.203593,6.6093e-09,6.58028e-09,5.11044e-07,3.84938e-06,3.84936e-06,3.90573e-06,0,0,0,0,0,0,0,0 +7885000,0.703833,0.00173985,-0.0136654,0.710231,-0.0181966,0.0122881,-0.163483,-0.00626284,0.0144616,-365.493,-1.64279e-05,-5.75153e-05,-1.9079e-06,-1.0332e-06,1.70916e-06,-5.44223e-05,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00247962,0.000347742,0.000348106,0.00207276,0.49794,0.497525,0.169435,0.888689,0.888296,0.194165,6.55421e-09,6.52921e-09,4.56881e-07,3.84767e-06,3.84766e-06,3.88335e-06,0,0,0,0,0,0,0,0 +7985000,0.704144,0.00176598,-0.013631,0.709924,-0.0201678,0.0130799,-0.17022,-0.00808807,0.0156867,-365.501,-1.62857e-05,-5.76488e-05,4.72922e-06,-1.2004e-06,1.82521e-06,-6.18446e-05,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00250178,0.000352588,0.000352948,0.00202203,0.54756,0.547114,0.157188,1.00916,1.00869,0.185915,6.53135e-09,6.50967e-09,4.07491e-07,3.84767e-06,3.84766e-06,3.85701e-06,0,0,0,0,0,0,0,0 +8085000,0.704614,0.00175343,-0.0136089,0.709459,-0.0224827,0.0139944,-0.182082,-0.0100438,0.0170115,-365.517,-1.60756e-05,-5.78435e-05,1.44833e-05,-1.24107e-06,1.82679e-06,-6.34497e-05,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00254919,0.000357761,0.000358108,0.00198833,0.600684,0.600211,0.152109,1.14437,1.14382,0.187046,6.51569e-09,6.49628e-09,3.73583e-07,3.84767e-06,3.84766e-06,3.8343e-06,0,0,0,0,0,0,0,0 +8185000,0.704208,0.00175147,-0.0135685,0.709862,-0.0255201,0.0152098,-0.188496,-0.0125173,0.0183369,-365.525,-1.62789e-05,-5.76427e-05,4.64122e-06,-1.37561e-06,2.08262e-06,-7.44077e-05,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00254999,0.000362251,0.00036259,0.00194723,0.651886,0.651407,0.144282,1.28108,1.28045,0.180015,6.46073e-09,6.44451e-09,3.32434e-07,3.84486e-06,3.84487e-06,3.79956e-06,0,0,0,0,0,0,0,0 +8285000,0.704194,0.00179338,-0.0136034,0.709875,-0.0276171,0.0156536,-0.187118,-0.0152485,0.0199089,-365.523,-1.63081e-05,-5.7622e-05,3.42564e-06,-1.89267e-06,2.50823e-06,-9.79336e-05,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00254183,0.000368016,0.000368356,0.00191091,0.711866,0.711356,0.13824,1.44876,1.44804,0.173788,6.44377e-09,6.42998e-09,2.95708e-07,3.84485e-06,3.84486e-06,3.75921e-06,0,0,0,0,0,0,0,0 +8385000,0.704414,0.00184535,-0.0135762,0.709657,-0.029632,0.0163798,-0.186909,-0.0177377,0.0211835,-365.522,-1.61963e-05,-5.77099e-05,8.14437e-06,-2.26364e-06,2.98673e-06,-0.000121509,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00252768,0.000372546,0.000372877,0.00187849,0.766915,0.766391,0.1337,1.61218,1.61137,0.168384,6.38687e-09,6.37571e-09,2.63336e-07,3.84054e-06,3.84056e-06,3.71335e-06,0,0,0,0,0,0,0,0 +8485000,0.704237,0.00184424,-0.013572,0.709833,-0.032131,0.0175283,-0.186442,-0.0210002,0.0229269,-365.522,-1.62664e-05,-5.76516e-05,5.04453e-06,-2.81924e-06,3.44894e-06,-0.000146897,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00250848,0.000378898,0.000379227,0.00184939,0.8337,0.833148,0.130276,1.81808,1.81716,0.163617,6.37371e-09,6.36439e-09,2.34745e-07,3.84053e-06,3.84055e-06,3.66111e-06,0,0,0,0,0,0,0,0 +8585000,0.703947,0.00187836,-0.0135197,0.710122,-0.0348671,0.01944,-0.187038,-0.0242269,0.0244665,-365.524,-1.63825e-05,-5.75206e-05,-9.70909e-07,-3.1613e-06,4.05859e-06,-0.000172531,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0024863,0.000383255,0.00038357,0.00182283,0.891204,0.890657,0.127798,2.00943,2.00843,0.159511,6.31428e-09,6.30714e-09,2.09668e-07,3.83422e-06,3.83425e-06,3.6028e-06,0,0,0,0,0,0,0,0 +8685000,0.704545,0.00192483,-0.0134572,0.709529,-0.0382062,0.0200694,-0.182644,-0.0274799,0.0262113,-365.519,-1.61687e-05,-5.77297e-05,9.20246e-06,-3.99564e-06,4.68775e-06,-0.000210024,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00246134,0.000390176,0.000390486,0.00179888,0.964717,0.964167,0.125985,2.25941,2.25828,0.155912,6.30416e-09,6.29839e-09,1.87589e-07,3.8342e-06,3.83424e-06,3.53762e-06,0,0,0,0,0,0,0,0 +8785000,0.704179,0.00186536,-0.0134174,0.709893,-0.0406463,0.0215838,-0.181206,-0.0311233,0.0278754,-365.52,-1.62951e-05,-5.75808e-05,2.54314e-06,-4.34771e-06,5.46338e-06,-0.000239918,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00246693,0.000394124,0.00039441,0.00178227,1.02277,1.02223,0.127643,2.47799,2.47677,0.158917,6.24395e-09,6.23972e-09,1.72807e-07,3.8254e-06,3.82545e-06,3.48415e-06,0,0,0,0,0,0,0,0 +8885000,0.704087,0.00191349,-0.0134109,0.709984,-0.0434278,0.0223572,-0.181606,-0.0355141,0.0302018,-365.522,-1.63471e-05,-5.75398e-05,3.05448e-07,-4.96619e-06,5.97282e-06,-0.0002683,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00243818,0.000401598,0.000401881,0.00176161,1.10289,1.10233,0.126647,2.77774,2.77638,0.15603,6.23593e-09,6.23273e-09,1.55204e-07,3.82537e-06,3.82543e-06,3.40703e-06,0,0,0,0,0,0,0,0 +8985000,0.70392,0.00195567,-0.0133764,0.71015,-0.0454983,0.0223251,-0.176123,-0.039158,0.0316888,-365.517,-1.63915e-05,-5.74591e-05,-2.70492e-06,-5.49921e-06,7.08426e-06,-0.000310994,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00240922,0.00040486,0.000405121,0.00174253,1.15918,1.15864,0.125958,3.0201,3.01867,0.153603,6.17053e-09,6.16889e-09,1.39762e-07,3.81355e-06,3.81363e-06,3.32376e-06,0,0,0,0,0,0,0,0 +9085000,0.703761,0.00201042,-0.0133863,0.710307,-0.0486,0.0230448,-0.17759,-0.0440404,0.0340642,-365.523,-1.64401e-05,-5.74196e-05,-4.81904e-06,-5.99883e-06,7.499e-06,-0.000334061,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00237978,0.000412863,0.000413122,0.00172531,1.24551,1.24497,0.125394,3.37479,3.37321,0.151499,6.16437e-09,6.16347e-09,1.26131e-07,3.81352e-06,3.81361e-06,3.23387e-06,0,0,0,0,0,0,0,0 +9185000,0.704416,0.00201903,-0.013393,0.709658,-0.0493759,0.0227658,-0.178477,-0.0467466,0.0347201,-365.527,-1.62105e-05,-5.75808e-05,4.60762e-06,-6.1003e-06,8.41606e-06,-0.000360591,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00235043,0.000415183,0.000415417,0.00170912,1.29715,1.29664,0.12486,3.63413,3.6325,0.149668,6.0966e-09,6.09703e-09,1.14088e-07,3.79826e-06,3.79837e-06,3.13766e-06,0,0,0,0,0,0,0,0 +9285000,0.704494,0.00201336,-0.0134166,0.70958,-0.0512892,0.0235833,-0.17716,-0.0518262,0.0370473,-365.528,-1.61989e-05,-5.76015e-05,5.40341e-06,-6.88555e-06,9.0389e-06,-0.000396458,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00232255,0.000423689,0.00042392,0.00169406,1.38952,1.38897,0.124343,4.04805,4.04625,0.148142,6.09186e-09,6.09282e-09,1.03485e-07,3.79823e-06,3.79835e-06,3.03654e-06,0,0,0,0,0,0,0,0 +9385000,0.704491,0.00197131,-0.0133548,0.709585,-0.0520295,0.0247533,-0.179344,-0.054849,0.0379477,-365.535,-1.61854e-05,-5.75474e-05,4.45223e-06,-6.80231e-06,1.0149e-05,-0.000421031,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0023198,0.000424825,0.000425018,0.0016832,1.43333,1.43284,0.126623,4.31382,4.31199,0.152471,6.02362e-09,6.02561e-09,9.63361e-08,3.77923e-06,3.77936e-06,2.95755e-06,0,0,0,0,0,0,0,0 +9485000,0.704869,0.00197539,-0.013362,0.709209,-0.0543616,0.0249077,-0.176786,-0.0598616,0.0401664,-365.538,-1.60869e-05,-5.76494e-05,9.30256e-06,-7.50704e-06,1.0664e-05,-0.000452423,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00229214,0.000433808,0.000433996,0.00166982,1.53086,1.53035,0.125874,4.78998,4.78798,0.151251,6.01982e-09,6.02218e-09,8.77423e-08,3.77919e-06,3.77933e-06,2.84838e-06,0,0,0,0,0,0,0,0 +9585000,0.705028,0.00198595,-0.0133423,0.709051,-0.0559779,0.0249307,-0.173492,-0.0622731,0.040548,-365.539,-1.60188e-05,-5.76403e-05,1.07371e-05,-7.60049e-06,1.21742e-05,-0.000489838,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00226529,0.000433558,0.000433707,0.00165693,1.56329,1.56289,0.124922,5.04773,5.04576,0.150137,5.95005e-09,5.9534e-09,8.00931e-08,3.75631e-06,3.75646e-06,2.73537e-06,0,0,0,0,0,0,0,0 +9685000,0.704694,0.00206487,-0.0133372,0.709383,-0.0588298,0.0272581,-0.167837,-0.068646,0.043614,-365.537,-1.61269e-05,-5.75483e-05,5.96148e-06,-8.52204e-06,1.29741e-05,-0.000533606,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00223962,0.000442991,0.000443132,0.00164513,1.66555,1.66514,0.123805,5.58749,5.58534,0.149171,5.94709e-09,5.95068e-09,7.32852e-08,3.75627e-06,3.75644e-06,2.62034e-06,0,0,0,0,0,0,0,0 +9785000,0.704973,0.00204824,-0.0132838,0.709107,-0.0575321,0.0278394,-0.159674,-0.0702206,0.0436031,-365.532,-1.60291e-05,-5.75605e-05,8.58876e-06,-8.75227e-06,1.48866e-05,-0.000582454,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00221445,0.000441239,0.000441331,0.00163376,1.68337,1.68303,0.12244,5.81966,5.8176,0.148238,5.87825e-09,5.88266e-09,6.719e-08,3.72962e-06,3.7298e-06,2.50324e-06,0,0,0,0,0,0,0,0 +9885000,0.704911,0.00206377,-0.0131973,0.70917,-0.0601972,0.0289322,-0.156746,-0.0763023,0.0465696,-365.535,-1.60496e-05,-5.75483e-05,7.83541e-06,-9.3814e-06,1.5404e-05,-0.000611827,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0021906,0.00045109,0.000451171,0.00162345,1.78938,1.78905,0.120886,6.42249,6.42026,0.147388,5.87593e-09,5.88048e-09,6.1745e-08,3.72958e-06,3.72977e-06,2.38591e-06,0,0,0,0,0,0,0,0 +9985000,0.704704,0.00209495,-0.0132196,0.709375,-0.0601403,0.0281511,-0.150916,-0.0774932,0.0465604,-365.532,-1.60565e-05,-5.74483e-05,5.13218e-06,-9.28399e-06,1.74459e-05,-0.000652809,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00216716,0.000447813,0.000447838,0.00161344,1.78989,1.78969,0.119079,6.60953,6.60744,0.146516,5.80931e-09,5.81452e-09,5.68464e-08,3.69953e-06,3.69973e-06,2.2683e-06,0,0,0,0,0,0,0,0 +10085000,0.704839,0.00213153,-0.0131944,0.709242,-0.0620669,0.0279415,-0.149442,-0.0836021,0.049324,-365.537,-1.60422e-05,-5.74686e-05,6.00351e-06,-9.80169e-06,1.78429e-05,-0.000676367,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00216266,0.000458064,0.000458077,0.00160645,1.89892,1.89871,0.119949,7.27295,7.27071,0.151181,5.80794e-09,5.8132e-09,5.34953e-08,3.6995e-06,3.69971e-06,2.18052e-06,0,0,0,0,0,0,0,0 +10185000,0.704446,0.00214861,-0.0132405,0.70963,-0.0647698,0.0305668,-0.146994,-0.0906592,0.0528033,-365.54,-1.61414e-05,-5.7378e-05,1.46358e-06,-1.03194e-05,1.8356e-05,-0.000702755,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00214033,0.000468603,0.00046861,0.0015977,2.01231,2.01211,0.117681,7.99165,7.98926,0.150211,5.80626e-09,5.81158e-09,4.94153e-08,3.69946e-06,3.69969e-06,2.06491e-06,0,0,0,0,0,0,0,0 +10285000,0.704236,0.00210429,-0.0132247,0.70984,-0.0635701,0.0291918,-0.135584,-0.090765,0.0521647,-365.53,-1.61447e-05,-5.72775e-05,-1.28033e-06,-1.03988e-05,2.08483e-05,-0.000757139,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00211854,0.000463953,0.000463896,0.00158911,1.99116,1.9911,0.115259,8.11468,8.11252,0.149242,5.74316e-09,5.74896e-09,4.57319e-08,3.66663e-06,3.66685e-06,1.95196e-06,0,0,0,0,0,0,0,0 +10385000,0.704242,0.00209157,-0.0131545,0.709835,0.00903194,-0.0197321,0.00583655,0.000845218,-0.00178303,-365.515,-1.61436e-05,-5.72879e-05,-9.38893e-07,-1.11674e-05,2.14562e-05,-0.000792692,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00209756,0.000474858,0.00047479,0.00158154,0.0361529,0.0361529,0.0375923,0.125282,0.125282,0.131952,5.74182e-09,5.74764e-09,4.2394e-08,3.66659e-06,3.66683e-06,1.85282e-06,0,0,0,0,0,0,0,0 +10485000,0.704012,0.00213523,-0.0131412,0.710063,0.007164,-0.0186187,0.00333361,0.00163646,-0.00370179,-365.498,-1.61952e-05,-5.72458e-05,-3.1419e-06,-1.19107e-05,2.21138e-05,-0.000828829,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00207744,0.000486051,0.000485973,0.00157432,0.0417289,0.0417296,0.0381152,0.126304,0.126304,0.118069,5.74062e-09,5.74644e-09,3.93643e-08,3.66656e-06,3.66682e-06,1.77591e-06,0,0,0,0,0,0,0,0 +10585000,0.704057,0.00223957,-0.0132639,0.710016,0.00570191,-0.0146246,0.00196687,0.00178385,-0.00345408,-365.488,-1.60924e-05,-5.70107e-05,-2.79854e-06,-1.54516e-05,2.23256e-05,-0.000849918,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00205819,0.000486734,0.000486636,0.00156729,0.0439609,0.0439626,0.0363722,0.0850012,0.0850012,0.107691,5.68288e-09,5.68847e-09,3.66149e-08,3.65878e-06,3.65904e-06,1.71217e-06,0,0,0,0,0,0,0,0 +10685000,0.704074,0.00228988,-0.013244,0.71,0.00303921,-0.0146631,-0.000901215,0.00225842,-0.00493381,-365.481,-1.60901e-05,-5.70168e-05,-2.57206e-06,-1.5773e-05,2.25762e-05,-0.000864708,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00205352,0.00049826,0.000498148,0.00156242,0.0564064,0.0564116,0.0372795,0.0871877,0.0871878,0.102852,5.68217e-09,5.68776e-09,3.47162e-08,3.65877e-06,3.65904e-06,1.67256e-06,0,0,0,0,0,0,0,0 +10785000,0.704089,0.00233619,-0.0134145,0.709981,0.00190215,-0.011505,-0.00343977,0.00229811,-0.00412331,-365.477,-1.58378e-05,-5.66948e-05,-2.39529e-06,-2.05246e-05,2.3756e-05,-0.000874527,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00203489,0.000472909,0.000472747,0.00155582,0.0589936,0.0590005,0.0358729,0.0664768,0.0664769,0.0964188,5.4892e-09,5.49407e-09,3.23785e-08,3.63427e-06,3.63453e-06,1.62123e-06,0,0,0,0,0,0,0,0 +10885000,0.704066,0.00229293,-0.0133623,0.710006,-0.000137286,-0.0106161,-0.00747696,0.00236479,-0.00521151,-365.475,-1.58466e-05,-5.66874e-05,-2.78247e-06,-2.06259e-05,2.38513e-05,-0.000879593,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00201744,0.000484159,0.000483989,0.00154972,0.0764919,0.0765026,0.036862,0.0701409,0.0701413,0.0922855,5.4884e-09,5.49329e-09,3.02423e-08,3.63426e-06,3.63453e-06,1.5812e-06,0,0,0,0,0,0,0,0 +10985000,0.704284,0.00228686,-0.0137205,0.709782,0.0012712,-0.00455082,-0.0114464,0.00355371,-0.00552758,-365.472,-1.50709e-05,-5.62572e-05,-9.70385e-07,-2.8837e-05,2.91303e-05,-0.00088958,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00200025,0.000432264,0.000431982,0.00154341,0.073566,0.0735785,0.0356104,0.0571714,0.0571718,0.0882195,5.16402e-09,5.16785e-09,2.82895e-08,3.59619e-06,3.59644e-06,1.53599e-06,0,0,0,0,0,0,0,0 +11085000,0.704491,0.00230072,-0.0136471,0.709577,-0.000310397,-0.00231122,-0.0125201,0.00362756,-0.00592219,-365.465,-1.50385e-05,-5.62924e-05,7.35454e-07,-2.92094e-05,2.93498e-05,-0.000904874,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00198429,0.000442647,0.00044235,0.00153783,0.0933447,0.0933604,0.0366725,0.062469,0.06247,0.0862586,5.16337e-09,5.16725e-09,2.6499e-08,3.59619e-06,3.59644e-06,1.50392e-06,0,0,0,0,0,0,0,0 +11185000,0.704277,0.00221587,-0.0139402,0.709785,0.00493615,0.00245233,-0.0170387,0.00532745,-0.00558967,-365.467,-1.43663e-05,-5.60377e-05,-9.28054e-07,-3.42782e-05,3.50122e-05,-0.000904236,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00196826,0.000378186,0.000377724,0.00153218,0.0823902,0.0823975,0.0355004,0.0525398,0.0525404,0.0834949,4.78278e-09,4.78567e-09,2.4856e-08,3.55554e-06,3.55577e-06,1.46048e-06,0,0,0,0,0,0,0,0 +11285000,0.703962,0.00230286,-0.01396,0.710097,0.00420431,0.00503493,-0.0194025,0.00578262,-0.00519778,-365.465,-1.4427e-05,-5.59817e-05,-3.88552e-06,-3.43666e-05,3.52472e-05,-0.000912262,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00195362,0.000387417,0.000386936,0.00152701,0.101958,0.101966,0.0366004,0.0592602,0.0592613,0.0828811,4.78227e-09,4.78521e-09,2.33443e-08,3.55553e-06,3.55577e-06,1.4333e-06,0,0,0,0,0,0,0,0 +11385000,0.703797,0.00236893,-0.0138715,0.710262,0.00143731,0.00627723,-0.0220628,0.00445765,-0.00432459,-365.465,-1.4642e-05,-5.60401e-05,-5.28118e-06,-3.29711e-05,3.40333e-05,-0.000917665,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00194913,0.00032556,0.00032488,0.00152308,0.0848087,0.0848121,0.0357553,0.0503016,0.0503022,0.0825098,4.42154e-09,4.42369e-09,2.22871e-08,3.52132e-06,3.52156e-06,1.39555e-06,0,0,0,0,0,0,0,0 +11485000,0.703483,0.0023884,-0.0138853,0.710573,-0.00113248,0.00906899,-0.0241718,0.00446674,-0.00354815,-365.465,-1.46913e-05,-5.59948e-05,-7.73449e-06,-3.30103e-05,3.4224e-05,-0.00092335,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00193476,0.000333673,0.000332976,0.00151852,0.102667,0.102674,0.0369142,0.0580237,0.0580246,0.0827569,4.42112e-09,4.42333e-09,2.09741e-08,3.52132e-06,3.52156e-06,1.37144e-06,0,0,0,0,0,0,0,0 +11585000,0.70328,0.00230661,-0.0138604,0.710774,-0.00432877,0.00982843,-0.0269199,0.00360779,-0.00333892,-365.465,-1.47519e-05,-5.62147e-05,-9.09623e-06,-3.10326e-05,3.49679e-05,-0.000929092,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00192041,0.000282098,0.000281227,0.00151401,0.0827312,0.0827366,0.0357998,0.0492392,0.0492397,0.0810419,4.11543e-09,4.11714e-09,1.97613e-08,3.49655e-06,3.49679e-06,1.32592e-06,0,0,0,0,0,0,0,0 +11685000,0.703175,0.00229236,-0.0138554,0.710878,-0.00752705,0.0130782,-0.0301955,0.00299141,-0.00222641,-365.469,-1.47684e-05,-5.61993e-05,-9.94797e-06,-3.09796e-05,3.49869e-05,-0.000928143,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00190706,0.000289305,0.000288416,0.00150979,0.0983845,0.098393,0.0369661,0.0575439,0.0575449,0.0818445,4.11511e-09,4.11687e-09,1.86391e-08,3.49655e-06,3.49679e-06,1.30409e-06,0,0,0,0,0,0,0,0 +11785000,0.703176,0.0023212,-0.0138313,0.710878,-0.0122002,0.0138288,-0.0324194,0.00113341,-0.00101539,-365.467,-1.48641e-05,-5.62545e-05,-9.99358e-06,-3.04726e-05,3.45934e-05,-0.000936482,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00189394,0.000249193,0.000248168,0.00150558,0.0783024,0.0783094,0.0358457,0.0487336,0.0487342,0.0803179,3.86744e-09,3.86891e-09,1.75986e-08,3.48028e-06,3.48052e-06,1.25708e-06,0,0,0,0,0,0,0,0 +11885000,0.702983,0.00233401,-0.0138127,0.711069,-0.0133714,0.0156274,-0.0340131,-0.000125288,0.00045575,-365.467,-1.48887e-05,-5.62328e-05,-1.12365e-05,-3.05475e-05,3.47523e-05,-0.000942311,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00188143,0.000255735,0.000254686,0.00150182,0.0918184,0.0918258,0.0370113,0.0573029,0.057304,0.0814563,3.86718e-09,3.86871e-09,1.66349e-08,3.48028e-06,3.48052e-06,1.23686e-06,0,0,0,0,0,0,0,0 +11985000,0.703081,0.00232484,-0.0137609,0.710973,-0.0144911,0.0158424,-0.0373564,-0.000906589,0.00105304,-365.47,-1.48072e-05,-5.63967e-05,-1.03328e-05,-2.99365e-05,3.55954e-05,-0.000944542,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00187767,0.000225395,0.000224227,0.00149903,0.072993,0.0729973,0.036281,0.0484818,0.0484823,0.0816619,3.66703e-09,3.66836e-09,1.59573e-08,3.47038e-06,3.47063e-06,1.19324e-06,0,0,0,0,0,0,0,0 +12085000,0.703308,0.00235241,-0.0137613,0.710748,-0.0159356,0.0184629,-0.042748,-0.00242785,0.00273997,-365.475,-1.47735e-05,-5.64272e-05,-8.58114e-06,-2.99497e-05,3.54593e-05,-0.000941521,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00186584,0.000231467,0.000230273,0.00149543,0.0846575,0.0846618,0.0374749,0.0571032,0.0571041,0.0830472,3.66682e-09,3.6682e-09,1.51097e-08,3.47038e-06,3.47063e-06,1.17436e-06,0,0,0,0,0,0,0,0 +12185000,0.703238,0.00206535,-0.0137835,0.710818,-0.0105829,0.0162769,-0.0387467,0.000854023,0.000998106,-365.468,-1.4281e-05,-5.69312e-05,-8.87453e-06,-2.93447e-05,3.9646e-05,-0.000965768,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00185432,0.0002086,0.000207322,0.00149195,0.0676293,0.0676314,0.0363174,0.0483362,0.0483366,0.0815585,3.50143e-09,3.50268e-09,1.43206e-08,3.46478e-06,3.46502e-06,1.12461e-06,0,0,0,0,0,0,0,0 +12285000,0.703294,0.00204872,-0.0137846,0.710762,-0.0133624,0.0184457,-0.0389664,-0.000317501,0.00274739,-365.466,-1.42721e-05,-5.69409e-05,-8.33504e-06,-2.96048e-05,3.98165e-05,-0.000976744,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00184338,0.00021434,0.00021304,0.00148862,0.0777416,0.0777444,0.0374953,0.0568768,0.0568775,0.0830421,3.50127e-09,3.50256e-09,1.3586e-08,3.46478e-06,3.46503e-06,1.10668e-06,0,0,0,0,0,0,0,0 +12385000,0.703204,0.0017962,-0.0137949,0.710853,-0.0085137,0.0157105,-0.0362858,0.00236956,0.00101867,-365.461,-1.38785e-05,-5.7383e-05,-9.01685e-06,-2.9376e-05,4.24882e-05,-0.000996412,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00183285,0.000196952,0.000195597,0.00148528,0.0626062,0.0626075,0.0363181,0.0482228,0.0482231,0.0815325,3.36003e-09,3.36125e-09,1.29003e-08,3.46185e-06,3.46209e-06,1.05646e-06,0,0,0,0,0,0,0,0 +12485000,0.703042,0.00177,-0.0138083,0.711012,-0.0100524,0.018358,-0.0390154,0.00145767,0.00271998,-365.462,-1.38977e-05,-5.73661e-05,-1.00189e-05,-2.94168e-05,4.26079e-05,-0.0010004,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00182261,0.000202468,0.000201093,0.0014822,0.0714806,0.0714818,0.0374724,0.056606,0.0566065,0.0830501,3.3599e-09,3.36116e-09,1.22601e-08,3.46185e-06,3.4621e-06,1.03929e-06,0,0,0,0,0,0,0,0 +12585000,0.702996,0.00179749,-0.0136348,0.711061,-0.0158059,0.0163189,-0.0429844,-0.00319595,0.00105972,-365.467,-1.43284e-05,-5.76796e-05,-1.00113e-05,-2.80888e-05,4.25215e-05,-0.00100126,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00181256,0.000189019,0.000187604,0.00147931,0.0581093,0.0581096,0.0362723,0.0481053,0.0481056,0.0815046,3.2346e-09,3.2358e-09,1.1661e-08,3.46039e-06,3.46064e-06,9.89121e-07,0,0,0,0,0,0,0,0 +12685000,0.702949,0.00184099,-0.0135869,0.711108,-0.0165724,0.01858,-0.0458843,-0.00482371,0.00280185,-365.472,-1.4329e-05,-5.76791e-05,-1.0045e-05,-2.80835e-05,4.25197e-05,-0.00100108,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00180958,0.000194391,0.000192942,0.0014773,0.0659891,0.0659892,0.0378607,0.0562901,0.0562905,0.0847749,3.23456e-09,3.23578e-09,1.12369e-08,3.46039e-06,3.46064e-06,9.76766e-07,0,0,0,0,0,0,0,0 +12785000,0.702996,0.00185891,-0.0134343,0.711065,-0.0203924,0.0152021,-0.0470693,-0.00786855,0.00114742,-365.472,-1.45855e-05,-5.80149e-05,-9.6354e-06,-2.78951e-05,4.3438e-05,-0.00101053,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00180002,0.000183746,0.000182264,0.0014745,0.0541673,0.0541673,0.0366064,0.0479675,0.0479677,0.0831233,3.11917e-09,3.12034e-09,1.07026e-08,3.45951e-06,3.45977e-06,9.26751e-07,0,0,0,0,0,0,0,0 +12885000,0.703033,0.00181304,-0.0134675,0.711027,-0.0216394,0.0156321,-0.0470796,-0.00997477,0.00266621,-365.47,-1.45813e-05,-5.802e-05,-9.33908e-06,-2.81209e-05,4.36096e-05,-0.00102072,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00179096,0.000188998,0.000187498,0.00147173,0.061277,0.0612772,0.037715,0.0559361,0.0559364,0.084666,3.11911e-09,3.1203e-09,1.02023e-08,3.45951e-06,3.45977e-06,9.11024e-07,0,0,0,0,0,0,0,0 +12985000,0.703259,0.00152061,-0.0136146,0.710801,-0.0111361,0.0128511,-0.044924,-0.00159723,0.00122927,-365.469,-1.37313e-05,-5.84368e-05,-7.95117e-06,-3.01328e-05,4.37319e-05,-0.00103919,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00178225,0.000180317,0.000178798,0.00146898,0.0507746,0.0507748,0.036433,0.0478029,0.0478031,0.0829784,3.00915e-09,3.01029e-09,9.7325e-09,3.45852e-06,3.45878e-06,8.6212e-07,0,0,0,0,0,0,0,0 +13085000,0.703035,0.00152991,-0.0135582,0.711025,-0.0121079,0.0136568,-0.0449958,-0.00275677,0.00256213,-365.47,-1.37502e-05,-5.84205e-05,-8.94549e-06,-3.02088e-05,4.38902e-05,-0.00104523,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00177355,0.000185495,0.000183945,0.0014666,0.057269,0.0572692,0.0374812,0.0555514,0.0555517,0.0844558,3.00911e-09,3.01027e-09,9.29084e-09,3.45853e-06,3.45879e-06,8.46846e-07,0,0,0,0,0,0,0,0 +13185000,0.70306,0.00130256,-0.013615,0.710999,-0.00385651,0.0125547,-0.0402419,0.00360847,0.00141661,-365.462,-1.31286e-05,-5.87462e-05,-8.66049e-06,-3.22924e-05,4.31383e-05,-0.00107195,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00176527,0.00017819,0.000176623,0.00146414,0.047899,0.0478993,0.036173,0.0476121,0.0476122,0.0827411,2.90144e-09,2.90255e-09,8.87571e-09,3.45689e-06,3.45715e-06,7.99511e-07,0,0,0,0,0,0,0,0 +13285000,0.703206,0.00131635,-0.0136084,0.710854,-0.0044361,0.0139381,-0.0382898,0.00319794,0.00274365,-365.457,-1.31126e-05,-5.8762e-05,-7.69394e-06,-3.2596e-05,4.33226e-05,-0.00108466,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00176293,0.000183301,0.000181706,0.00146236,0.0539271,0.0539274,0.0376457,0.0551478,0.055148,0.085991,2.90145e-09,2.90257e-09,8.5806e-09,3.45689e-06,3.45716e-06,7.88577e-07,0,0,0,0,0,0,0,0 +13385000,0.70338,0.00114456,-0.0135492,0.710684,-0.00355586,0.0123468,-0.033519,0.00245048,0.00153037,-365.447,-1.29196e-05,-5.90574e-05,-6.70564e-06,-3.44161e-05,4.23186e-05,-0.00110737,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00175517,0.0001769,0.000175308,0.00145989,0.0454984,0.0454987,0.0362809,0.0473995,0.0473996,0.084183,2.79364e-09,2.79469e-09,8.20703e-09,3.45415e-06,3.45443e-06,7.42794e-07,0,0,0,0,0,0,0,0 +13485000,0.703527,0.00117608,-0.0135389,0.710538,-0.00448686,0.0129033,-0.0325624,0.00207935,0.0027868,-365.443,-1.2905e-05,-5.90716e-05,-5.82718e-06,-3.46501e-05,4.24483e-05,-0.0011169,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00174766,0.00018195,0.000180326,0.00145751,0.0511661,0.0511661,0.0372262,0.0547355,0.0547356,0.0856054,2.79362e-09,2.7947e-09,7.85481e-09,3.45416e-06,3.45443e-06,7.28786e-07,0,0,0,0,0,0,0,0 +13585000,0.703489,0.00107939,-0.0134941,0.710577,-0.00385683,0.0125054,-0.0324475,0.00147199,0.0017152,-365.444,-1.27239e-05,-5.93303e-05,-6.1078e-06,-3.63336e-05,4.09315e-05,-0.00112303,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00174046,0.000176141,0.000174516,0.00145514,0.0435149,0.0435148,0.0358425,0.0471713,0.0471714,0.0837886,2.68403e-09,2.68503e-09,7.52279e-09,3.44997e-06,3.45025e-06,6.85276e-07,0,0,0,0,0,0,0,0 +13685000,0.70366,0.00105814,-0.0134564,0.710409,-0.00348565,0.0147849,-0.0357908,0.00107087,0.00305627,-365.447,-1.27034e-05,-5.93487e-05,-4.96649e-06,-3.63908e-05,4.08744e-05,-0.001123,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00173337,0.000181115,0.000179465,0.00145298,0.0489142,0.0489144,0.0367136,0.0543246,0.0543247,0.0851477,2.68403e-09,2.68505e-09,7.20913e-09,3.44997e-06,3.45025e-06,6.71805e-07,0,0,0,0,0,0,0,0 +13785000,0.703653,0.000936223,-0.0133643,0.710418,-0.00262561,0.0102546,-0.0357361,0.00250252,0.000323012,-365.449,-1.24765e-05,-5.98449e-05,-4.84943e-06,-4.0154e-05,3.94724e-05,-0.0011305,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00172648,0.000175624,0.00017398,0.00145085,0.0419103,0.0419095,0.0353173,0.0469347,0.0469348,0.0833313,2.5715e-09,2.57246e-09,6.91291e-09,3.44403e-06,3.44432e-06,6.30789e-07,0,0,0,0,0,0,0,0 +13885000,0.703663,0.00089008,-0.0133881,0.710407,-0.00255977,0.0106537,-0.0388677,0.00222883,0.00136101,-365.452,-1.2472e-05,-5.98489e-05,-4.59789e-06,-4.01631e-05,3.94567e-05,-0.00113031,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00171982,0.000180517,0.000178856,0.00144881,0.0471022,0.0471014,0.0361109,0.0539252,0.0539252,0.0846267,2.57151e-09,2.57249e-09,6.63267e-09,3.44403e-06,3.44432e-06,6.17878e-07,0,0,0,0,0,0,0,0 +13985000,0.703843,0.000806196,-0.0133366,0.71023,-0.00200581,0.00787131,-0.0374109,0.00339815,-0.000816296,-365.452,-1.22397e-05,-6.02836e-05,-3.69061e-06,-4.39681e-05,3.77963e-05,-0.00114074,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00171807,0.000175159,0.000173509,0.00144718,0.0406247,0.0406229,0.0351447,0.0466972,0.0466973,0.0845694,2.45555e-09,2.45646e-09,6.43224e-09,3.43613e-06,3.43643e-06,5.82426e-07,0,0,0,0,0,0,0,0 +14085000,0.703955,0.000784728,-0.0133434,0.710119,-0.00235692,0.00818139,-0.0380365,0.00314924,-2.40282e-05,-365.454,-1.22276e-05,-6.02945e-05,-3.00277e-06,-4.40269e-05,3.77837e-05,-0.00114192,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00171175,0.000179965,0.000178293,0.00144516,0.0456513,0.0456488,0.0358807,0.0535452,0.0535452,0.0858542,2.45557e-09,2.4565e-09,6.17754e-09,3.43614e-06,3.43644e-06,5.70239e-07,0,0,0,0,0,0,0,0 +14185000,0.704109,0.000645172,-0.0133489,0.709966,0.00119691,0.00694534,-0.038609,0.00556707,-0.000372494,-365.457,-1.17969e-05,-6.04897e-05,-2.0836e-06,-4.59365e-05,3.38275e-05,-0.00114569,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00170563,0.000174587,0.000172942,0.00144314,0.0396012,0.0395994,0.0344487,0.0464656,0.0464656,0.0839842,2.33608e-09,2.33696e-09,5.93634e-09,3.42618e-06,3.4265e-06,5.34243e-07,0,0,0,0,0,0,0,0 +14285000,0.70422,0.000647507,-0.0133061,0.709857,0.00144374,0.00795024,-0.0377706,0.00569266,0.000353535,-365.456,-1.17888e-05,-6.04975e-05,-1.58666e-06,-4.60774e-05,3.39131e-05,-0.00115183,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00169985,0.00017929,0.000177618,0.00144109,0.0445161,0.0445138,0.0351043,0.0531915,0.0531915,0.0852026,2.33611e-09,2.33701e-09,5.70758e-09,3.42619e-06,3.4265e-06,5.22638e-07,0,0,0,0,0,0,0,0 +14385000,0.704439,0.000521731,-0.0132904,0.70964,0.00348892,0.00792392,-0.0386799,0.00741999,6.40911e-06,-365.458,-1.14429e-05,-6.06927e-05,-4.7705e-07,-4.80666e-05,3.04121e-05,-0.00115555,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00169418,0.000173791,0.000172152,0.00143906,0.0388084,0.0388058,0.0336769,0.0462455,0.0462455,0.0833379,2.21337e-09,2.21421e-09,5.4903e-09,3.41412e-06,3.41445e-06,4.8932e-07,0,0,0,0,0,0,0,0 +14485000,0.704475,0.0005128,-0.0132313,0.709606,0.0031965,0.0096148,-0.0410569,0.00774965,0.000888498,-365.464,-1.14361e-05,-6.06985e-05,-1.12276e-07,-4.80395e-05,3.03468e-05,-0.00115296,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00168862,0.000178368,0.000176704,0.00143727,0.0436361,0.0436322,0.0342537,0.0528696,0.0528695,0.0844897,2.2134e-09,2.21425e-09,5.28426e-09,3.41412e-06,3.41445e-06,4.78308e-07,0,0,0,0,0,0,0,0 +14585000,0.704433,0.00045345,-0.013021,0.709651,0.000643953,0.00750232,-0.040398,0.00491147,-0.00096643,-365.467,-1.17577e-05,-6.10804e-05,-3.54011e-07,-5.2237e-05,3.37413e-05,-0.00115889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00168717,0.000172676,0.000171057,0.00143582,0.0381874,0.0381839,0.033269,0.0460418,0.0460417,0.0844153,2.08806e-09,2.08886e-09,5.13639e-09,3.39999e-06,3.40033e-06,4.50246e-07,0,0,0,0,0,0,0,0 +14685000,0.704613,0.000421675,-0.0130047,0.709473,0.0019525,0.00490909,-0.0382468,0.00507054,-0.000326158,-365.464,-1.17412e-05,-6.10957e-05,6.12905e-07,-5.24303e-05,3.3825e-05,-0.00116641,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00168188,0.000177109,0.000175473,0.00143401,0.0429401,0.0429375,0.0337877,0.0525821,0.0525819,0.0855486,2.0881e-09,2.08892e-09,4.94774e-09,3.39999e-06,3.40034e-06,4.39937e-07,0,0,0,0,0,0,0,0 +14785000,0.70465,0.000403892,-0.0128501,0.709439,-0.000356247,0.00257732,-0.0348767,0.0027795,-0.00179944,-365.459,-1.20121e-05,-6.13848e-05,8.0469e-07,-5.59382e-05,3.71034e-05,-0.00117983,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00167669,0.00017121,0.000169615,0.00143216,0.0376995,0.037697,0.0323758,0.0458576,0.0458574,0.0836679,1.96114e-09,1.9619e-09,4.76809e-09,3.38393e-06,3.3843e-06,4.11654e-07,0,0,0,0,0,0,0,0 +14885000,0.70478,0.000392616,-0.0128034,0.70931,0.000507355,0.00384946,-0.0370909,0.00276926,-0.00148648,-365.462,-1.20003e-05,-6.13954e-05,1.46872e-06,-5.59928e-05,3.70788e-05,-0.00118047,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00167173,0.000175489,0.000173873,0.0014304,0.0424055,0.0424031,0.0328214,0.0523309,0.0523307,0.0847327,1.96119e-09,1.96196e-09,4.5973e-09,3.38394e-06,3.38431e-06,4.01937e-07,0,0,0,0,0,0,0,0 +14985000,0.704739,0.000337996,-0.0127876,0.709351,0.000109091,0.00292243,-0.0333829,0.00225565,-0.00136046,-365.459,-1.20374e-05,-6.14577e-05,1.39226e-06,-5.69851e-05,3.76347e-05,-0.00119254,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00166673,0.000169351,0.00016779,0.0014287,0.0373103,0.037308,0.0314448,0.0456947,0.0456946,0.0828908,1.83369e-09,1.8344e-09,4.43441e-09,3.36612e-06,3.3665e-06,3.76167e-07,0,0,0,0,0,0,0,0 +15085000,0.70479,0.000268969,-0.0127583,0.709302,0.000135388,0.00272987,-0.0348836,0.00226374,-0.00108717,-365.465,-1.20359e-05,-6.14588e-05,1.46269e-06,-5.69366e-05,3.75764e-05,-0.00118943,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00166217,0.00017345,0.000171878,0.00142688,0.0419466,0.0419433,0.0318223,0.0521146,0.0521143,0.0838883,1.83374e-09,1.83446e-09,4.27935e-09,3.36612e-06,3.36651e-06,3.67043e-07,0,0,0,0,0,0,0,0 +15185000,0.704836,0.000231143,-0.0127292,0.709256,1.8695e-05,0.00303014,-0.0323421,0.00186139,-0.000949324,-365.463,-1.20534e-05,-6.15072e-05,1.59068e-06,-5.7694e-05,3.79068e-05,-0.00119871,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00165755,0.000167115,0.000165599,0.00142509,0.0369698,0.0369666,0.0304865,0.0455536,0.0455534,0.0820883,1.70709e-09,1.70775e-09,4.13127e-09,3.34688e-06,3.34729e-06,3.43644e-07,0,0,0,0,0,0,0,0 +15285000,0.704937,0.000198524,-0.0127612,0.709156,0.000299609,0.00330912,-0.0317775,0.00188756,-0.000632944,-365.462,-1.20475e-05,-6.15127e-05,1.94127e-06,-5.77993e-05,3.79711e-05,-0.00120368,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0016565,0.000171035,0.000169507,0.00142379,0.0415576,0.0415535,0.0312031,0.0519314,0.051931,0.0847792,1.70716e-09,1.70782e-09,4.02476e-09,3.34688e-06,3.3473e-06,3.37242e-07,0,0,0,0,0,0,0,0 +15385000,0.705172,0.00017033,-0.0127106,0.708923,0.000358323,0.00314782,-0.0293671,-0.000302306,-0.000604248,-365.459,-1.21239e-05,-6.15876e-05,2.98011e-06,-5.87595e-05,3.89347e-05,-0.00121161,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00165203,0.000164525,0.00016306,0.00142206,0.036664,0.0366619,0.029884,0.0454332,0.045433,0.0829487,1.58257e-09,1.58318e-09,3.8883e-09,3.32649e-06,3.32692e-06,3.15838e-07,0,0,0,0,0,0,0,0 +15485000,0.705071,0.000181862,-0.0127113,0.709022,0.00133392,0.00258174,-0.0288472,-0.000221571,-0.000336631,-365.463,-1.21337e-05,-6.15788e-05,2.42829e-06,-5.87037e-05,3.89513e-05,-0.0012105,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00164781,0.000168258,0.000166775,0.00142042,0.0411728,0.0411709,0.0301536,0.0517771,0.0517767,0.0838521,1.58263e-09,1.58325e-09,3.75816e-09,3.32649e-06,3.32693e-06,3.07917e-07,0,0,0,0,0,0,0,0 +15585000,0.70501,0.000161617,-0.012668,0.709084,-2.0823e-05,0.00213234,-0.0268341,-0.00212756,-0.000394991,-365.464,-1.22352e-05,-6.1624e-05,2.18524e-06,-5.93902e-05,4.00645e-05,-0.00121403,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00164345,0.00016164,0.000160219,0.00141884,0.0363411,0.0363389,0.0288849,0.0453315,0.0453312,0.0820701,1.46144e-09,1.462e-09,3.63359e-09,3.30535e-06,3.30581e-06,2.88583e-07,0,0,0,0,0,0,0,0 +15685000,0.705037,0.00016621,-0.0126875,0.709057,0.000110067,0.00194577,-0.0272472,-0.00214514,-0.000185108,-365.466,-1.22341e-05,-6.1625e-05,2.24842e-06,-5.9405e-05,4.00715e-05,-0.00121471,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00163937,0.000165171,0.000163736,0.00141729,0.0407904,0.0407873,0.0290962,0.0516469,0.0516465,0.0828916,1.4615e-09,1.46207e-09,3.51452e-09,3.30535e-06,3.30581e-06,2.81174e-07,0,0,0,0,0,0,0,0 +15785000,0.705074,0.00010621,-0.0126946,0.70902,0.000830694,-0.000390696,-0.0282529,-0.00173446,-0.00156449,-365.47,-1.22247e-05,-6.18478e-05,2.32944e-06,-6.2487e-05,4.00482e-05,-0.00121414,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0016353,0.000158501,0.000157129,0.00141567,0.0360197,0.0360173,0.0278806,0.0452454,0.0452451,0.08116,1.34475e-09,1.34526e-09,3.4006e-09,3.28376e-06,3.28425e-06,2.63748e-07,0,0,0,0,0,0,0,0 +15885000,0.705048,5.74536e-05,-0.0126897,0.709046,0.00174548,-0.000830653,-0.0275184,-0.00157778,-0.00163668,-365.472,-1.22269e-05,-6.1846e-05,2.21491e-06,-6.24971e-05,4.00763e-05,-0.00121539,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00163428,0.000161823,0.000160444,0.00141462,0.0403848,0.0403825,0.0284166,0.0515364,0.0515359,0.083647,1.34482e-09,1.34534e-09,3.31847e-09,3.28376e-06,3.28425e-06,2.58615e-07,0,0,0,0,0,0,0,0 +15985000,0.705211,-3.29251e-05,-0.0126704,0.708884,0.00192131,-0.00229784,-0.0240688,-0.00136023,-0.00265281,-365.467,-1.22371e-05,-6.20212e-05,3.08169e-06,-6.51118e-05,4.06826e-05,-0.00122394,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00163014,0.000155151,0.000153839,0.00141324,0.0356627,0.0356604,0.0272301,0.0451722,0.045172,0.0818956,1.23344e-09,1.23386e-09,3.21288e-09,3.26202e-06,3.26254e-06,2.42761e-07,0,0,0,0,0,0,0,0 +16085000,0.70533,-3.56999e-05,-0.0126823,0.708766,0.0033306,-0.00254543,-0.021759,-0.00110902,-0.00292286,-365.463,-1.22323e-05,-6.20314e-05,3.53187e-06,-6.54311e-05,4.09452e-05,-0.00123009,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00162638,0.000158276,0.000156952,0.0014118,0.0399442,0.0399426,0.027362,0.05144,0.0514396,0.0826223,1.23353e-09,1.23391e-09,3.11181e-09,3.262e-06,3.26254e-06,2.36407e-07,0,0,0,0,0,0,0,0 +16185000,0.705461,-2.82263e-05,-0.0126494,0.708636,0.0036536,-0.00235634,-0.0199764,-0.00107288,-0.00240302,-365.46,-1.22823e-05,-6.19828e-05,4.13225e-06,-6.49415e-05,4.20904e-05,-0.00123638,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00162258,0.000151674,0.000150405,0.00141037,0.0352726,0.0352715,0.0262324,0.0451086,0.0451083,0.0809254,1.12819e-09,1.12849e-09,3.01499e-09,3.2404e-06,3.24098e-06,2.22155e-07,0,0,0,0,0,0,0,0 +16285000,0.705664,-1.70096e-05,-0.0126583,0.708433,0.00537976,-0.00312313,-0.0207119,-0.000625306,-0.00267203,-365.463,-1.22729e-05,-6.19996e-05,4.89649e-06,-6.53101e-05,4.23409e-05,-0.0012358,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00161907,0.000154601,0.000153319,0.00140892,0.0394568,0.0394568,0.0263276,0.0513529,0.0513525,0.081591,1.12828e-09,1.12854e-09,2.92221e-09,3.24039e-06,3.24097e-06,2.16276e-07,0,0,0,0,0,0,0,0 +16385000,0.70564,-4.13633e-05,-0.0126697,0.708457,0.00466512,-0.00381306,-0.0197022,-0.00069368,-0.00214104,-365.462,-1.23631e-05,-6.19206e-05,4.71351e-06,-6.41643e-05,4.36422e-05,-0.00124014,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00161556,0.000148111,0.000146889,0.00140746,0.0348365,0.0348359,0.0252548,0.045051,0.0450508,0.0799487,1.02947e-09,1.02966e-09,2.83322e-09,3.21919e-06,3.21981e-06,2.03475e-07,0,0,0,0,0,0,0,0 +16485000,0.705647,-4.27333e-05,-0.0126167,0.708451,0.00376788,-0.00347272,-0.0218393,-0.000296501,-0.00250154,-365.466,-1.23634e-05,-6.192e-05,4.68701e-06,-6.41218e-05,4.35999e-05,-0.00123777,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00161218,0.000150841,0.000149606,0.00140611,0.0389215,0.0389189,0.0253182,0.0512699,0.0512695,0.0805565,1.02956e-09,1.02972e-09,2.74786e-09,3.21918e-06,3.21981e-06,1.98046e-07,0,0,0,0,0,0,0,0 +16585000,0.705794,0.00018265,-0.0125762,0.708305,0.000589669,-0.00128613,-0.0228935,-0.0029699,0.00061804,-365.466,-1.27359e-05,-6.15137e-05,5.15972e-06,-5.77622e-05,4.92736e-05,-0.00123946,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00161139,0.000144535,0.000143339,0.00140496,0.0343652,0.0343629,0.024608,0.0449965,0.0449963,0.0805587,9.37563e-10,9.37708e-10,2.68604e-09,3.19862e-06,3.19927e-06,1.87784e-07,0,0,0,0,0,0,0,0 +16685000,0.705745,0.000178116,-0.0125603,0.708355,0.000854102,-0.00111868,-0.0206745,-0.00288511,0.000501061,-365.461,-1.27432e-05,-6.15085e-05,4.80222e-06,-5.78518e-05,4.94411e-05,-0.00124609,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00160819,0.000147076,0.000145871,0.00140357,0.0383395,0.0383368,0.0246495,0.0511875,0.0511871,0.0811342,9.37631e-10,9.37791e-10,2.60653e-09,3.19863e-06,3.19928e-06,1.82784e-07,0,0,0,0,0,0,0,0 +16785000,0.705775,0.000284496,-0.0125388,0.708325,-0.00218509,0.000847522,-0.020181,-0.00504486,0.00299718,-365.46,-1.30455e-05,-6.11751e-05,4.82947e-06,-5.25801e-05,5.41597e-05,-0.00124857,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00160493,0.000140962,0.000139806,0.00140219,0.0338427,0.03384,0.0236674,0.0449422,0.0449419,0.0795373,8.52531e-10,8.52674e-10,2.53012e-09,3.17881e-06,3.17948e-06,1.72356e-07,0,0,0,0,0,0,0,0 +16885000,0.705732,0.000296108,-0.0124825,0.708369,-0.00253119,0.00154794,-0.0186299,-0.00526785,0.00307947,-365.456,-1.3048e-05,-6.11734e-05,4.70947e-06,-5.26358e-05,5.42515e-05,-0.00125334,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00160166,0.000143325,0.000142155,0.00140103,0.0376999,0.0376961,0.0236851,0.051101,0.0511005,0.0800589,8.52602e-10,8.52758e-10,2.45671e-09,3.17882e-06,3.17949e-06,1.67749e-07,0,0,0,0,0,0,0,0 +16985000,0.705668,0.000230778,-0.0123844,0.708435,-0.00213964,-0.000698286,-0.0182556,-0.00556017,0.00122868,-365.456,-1.3135e-05,-6.13556e-05,4.37718e-06,-5.55613e-05,5.57465e-05,-0.00125303,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00159848,0.000137451,0.000136329,0.00139974,0.0332741,0.0332718,0.0227539,0.0448853,0.044885,0.0785043,7.7438e-10,7.7452e-10,2.38603e-09,3.15991e-06,3.16061e-06,1.58374e-07,0,0,0,0,0,0,0,0 +17085000,0.705714,0.000194256,-0.0124689,0.708387,-0.00143618,-0.000183956,-0.0177262,-0.00574529,0.00116511,-365.458,-1.31329e-05,-6.13572e-05,4.4822e-06,-5.55577e-05,5.57211e-05,-0.00125275,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00159545,0.000139637,0.000138517,0.00139851,0.0370017,0.0369995,0.0227516,0.0510071,0.0510066,0.0789751,7.74453e-10,7.74604e-10,2.31814e-09,3.15992e-06,3.16062e-06,1.54133e-07,0,0,0,0,0,0,0,0 +17185000,0.705808,0.000189207,-0.0123934,0.708295,-0.000846784,-5.93418e-05,-0.0187542,-0.00595603,-0.00025657,-365.463,-1.32145e-05,-6.15131e-05,4.73544e-06,-5.79614e-05,5.7171e-05,-0.00124914,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0015947,0.000134038,0.000132959,0.0013975,0.0326641,0.032663,0.0221507,0.0448234,0.0448231,0.0790196,7.02947e-10,7.03076e-10,2.26889e-09,3.14206e-06,3.14278e-06,1.46702e-07,0,0,0,0,0,0,0,0 +17285000,0.705804,0.000159347,-0.012359,0.7083,0.00124187,0.000609148,-0.0150062,-0.00593532,-0.000237154,-365.456,-1.32147e-05,-6.15131e-05,4.72906e-06,-5.80331e-05,5.72677e-05,-0.00125635,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00159166,0.000136064,0.00013498,0.00139639,0.0362715,0.0362723,0.0221351,0.0509036,0.0509032,0.0794602,7.03021e-10,7.03162e-10,2.2054e-09,3.14207e-06,3.14278e-06,1.428e-07,0,0,0,0,0,0,0,0 +17385000,0.705889,0.000116509,-0.0122999,0.708216,0.00216526,-4.44627e-05,-0.0131032,-0.00493164,-0.00145649,-365.453,-1.31941e-05,-6.166e-05,4.88896e-06,-6.04298e-05,5.71273e-05,-0.00126105,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00158875,0.000130741,0.000129698,0.00139508,0.0320347,0.0320355,0.0212909,0.0447553,0.0447551,0.0779574,6.37911e-10,6.38031e-10,2.14421e-09,3.12528e-06,3.12601e-06,1.3516e-07,0,0,0,0,0,0,0,0 +17485000,0.705927,0.000113967,-0.0122993,0.708178,0.00265941,-0.000794759,-0.0113227,-0.00471232,-0.00149814,-365.451,-1.31928e-05,-6.16611e-05,4.95805e-06,-6.04508e-05,5.71425e-05,-0.00126344,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00158591,0.00013262,0.000131571,0.00139393,0.0355156,0.0355166,0.021261,0.05079,0.0507897,0.0783518,6.37988e-10,6.38118e-10,2.08536e-09,3.12529e-06,3.12602e-06,1.31572e-07,0,0,0,0,0,0,0,0 +17585000,0.705953,3.49618e-05,-0.0122719,0.708152,0.00395009,-0.00202473,-0.00650135,-0.00395693,-0.00250605,-365.443,-1.31953e-05,-6.17717e-05,5.08537e-06,-6.23201e-05,5.73829e-05,-0.00127127,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00158295,0.00012758,0.000126579,0.00139284,0.0313757,0.0313773,0.0204668,0.0446797,0.0446795,0.0769047,5.78911e-10,5.79022e-10,2.02859e-09,3.10959e-06,3.11032e-06,1.24709e-07,0,0,0,0,0,0,0,0 +17685000,0.705998,-2.47225e-06,-0.0122517,0.708108,0.00502641,-0.00170023,-0.00685903,-0.00350486,-0.0026942,-365.443,-1.31928e-05,-6.17752e-05,5.25567e-06,-6.24152e-05,5.74421e-05,-0.00127134,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00158015,0.000129314,0.000128311,0.0013918,0.0347368,0.0347392,0.0204256,0.0506644,0.0506643,0.0772565,5.78997e-10,5.79101e-10,1.97395e-09,3.10958e-06,3.11032e-06,1.21413e-07,0,0,0,0,0,0,0,0 +17785000,0.706184,-9.02459e-05,-0.0122791,0.707922,0.00751341,-0.00167263,-0.00709601,-0.00236337,-0.0022594,-365.446,-1.30468e-05,-6.17585e-05,5.96753e-06,-6.23328e-05,5.52496e-05,-0.00127058,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00157733,0.000124565,0.000123607,0.00139073,0.0307071,0.0307097,0.0196789,0.0445958,0.0445958,0.0758634,5.25565e-10,5.25637e-10,1.92124e-09,3.09494e-06,3.0957e-06,1.15244e-07,0,0,0,0,0,0,0,0 +17885000,0.706223,-8.44781e-05,-0.0122643,0.707884,0.00900759,-0.00266712,-0.00637263,-0.00154624,-0.0024454,-365.446,-1.30457e-05,-6.17599e-05,6.03738e-06,-6.23736e-05,5.52769e-05,-0.00127111,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00157675,0.000126174,0.000125211,0.00138989,0.0339412,0.0339448,0.0198728,0.0505271,0.0505271,0.0776546,5.25657e-10,5.25721e-10,1.88298e-09,3.09494e-06,3.09571e-06,1.12967e-07,0,0,0,0,0,0,0,0 +17985000,0.70633,-0.000139114,-0.0122749,0.707777,0.0108106,-0.00430797,-0.00456107,-0.000827187,-0.00207042,-365.445,-1.2974e-05,-6.17164e-05,6.20425e-06,-6.1705e-05,5.40107e-05,-0.00127328,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00157427,0.000121718,0.000120793,0.00138861,0.0300233,0.0300265,0.0191566,0.0445035,0.0445036,0.0762616,4.77434e-10,4.77472e-10,1.83351e-09,3.08136e-06,3.08213e-06,1.07356e-07,0,0,0,0,0,0,0,0 +18085000,0.706237,-0.000141534,-0.0122867,0.707869,0.0114181,-0.00484221,-0.00282013,0.000295101,-0.00256311,-365.44,-1.29804e-05,-6.17082e-05,5.78938e-06,-6.15052e-05,5.39265e-05,-0.00127703,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00157176,0.000123206,0.000122278,0.00138754,0.0331408,0.0331441,0.0191009,0.0503777,0.050378,0.0765484,4.77523e-10,4.77553e-10,1.78582e-09,3.08135e-06,3.08214e-06,1.04569e-07,0,0,0,0,0,0,0,0 +18185000,0.70635,-0.000168937,-0.0122685,0.707756,0.0121278,-0.00385645,-0.00135958,0.00118856,-0.00198872,-365.438,-1.29943e-05,-6.16435e-05,6.06576e-06,-6.04475e-05,5.43025e-05,-0.00127901,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00156929,0.000119035,0.000118138,0.0013864,0.0293414,0.0293441,0.0184283,0.0444026,0.0444028,0.0752084,4.34076e-10,4.34085e-10,1.73973e-09,3.06877e-06,3.06956e-06,9.95165e-08,0,0,0,0,0,0,0,0 +18285000,0.706374,-0.000234388,-0.0122225,0.707734,0.0122492,-0.00463252,-0.00028924,0.00240466,-0.00240561,-365.436,-1.29971e-05,-6.16401e-05,5.88959e-06,-6.03612e-05,5.42643e-05,-0.00128026,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00156703,0.000120405,0.00011951,0.00138519,0.0323383,0.0323405,0.0183644,0.0502171,0.0502174,0.0754492,4.34164e-10,4.34168e-10,1.69523e-09,3.06877e-06,3.06957e-06,9.69475e-08,0,0,0,0,0,0,0,0 +18385000,0.70653,-0.000219844,-0.0122503,0.707577,0.0136065,-0.00279817,0.00107759,0.00300074,-0.00182433,-365.432,-1.30286e-05,-6.15849e-05,6.25772e-06,-5.946e-05,5.49801e-05,-0.00128292,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00156471,0.000116511,0.000115644,0.00138402,0.0286592,0.0286618,0.0177329,0.0442935,0.0442938,0.0741607,3.95076e-10,3.95065e-10,1.65226e-09,3.05715e-06,3.05797e-06,9.23955e-08,0,0,0,0,0,0,0,0 +18485000,0.70661,-0.000194901,-0.0122357,0.707498,0.0146348,-0.00286205,0.000917934,0.00445565,-0.00210912,-365.43,-1.30254e-05,-6.15887e-05,6.45296e-06,-5.95579e-05,5.50345e-05,-0.00128407,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0015642,0.00011779,0.000116917,0.00138324,0.0315464,0.0315494,0.017883,0.0500459,0.0500464,0.0757904,3.95168e-10,3.95154e-10,1.62103e-09,3.05716e-06,3.05797e-06,9.06296e-08,0,0,0,0,0,0,0,0 +18585000,0.706739,-0.000190791,-0.0121563,0.70737,0.0136963,-0.00260836,0.000282295,0.00341875,-0.00173338,-365.432,-1.31861e-05,-6.15544e-05,6.75772e-06,-5.89312e-05,5.79856e-05,-0.00128345,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00156191,0.000114147,0.000113302,0.00138213,0.0279844,0.0279869,0.017278,0.0441763,0.0441766,0.0745041,3.60026e-10,3.60001e-10,1.58057e-09,3.04643e-06,3.04726e-06,8.64766e-08,0,0,0,0,0,0,0,0 +18685000,0.70673,-0.000239236,-0.0121757,0.707379,0.0140345,-0.00333343,-0.00131484,0.00480848,-0.00199011,-365.437,-1.31872e-05,-6.15531e-05,6.69343e-06,-5.88996e-05,5.79519e-05,-0.00128014,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0015596,0.000115325,0.000114484,0.00138119,0.0307564,0.0307586,0.0172085,0.0498647,0.0498653,0.074692,3.60115e-10,3.60088e-10,1.54147e-09,3.04644e-06,3.04727e-06,8.4302e-08,0,0,0,0,0,0,0,0 +18785000,0.706712,-0.000199904,-0.0121473,0.707397,0.0127252,-0.00309272,-0.000681207,0.0037222,-0.00156774,-365.438,-1.33449e-05,-6.15051e-05,6.52439e-06,-5.79531e-05,6.06432e-05,-0.00127999,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00155736,0.000111935,0.000111118,0.00138015,0.0273095,0.0273111,0.0166407,0.0440514,0.0440519,0.0734556,3.28547e-10,3.28513e-10,1.50365e-09,3.03656e-06,3.0374e-06,8.05522e-08,0,0,0,0,0,0,0,0 +18885000,0.706847,-0.000197093,-0.0121209,0.707262,0.0133875,-0.00271788,-0.000206854,0.00501782,-0.00182557,-365.436,-1.3338e-05,-6.15129e-05,6.93741e-06,-5.81383e-05,6.07247e-05,-0.00128115,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00155513,0.000113033,0.000112213,0.00137923,0.0299776,0.0299792,0.0165697,0.0496738,0.0496744,0.0736166,3.28636e-10,3.286e-10,1.46708e-09,3.03657e-06,3.03741e-06,7.85535e-08,0,0,0,0,0,0,0,0 +18985000,0.706893,-0.000188916,-0.0121337,0.707216,0.0146306,-0.00176156,-0.00163385,0.00630432,-0.00146754,-365.438,-1.33039e-05,-6.14833e-05,7.10806e-06,-5.76798e-05,6.01325e-05,-0.00127977,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00155286,0.000109877,0.000109078,0.00137834,0.0266526,0.026654,0.0160367,0.0439191,0.0439195,0.0724282,3.00284e-10,3.00244e-10,1.43172e-09,3.02748e-06,3.02833e-06,7.51635e-08,0,0,0,0,0,0,0,0 +19085000,0.706941,-0.000212007,-0.012078,0.70717,0.015391,-0.00133375,0.00161701,0.00778276,-0.0015936,-365.431,-1.33015e-05,-6.14857e-05,7.24012e-06,-5.77213e-05,6.01643e-05,-0.0012835,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00155071,0.000110894,0.000110093,0.00137747,0.029215,0.0292164,0.0159652,0.0494745,0.0494751,0.0725648,3.00374e-10,3.00332e-10,1.39749e-09,3.02749e-06,3.02834e-06,7.33262e-08,0,0,0,0,0,0,0,0 +19185000,0.706966,-0.000205744,-0.0119838,0.707146,0.0152579,-0.00108926,0.000401378,0.00856395,-0.00130914,-365.432,-1.33006e-05,-6.14674e-05,7.27443e-06,-5.74426e-05,6.00991e-05,-0.00128226,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0015502,0.000107954,0.000107169,0.00137675,0.0260048,0.0260053,0.0156443,0.0437802,0.0437806,0.0727207,2.74912e-10,2.7487e-10,1.37255e-09,3.01913e-06,3.01999e-06,7.06811e-08,0,0,0,0,0,0,0,0 +19285000,0.706908,-0.000174678,-0.0119308,0.707205,0.0155501,-0.00191372,0.00257128,0.0100745,-0.00145094,-365.426,-1.33047e-05,-6.1463e-05,7.0335e-06,-5.73219e-05,6.00746e-05,-0.00128563,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00154811,0.000108906,0.000108113,0.00137587,0.0284722,0.0284723,0.0155731,0.0492677,0.0492681,0.0728394,2.75002e-10,2.74959e-10,1.3402e-09,3.01914e-06,3.02e-06,6.89846e-08,0,0,0,0,0,0,0,0 +19385000,0.706981,-0.000172201,-0.0118636,0.707133,0.0133349,-0.00263749,0.006256,0.00813176,-0.00121038,-365.42,-1.34703e-05,-6.14411e-05,7.19456e-06,-5.68443e-05,6.31647e-05,-0.00128882,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00154605,0.000106165,0.000105397,0.00137494,0.0253679,0.0253676,0.0150938,0.043635,0.0436353,0.0717008,2.52128e-10,2.52085e-10,1.30888e-09,3.01146e-06,3.01233e-06,6.6173e-08,0,0,0,0,0,0,0,0 +19485000,0.707108,-0.000158731,-0.0118754,0.707006,0.0125263,-0.003866,0.00363273,0.00939879,-0.00154825,-365.424,-1.3465e-05,-6.14467e-05,7.50526e-06,-5.69899e-05,6.31951e-05,-0.00128628,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0015441,0.00010705,0.00010628,0.00137402,0.0277447,0.0277434,0.0150234,0.0490538,0.0490541,0.0717989,2.52219e-10,2.52175e-10,1.27854e-09,3.01146e-06,3.01234e-06,6.46117e-08,0,0,0,0,0,0,0,0 +19585000,0.70722,-9.16465e-05,-0.0117826,0.706895,0.0106124,-0.00456627,0.00315134,0.00766498,-0.00129565,-365.426,-1.35923e-05,-6.14181e-05,7.88878e-06,-5.64351e-05,6.56837e-05,-0.00128519,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00154203,0.000104508,0.000103752,0.00137322,0.0247543,0.024753,0.0145712,0.0434842,0.0434844,0.0706952,2.31664e-10,2.3162e-10,1.24914e-09,3.0044e-06,3.00529e-06,6.2056e-08,0,0,0,0,0,0,0,0 +19685000,0.707185,-0.000103493,-0.0118222,0.70693,0.0112599,-0.00717011,0.00483191,0.00875317,-0.00187812,-365.425,-1.35963e-05,-6.1414e-05,7.6601e-06,-5.63458e-05,6.5664e-05,-0.00128534,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00154018,0.00010533,0.000104578,0.0013723,0.0270336,0.0270326,0.0145022,0.0488341,0.0488342,0.0707748,2.31755e-10,2.31711e-10,1.22066e-09,3.00441e-06,3.0053e-06,6.06184e-08,0,0,0,0,0,0,0,0 +19785000,0.707238,-3.11169e-05,-0.0118151,0.706876,0.00870298,-0.00784811,0.00507958,0.00714472,-0.00153459,-365.424,-1.37091e-05,-6.13576e-05,7.70695e-06,-5.5255e-05,6.77609e-05,-0.00128511,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00153983,0.000102971,0.000102233,0.00137155,0.0241511,0.0241499,0.0142383,0.0433284,0.0433285,0.0709594,2.13278e-10,2.13234e-10,1.19989e-09,2.99793e-06,2.99884e-06,5.8635e-08,0,0,0,0,0,0,0,0 +19885000,0.707398,-7.5632e-05,-0.0117529,0.706718,0.00764875,-0.00840997,0.00652924,0.00797459,-0.0023555,-365.423,-1.37012e-05,-6.13656e-05,8.14986e-06,-5.54141e-05,6.77901e-05,-0.00128543,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00153795,0.000103736,0.000102998,0.00137072,0.026348,0.026346,0.0141709,0.0486094,0.0486093,0.0710248,2.13369e-10,2.13325e-10,1.17291e-09,2.99794e-06,2.99885e-06,5.73048e-08,0,0,0,0,0,0,0,0 +19985000,0.707546,-9.6476e-05,-0.0117457,0.70657,0.00519696,-0.00896752,0.00840485,0.00652183,-0.0019532,-365.419,-1.37772e-05,-6.13083e-05,8.52246e-06,-5.4298e-05,6.93267e-05,-0.00128643,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00153615,0.000101534,0.000100818,0.00136984,0.0235675,0.0235656,0.0137637,0.0431681,0.043168,0.069968,1.96743e-10,1.96698e-10,1.14674e-09,2.99199e-06,2.99292e-06,5.51697e-08,0,0,0,0,0,0,0,0 +20085000,0.707745,-0.000118466,-0.0117124,0.706371,0.00483967,-0.0109306,0.00917836,0.00702809,-0.00292566,-365.416,-1.37665e-05,-6.13189e-05,9.12014e-06,-5.44926e-05,6.93478e-05,-0.00128749,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00153433,0.000102252,0.000101536,0.00136906,0.0256868,0.0256849,0.0136984,0.0483804,0.0483801,0.0700181,1.96835e-10,1.9679e-10,1.12138e-09,2.992e-06,2.99293e-06,5.39432e-08,0,0,0,0,0,0,0,0 +20185000,0.70782,-4.23287e-06,-0.0117,0.706296,0.00278404,-0.0113978,0.0116133,0.0047046,-0.00238423,-365.412,-1.38836e-05,-6.12405e-05,9.31026e-06,-5.27245e-05,7.14493e-05,-0.00128922,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00153257,0.000100217,9.95076e-05,0.00136823,0.0230055,0.0230041,0.0133155,0.043004,0.0430037,0.0690022,1.81859e-10,1.81816e-10,1.09676e-09,2.98653e-06,2.98748e-06,5.19986e-08,0,0,0,0,0,0,0,0 +20285000,0.707893,-3.61767e-05,-0.0116782,0.706223,0.00180912,-0.0132416,0.0100851,0.00492817,-0.00361614,-365.414,-1.38814e-05,-6.12427e-05,9.43664e-06,-5.27904e-05,7.14579e-05,-0.00128781,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00153093,0.000100888,0.00010018,0.00136737,0.0250502,0.0250489,0.0132525,0.0481484,0.0481479,0.0690386,1.8195e-10,1.81909e-10,1.0729e-09,2.98654e-06,2.98748e-06,5.08672e-08,0,0,0,0,0,0,0,0 +20385000,0.707918,-9.59066e-06,-0.0117283,0.706197,-0.000766754,-0.0137158,0.0124022,0.00297788,-0.00295258,-365.409,-1.39689e-05,-6.11475e-05,9.34708e-06,-5.0902e-05,7.31143e-05,-0.00128991,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00152939,9.89872e-05,9.82949e-05,0.00136641,0.022466,0.0224652,0.0128923,0.0428368,0.0428365,0.0680616,1.68448e-10,1.68409e-10,1.04971e-09,2.98151e-06,2.98247e-06,5e-08,0,0,0,0,0,0,0,0 +20485000,0.707967,2.65937e-05,-0.0117363,0.706148,-0.00113463,-0.0148652,0.0125089,0.00287192,-0.0043765,-365.41,-1.39693e-05,-6.11473e-05,9.33151e-06,-5.09519e-05,7.31538e-05,-0.00128879,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00152921,9.9624e-05,9.89279e-05,0.00136566,0.024435,0.0244343,0.0129735,0.0479141,0.0479135,0.069265,1.68542e-10,1.68504e-10,1.03279e-09,2.98152e-06,2.98247e-06,5.0002e-08,0,0,0,0,0,0,0,0 +20585000,0.707922,5.82116e-05,-0.0118131,0.706192,-0.000889398,-0.0145911,0.00967212,0.00241788,-0.00360666,-365.414,-1.39784e-05,-6.10461e-05,9.11227e-06,-4.91903e-05,7.3345e-05,-0.00128591,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00152758,9.78576e-05,9.71734e-05,0.00136482,0.0219466,0.0219464,0.0126285,0.0426673,0.0426669,0.0682925,1.56357e-10,1.56321e-10,1.01075e-09,2.97689e-06,2.97786e-06,5.0001e-08,0,0,0,0,0,0,0,0 +20685000,0.707989,7.7341e-05,-0.0118311,0.706124,-0.00079266,-0.01621,0.0108237,0.00232795,-0.00512709,-365.41,-1.39776e-05,-6.10467e-05,9.14774e-06,-4.91492e-05,7.33128e-05,-0.00128733,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00152608,9.84548e-05,9.77687e-05,0.00136392,0.0238495,0.0238496,0.0125718,0.0476786,0.0476779,0.0683069,1.56448e-10,1.56416e-10,9.89362e-10,2.9769e-06,2.97786e-06,5.0001e-08,0,0,0,0,0,0,0,0 +20785000,0.708041,0.000112822,-0.0118369,0.706072,-0.00196349,-0.0149392,0.0108667,0.0019228,-0.00418274,-365.41,-1.39798e-05,-6.09447e-05,9.18363e-06,-4.71471e-05,7.32866e-05,-0.00128624,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00152453,9.68085e-05,9.61277e-05,0.00136307,0.0214454,0.0214456,0.0122483,0.0424959,0.0424954,0.0673715,1.45438e-10,1.45405e-10,9.68569e-10,2.97263e-06,2.9736e-06,5.0001e-08,0,0,0,0,0,0,0,0 +20885000,0.708172,9.77693e-05,-0.0118259,0.705941,-0.00240923,-0.0176525,0.0104994,0.00171443,-0.00580595,-365.411,-1.39747e-05,-6.09485e-05,9.43015e-06,-4.70799e-05,7.31214e-05,-0.00128528,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00152305,9.73675e-05,9.66866e-05,0.00136222,0.0232831,0.0232841,0.012195,0.047442,0.0474413,0.0673687,1.4553e-10,1.455e-10,9.48364e-10,2.97264e-06,2.9736e-06,5e-08,0,0,0,0,0,0,0,0 +20985000,0.708195,0.000111138,-0.0118725,0.705917,-0.00261986,-0.0180357,0.011163,0.003197,-0.00484129,-365.411,-1.39296e-05,-6.08407e-05,9.42545e-06,-4.4968e-05,7.21961e-05,-0.00128482,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00152151,9.58328e-05,9.51578e-05,0.00136143,0.0209628,0.0209646,0.0118924,0.0423231,0.0423226,0.0664689,1.3557e-10,1.35539e-10,9.28736e-10,2.9687e-06,2.96968e-06,5e-08,0,0,0,0,0,0,0,0 +21085000,0.708325,9.62031e-05,-0.0118662,0.705787,-0.0025747,-0.0207802,0.0119946,0.00292439,-0.00678395,-365.41,-1.39265e-05,-6.0843e-05,9.57728e-06,-4.49158e-05,7.20911e-05,-0.00128479,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00152143,9.636e-05,9.56857e-05,0.00136064,0.0227384,0.0227413,0.0119725,0.0472049,0.0472044,0.0675889,1.35664e-10,1.35636e-10,9.14404e-10,2.96871e-06,2.96969e-06,5.0002e-08,0,0,0,0,0,0,0,0 +21185000,0.708323,0.000135117,-0.0118969,0.705788,-0.00193928,-0.0195788,0.0114411,0.00426542,-0.00563742,-365.413,-1.38876e-05,-6.07205e-05,9.4408e-06,-4.2611e-05,7.131e-05,-0.00128272,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00151998,9.49321e-05,9.42582e-05,0.00135979,0.020499,0.0205018,0.0116846,0.0421491,0.0421487,0.0666936,1.26644e-10,1.26613e-10,8.95719e-10,2.96509e-06,2.96608e-06,5.0002e-08,0,0,0,0,0,0,0,0 +21285000,0.70849,0.000168385,-0.0118573,0.705621,-0.00266649,-0.021776,0.0128821,0.00403432,-0.0076939,-365.409,-1.38827e-05,-6.07243e-05,9.67936e-06,-4.2511e-05,7.11379e-05,-0.00128365,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00151871,9.54353e-05,9.47549e-05,0.00135884,0.0222178,0.0222215,0.0116431,0.046968,0.0469677,0.0666762,1.26736e-10,1.26709e-10,8.77545e-10,2.9651e-06,2.96608e-06,5.0001e-08,0,0,0,0,0,0,0,0 +21385000,0.708442,0.000226404,-0.0118823,0.705669,-0.00346295,-0.0210351,0.0130913,0.0033724,-0.00543726,-365.411,-1.3886e-05,-6.05541e-05,9.51411e-06,-3.91943e-05,7.1125e-05,-0.00128207,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00151718,9.41023e-05,9.34214e-05,0.00135814,0.0200547,0.0200589,0.0113748,0.0419746,0.0419743,0.065815,1.18556e-10,1.18526e-10,8.59875e-10,2.96176e-06,2.96276e-06,5.0001e-08,0,0,0,0,0,0,0,0 +21485000,0.708514,0.000236512,-0.0118589,0.705597,-0.00388952,-0.0224927,0.0131033,0.00297179,-0.00760005,-365.411,-1.3884e-05,-6.05557e-05,9.61153e-06,-3.9177e-05,7.10623e-05,-0.00128148,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00151578,9.45766e-05,9.38927e-05,0.00135737,0.0217197,0.0217244,0.0113402,0.0467319,0.0467319,0.0657927,1.18649e-10,1.18622e-10,8.42682e-10,2.96177e-06,2.96276e-06,5e-08,0,0,0,0,0,0,0,0 +21585000,0.708508,0.000252447,-0.0118577,0.705603,-0.00462234,-0.0194569,0.0129351,0.00245422,-0.00533626,-365.414,-1.38776e-05,-6.03945e-05,9.49267e-06,-3.6e-05,7.08428e-05,-0.00127961,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00151437,9.33276e-05,9.26439e-05,0.0013566,0.0196305,0.0196344,0.0110907,0.0417999,0.0417999,0.0649643,1.1122e-10,1.1119e-10,8.25956e-10,2.95869e-06,2.95969e-06,5e-08,0,0,0,0,0,0,0,0 +21685000,0.708517,0.000249341,-0.011893,0.705594,-0.00450575,-0.0209696,0.0146777,0.00199221,-0.00737471,-365.413,-1.38782e-05,-6.03941e-05,9.46351e-06,-3.6017e-05,7.08659e-05,-0.00127927,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00151296,9.37762e-05,9.30946e-05,0.00135591,0.0212412,0.0212454,0.0110633,0.0464971,0.0464973,0.0649385,1.11313e-10,1.11286e-10,8.09677e-10,2.9587e-06,2.95969e-06,5e-08,0,0,0,0,0,0,0,0 +21785000,0.708492,0.000275343,-0.0119234,0.705618,-0.00518398,-0.0160357,0.0136043,0.000665961,-0.00316575,-365.417,-1.3909e-05,-6.01665e-05,9.29735e-06,-3.14436e-05,7.13792e-05,-0.00127693,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00151271,9.2606e-05,9.1928e-05,0.0013553,0.0192233,0.0192264,0.0109408,0.0416255,0.0416257,0.0651869,1.0456e-10,1.0453e-10,7.97771e-10,2.95586e-06,2.95687e-06,5.0002e-08,0,0,0,0,0,0,0,0 +21885000,0.708518,0.000277178,-0.0118729,0.705593,-0.00486552,-0.0164753,0.0144948,0.000160776,-0.00478824,-365.418,-1.3911e-05,-6.01649e-05,9.19845e-06,-3.14961e-05,7.14578e-05,-0.00127589,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00151146,9.30327e-05,9.2351e-05,0.00135448,0.0207865,0.0207893,0.0109206,0.046264,0.0462644,0.0651581,1.04653e-10,1.04626e-10,7.82236e-10,2.95587e-06,2.95688e-06,5.0001e-08,0,0,0,0,0,0,0,0 +21985000,0.708562,0.000310973,-0.0119431,0.705548,-0.0055841,-0.0138389,0.0149766,-0.000842855,-0.00112719,-365.419,-1.39291e-05,-5.9975e-05,9.20277e-06,-2.75613e-05,7.16886e-05,-0.00127439,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00151013,9.19384e-05,9.12608e-05,0.00135372,0.0189281,0.0189309,0.0107012,0.0414521,0.0414524,0.0643666,9.85014e-11,9.84728e-11,7.67112e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +22085000,0.70857,0.000319922,-0.0119289,0.705539,-0.00582782,-0.01315,0.0135736,-0.00139208,-0.00246681,-365.421,-1.39308e-05,-5.99736e-05,9.11767e-06,-2.75613e-05,7.16886e-05,-0.00127317,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00150882,9.23453e-05,9.16656e-05,0.001353,0.0213021,0.0213054,0.0106888,0.0460579,0.0460585,0.0643371,9.85953e-11,9.8569e-11,7.5238e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +22185000,0.708612,0.000307782,-0.0119272,0.705498,-0.00543725,-0.0119613,0.0145338,-0.00118054,-0.0020626,-365.422,-1.39061e-05,-5.99178e-05,9.11335e-06,-2.75613e-05,7.16886e-05,-0.00127196,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00150751,9.04804e-05,8.97974e-05,0.00135226,0.0205922,0.0205953,0.0104844,0.0413163,0.0413167,0.0635697,9.28048e-11,9.27782e-11,7.38025e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +22285000,0.70857,0.00034313,-0.0119603,0.705539,-0.00679179,-0.0128774,0.0146429,-0.00179045,-0.00331136,-365.424,-1.39094e-05,-5.99152e-05,8.95197e-06,-2.75613e-05,7.16886e-05,-0.00127083,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00150615,9.08636e-05,9.01786e-05,0.00135162,0.0240449,0.0240493,0.0104793,0.0459703,0.0459712,0.0635411,9.2899e-11,9.28745e-11,7.24048e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +22385000,0.708595,0.000337721,-0.0119928,0.705514,-0.00732942,-0.0118242,0.0162314,-0.00154343,-0.00280452,-365.421,-1.38786e-05,-5.98609e-05,8.97858e-06,-2.75613e-05,7.16886e-05,-0.00127121,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00150581,8.73334e-05,8.66389e-05,0.00135111,0.0238053,0.0238096,0.0103908,0.0412679,0.0412686,0.0638117,8.74202e-11,8.73967e-11,7.13824e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +22485000,0.708624,0.000346478,-0.0119583,0.705485,-0.00782361,-0.0117703,0.0176486,-0.00229737,-0.00401065,-365.417,-1.3879e-05,-5.98606e-05,8.9606e-06,-2.75613e-05,7.16886e-05,-0.00127201,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00150454,8.76777e-05,8.69796e-05,0.00135044,0.0281744,0.0281789,0.0103931,0.0460474,0.0460486,0.0637843,8.75148e-11,8.74932e-11,7.00464e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +22585000,0.708659,0.000332284,-0.0120246,0.705449,-0.00719769,-0.0102298,0.0167409,-0.00264725,-0.00234229,-365.419,-1.38391e-05,-5.97764e-05,8.96061e-06,-2.75613e-05,7.16886e-05,-0.00127054,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00150321,8.2308e-05,8.15923e-05,0.00134971,0.0278357,0.0278393,0.0102135,0.0413465,0.0413474,0.0630526,8.24884e-11,8.24696e-11,6.87438e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +22685000,0.70869,0.000371015,-0.0120511,0.705417,-0.0082765,-0.0101464,0.0180647,-0.00340394,-0.00336776,-365.418,-1.38391e-05,-5.97764e-05,8.96099e-06,-2.75613e-05,7.16886e-05,-0.00127039,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00150194,8.26125e-05,8.18938e-05,0.00134907,0.032889,0.0328931,0.0102229,0.0463384,0.04634,0.0630286,8.25834e-11,8.25662e-11,6.74745e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +22785000,0.708571,0.000363692,-0.0120793,0.705536,-0.00836294,-0.00801612,0.0188425,-0.00459575,-0.00272655,-365.414,-1.3841e-05,-5.97293e-05,8.50529e-06,-2.75613e-05,7.16886e-05,-0.00127097,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00150069,7.56419e-05,7.48963e-05,0.00134826,0.031908,0.0319103,0.0100563,0.0415782,0.0415793,0.0623255,7.81722e-11,7.81588e-11,6.62365e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +22885000,0.708588,0.000376498,-0.0120557,0.705519,-0.00949655,-0.00776622,0.0204821,-0.00548098,-0.00351572,-365.412,-1.38431e-05,-5.97276e-05,8.39964e-06,-2.75613e-05,7.16886e-05,-0.00127103,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00149952,7.58975e-05,7.51484e-05,0.00134755,0.037382,0.0373845,0.0100726,0.0468477,0.0468494,0.062306,7.82674e-11,7.82555e-11,6.50294e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +22985000,0.708606,0.000363317,-0.0120943,0.705501,-0.00910387,-0.00719213,0.0214986,-0.00624538,-0.00288444,-365.409,-1.38297e-05,-5.96977e-05,8.33891e-06,-2.75613e-05,7.16886e-05,-0.0012712,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00149823,6.78716e-05,6.70901e-05,0.00134681,0.0353838,0.0353849,0.00991762,0.0419545,0.0419556,0.0616306,7.45867e-11,7.45789e-11,6.3852e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +23085000,0.708594,0.000325217,-0.0120465,0.705514,-0.00949669,-0.00710971,0.0216372,-0.00717952,-0.00358481,-365.405,-1.38318e-05,-5.9696e-05,8.22943e-06,-2.75613e-05,7.16886e-05,-0.00127196,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00149798,6.80768e-05,6.72958e-05,0.00134633,0.0410269,0.0410273,0.0100336,0.0475269,0.0475286,0.0625806,7.46833e-11,7.46766e-11,6.29902e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +23185000,0.708605,0.000467851,-0.0119708,0.705504,-0.0125809,-0.00699628,0.0229671,-0.0111961,-0.0029176,-365.4,-1.38907e-05,-5.9668e-05,8.11959e-06,-2.75613e-05,7.16886e-05,-0.0012725,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00149672,5.96734e-05,5.88472e-05,0.00134556,0.0378865,0.0378851,0.00988619,0.0424338,0.042435,0.0619112,7.17638e-11,7.17611e-11,6.18622e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23285000,0.708589,0.000402301,-0.0119829,0.705519,-0.0131271,-0.0083338,0.0235257,-0.012481,-0.00369692,-365.4,-1.38922e-05,-5.96667e-05,8.0456e-06,-2.75613e-05,7.16886e-05,-0.00127164,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00149544,5.98353e-05,5.90165e-05,0.00134504,0.0434484,0.0434462,0.00991536,0.0482917,0.0482932,0.0619032,7.18596e-11,7.18581e-11,6.07623e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23385000,0.708611,0.000547208,-0.0119166,0.705498,-0.0153435,-0.00750471,0.0221149,-0.0156235,-0.00293001,-365.404,-1.39234e-05,-5.96404e-05,7.96211e-06,-2.75613e-05,7.16886e-05,-0.00126947,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00149419,5.16609e-05,5.07869e-05,0.00134428,0.0392747,0.0392711,0.00977781,0.0429581,0.0429591,0.0612602,6.96499e-11,6.96521e-11,5.96885e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23485000,0.708663,0.00269086,-0.00975969,0.705475,-0.0221865,-0.0082692,-0.00981245,-0.0174432,-0.00372432,-365.405,-1.39223e-05,-5.96413e-05,8.01874e-06,-2.75613e-05,7.16886e-05,-0.0012689,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00149274,5.20589e-05,5.07971e-05,0.00134382,0.0447705,0.0447716,0.0098112,0.0490546,0.0490558,0.0612537,6.9746e-11,6.97492e-11,5.86405e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +23585000,0.708243,0.00805878,-0.00226894,0.705919,-0.03025,-0.00486546,-0.0415761,-0.0155926,-0.00152742,-365.406,-1.3872e-05,-5.96038e-05,7.83968e-06,-2.75613e-05,7.16886e-05,-0.00126945,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00148936,4.52916e-05,4.29354e-05,0.00134476,0.039913,0.0399134,0.00968127,0.043474,0.0434748,0.0606358,6.81396e-11,6.81458e-11,5.76185e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +23685000,0.7076,0.00792972,0.00397868,0.706558,-0.0607622,-0.0125567,-0.0903229,-0.0200373,-0.00231898,-365.414,-1.3873e-05,-5.96028e-05,7.78534e-06,-2.75613e-05,7.16886e-05,-0.00126883,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00148641,4.53981e-05,4.30545e-05,0.00134702,0.0451554,0.0451562,0.00980536,0.0497582,0.0497594,0.0615762,6.82369e-11,6.82436e-11,5.68702e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +23785000,0.707289,0.00496641,0.000772219,0.706907,-0.0799222,-0.021325,-0.144078,-0.0171388,-0.000639684,-365.424,-1.3772e-05,-5.95727e-05,7.74228e-06,-2.75613e-05,7.16886e-05,-0.00127054,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00148434,3.81947e-05,3.62436e-05,0.0013477,0.0398125,0.039802,0.00967771,0.0439444,0.0439453,0.0609635,6.71106e-11,6.712e-11,5.58896e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +23885000,0.707121,0.00226297,-0.00528971,0.707069,-0.0967645,-0.0302902,-0.197378,-0.0260915,-0.00326706,-365.445,-1.37722e-05,-5.95724e-05,7.72958e-06,-2.75613e-05,7.16886e-05,-0.00126926,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00148303,3.79023e-05,3.64204e-05,0.00134762,0.0446823,0.0446602,0.00972009,0.0503519,0.0503539,0.0609729,6.72071e-11,6.72172e-11,5.49322e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23985000,0.707024,0.000747364,-0.010112,0.707117,-0.0955347,-0.0330888,-0.250312,-0.0292058,-0.00631947,-365.467,-1.37186e-05,-5.95731e-05,7.63828e-06,-2.75613e-05,7.16886e-05,-0.00126977,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00148163,3.1863e-05,3.08047e-05,0.00134675,0.0389672,0.0389471,0.00960433,0.0443399,0.0443411,0.0603837,6.64437e-11,6.64558e-11,5.39965e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +24085000,0.707046,0.00195058,-0.00908937,0.707107,-0.0969478,-0.0330736,-0.298282,-0.0388022,-0.00963384,-365.492,-1.37175e-05,-5.95742e-05,7.70211e-06,-2.75613e-05,7.16886e-05,-0.00127081,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00148023,3.20917e-05,3.08259e-05,0.00134638,0.0433685,0.0433448,0.00965447,0.0507985,0.0508003,0.0604019,6.65403e-11,6.65532e-11,5.30829e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +24185000,0.707037,0.00303228,-0.00683631,0.707137,-0.0966131,-0.0326886,-0.345769,-0.0397644,-0.0113581,-365.517,-1.36555e-05,-5.95682e-05,7.6787e-06,-2.75613e-05,7.16886e-05,-0.00127498,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00147859,2.73012e-05,2.57981e-05,0.00134591,0.0375762,0.0375516,0.0095451,0.0446412,0.0446422,0.0598352,6.60395e-11,6.60539e-11,5.21905e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +24285000,0.706911,0.00355162,-0.00592156,0.707269,-0.106642,-0.0365233,-0.400772,-0.0499199,-0.0148316,-365.558,-1.36595e-05,-5.95645e-05,7.46513e-06,-2.75613e-05,7.16886e-05,-0.00127384,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00147717,2.7443e-05,2.58303e-05,0.00134567,0.0415728,0.0415389,0.00959791,0.0510877,0.0510885,0.0598626,6.61363e-11,6.61514e-11,5.1319e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +24385000,0.706858,0.00355263,-0.00611847,0.70732,-0.114283,-0.0470599,-0.452515,-0.0565558,-0.0284769,-365.599,-1.36324e-05,-5.96179e-05,7.40123e-06,-2.75613e-05,7.16886e-05,-0.00127521,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00147651,2.33441e-05,2.17551e-05,0.00134521,0.0359081,0.0358728,0.00957571,0.0448415,0.0448421,0.0602099,6.58213e-11,6.58375e-11,5.06802e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +24485000,0.706865,0.00439674,-0.00215091,0.707332,-0.126991,-0.051922,-0.503361,-0.068558,-0.0333892,-365.646,-1.36349e-05,-5.96157e-05,7.27029e-06,-2.75613e-05,7.16886e-05,-0.00127534,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00147527,2.35336e-05,2.16932e-05,0.00134485,0.0394912,0.0394411,0.00963241,0.0512265,0.0512259,0.0602475,6.59183e-11,6.59351e-11,4.9843e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +24585000,0.706968,0.0048374,0.00161379,0.707227,-0.138662,-0.0642015,-0.552901,-0.07163,-0.0435267,-365.697,-1.35831e-05,-5.9641e-05,7.37933e-06,-2.75613e-05,7.16886e-05,-0.001278,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00147376,2.022e-05,1.82681e-05,0.00134421,0.0340802,0.0340189,0.00952862,0.0449439,0.0449435,0.0597059,6.57307e-11,6.57484e-11,4.90243e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +24685000,0.706989,0.00488716,0.00268553,0.707203,-0.162937,-0.0775647,-0.632598,-0.0866773,-0.0506247,-365.758,-1.35818e-05,-5.96421e-05,7.44726e-06,-2.75613e-05,7.16886e-05,-0.00127713,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0014725,2.02949e-05,1.8331e-05,0.00134389,0.0374025,0.0373033,0.00958588,0.0512295,0.0512267,0.0597526,6.58278e-11,6.58462e-11,4.82247e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +24785000,0.706895,0.00458776,0.0013278,0.707302,-0.177731,-0.0884257,-0.720459,-0.0933429,-0.0606428,-365.828,-1.35448e-05,-5.96702e-05,7.25417e-06,-2.75613e-05,7.16886e-05,-0.00127739,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0014708,1.74453e-05,1.55559e-05,0.00134298,0.0323849,0.0322721,0.00948494,0.0449583,0.0449566,0.0592247,6.57282e-11,6.57474e-11,4.74414e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +24885000,0.706824,0.00623442,0.00285539,0.707356,-0.198873,-0.0994034,-0.743393,-0.112126,-0.070023,-365.904,-1.35474e-05,-5.96678e-05,7.11686e-06,-2.75613e-05,7.16886e-05,-0.00127638,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00146941,1.77573e-05,1.5617e-05,0.00134259,0.0352227,0.0350655,0.0095462,0.0511254,0.051119,0.0592803,6.58255e-11,6.58452e-11,4.6677e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +24985000,0.706744,0.00808653,0.00451686,0.707409,-0.211877,-0.104066,-0.798394,-0.11363,-0.0761178,-365.979,-1.34965e-05,-5.96812e-05,6.91143e-06,-2.75613e-05,7.16886e-05,-0.00127902,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00146795,1.57472e-05,1.33503e-05,0.00134138,0.0304886,0.0303076,0.00953002,0.0448944,0.0448902,0.0596521,6.57869e-11,6.58073e-11,4.61151e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +25085000,0.706684,0.0084762,0.00402038,0.707467,-0.241478,-0.114568,-0.848667,-0.136311,-0.0870463,-366.062,-1.34991e-05,-5.96788e-05,6.77064e-06,-2.75613e-05,7.16886e-05,-0.00127875,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0014668,1.58774e-05,1.34151e-05,0.00134095,0.0331409,0.032877,0.00959366,0.0509132,0.0509006,0.0597181,6.58843e-11,6.59052e-11,4.53799e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +25185000,0.706688,0.00790533,0.00255497,0.707477,-0.265777,-0.12998,-0.898536,-0.157206,-0.114838,-366.147,-1.3479e-05,-5.97341e-05,6.76245e-06,-2.75613e-05,7.16886e-05,-0.00128047,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00146428,1.38774e-05,1.15547e-05,0.0013392,0.0287517,0.0284669,0.00949882,0.044757,0.0447484,0.05921,6.58868e-11,6.59083e-11,4.4657e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25285000,0.706726,0.0097275,0.00900755,0.707363,-0.293659,-0.139096,-0.952857,-0.18509,-0.128249,-366.239,-1.34794e-05,-5.97337e-05,6.74016e-06,-2.75613e-05,7.16886e-05,-0.00128065,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00146288,1.42672e-05,1.16936e-05,0.00133874,0.0311691,0.0307822,0.00956545,0.050618,0.0505954,0.0592846,6.59843e-11,6.60063e-11,4.39538e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25385000,0.706788,0.0110875,0.0156403,0.707166,-0.321047,-0.159077,-1.00138,-0.196989,-0.148902,-366.335,-1.34379e-05,-5.97635e-05,6.73097e-06,-2.75613e-05,7.16886e-05,-0.0012835,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00145944,1.29475e-05,1.04323e-05,0.00133619,0.0271778,0.0267358,0.00946946,0.04456,0.0445442,0.0587924,6.60158e-11,6.60384e-11,4.32611e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +25485000,0.706806,0.011384,0.0171543,0.707107,-0.368972,-0.182299,-1.05454,-0.231493,-0.165974,-366.443,-1.34375e-05,-5.97639e-05,6.76052e-06,-2.75613e-05,7.16886e-05,-0.00128175,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00145828,1.30827e-05,1.06036e-05,0.00133576,0.0294848,0.0288307,0.00953284,0.0502609,0.0502212,0.0588747,6.61134e-11,6.61366e-11,4.25885e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +25585000,0.706892,0.0107843,0.0151964,0.707076,-0.408802,-0.214013,-1.10964,-0.259991,-0.205372,-366.555,-1.34118e-05,-5.9825e-05,6.76404e-06,-2.75613e-05,7.16886e-05,-0.00128101,0.208315,0.00202315,0.435262,0,0,0,0,0,0.001454,1.1635e-05,9.18043e-06,0.001332,0.0258546,0.0251363,0.00943846,0.0443166,0.0442881,0.0583968,6.61654e-11,6.61892e-11,4.19223e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +25685000,0.706832,0.01419,0.0214927,0.706912,-0.456088,-0.234126,-1.16184,-0.303137,-0.227768,-366.674,-1.34124e-05,-5.98246e-05,6.73706e-06,-2.75613e-05,7.16886e-05,-0.00127934,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00145299,1.23596e-05,9.69766e-06,0.00133139,0.0280267,0.0270321,0.00958469,0.049861,0.0497934,0.0593539,6.62637e-11,6.62879e-11,4.14404e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +25785000,0.706758,0.0168884,0.0280597,0.706697,-0.4976,-0.25921,-1.2085,-0.318713,-0.256078,-366.793,-1.33675e-05,-5.98618e-05,6.7538e-06,-2.75613e-05,7.16886e-05,-0.00128093,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0014455,1.17923e-05,9.2576e-06,0.00132576,0.0248013,0.0236483,0.00948792,0.0440394,0.0439895,0.0588753,6.63303e-11,6.63552e-11,4.07951e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25885000,0.706835,0.0172865,0.0287436,0.706583,-0.567337,-0.288664,-1.25826,-0.371982,-0.283514,-366.921,-1.33654e-05,-5.98638e-05,6.87507e-06,-2.75613e-05,7.16886e-05,-0.00127925,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00144448,1.19596e-05,9.4233e-06,0.00132524,0.0270539,0.0253886,0.00955213,0.0494384,0.0493226,0.0589733,6.64281e-11,6.64535e-11,4.01755e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25985000,0.706731,0.0161233,0.0254621,0.70684,-0.620211,-0.327594,-1.31401,-0.412653,-0.341035,-367.054,-1.33412e-05,-5.99262e-05,6.88577e-06,-2.75613e-05,7.16886e-05,-0.00127714,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00143388,1.07125e-05,8.08911e-06,0.00131741,0.0241152,0.022306,0.00945839,0.0437429,0.0436563,0.0585069,6.65051e-11,6.6531e-11,3.955e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +26085000,0.702934,0.020705,0.0348546,0.710099,-0.685229,-0.354126,-1.34048,-0.477838,-0.37511,-367.193,-1.33452e-05,-5.99229e-05,6.67919e-06,-2.75613e-05,7.16886e-05,-0.00127544,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00141905,1.17995e-05,9.29979e-06,0.00132883,0.0262623,0.0238613,0.00952506,0.0490127,0.0488211,0.0586055,6.6603e-11,6.66294e-11,3.89565e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +26185000,0.701024,0.023038,0.0446349,0.711367,-0.731962,-0.387527,-1.30957,-0.500162,-0.417073,-367.325,-1.32979e-05,-5.99572e-05,6.58375e-06,-2.75613e-05,7.16886e-05,-0.00127536,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00139755,1.15121e-05,1.00463e-05,0.00132158,0.0235804,0.020955,0.00943062,0.0434387,0.0432929,0.0581504,6.66867e-11,6.67136e-11,3.83496e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +26285000,0.701106,0.0240576,0.0473043,0.71108,-0.824099,-0.429156,-1.29752,-0.577925,-0.457905,-367.459,-1.32995e-05,-5.99561e-05,6.50769e-06,-2.75613e-05,7.16886e-05,-0.00127404,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00139751,1.18624e-05,1.06661e-05,0.00132033,0.026007,0.0223726,0.00957382,0.0485875,0.0482777,0.05912,6.67851e-11,6.68125e-11,3.79249e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +26385000,0.70206,0.0229246,0.0438292,0.710398,-0.904195,-0.489129,-1.30219,-0.645583,-0.545914,-367.595,-1.32777e-05,-6.00135e-05,6.56625e-06,-2.75613e-05,7.16886e-05,-0.00127092,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00137991,1.07248e-05,9.10299e-06,0.00129935,0.0236888,0.0197952,0.00947942,0.043139,0.0428993,0.0586617,6.68728e-11,6.69004e-11,3.73269e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +26485000,0.702539,0.0304208,0.0586892,0.708568,-0.997293,-0.527981,-1.30614,-0.740448,-0.596774,-367.729,-1.32789e-05,-6.00128e-05,6.51367e-06,-2.75613e-05,7.16886e-05,-0.00126948,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0013796,1.27563e-05,1.23692e-05,0.00129339,0.0262711,0.0211148,0.00954614,0.0482075,0.0477182,0.0587726,6.69708e-11,6.69991e-11,3.67801e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +26585000,0.702742,0.0368271,0.0753494,0.706485,-1.08462,-0.581728,-1.2948,-0.781358,-0.662144,-367.863,-1.32253e-05,-6.00283e-05,6.02445e-06,-2.75613e-05,7.16886e-05,-0.00126615,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00135071,1.38463e-05,1.61412e-05,0.00126107,0.0246112,0.018781,0.00945008,0.0428737,0.0424884,0.058324,6.70599e-11,6.70878e-11,3.61922e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +26685000,0.70367,0.038271,0.0788021,0.705106,-1.23007,-0.643975,-1.28434,-0.897089,-0.723433,-367.997,-1.32239e-05,-6.00297e-05,6.10393e-06,-2.75613e-05,7.16886e-05,-0.0012642,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00135256,1.43987e-05,1.7398e-05,0.0012564,0.0282715,0.0200847,0.00951486,0.0479291,0.0471509,0.0584379,6.71578e-11,6.71866e-11,3.56688e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +26785000,0.704771,0.0360156,0.07313,0.704736,-1.34964,-0.730263,-1.28717,-0.99259,-0.85503,-368.136,-1.32014e-05,-6.00802e-05,5.95112e-06,-2.75613e-05,7.16886e-05,-0.00125921,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00131191,1.27065e-05,1.42589e-05,0.0012154,0.026823,0.0179769,0.00942525,0.0426847,0.0420686,0.0579982,6.7246e-11,6.72735e-11,3.50767e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +26885000,0.7044,0.0444926,0.0936959,0.702184,-1.49322,-0.788868,-1.29945,-1.13446,-0.930886,-368.272,-1.32001e-05,-6.00816e-05,6.02878e-06,-2.75613e-05,7.16886e-05,-0.00125667,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00130843,1.55463e-05,2.13962e-05,0.00120809,0.0309389,0.0192024,0.00949566,0.0478034,0.0465893,0.0581148,6.7344e-11,6.73724e-11,3.45766e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +26985000,0.703731,0.0511869,0.116207,0.699026,-1.60819,-0.868527,-1.27724,-1.19006,-1.02954,-368.406,-1.30957e-05,-6.00767e-05,5.55068e-06,-2.75613e-05,7.16886e-05,-0.00125257,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00124491,1.68968e-05,2.90594e-05,0.00114596,0.0301983,0.0173088,0.00948964,0.0426126,0.0416498,0.058528,6.74296e-11,6.74543e-11,3.41027e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +27085000,0.704369,0.05237,0.121137,0.697458,-1.81338,-0.960536,-1.24944,-1.36108,-1.12104,-368.536,-1.30972e-05,-6.00758e-05,5.48077e-06,-2.75613e-05,7.16886e-05,-0.00125114,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00124591,1.7464e-05,3.155e-05,0.00114098,0.0363034,0.0186061,0.00957896,0.0479125,0.0460414,0.0586507,6.75273e-11,6.75533e-11,3.36227e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27185000,0.706071,0.0491398,0.11115,0.697635,-2.01385,-1.03029,-1.23106,-1.55695,-1.20024,-368.664,-1.30994e-05,-6.00109e-05,5.77035e-06,-2.75613e-05,7.16886e-05,-0.00124741,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00116884,1.48531e-05,2.45479e-05,0.00106992,0.0375919,0.0185519,0.00950868,0.0504457,0.0485642,0.0582172,6.76127e-11,6.76322e-11,3.30073e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27285000,0.707563,0.0435064,0.0960836,0.698734,-2.17739,-1.10116,-1.22084,-1.76683,-1.307,-368.793,-1.30986e-05,-6.00115e-05,5.80268e-06,-2.75613e-05,7.16886e-05,-0.00124517,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00117315,1.31682e-05,1.90242e-05,0.00107204,0.0434401,0.0197699,0.00959967,0.0569201,0.0535655,0.058344,6.77107e-11,6.77313e-11,3.25509e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27385000,0.70858,0.0371669,0.0801168,0.700082,-2.25277,-1.12718,-1.21541,-1.94752,-1.38006,-368.923,-1.30071e-05,-5.98953e-05,5.61791e-06,-2.75613e-05,7.16886e-05,-0.00123838,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00107686,1.04164e-05,1.26975e-05,0.000988995,0.0413949,0.0193746,0.00950971,0.0591364,0.0560919,0.0579153,6.77901e-11,6.77968e-11,3.19287e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +27485000,0.709093,0.0314049,0.0650122,0.701409,-2.34088,-1.16845,-1.2001,-2.17739,-1.49508,-369.053,-1.30076e-05,-5.98946e-05,5.57012e-06,-2.75613e-05,7.16886e-05,-0.00123531,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00107807,9.33066e-06,9.61695e-06,0.000991251,0.0451396,0.0204105,0.00959099,0.0666474,0.0616836,0.0580475,6.78884e-11,6.78959e-11,3.14956e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +27585000,0.709532,0.026789,0.0523333,0.702216,-2.43754,-1.18561,-1.20261,-2.45223,-1.59822,-369.183,-1.30752e-05,-5.98202e-05,6.20536e-06,-2.75613e-05,7.16886e-05,-0.00122849,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000986571,7.79914e-06,7.01293e-06,0.00091332,0.0408805,0.0198494,0.00957848,0.0683987,0.0641462,0.0584748,6.79603e-11,6.79433e-11,3.10146e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +27685000,0.709319,0.025875,0.0501184,0.702627,-2.47742,-1.20366,-1.20342,-2.69791,-1.71786,-369.31,-1.30768e-05,-5.98184e-05,6.09105e-06,-2.75613e-05,7.16886e-05,-0.00122604,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000985664,7.8102e-06,6.90704e-06,0.000913651,0.0432163,0.0209023,0.00966481,0.0766957,0.0702966,0.0586171,6.80586e-11,6.80424e-11,3.06011e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +27785000,0.709244,0.0263987,0.0519774,0.702549,-2.5334,-1.21125,-1.2012,-2.96672,-1.81771,-369.438,-1.31119e-05,-5.97165e-05,6.32295e-06,-2.75613e-05,7.16886e-05,-0.00121992,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000909484,7.3049e-06,6.63403e-06,0.000848667,0.0388125,0.0203588,0.00957798,0.0779918,0.0726394,0.0581919,6.81186e-11,6.80657e-11,3.00638e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27885000,0.709266,0.0257771,0.0502547,0.702675,-2.57193,-1.23059,-1.20091,-3.22187,-1.94005,-369.57,-1.31121e-05,-5.97149e-05,6.25276e-06,-2.75613e-05,7.16886e-05,-0.00121582,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000909103,7.37635e-06,6.61517e-06,0.000848372,0.0409283,0.0215467,0.00966523,0.086907,0.0793241,0.05834,6.8217e-11,6.81648e-11,2.96694e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27985000,0.709515,0.0248589,0.0461656,0.702737,-2.64647,-1.23704,-1.20508,-3.5343,-2.05356,-369.7,-1.32334e-05,-5.96502e-05,6.75385e-06,-2.75613e-05,7.16886e-05,-0.00121003,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000847482,6.80367e-06,5.96368e-06,0.000795853,0.0369054,0.0210272,0.00958444,0.0877626,0.0814989,0.0579211,6.82629e-11,6.81599e-11,2.91804e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +28085000,0.708976,0.0302904,0.0586325,0.702138,-2.68273,-1.25286,-1.21745,-3.80022,-2.17835,-369.829,-1.32374e-05,-5.96457e-05,6.50621e-06,-2.75613e-05,7.16886e-05,-0.00120721,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000846287,7.49334e-06,7.13726e-06,0.00079465,0.0388535,0.0223754,0.00967339,0.0971952,0.0887008,0.0580747,6.83613e-11,6.82589e-11,2.88033e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +28185000,0.708781,0.0357797,0.0727693,0.700753,-2.75446,-1.2652,-0.979638,-4.10723,-2.28993,-369.958,-1.33212e-05,-5.95624e-05,6.78851e-06,-2.75613e-05,7.16886e-05,-0.0012008,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000794829,7.59301e-06,8.30787e-06,0.000749281,0.0352083,0.0215208,0.00959165,0.0976256,0.0906581,0.0576613,6.83897e-11,6.82213e-11,2.83554e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +28285000,0.710582,0.0287655,0.0571959,0.700695,-2.75854,-1.27949,-0.120448,-4.38274,-2.41747,-370.02,-1.33239e-05,-5.95589e-05,6.61805e-06,-2.75613e-05,7.16886e-05,-0.00119849,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000798266,7.02552e-06,6.77077e-06,0.000748064,0.0353766,0.0217843,0.0097706,0.107406,0.0982725,0.0586679,6.84883e-11,6.83206e-11,2.80859e-10,2.95326e-06,2.95427e-06,5.0002e-08,0,0,0,0,0,0,0,0 +28385000,0.712785,0.0128985,0.0258363,0.700788,-2.79237,-1.27956,0.746316,-4.71784,-2.53546,-369.999,-1.3466e-05,-5.94988e-05,6.93946e-06,-2.75613e-05,7.16886e-05,-0.00119393,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000760933,5.9396e-06,5.44799e-06,0.000712451,0.0310206,0.0202711,0.00986667,0.107573,0.100027,0.0588136,6.85207e-11,6.82836e-11,2.76698e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +28485000,0.713032,0.00336585,0.00654257,0.701093,-2.75139,-1.27454,1.0788,-4.99512,-2.66365,-369.913,-1.34662e-05,-5.94953e-05,6.82635e-06,-2.75613e-05,7.16886e-05,-0.00118966,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000760628,6.09991e-06,6.31244e-06,0.000711335,0.0311205,0.0212242,0.00997579,0.11739,0.107886,0.0589789,6.86192e-11,6.83824e-11,2.73218e-10,2.95326e-06,2.95427e-06,5.0001e-08,0,0,0,0,0,0,0,0 +28585000,0.712319,0.00169004,0.0027962,0.701849,-2.71485,-1.24784,0.978175,-5.32941,-2.78031,-369.822,-1.36204e-05,-5.94429e-05,7.14193e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000728822,6.10726e-06,6.57549e-06,0.000687275,0.0468799,0.0401808,0.0289733,0.117548,0.109554,0.0591505,6.86462e-11,6.83402e-11,2.69411e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +28685000,0.711304,0.000958246,0.00181714,0.702881,-2.64349,-1.23211,0.97782,-5.59692,-2.9046,-369.739,-1.36195e-05,-5.94391e-05,7.05414e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00072681,6.28903e-06,6.81521e-06,0.000688428,0.0709078,0.0656725,0.0525805,0.127879,0.118252,0.059622,6.87449e-11,6.8439e-11,2.66064e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +28785000,0.710577,0.000829105,0.00153573,0.703618,-2.65221,-1.19635,0.976945,-5.92425,-3.01337,-369.658,-1.3798e-05,-5.93732e-05,7.12721e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000707014,6.29676e-06,6.82675e-06,0.00067358,0.0783882,0.0763615,0.0711963,0.127632,0.119358,0.059669,6.87433e-11,6.83763e-11,2.62622e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +28885000,0.710071,0.000790771,0.00172846,0.704128,-2.5843,-1.18202,0.965082,-6.18576,-3.13249,-369.572,-1.37969e-05,-5.93704e-05,7.08233e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000706245,6.46639e-06,6.98422e-06,0.000674172,0.102646,0.10184,0.0946443,0.138334,0.12897,0.0623756,6.88423e-11,6.84754e-11,2.6022e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +28985000,0.709735,0.0010924,0.00219247,0.704464,-2.63915,-1.15701,0.946787,-6.51881,-3.2445,-369.495,-1.4009e-05,-5.93446e-05,7.03669e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00069624,6.51353e-06,6.97664e-06,0.000665787,0.0958466,0.0962877,0.103508,0.137714,0.129329,0.0630862,6.88358e-11,6.84323e-11,2.57e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +29085000,0.709539,0.0012217,0.00256978,0.704661,-2.57683,-1.14362,0.934903,-6.77921,-3.35983,-369.415,-1.40092e-05,-5.93398e-05,6.9112e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000695762,6.68256e-06,7.12438e-06,0.000665602,0.120263,0.121601,0.126069,0.148675,0.139698,0.066524,6.89344e-11,6.8531e-11,2.53867e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +29185000,0.709505,0.00140481,0.0028944,0.704693,-2.55532,-1.12286,0.902753,-7.05698,-3.46943,-369.346,-1.4066e-05,-5.93241e-05,6.89728e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000690697,6.77575e-06,7.16775e-06,0.000660385,0.104256,0.105461,0.124652,0.147803,0.139393,0.0673643,6.89341e-11,6.85164e-11,2.50784e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +29285000,0.709388,0.0017137,0.00368219,0.704807,-2.49837,-1.11207,0.921986,-7.30928,-3.58149,-369.271,-1.40666e-05,-5.93189e-05,6.75662e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000690398,6.94296e-06,7.29372e-06,0.000660104,0.128727,0.130561,0.146225,0.158931,0.150286,0.0721247,6.90328e-11,6.86151e-11,2.47756e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +29385000,0.709298,0.00219343,0.00504008,0.704887,-2.51357,-1.10436,0.907373,-7.59457,-3.69431,-369.203,-1.4166e-05,-5.93156e-05,6.47793e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000687252,7.05186e-06,7.30762e-06,0.00065621,0.108008,0.109206,0.13687,0.157905,0.149499,0.0724557,6.90411e-11,6.86232e-11,2.44772e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +29485000,0.709341,0.00266729,0.00616101,0.704834,-2.46342,-1.09642,0.899325,-7.84321,-3.80446,-369.125,-1.41652e-05,-5.93134e-05,6.45424e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000687134,7.21973e-06,7.42342e-06,0.000655818,0.13252,0.134168,0.157449,0.169144,0.160725,0.0779546,6.91398e-11,6.87221e-11,2.41844e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +29585000,0.70935,0.00297096,0.00712733,0.704814,-2.41729,-1.06941,0.876782,-8.08774,-3.9029,-369.054,-1.4163e-05,-5.92854e-05,6.35212e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000684872,7.35767e-06,7.49465e-06,0.000652633,0.109636,0.110627,0.143926,0.168013,0.159616,0.0789454,6.91542e-11,6.87439e-11,2.39687e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +29685000,0.709427,0.00324913,0.00778181,0.704729,-2.37405,-1.06231,0.865273,-8.32704,-4.00971,-368.979,-1.41649e-05,-5.92813e-05,6.20374e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000684908,7.54135e-06,7.65146e-06,0.00065208,0.134147,0.135474,0.164,0.179336,0.171058,0.0848815,6.9253e-11,6.88428e-11,2.36845e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +29785000,0.709587,0.00341485,0.00816126,0.704563,-2.36585,-1.0484,0.843497,-8.58037,-4.11138,-368.909,-1.42037e-05,-5.92705e-05,6.19699e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000682697,7.70184e-06,7.7807e-06,0.000648816,0.110312,0.111091,0.146768,0.178124,0.169734,0.0833645,6.92695e-11,6.88709e-11,2.34025e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +29885000,0.709596,0.00345745,0.0083014,0.704552,-2.32799,-1.04256,0.823589,-8.81474,-4.21623,-368.843,-1.42062e-05,-5.92657e-05,6.01994e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000682636,7.90162e-06,7.97617e-06,0.000648356,0.134813,0.13585,0.166268,0.189514,0.181314,0.0891498,6.93683e-11,6.89699e-11,2.31278e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +29985000,0.709682,0.00346856,0.00836244,0.704464,-2.27767,-1.01892,0.802674,-9.03907,-4.3099,-368.774,-1.41892e-05,-5.92412e-05,5.90885e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000680552,8.07802e-06,8.13558e-06,0.000645343,0.110587,0.111199,0.147716,0.188237,0.179849,0.0867785,6.93849e-11,6.90001e-11,2.28545e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +30085000,0.709733,0.00343373,0.00823778,0.704415,-2.24141,-1.01371,0.787017,-9.26484,-4.41175,-368.705,-1.41917e-05,-5.92377e-05,5.75815e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000680528,8.28826e-06,8.35297e-06,0.000644855,0.135086,0.135907,0.166827,0.199675,0.191518,0.092216,6.94838e-11,6.90991e-11,2.25889e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +30185000,0.709945,0.00336601,0.00799266,0.704203,-2.22467,-1.00072,0.781184,-9.49782,-4.50815,-368.628,-1.42129e-05,-5.92284e-05,5.8071e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000678877,8.47868e-06,8.54141e-06,0.000642122,0.110697,0.111184,0.148908,0.198354,0.189964,0.0912825,6.94986e-11,6.91288e-11,2.23919e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +30285000,0.710022,0.00324945,0.0077846,0.704129,-2.18821,-0.997402,0.771715,-9.71835,-4.6082,-368.552,-1.42151e-05,-5.92262e-05,5.69259e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000678863,8.69778e-06,8.77051e-06,0.000641635,0.135206,0.135856,0.16811,0.209825,0.201689,0.096561,6.95976e-11,6.9228e-11,2.2134e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +30385000,0.710089,0.0031396,0.00750214,0.704065,-2.13663,-0.990298,0.761471,-9.92636,-4.70639,-368.483,-1.41942e-05,-5.92215e-05,5.62984e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000676896,8.8948e-06,8.96742e-06,0.000639023,0.110755,0.111146,0.14868,0.208476,0.200075,0.0929545,6.96086e-11,6.92549e-11,2.1877e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +30485000,0.710154,0.0030095,0.00722848,0.704003,-2.10303,-0.986193,0.74979,-10.1383,-4.80528,-368.409,-1.4195e-05,-5.92207e-05,5.58564e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000676799,9.12141e-06,9.20729e-06,0.000638632,0.135265,0.135794,0.167725,0.219967,0.211838,0.0978331,6.97076e-11,6.93541e-11,2.16275e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +30585000,0.710297,0.00280688,0.00678226,0.703863,-2.08261,-0.982429,0.722028,-10.3549,-4.90452,-368.337,-1.42137e-05,-5.92217e-05,5.5928e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00067497,9.32827e-06,9.42152e-06,0.000636097,0.110794,0.111119,0.148355,0.218598,0.210186,0.0939272,6.97138e-11,6.9377e-11,2.13789e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +30685000,0.710364,0.00260773,0.00640925,0.7038,-2.04896,-0.977424,0.715016,-10.5614,-5.00262,-368.271,-1.4215e-05,-5.92203e-05,5.5223e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000674899,9.56403e-06,9.67454e-06,0.000635685,0.135312,0.135757,0.167299,0.23011,0.221976,0.0984609,6.98129e-11,6.94763e-11,2.11376e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +30785000,0.710397,0.00246279,0.00600796,0.703771,-2.01016,-0.959872,0.714843,-10.7616,-5.09272,-368.197,-1.42074e-05,-5.92015e-05,5.40322e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000673092,9.77419e-06,9.88979e-06,0.000633324,0.110812,0.111078,0.148038,0.228721,0.220296,0.0943772,6.98132e-11,6.9494e-11,2.08971e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +30885000,0.710358,0.002247,0.00554543,0.703815,-1.97628,-0.95479,0.704606,-10.9609,-5.1885,-368.129,-1.42083e-05,-5.92007e-05,5.35553e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000673096,1.0019e-05,1.01554e-05,0.000633256,0.135346,0.135713,0.168285,0.240241,0.232099,0.101124,6.99125e-11,6.95935e-11,2.0724e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +30985000,0.710386,0.00208054,0.00494532,0.703792,-1.96325,-0.94542,0.703804,-11.1683,-5.28091,-368.061,-1.42381e-05,-5.91919e-05,5.27967e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000671302,1.02369e-05,1.03893e-05,0.000631051,0.110838,0.111055,0.148804,0.238845,0.230405,0.0967373,6.99071e-11,6.96061e-11,2.04902e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +31085000,0.710396,0.00184215,0.00438558,0.703786,-1.93024,-0.940347,0.692146,-11.3628,-5.37532,-367.999,-1.424e-05,-5.91901e-05,5.18405e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000671153,1.0489e-05,1.06683e-05,0.000630716,0.135385,0.13568,0.167912,0.250369,0.242216,0.100972,7.00063e-11,6.97054e-11,2.02633e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +31185000,0.710407,0.00162903,0.00398366,0.703777,-1.89141,-0.936186,0.668373,-11.5508,-5.4692,-367.949,-1.42329e-05,-5.91895e-05,5.1335e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000669399,1.071e-05,1.08939e-05,0.000628667,0.110867,0.111037,0.148535,0.248971,0.240513,0.0965481,6.99947e-11,6.97124e-11,2.0037e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +31285000,0.710444,0.00137949,0.00339808,0.703744,-1.85723,-0.929724,0.669797,-11.7382,-5.56256,-367.89,-1.42337e-05,-5.91887e-05,5.0923e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00066924,1.09694e-05,1.11821e-05,0.000628346,0.135425,0.135663,0.167518,0.260495,0.252329,0.100566,7.00939e-11,6.98118e-11,1.98173e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +31385000,0.710446,0.00111492,0.00275909,0.703746,-1.84266,-0.928284,0.662,-11.9334,-5.65758,-367.83,-1.42667e-05,-5.91924e-05,5.01393e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000667537,1.1199e-05,1.14286e-05,0.000626366,0.110896,0.111035,0.148242,0.259098,0.250622,0.0961496,7.00763e-11,6.98131e-11,1.95982e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +31485000,0.71038,0.000891112,0.00207428,0.703815,-1.80771,-0.922987,0.659266,-12.1158,-5.75027,-367.768,-1.42687e-05,-5.91907e-05,4.90823e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000667533,1.14665e-05,1.17312e-05,0.000626286,0.135483,0.135663,0.168576,0.270618,0.262441,0.102627,7.01757e-11,6.99126e-11,1.94408e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +31585000,0.710373,0.000683014,0.00160442,0.703823,-1.77523,-0.901207,0.652205,-12.2962,-5.83355,-367.709,-1.42715e-05,-5.91682e-05,4.86866e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000665822,1.16965e-05,1.19684e-05,0.000624411,0.110934,0.11104,0.149055,0.269229,0.260732,0.098014,7.0151e-11,6.99076e-11,1.92278e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +31685000,0.710347,0.000416192,0.000910079,0.703851,-1.74225,-0.895639,0.660014,-12.472,-5.92344,-367.646,-1.4272e-05,-5.91677e-05,4.84416e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000665541,1.1971e-05,1.22793e-05,0.000624209,0.13553,0.135661,0.168201,0.280745,0.27255,0.101971,7.02503e-11,7.0007e-11,1.90209e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +31785000,0.710359,6.53235e-05,0.00011919,0.703839,-1.73282,-0.884511,0.655609,-12.6588,-6.00965,-367.589,-1.43134e-05,-5.91587e-05,4.81765e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000663884,1.22125e-05,1.25446e-05,0.000622379,0.11097,0.111037,0.148769,0.279358,0.270842,0.097407,7.02189e-11,6.99956e-11,1.88145e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +31885000,0.710374,-0.000221293,-0.000639621,0.703824,-1.69612,-0.876785,0.653931,-12.8302,-6.09777,-367.527,-1.43145e-05,-5.91578e-05,4.75752e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000663699,1.2495e-05,1.28686e-05,0.00062208,0.135598,0.13568,0.167832,0.290868,0.28266,0.101266,7.03182e-11,7.00951e-11,1.86142e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +31985000,0.71031,-0.00046435,-0.00121798,0.703888,-1.65183,-0.858184,0.648805,-12.9936,-6.17784,-367.469,-1.4302e-05,-5.91367e-05,4.66051e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000662016,1.27336e-05,1.31193e-05,0.000620341,0.111023,0.111054,0.148489,0.289489,0.280951,0.096761,7.02789e-11,7.00766e-11,1.84142e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +32085000,0.710219,-0.000773434,-0.0019909,0.703978,-1.61672,-0.851349,0.655797,-13.1569,-6.26342,-367.411,-1.43039e-05,-5.91352e-05,4.5625e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0006617,1.30239e-05,1.34524e-05,0.000620174,0.135667,0.135689,0.167475,0.300991,0.29277,0.10054,7.03783e-11,7.01761e-11,1.82201e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +32185000,0.710166,-0.00112689,-0.00292778,0.704027,-1.60131,-0.842189,0.655799,-13.3282,-6.34623,-367.353,-1.43409e-05,-5.91265e-05,4.42885e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000660323,1.32746e-05,1.37356e-05,0.000618542,0.111067,0.111055,0.149255,0.299623,0.291062,0.0984615,7.03316e-11,7.01507e-11,1.80762e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +32285000,0.710132,-0.00140222,-0.0037421,0.704058,-1.56443,-0.835099,0.650808,-13.4864,-6.43022,-367.296,-1.43425e-05,-5.91252e-05,4.34605e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000660074,1.3571e-05,1.40805e-05,0.000618302,0.135747,0.135704,0.168459,0.311114,0.302881,0.10236,7.04311e-11,7.02502e-11,1.78873e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +32385000,0.710098,-0.00165414,-0.00443691,0.704087,-1.51512,-0.822571,0.654796,-13.6348,-6.51042,-367.228,-1.43231e-05,-5.91172e-05,4.33754e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000658388,1.38158e-05,1.43457e-05,0.000616678,0.111125,0.111076,0.148968,0.309757,0.301172,0.0977577,7.03757e-11,7.02168e-11,1.76987e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +32485000,0.709991,-0.00180952,-0.00474784,0.704192,-1.47803,-0.814168,0.664344,-13.7845,-6.5923,-367.164,-1.43237e-05,-5.91167e-05,4.30349e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00065801,1.41093e-05,1.46582e-05,0.000616623,0.135822,0.135733,0.168092,0.321239,0.31299,0.101591,7.04752e-11,7.03164e-11,1.75156e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +32585000,0.709881,-0.00187082,-0.00505173,0.704301,-1.4619,-0.808903,0.665219,-13.9415,-6.67475,-367.095,-1.43617e-05,-5.91184e-05,4.20312e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000656307,1.43466e-05,1.4896e-05,0.000615074,0.111168,0.111092,0.14864,0.319894,0.311283,0.0970254,7.04117e-11,7.02754e-11,1.73326e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +32685000,0.709794,-0.00193477,-0.00516633,0.704388,-1.42574,-0.801637,0.667832,-14.0858,-6.75535,-367.025,-1.43625e-05,-5.91175e-05,4.14455e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000655992,1.4641e-05,1.51988e-05,0.000614981,0.135895,0.13576,0.167669,0.331372,0.323102,0.100793,7.05112e-11,7.0375e-11,1.71552e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +32785000,0.709741,-0.00194743,-0.00517992,0.704441,-1.38986,-0.787127,0.666938,-14.2262,-6.83092,-366.959,-1.43612e-05,-5.91041e-05,4.1038e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000654623,1.48754e-05,1.54125e-05,0.000613587,0.111216,0.111112,0.149407,0.330032,0.321394,0.0987094,7.0439e-11,7.03255e-11,1.70237e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +32885000,0.709592,-0.0019059,-0.00517555,0.704591,-1.35673,-0.780082,0.671256,-14.3634,-6.90943,-366.895,-1.43632e-05,-5.91024e-05,3.98516e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000654274,1.51711e-05,1.57114e-05,0.000613546,0.135952,0.135783,0.168661,0.341507,0.333213,0.102612,7.05385e-11,7.04251e-11,1.6851e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +32985000,0.709491,-0.00183931,-0.00521388,0.704693,-1.34682,-0.774718,0.667938,-14.5107,-6.98726,-366.832,-1.44088e-05,-5.91016e-05,3.97624e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000652599,1.54039e-05,1.59307e-05,0.000612214,0.111255,0.111127,0.149078,0.340167,0.331505,0.097961,7.04577e-11,7.03669e-11,1.66783e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +33085000,0.709492,-0.00190269,-0.00526633,0.704691,-1.31403,-0.768798,0.667127,-14.6438,-7.06434,-366.765,-1.44078e-05,-5.91025e-05,4.03804e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000652308,1.57098e-05,1.62403e-05,0.000612111,0.136018,0.135813,0.168238,0.351642,0.343324,0.101803,7.05572e-11,7.04666e-11,1.65108e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +33185000,0.70652,0.000623797,-0.00456049,0.707678,-1.28205,-0.752552,0.612662,-14.7736,-7.13511,-366.701,-1.44076e-05,-5.9084e-05,4.02377e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000646298,1.58551e-05,1.63925e-05,0.000615393,0.111322,0.111175,0.148756,0.350306,0.341616,0.097226,7.04673e-11,7.03993e-11,1.63433e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +33285000,0.657846,0.0134649,-0.00316472,0.753026,-1.27234,-0.737547,0.585752,-14.901,-7.2097,-366.64,-1.44076e-05,-5.90838e-05,4.0169e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000574035,1.59388e-05,1.65303e-05,0.000688336,0.136079,0.135906,0.167826,0.3618,0.35345,0.101011,7.05668e-11,7.04989e-11,1.61806e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +33385000,0.556666,0.0114117,-0.00359748,0.83065,-1.27766,-0.728834,0.784012,-15.0355,-7.2837,-366.573,-1.44344e-05,-5.90858e-05,4.01627e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000439217,1.62229e-05,1.66693e-05,0.000822632,0.111199,0.111096,0.148446,0.360426,0.351719,0.0965058,7.04643e-11,7.04186e-11,1.60179e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +33485000,0.420276,0.00470225,-0.000587222,0.907384,-1.2551,-0.726122,0.81586,-15.1622,-7.35645,-366.491,-1.44362e-05,-5.90843e-05,3.91521e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000292795,1.67724e-05,1.66867e-05,0.000972197,0.135991,0.135772,0.168777,0.371902,0.363513,0.102812,7.0564e-11,7.05184e-11,1.59014e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +33585000,0.263628,-0.00156023,-0.00249452,0.96462,-1.19802,-0.710344,0.757696,-15.2776,-7.41783,-366.427,-1.44075e-05,-5.9048e-05,3.88543e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000171859,1.74053e-05,1.68682e-05,0.00109355,0.111443,0.111144,0.149174,0.370564,0.361833,0.0981504,7.04689e-11,7.04449e-11,1.57426e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +33685000,0.0972474,-0.00509145,-0.00515162,0.995234,-1.1374,-0.709074,0.769573,-15.3945,-7.48887,-366.35,-1.44071e-05,-5.90482e-05,3.90485e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000101062,1.7976e-05,1.7087e-05,0.0011672,0.136577,0.135836,0.168373,0.381933,0.373641,0.102014,7.05684e-11,7.05447e-11,1.55877e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +33785000,-0.0722872,-0.00679572,-0.00647117,0.99734,-1.09418,-0.682914,0.742199,-15.5205,-7.55141,-366.277,-1.44667e-05,-5.9018e-05,3.8409e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,9.07224e-05,1.81926e-05,1.7073e-05,0.00117699,0.111974,0.11118,0.148872,0.38073,0.371946,0.0974252,7.04535e-11,7.04564e-11,1.54322e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +33885000,-0.239452,-0.0079742,-0.00670108,0.970852,-1.0184,-0.659578,0.732249,-15.6261,-7.61864,-366.206,-1.4467e-05,-5.90178e-05,3.8219e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000142475,1.83393e-05,1.70468e-05,0.00112843,0.137472,0.1359,0.167926,0.39192,0.38376,0.101197,7.05532e-11,7.05561e-11,1.5281e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +33985000,-0.386874,-0.00652861,-0.00964592,0.922059,-1.00102,-0.618081,0.704418,-15.7553,-7.67942,-366.137,-1.45899e-05,-5.89953e-05,3.75397e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000239146,1.79948e-05,1.69029e-05,0.00102854,0.112538,0.111216,0.148532,0.390906,0.382057,0.0966838,7.04215e-11,7.04558e-11,1.51278e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +34085000,-0.494822,-0.00522302,-0.0109874,0.868909,-0.937673,-0.570974,0.712076,-15.8522,-7.73891,-366.063,-1.45894e-05,-5.89957e-05,3.78131e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000341421,1.77071e-05,1.67589e-05,0.000928269,0.138085,0.135931,0.168907,0.401972,0.393878,0.103022,7.05213e-11,7.05555e-11,1.50196e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +34185000,-0.565942,-0.0051291,-0.00932239,0.824377,-0.966261,-0.545546,0.717906,-15.9891,-7.80842,-365.991,-1.47779e-05,-5.90294e-05,3.74824e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000420636,1.73591e-05,1.64917e-05,0.000842018,0.112711,0.111211,0.149286,0.401073,0.39217,0.0983492,7.03839e-11,7.04499e-11,1.48687e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +34285000,-0.610155,-0.00594812,-0.00627278,0.792235,-0.90794,-0.493978,0.720896,-16.0828,-7.86042,-365.92,-1.47784e-05,-5.90291e-05,3.7183e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000476535,1.72102e-05,1.6334e-05,0.000786061,0.138204,0.135911,0.16847,0.412102,0.403988,0.102201,7.04835e-11,7.05496e-11,1.47252e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +34385000,-0.636955,-0.00681478,-0.0033112,0.770864,-0.915096,-0.46989,0.714973,-16.2069,-7.92174,-365.855,-1.49279e-05,-5.90627e-05,3.68214e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000509508,1.69513e-05,1.6116e-05,0.000744907,0.112745,0.111188,0.148954,0.411231,0.402281,0.0976035,7.03514e-11,7.04461e-11,1.45783e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +34485000,-0.653132,-0.00775007,-0.00101744,0.757204,-0.851787,-0.423744,0.717446,-16.2952,-7.9664,-365.787,-1.49281e-05,-5.90627e-05,3.67893e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000531732,1.68331e-05,1.59934e-05,0.000722225,0.138216,0.135869,0.168044,0.422247,0.414097,0.101398,7.0451e-11,7.0546e-11,1.44393e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +34585000,-0.663022,-0.0082974,0.000428762,0.748554,-0.875702,-0.428349,0.71365,-16.4244,-8.03515,-365.719,-1.51202e-05,-5.91381e-05,3.6887e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000542441,1.65765e-05,1.5768e-05,0.000703294,0.112735,0.111159,0.148633,0.421386,0.412393,0.0968739,7.03284e-11,7.04477e-11,1.42967e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +34685000,-0.669145,-0.00866493,0.00127143,0.74308,-0.809698,-0.382714,0.716297,-16.5086,-8.07577,-365.644,-1.51206e-05,-5.91375e-05,3.62841e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000550922,1.64277e-05,1.56187e-05,0.000694384,0.138203,0.135829,0.167638,0.432396,0.424207,0.100613,7.04281e-11,7.05475e-11,1.41621e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +34785000,-0.673107,-0.0086727,0.00179471,0.739492,-0.822375,-0.384817,0.716044,-16.6279,-8.13877,-365.572,-1.52885e-05,-5.92045e-05,3.48237e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000553245,1.61435e-05,1.53727e-05,0.000684302,0.112719,0.111134,0.149362,0.431544,0.422505,0.0985285,7.03169e-11,7.04563e-11,1.40589e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +34885000,-0.675549,-0.00870958,0.00192701,0.737261,-0.757293,-0.341815,0.719835,-16.7069,-8.17512,-365.498,-1.52885e-05,-5.92043e-05,3.47038e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000556578,1.59783e-05,1.52063e-05,0.000680586,0.138139,0.135788,0.168581,0.442549,0.434317,0.102402,7.04167e-11,7.05562e-11,1.39279e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +34985000,-0.678839,-0.0158894,-0.000284654,0.734115,0.17034,0.26334,-0.05441,-16.7638,-8.1971,-365.492,-1.54923e-05,-5.92907e-05,3.30033e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000557826,1.63277e-05,1.49619e-05,0.000670894,0.13489,0.112398,0.149216,0.440409,0.4327,0.0977966,7.0318e-11,7.04739e-11,1.3793e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +35085000,-0.678932,-0.0162748,-0.000686946,0.73402,0.40196,0.291271,-0.147705,-16.7268,-8.17002,-365.497,-1.54914e-05,-5.929e-05,3.26317e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000557785,1.62061e-05,1.4791e-05,0.000670532,0.165769,0.137927,0.168392,0.449706,0.444677,0.101621,7.04176e-11,7.05738e-11,1.36661e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +35185000,-0.679038,-0.015802,-0.000885672,0.733932,0.201401,0.235787,-0.111397,-16.7893,-8.19632,-365.49,-1.59819e-05,-5.93787e-05,2.94442e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00052327,1.56873e-05,1.44797e-05,0.000622045,0.123839,0.111968,0.148824,0.450201,0.442799,0.09705,7.02394e-11,7.04125e-11,1.3486e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +35285000,-0.679042,-0.0158216,-0.000962609,0.733929,0.243607,0.279236,-0.100122,-16.767,-8.17063,-365.491,-1.59813e-05,-5.93779e-05,2.86254e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000523041,1.55402e-05,1.43231e-05,0.000621929,0.149824,0.136614,0.167862,0.460269,0.454704,0.100815,7.0339e-11,7.05124e-11,1.3364e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +35385000,-0.679113,-0.0155381,-0.00102719,0.733868,0.115924,0.22277,-0.0724209,-16.8222,-8.19767,-365.484,-1.63107e-05,-5.95007e-05,2.66235e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000507565,1.51749e-05,1.40666e-05,0.000600348,0.117526,0.111439,0.149527,0.460206,0.452906,0.0987273,7.02315e-11,7.04037e-11,1.325e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +35485000,-0.679208,-0.0155699,-0.00103886,0.73378,0.157772,0.264775,-0.0635024,-16.8084,-8.17341,-365.483,-1.63106e-05,-5.95002e-05,2.54775e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000507419,1.50373e-05,1.39201e-05,0.00060016,0.143051,0.136075,0.168787,0.470744,0.464766,0.102629,7.03311e-11,7.05036e-11,1.31317e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +35585000,-0.679164,-0.0154303,-0.00102287,0.733824,0.143343,0.211903,-0.0454067,-16.8193,-8.19983,-365.48,-1.64243e-05,-5.96545e-05,2.58762e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000499346,1.47427e-05,1.36923e-05,0.000588972,0.11462,0.111209,0.149157,0.470295,0.463017,0.0979744,7.026e-11,7.04272e-11,1.3001e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +35685000,-0.679191,-0.0154341,-0.000982936,0.733799,0.184519,0.25436,-0.0397542,-16.8028,-8.1766,-365.483,-1.64247e-05,-5.96545e-05,2.51171e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000499148,1.46114e-05,1.35547e-05,0.000588848,0.13988,0.13583,0.16832,0.481129,0.474848,0.101817,7.03596e-11,7.05271e-11,1.28864e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +35785000,-0.679174,-0.0153219,-0.00098241,0.733817,0.161626,0.204532,-0.0241794,-16.8163,-8.2019,-365.478,-1.65492e-05,-5.97909e-05,2.49416e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000494385,1.43613e-05,1.33478e-05,0.000582381,0.113186,0.111097,0.148808,0.480418,0.47313,0.0972367,7.03115e-11,7.04731e-11,1.27649e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +35885000,-0.679192,-0.0153339,-0.00103131,0.7338,0.202385,0.247395,-0.0163324,-16.7981,-8.17932,-365.476,-1.65488e-05,-5.97906e-05,2.46298e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000494219,1.42387e-05,1.32178e-05,0.000582232,0.138278,0.135706,0.167882,0.49144,0.484942,0.101022,7.04112e-11,7.05731e-11,1.26537e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +35985000,-0.679166,-0.0151371,-0.00101027,0.733828,0.165125,0.195244,-0.0119325,-16.8176,-8.20599,-365.476,-1.66914e-05,-5.99186e-05,2.48047e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000491068,1.40111e-05,1.3027e-05,0.000577999,0.112418,0.111034,0.148481,0.490557,0.483245,0.0965145,7.03798e-11,7.05362e-11,1.25384e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +36085000,-0.679178,-0.0151871,-0.00100845,0.733816,0.205737,0.237594,-0.00482547,-16.799,-8.18431,-365.473,-1.66911e-05,-5.99184e-05,2.44815e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000491019,1.38994e-05,1.29065e-05,0.000578029,0.137397,0.135631,0.168815,0.501701,0.495043,0.102821,7.04796e-11,7.06362e-11,1.24598e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +36185000,-0.679233,-0.0150365,-0.00101166,0.733768,0.166828,0.189452,-0.000449575,-16.8189,-8.21009,-365.47,-1.68294e-05,-6.00344e-05,2.28785e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000488645,1.36953e-05,1.27295e-05,0.000575037,0.111987,0.110995,0.149198,0.500701,0.493362,0.0981581,7.04615e-11,7.06131e-11,1.23488e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +36285000,-0.679278,-0.0151127,-0.000981645,0.733725,0.207107,0.231639,0.0113523,-16.8001,-8.1891,-365.458,-1.68282e-05,-6.00338e-05,2.23237e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000488491,1.35935e-05,1.26168e-05,0.000574881,0.136888,0.13558,0.168398,0.511925,0.505149,0.102022,7.05612e-11,7.07131e-11,1.22435e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +36385000,-0.679247,-0.0150165,-0.000982556,0.733756,0.171804,0.187457,0.0114384,-16.8185,-8.21208,-365.457,-1.69549e-05,-6.01359e-05,2.22804e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000486603,1.34091e-05,1.24524e-05,0.000572491,0.111726,0.110963,0.148887,0.51085,0.503479,0.0974315,7.05544e-11,7.07017e-11,1.21364e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +36485000,-0.679205,-0.0150813,-0.00102523,0.733793,0.213169,0.228897,0.0162623,-16.7993,-8.1912,-365.456,-1.69546e-05,-6.01357e-05,2.27613e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000486441,1.33144e-05,1.23472e-05,0.000572349,0.136576,0.135535,0.16794,0.522124,0.515258,0.101204,7.06542e-11,7.08017e-11,1.20341e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +36585000,-0.67928,-0.0150053,-0.000992915,0.733725,0.174996,0.187413,0.0185821,-16.8183,-8.21395,-365.453,-1.70792e-05,-6.02304e-05,2.17659e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000484864,1.31453e-05,1.21944e-05,0.000570296,0.111566,0.110937,0.148539,0.520999,0.513596,0.096689,7.06573e-11,7.08005e-11,1.19305e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +36685000,-0.679344,-0.0149981,-0.000950711,0.733666,0.215367,0.229266,0.0254252,-16.7987,-8.19318,-365.448,-1.70793e-05,-6.02305e-05,2.10221e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000484844,1.30533e-05,1.20976e-05,0.000570304,0.136376,0.1355,0.168913,0.532305,0.525369,0.103027,7.07572e-11,7.09005e-11,1.18582e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +36785000,-0.679424,-0.014918,-0.000969207,0.733594,0.176941,0.191524,0.0214012,-16.818,-8.2139,-365.447,-1.71993e-05,-6.03152e-05,2.00855e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000483435,1.2896e-05,1.19551e-05,0.000568459,0.111462,0.110915,0.149288,0.531148,0.523715,0.0983535,7.07695e-11,7.09086e-11,1.17575e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +36885000,-0.679507,-0.0149764,-0.000968153,0.733516,0.216926,0.231592,0.0267841,-16.7982,-8.19285,-365.444,-1.71997e-05,-6.03156e-05,1.90816e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000483295,1.28165e-05,1.18658e-05,0.000568303,0.136237,0.135466,0.16847,0.542473,0.535482,0.102205,7.08693e-11,7.10086e-11,1.16603e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +36985000,-0.679551,-0.014873,-0.000894602,0.733477,0.178434,0.192491,0.0200247,-16.8177,-8.21377,-365.445,-1.73157e-05,-6.03958e-05,1.84055e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.00048197,1.2669e-05,1.17339e-05,0.000566622,0.111386,0.110893,0.148952,0.541297,0.533834,0.0976069,7.089e-11,7.10251e-11,1.15625e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +37085000,-0.679556,-0.0149071,-0.000863621,0.733471,0.21898,0.233018,0.0273199,-16.7978,-8.1925,-365.442,-1.73157e-05,-6.03959e-05,1.81739e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000481811,1.25956e-05,1.16524e-05,0.000566493,0.136144,0.135433,0.16804,0.552634,0.545596,0.101401,7.09899e-11,7.11251e-11,1.1468e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +37185000,-0.679584,-0.01483,-0.000842889,0.733447,0.17991,0.189113,0.0259159,-16.8176,-8.21557,-365.445,-1.74281e-05,-6.04751e-05,1.81123e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000480584,1.24607e-05,1.15301e-05,0.000564864,0.111331,0.110871,0.148628,0.551447,0.543953,0.0968766,7.10184e-11,7.11494e-11,1.1373e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +37285000,-0.679618,-0.0148535,-0.000867694,0.733415,0.220135,0.2296,0.0317201,-16.7975,-8.19469,-365.441,-1.74284e-05,-6.04754e-05,1.74743e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000480426,1.23942e-05,1.14561e-05,0.000564738,0.136072,0.135403,0.16763,0.56279,0.555711,0.100616,7.11183e-11,7.12494e-11,1.12811e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +37385000,-0.679668,-0.0147818,-0.000805805,0.73337,0.179603,0.18595,0.0287104,-16.8174,-8.21742,-365.444,-1.75361e-05,-6.05477e-05,1.71334e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000479366,1.22699e-05,1.13439e-05,0.000563331,0.111284,0.110851,0.149355,0.561598,0.554073,0.0985305,7.11541e-11,7.12809e-11,1.12138e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +37485000,-0.679742,-0.0148052,-0.000784162,0.733302,0.219443,0.227784,0.0335994,-16.7974,-8.19682,-365.443,-1.75366e-05,-6.05482e-05,1.62676e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000479236,1.22111e-05,1.12779e-05,0.00056318,0.136014,0.135378,0.168571,0.572946,0.565827,0.102404,7.1254e-11,7.13809e-11,1.1124e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +37585000,-0.679777,-0.014727,-0.000762336,0.733271,0.1786,0.185854,0.0384048,-16.8171,-8.21938,-365.439,-1.76386e-05,-6.06143e-05,1.55266e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000478039,1.20958e-05,1.11744e-05,0.000561717,0.111252,0.110837,0.149041,0.571749,0.564194,0.0977962,7.12966e-11,7.14192e-11,1.10339e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +37685000,-0.679805,-0.0147817,-0.000797616,0.733244,0.217795,0.227691,0.0492461,-16.7973,-8.19874,-365.428,-1.76383e-05,-6.06143e-05,1.49278e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000477884,1.20468e-05,1.1116e-05,0.000561594,0.135968,0.135358,0.168172,0.583098,0.575944,0.101615,7.13966e-11,7.15192e-11,1.09466e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +37785000,-0.679829,-0.0146522,-0.000825367,0.733224,0.177524,0.185874,0.0503223,-16.8169,-8.22122,-365.424,-1.77349e-05,-6.06752e-05,1.45807e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000476732,1.19372e-05,1.1021e-05,0.000560136,0.111225,0.110824,0.148692,0.581899,0.574315,0.0970465,7.14455e-11,7.15638e-11,1.08589e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +37885000,-0.67985,-0.0146676,-0.000819554,0.733204,0.216609,0.226995,0.0538039,-16.7972,-8.20061,-365.424,-1.77354e-05,-6.06756e-05,1.42923e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.0004766,1.18932e-05,1.09703e-05,0.000559997,0.135928,0.135337,0.167725,0.593248,0.586061,0.100807,7.15455e-11,7.16638e-11,1.07739e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +37985000,-0.679844,-0.0145802,-0.000854181,0.733211,0.173687,0.185371,0.0493874,-16.8187,-8.22299,-365.425,-1.78305e-05,-6.07301e-05,1.41228e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000475558,1.17959e-05,1.08848e-05,0.000558733,0.111202,0.110809,0.149443,0.59205,0.584436,0.0987214,7.16003e-11,7.17144e-11,1.0712e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +38085000,-0.67985,-0.0146116,-0.000859714,0.733206,0.211976,0.226159,0.0616089,-16.7994,-8.20249,-365.413,-1.78303e-05,-6.07302e-05,1.351e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000475378,1.17606e-05,1.08418e-05,0.000558643,0.135893,0.135316,0.1687,0.603398,0.596179,0.10262,7.17003e-11,7.18144e-11,1.0629e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +38185000,-0.679848,-0.0145046,-0.000827092,0.733209,0.169005,0.184245,0.0530879,-16.8205,-8.22484,-365.416,-1.79191e-05,-6.07799e-05,1.3284e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000474241,1.16709e-05,1.07649e-05,0.000557254,0.111174,0.110797,0.149103,0.602201,0.594558,0.0979675,7.17606e-11,7.18704e-11,1.05457e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +38285000,-0.679863,-0.0145381,-0.000828996,0.733194,0.20829,0.223846,0.0589563,-16.8016,-8.20444,-365.412,-1.79192e-05,-6.078e-05,1.3038e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000474109,1.16433e-05,1.07296e-05,0.000557119,0.135857,0.135296,0.168265,0.613551,0.606298,0.101807,7.18606e-11,7.19704e-11,1.04648e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +38385000,-0.679848,-0.0144335,-0.000774612,0.733211,0.170713,0.183673,0.0458363,-16.8205,-8.22644,-365.415,-1.79993e-05,-6.08251e-05,1.3011e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000472999,1.15625e-05,1.06613e-05,0.000555764,0.111158,0.110786,0.148774,0.612351,0.60468,0.0972297,7.19259e-11,7.20315e-11,1.03838e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +38485000,-0.67987,-0.0144471,-0.000789148,0.73319,0.210083,0.224406,0.0508281,-16.8014,-8.20607,-365.413,-1.79995e-05,-6.08253e-05,1.27014e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000472872,1.1541e-05,1.06334e-05,0.00055563,0.135839,0.135283,0.167846,0.623699,0.616417,0.101013,7.20258e-11,7.21314e-11,1.0305e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +38585000,-0.679836,-0.0143811,-0.00070812,0.733223,0.173402,0.184066,0.0366382,-16.8203,-8.22814,-365.42,-1.80756e-05,-6.08654e-05,1.26257e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000471738,1.14713e-05,1.05739e-05,0.000554304,0.111152,0.110776,0.148459,0.622501,0.614803,0.0965079,7.20958e-11,7.21972e-11,1.02261e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +38685000,-0.679879,-0.0144653,-0.000719338,0.733181,0.211854,0.222771,0.0410858,-16.801,-8.20784,-365.422,-1.80759e-05,-6.08657e-05,1.22318e-06,-2.75613e-05,7.16886e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000471735,1.14624e-05,1.05542e-05,0.000554296,0.135819,0.135265,0.168791,0.633846,0.626537,0.102813,7.21958e-11,7.22972e-11,1.0171e-10,2.95326e-06,2.95427e-06,5e-08,0,0,0,0,0,0,0,0 +38785000,-0.679866,-0.0143698,-0.000703988,0.733196,0.170507,0.178643,0.0385295,-16.822,-8.23181,-365.422,-1.81508e-05,-6.09012e-05,1.19627e-06,-2.7561e-05,7.16884e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000470624,1.13993e-05,1.05026e-05,0.000552982,0.0898494,0.0894787,0.127717,0.632603,0.624878,0.098106,7.227e-11,7.23672e-11,1.00939e-10,2.95327e-06,2.95428e-06,5.0009e-08,0,0,0,0,0,0,0,0 +38885000,-0.679877,-0.0145496,-0.000760757,0.733181,0.191463,0.199704,0.491587,-16.8034,-8.21245,-365.404,-1.81508e-05,-6.09012e-05,1.17477e-06,-2.75594e-05,7.1687e-05,-0.00118889,0.208315,0.00202315,0.435262,0,0,0,0,0,0.000470495,1.14043e-05,1.04906e-05,0.000552845,0.0911222,0.0906599,0.123341,0.643495,0.63615,0.101577,7.237e-11,7.24672e-11,1.0019e-10,2.95328e-06,2.95429e-06,5.0019e-08,0,0,0,0,0,0,0,0 diff --git a/src/modules/ekf2/test/change_indication/iris_gps.csv b/src/modules/ekf2/test/change_indication/iris_gps.csv new file mode 100644 index 0000000000..cf6f36d98f --- /dev/null +++ b/src/modules/ekf2/test/change_indication/iris_gps.csv @@ -0,0 +1,351 @@ +Timestamp,state[0],state[1],state[2],state[3],state[4],state[5],state[6],state[7],state[8],state[9],state[10],state[11],state[12],state[13],state[14],state[15],state[16],state[17],state[18],state[19],state[20],state[21],state[22],state[23],variance[0],variance[1],variance[2],variance[3],variance[4],variance[5],variance[6],variance[7],variance[8],variance[9],variance[10],variance[11],variance[12],variance[13],variance[14],variance[15],variance[16],variance[17],variance[18],variance[19],variance[20],variance[21],variance[22],variance[23] +15000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +85000,1,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0 +185000,0.979315,-0.00941534,-0.0138038,0.201649,0.000856322,-0.000411629,-0.0109864,5.47934e-05,-6.84752e-06,-0.0416696,5.00889e-13,-3.73116e-13,-2.04073e-14,0,0,-2.00585e-09,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000204663,0.002482,0.00248157,0.00481116,0.256366,0.256365,0.562563,0.126414,0.126414,1.00079,1e-06,1e-06,1e-06,4e-06,4e-06,4.00001e-06,0,0,0,0,0,0,0,0 +285000,0.979308,-0.00949873,-0.0141086,0.20166,0.002379,-0.00213114,-0.0263621,0.000165842,-0.000101819,-0.0412744,4.72333e-12,-1.36589e-12,-1.42115e-13,0,0,-1.03405e-08,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00020737,0.00254707,0.00254659,0.00487353,0.282172,0.282169,0.562506,0.132888,0.132888,0.576885,1e-06,1e-06,1e-06,4e-06,4e-06,4.00001e-06,0,0,0,0,0,0,0,0 +385000,0.979291,-0.00951138,-0.0143965,0.201721,0.00537783,-0.00315158,-0.0396036,0.000429404,-0.00026618,-0.0244167,-1.0942e-09,-7.23618e-10,8.85773e-12,0,0,-2.11601e-07,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000212229,0.00265868,0.00265816,0.00498376,0.319167,0.319162,0.560114,0.0942198,0.0942198,0.375592,9.99994e-07,9.99994e-07,1e-06,4e-06,4e-06,3.99998e-06,0,0,0,0,0,0,0,0 +485000,0.979278,-0.00952859,-0.0147624,0.201755,0.00880115,-0.00649446,-0.0568877,0.0011663,-0.000751267,-0.0284287,-1.35448e-09,-8.91104e-10,1.09489e-11,0,0,-1.48264e-08,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000219099,0.00282371,0.00282311,0.00514201,0.386741,0.386732,0.553871,0.109438,0.109437,0.287379,9.99994e-07,9.99994e-07,1e-06,4e-06,4e-06,3.99978e-06,0,0,0,0,0,0,0,0 +585000,0.979269,-0.0095287,-0.0149642,0.201785,0.0102124,-0.00954546,-0.0751953,0.00161955,-0.00119412,-0.0361541,-5.53152e-08,-3.52001e-08,4.57828e-10,1.90215e-09,-2.55283e-09,2.77562e-07,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00022799,0.00298935,0.00298869,0.00534822,0.436306,0.436292,0.542813,0.0904939,0.0904935,0.242024,9.99625e-07,9.99625e-07,1e-06,4.00001e-06,4.00001e-06,3.99919e-06,0,0,0,0,0,0,0,0 +685000,0.979259,-0.00955857,-0.0153322,0.201804,0.0151135,-0.0119584,-0.0797677,0.00292576,-0.00226341,-0.0326607,-5.19032e-08,-3.35021e-08,4.17757e-10,-5.01186e-09,4.19761e-09,-1.69524e-06,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000238947,0.003253,0.00325224,0.00560241,0.548703,0.548684,0.525909,0.117161,0.117159,0.217499,9.99625e-07,9.99625e-07,1e-06,4.00002e-06,4.00002e-06,3.99786e-06,0,0,0,0,0,0,0,0 +785000,0.979257,-0.00947262,-0.0154864,0.201808,0.0173936,-0.0110414,-0.0884129,0.00313482,-0.00236265,-0.0373938,-4.47419e-07,-2.5301e-07,4.57069e-09,6.57809e-08,-1.29729e-07,-2.80911e-06,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00025184,0.00335584,0.003355,0.00590458,0.569918,0.569902,0.503502,0.101288,0.101287,0.204568,9.96263e-07,9.96263e-07,9.99997e-07,3.99961e-06,3.99961e-06,3.99537e-06,0,0,0,0,0,0,0,0 +885000,0.979246,-0.00951693,-0.0158372,0.201831,0.0211364,-0.0115675,-0.104517,0.00502931,-0.00352356,-0.0502256,-4.49455e-07,-2.54178e-07,4.59119e-09,7.25345e-08,-1.36245e-07,-1.88445e-06,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00026693,0.00371094,0.00370998,0.00625468,0.724106,0.724087,0.475834,0.141191,0.141189,0.198089,9.96263e-07,9.96263e-07,9.99997e-07,3.99962e-06,3.99962e-06,3.99118e-06,0,0,0,0,0,0,0,0 +985000,0.979255,-0.00927576,-0.0159465,0.201791,0.0211524,-0.00878636,-0.116406,0.00448618,-0.00282834,-0.0592979,-1.60242e-06,-1.01065e-06,1.37841e-08,4.35548e-07,-6.96467e-07,-2.95376e-06,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000283718,0.00362061,0.00361954,0.00665284,0.668295,0.668285,0.453927,0.116363,0.116362,0.20526,9.83343e-07,9.83342e-07,9.99986e-07,3.99647e-06,3.99647e-06,3.9866e-06,0,0,0,0,0,0,0,0 +1085000,0.979258,-0.00936227,-0.0161341,0.201755,0.0305208,-0.0112904,-0.134492,0.00700998,-0.0037647,-0.0779799,-1.60885e-06,-1.01601e-06,1.38092e-08,4.65212e-07,-7.24577e-07,-3.32431e-07,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000302726,0.00404969,0.00404851,0.00709903,0.850898,0.850896,0.420561,0.167281,0.167278,0.20383,9.83343e-07,9.83342e-07,9.99986e-07,3.99648e-06,3.99648e-06,3.97832e-06,0,0,0,0,0,0,0,0 +1185000,0.979274,-0.0090459,-0.0160539,0.201702,0.0296497,-0.00978035,-0.130926,0.0056794,-0.00270907,-0.0734198,-3.62777e-06,-2.73434e-06,2.02064e-08,1.24829e-06,-1.67126e-06,-9.50701e-06,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00032343,0.00374423,0.00374297,0.00759315,0.707178,0.707189,0.386379,0.127112,0.127111,0.203012,9.53986e-07,9.53985e-07,9.9996e-07,3.98859e-06,3.98859e-06,3.96733e-06,0,0,0,0,0,0,0,0 +1285000,0.979284,-0.00891876,-0.0163066,0.201639,0.0387731,-0.0103991,-0.137004,0.00914971,-0.00375846,-0.0780552,-3.61133e-06,-2.71611e-06,2.02439e-08,1.17027e-06,-1.59866e-06,-1.47579e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000346393,0.00422296,0.00422152,0.00813541,0.903463,0.903491,0.352467,0.183801,0.1838,0.201851,9.53986e-07,9.53985e-07,9.9996e-07,3.9886e-06,3.9886e-06,3.95329e-06,0,0,0,0,0,0,0,0 +1385000,0.979303,-0.00856301,-0.0159859,0.201587,0.0363251,-0.00762584,-0.13459,0.00682589,-0.00242195,-0.0751112,-6.51455e-06,-5.79887e-06,1.52331e-08,2.51797e-06,-2.86839e-06,-2.57587e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000371059,0.00377875,0.00377732,0.0087255,0.705484,0.70552,0.320038,0.131056,0.131056,0.199991,9.0574e-07,9.05739e-07,9.9992e-07,3.97717e-06,3.97717e-06,3.93598e-06,0,0,0,0,0,0,0,0 +1485000,0.979297,-0.00849968,-0.0161527,0.201606,0.0417935,-0.00826412,-0.145861,0.0107436,-0.00314307,-0.0873173,-6.50884e-06,-5.79097e-06,1.52816e-08,2.49191e-06,-2.84447e-06,-2.72386e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000398351,0.00428321,0.00428161,0.00936342,0.904827,0.90488,0.290235,0.188933,0.188935,0.197531,9.0574e-07,9.05738e-07,9.99921e-07,3.97717e-06,3.97717e-06,3.91566e-06,0,0,0,0,0,0,0,0 +1585000,0.9793,-0.00824164,-0.0158513,0.201624,0.0352096,-0.00530316,-0.156317,0.00734178,-0.00194073,-0.0981854,-9.96857e-06,-1.02034e-05,-6.84091e-09,4.31943e-06,-4.26866e-06,-3.0711e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000427333,0.00376817,0.00376662,0.0100492,0.689322,0.689366,0.271812,0.130171,0.130172,0.204447,8.39878e-07,8.39879e-07,9.9987e-07,3.96521e-06,3.96521e-06,3.8983e-06,0,0,0,0,0,0,0,0 +1685000,0.979285,-0.00828357,-0.0160684,0.201679,0.0424589,-0.00443601,-0.161574,0.0112481,-0.00236583,-0.103483,-9.93997e-06,-1.01616e-05,-6.55926e-09,4.16876e-06,-4.13092e-06,-3.90932e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000458896,0.0042778,0.00427607,0.0107828,0.888542,0.88861,0.247173,0.186918,0.186922,0.200424,8.39878e-07,8.39878e-07,9.9987e-07,3.96521e-06,3.96521e-06,3.87227e-06,0,0,0,0,0,0,0,0 +1785000,0.979292,-0.00839034,-0.0163254,0.201618,0.0519153,-0.00520496,-0.162467,0.0160505,-0.00286508,-0.10601,-9.89447e-06,-1.00916e-05,-6.02571e-09,3.94616e-06,-3.9282e-06,-5.09331e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000492001,0.00482942,0.00482749,0.0115649,1.13195,1.13206,0.225509,0.268083,0.268092,0.195911,8.39878e-07,8.39877e-07,9.9987e-07,3.96521e-06,3.96521e-06,3.84277e-06,0,0,0,0,0,0,0,0 +1885000,0.979303,-0.00797446,-0.0157677,0.201628,0.0421386,0.000521569,-0.163789,0.0114175,-0.00143326,-0.1107,-1.34696e-05,-1.55371e-05,-4.81995e-08,5.67662e-06,-5.01002e-06,-6.1771e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000526961,0.00421003,0.00420823,0.0123946,0.868615,0.868693,0.206851,0.181893,0.181898,0.191243,7.59172e-07,7.59175e-07,9.9981e-07,3.95524e-06,3.95524e-06,3.81008e-06,0,0,0,0,0,0,0,0 +1985000,0.979296,-0.0080205,-0.016088,0.201633,0.0492257,0.00113807,-0.162388,0.0160315,-0.00142097,-0.110034,-1.34109e-05,-1.54311e-05,-4.71676e-08,5.34451e-06,-4.70677e-06,-7.88007e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000564434,0.00474468,0.00474264,0.0132723,1.10904,1.10916,0.190823,0.260678,0.260689,0.186407,7.59172e-07,7.59174e-07,9.9981e-07,3.95523e-06,3.95524e-06,3.77376e-06,0,0,0,0,0,0,0,0 +2085000,0.979299,-0.00779835,-0.0155539,0.201668,0.0389515,0.00361264,-0.160859,0.0110516,-0.000406741,-0.107749,-1.66857e-05,-2.15891e-05,-1.12163e-07,6.65193e-06,-5.2462e-06,-9.90527e-05,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000603623,0.00406417,0.00406232,0.0141977,0.84792,0.847995,0.177274,0.175994,0.175999,0.181666,6.67724e-07,6.67732e-07,9.99743e-07,3.94848e-06,3.94849e-06,3.73407e-06,0,0,0,0,0,0,0,0 +2185000,0.979304,-0.00770002,-0.0158459,0.201628,0.0452023,0.00469301,-0.162038,0.0152797,5.06208e-05,-0.11216,-1.66479e-05,-2.15055e-05,-1.11149e-07,6.3791e-06,-4.99432e-06,-0.000112771,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000644866,0.00456539,0.00456328,0.0151716,1.08185,1.08196,0.165813,0.252257,0.252269,0.176976,6.67723e-07,6.67731e-07,9.99743e-07,3.94848e-06,3.94848e-06,3.69045e-06,0,0,0,0,0,0,0,0 +2285000,0.979317,-0.00754723,-0.0152768,0.201614,0.0332354,0.00646442,-0.159545,0.010113,0.000514001,-0.112059,-1.93418e-05,-2.79671e-05,-1.96492e-07,7.23671e-06,-5.14776e-06,-0.000132659,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000687783,0.00383184,0.00382998,0.0161932,0.820509,0.820572,0.160777,0.169932,0.169938,0.180303,5.71084e-07,5.71102e-07,9.99671e-07,3.94496e-06,3.94496e-06,3.65505e-06,0,0,0,0,0,0,0,0 +2385000,0.97931,-0.0075364,-0.0154123,0.201635,0.03907,0.00676796,-0.159081,0.0137669,0.00113817,-0.110577,-1.92982e-05,-2.78499e-05,-1.94858e-07,6.7913e-06,-4.732e-06,-0.00015487,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000733445,0.00428666,0.00428463,0.0172627,1.04481,1.0449,0.152406,0.243439,0.243451,0.175638,5.71084e-07,5.711e-07,9.99672e-07,3.94495e-06,3.94496e-06,3.60432e-06,0,0,0,0,0,0,0,0 +2485000,0.979303,-0.00731472,-0.0148506,0.201721,0.0267141,0.0075031,-0.159923,0.0088385,0.00108175,-0.113785,-2.12954e-05,-3.40056e-05,-2.89037e-07,7.14087e-06,-4.63562e-06,-0.00017182,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000781171,0.00352419,0.00352238,0.0183795,0.784592,0.784645,0.145495,0.163762,0.163767,0.17132,4.75655e-07,4.75683e-07,9.99598e-07,3.94377e-06,3.94378e-06,3.54971e-06,0,0,0,0,0,0,0,0 +2585000,0.979318,-0.0073645,-0.0149504,0.20164,0.0287877,0.00730873,-0.161931,0.0116097,0.00184955,-0.117685,-2.12738e-05,-3.39316e-05,-2.87872e-07,6.79286e-06,-4.30824e-06,-0.000188973,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000830103,0.00392466,0.00392273,0.0195456,0.994248,0.994325,0.139758,0.234128,0.234138,0.167259,4.75655e-07,4.75682e-07,9.99598e-07,3.94375e-06,3.94376e-06,3.49057e-06,0,0,0,0,0,0,0,0 +2685000,0.979315,-0.00736106,-0.0144328,0.201691,0.0191911,0.00786502,-0.160594,0.00716792,0.00141447,-0.116797,-2.25294e-05,-3.91305e-05,-3.77358e-07,6.42197e-06,-3.84283e-06,-0.000215094,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000881684,0.00316761,0.00316592,0.0207584,0.738936,0.738982,0.134988,0.157395,0.1574,0.163465,3.87158e-07,3.87194e-07,9.99524e-07,3.94365e-06,3.94366e-06,3.42673e-06,0,0,0,0,0,0,0,0 +2785000,0.979325,-0.0072377,-0.0145503,0.201637,0.0234862,0.0092336,-0.157151,0.00942993,0.00227029,-0.113291,-2.25086e-05,-3.90259e-05,-3.75472e-07,5.77439e-06,-3.23237e-06,-0.000246367,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000934814,0.00351118,0.00350932,0.0220203,0.931054,0.931121,0.131113,0.224127,0.224136,0.160037,3.87158e-07,3.87193e-07,9.99524e-07,3.94363e-06,3.94365e-06,3.35878e-06,0,0,0,0,0,0,0,0 +2885000,0.979346,-0.0072543,-0.0141567,0.201567,0.0165265,0.00674893,-0.157845,0.00580643,0.00157895,-0.114622,-2.3164e-05,-4.32245e-05,-4.56732e-07,5.07063e-06,-2.73188e-06,-0.000270164,0.202688,0.0101969,0.433398,0,0,0,0,0,0.000989343,0.00279383,0.00279212,0.0233301,0.68584,0.685884,0.131194,0.150811,0.150815,0.163368,3.09461e-07,3.09503e-07,9.99451e-07,3.94343e-06,3.94345e-06,3.30491e-06,0,0,0,0,0,0,0,0 +2985000,0.979343,-0.00721393,-0.0142169,0.201576,0.0184314,0.00696196,-0.159625,0.00764903,0.00227137,-0.118328,-2.3159e-05,-4.31755e-05,-4.55744e-07,4.64135e-06,-2.3277e-06,-0.000290601,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00104703,0.00308251,0.00308069,0.0246874,0.858583,0.858647,0.128413,0.213482,0.213489,0.160302,3.09461e-07,3.09502e-07,9.99452e-07,3.94341e-06,3.94343e-06,3.22904e-06,0,0,0,0,0,0,0,0 +3085000,0.979304,-0.00721607,-0.0139572,0.201781,0.0147407,0.00394272,-0.162257,0.00477884,0.00141258,-0.122504,-2.35441e-05,-4.6452e-05,-5.21103e-07,3.75944e-06,-1.85399e-06,-0.000311858,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00110857,0.00243022,0.00242842,0.0260902,0.628826,0.628867,0.126055,0.14409,0.144093,0.157493,2.44204e-07,2.44248e-07,9.99387e-07,3.94228e-06,3.94231e-06,3.14852e-06,0,0,0,0,0,0,0,0 +3185000,0.979296,-0.00719355,-0.014055,0.201815,0.0173626,0.00345103,-0.162682,0.00641863,0.00174375,-0.127191,-2.35436e-05,-4.6417e-05,-5.20335e-07,3.31679e-06,-1.44e-06,-0.000332593,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00117074,0.0026692,0.00266728,0.0275429,0.781632,0.78169,0.124089,0.202448,0.202454,0.155008,2.44204e-07,2.44248e-07,9.99387e-07,3.94225e-06,3.94229e-06,3.06427e-06,0,0,0,0,0,0,0,0 +3285000,0.979295,-0.00716704,-0.0137061,0.201847,0.0122556,0.00267657,-0.165384,0.00406869,0.00102184,-0.134897,-2.39546e-05,-4.89669e-05,-5.64953e-07,2.40686e-06,-1.01699e-06,-0.000349353,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00123463,0.00209508,0.00209318,0.0290434,0.570865,0.570902,0.122347,0.137367,0.13737,0.152735,1.91194e-07,1.91236e-07,9.99334e-07,3.93981e-06,3.93986e-06,2.97581e-06,0,0,0,0,0,0,0,0 +3385000,0.979295,-0.00695249,-0.013721,0.201855,0.0126511,0.00432205,-0.163312,0.00527626,0.00137109,-0.132683,-2.39571e-05,-4.89227e-05,-5.63945e-07,1.6003e-06,-2.72179e-07,-0.000386477,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00130061,0.00229095,0.00228889,0.0305924,0.705267,0.70532,0.120822,0.191349,0.191354,0.150734,1.91194e-07,1.91236e-07,9.99335e-07,3.93978e-06,3.93983e-06,2.88423e-06,0,0,0,0,0,0,0,0 +3485000,0.979301,-0.00690235,-0.0134601,0.201844,0.0106396,0.00621978,-0.161134,0.00337233,0.00100183,-0.132551,-2.42075e-05,-5.08504e-05,-5.98425e-07,2.86771e-07,4.69644e-07,-0.000419677,0.202688,0.0101969,0.433398,0,0,0,0,0,0.0013681,0.00179771,0.00179556,0.0321893,0.51555,0.515583,0.119375,0.13079,0.130792,0.148896,1.49129e-07,1.49165e-07,9.99289e-07,3.93597e-06,3.93603e-06,2.78916e-06,0,0,0,0,0,0,0,0 +3585000,0.979312,-0.00679513,-0.0133728,0.201802,0.0123492,0.00664925,-0.166152,0.00455885,0.00164879,-0.140062,-2.42111e-05,-5.08359e-05,-5.98018e-07,-1.12858e-07,8.36805e-07,-0.000437853,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00143741,0.00195734,0.00195513,0.0338348,0.632699,0.632744,0.120812,0.180524,0.180529,0.152904,1.49129e-07,1.49165e-07,9.99289e-07,3.93595e-06,3.93601e-06,2.71586e-06,0,0,0,0,0,0,0,0 +3685000,0.979312,-0.00680018,-0.0131834,0.201812,0.00819874,0.00583057,-0.162064,0.00296595,0.0011775,-0.138295,-2.42651e-05,-5.24346e-05,-6.31539e-07,-1.595e-06,1.6327e-06,-0.000476298,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00150927,0.00154034,0.00153801,0.0355273,0.463902,0.463933,0.119368,0.124473,0.124475,0.151278,1.16241e-07,1.16273e-07,9.99252e-07,3.93092e-06,3.93099e-06,2.61615e-06,0,0,0,0,0,0,0,0 +3785000,0.979309,-0.00670602,-0.0132696,0.201824,0.00762262,0.0100102,-0.163007,0.00376506,0.00205705,-0.14312,-2.42718e-05,-5.2422e-05,-6.31085e-07,-2.12226e-06,2.11541e-06,-0.000500071,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00158344,0.00167033,0.0016678,0.0372678,0.565387,0.565432,0.117929,0.170176,0.170181,0.149832,1.16241e-07,1.16273e-07,9.99252e-07,3.93088e-06,3.93096e-06,2.51508e-06,0,0,0,0,0,0,0,0 +3885000,0.979296,-0.00663172,-0.0133026,0.20189,0.00698334,0.0116441,-0.160451,0.00458178,0.0032052,-0.14413,-2.42815e-05,-5.24037e-05,-6.30393e-07,-2.82933e-06,2.76451e-06,-0.000531919,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00166053,0.00180607,0.0018034,0.0390555,0.682652,0.682717,0.116398,0.231601,0.231609,0.148459,1.16241e-07,1.16274e-07,9.99252e-07,3.93083e-06,3.93093e-06,2.41244e-06,0,0,0,0,0,0,0,0 +3985000,0.97928,-0.00669795,-0.0131384,0.201972,0.00611485,0.0103681,-0.159463,0.00283543,0.00255035,-0.1433,-2.40184e-05,-5.3667e-05,-6.69434e-07,-4.26806e-06,3.38266e-06,-0.000568621,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00173982,0.00142726,0.00142445,0.0408903,0.504756,0.504797,0.114753,0.160441,0.160445,0.147137,9.07589e-08,9.07898e-08,9.99216e-07,3.92483e-06,3.92494e-06,2.30882e-06,0,0,0,0,0,0,0,0 +4085000,0.979272,-0.00661221,-0.0130466,0.202021,0.00718728,0.0110456,-0.147987,0.00359379,0.00365774,-0.132269,-2.40406e-05,-5.36456e-05,-6.68235e-07,-5.55333e-06,4.56172e-06,-0.000625999,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00182091,0.00153744,0.00153458,0.0427741,0.60592,0.605974,0.11304,0.216411,0.216418,0.145921,9.0759e-08,9.07899e-08,9.99216e-07,3.92479e-06,3.9249e-06,2.20555e-06,0,0,0,0,0,0,0,0 +4185000,0.979278,-0.00679373,-0.0128762,0.201995,0.00489225,0.00855568,-0.149535,0.00232707,0.00268897,-0.138497,-2.36264e-05,-5.46481e-05,-7.0844e-07,-6.56017e-06,4.70024e-06,-0.000644691,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00190247,0.00122319,0.00122028,0.0447065,0.450363,0.450402,0.113939,0.15138,0.151384,0.150229,7.10939e-08,7.11239e-08,9.99183e-07,3.9181e-06,3.91822e-06,2.12841e-06,0,0,0,0,0,0,0,0 +4285000,0.979273,-0.00682,-0.0129154,0.202016,0.00704888,0.0103659,-0.15182,0.00298038,0.00362309,-0.14428,-2.36344e-05,-5.46436e-05,-7.08079e-07,-7.01413e-06,5.11488e-06,-0.000664834,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00198719,0.001313,0.00130997,0.0466863,0.537875,0.53792,0.11195,0.202389,0.202396,0.149006,7.1094e-08,7.1124e-08,9.99183e-07,3.91805e-06,3.91818e-06,2.0262e-06,0,0,0,0,0,0,0,0 +4385000,0.979281,-0.00681346,-0.0128401,0.201985,0.00652075,0.00693624,-0.143085,0.00215397,0.00255005,-0.134651,-2.32365e-05,-5.54446e-05,-7.43418e-07,-8.74951e-06,5.90312e-06,-0.000717121,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00207267,0.00105307,0.00104973,0.0487148,0.402512,0.402541,0.109819,0.143008,0.143011,0.147764,5.59328e-08,5.5961e-08,9.99156e-07,3.91089e-06,3.91104e-06,1.92514e-06,0,0,0,0,0,0,0,0 +4485000,0.979271,-0.00684043,-0.0127807,0.202034,0.00722956,0.0102083,-0.139658,0.00290011,0.00346681,-0.133205,-2.32493e-05,-5.54403e-05,-7.4293e-07,-9.49869e-06,6.58452e-06,-0.000750285,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00216209,0.00112633,0.00112298,0.05079,0.478125,0.478162,0.10761,0.189553,0.189559,0.146566,5.59328e-08,5.59611e-08,9.99156e-07,3.91085e-06,3.911e-06,1.82639e-06,0,0,0,0,0,0,0,0 +4585000,0.979257,-0.00690589,-0.0127252,0.202106,0.00621044,0.00686951,-0.139118,0.00207989,0.00253641,-0.135924,-2.28941e-05,-5.61484e-05,-7.73411e-07,-1.06026e-05,6.78634e-06,-0.000774217,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00225393,0.000911289,0.00090766,0.0529121,0.360272,0.360296,0.105273,0.135302,0.135305,0.145325,4.42269e-08,4.42528e-08,9.99135e-07,3.90346e-06,3.90362e-06,1.72971e-06,0,0,0,0,0,0,0,0 +4685000,0.979268,-0.00684209,-0.0126669,0.202057,0.00569871,0.00778768,-0.130654,0.00275268,0.0033514,-0.129864,-2.29092e-05,-5.61453e-05,-7.72894e-07,-1.15329e-05,7.63093e-06,-0.000815419,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00234533,0.000971354,0.000967622,0.0550854,0.425692,0.425726,0.102876,0.177842,0.177847,0.144108,4.4227e-08,4.42529e-08,9.99135e-07,3.90342e-06,3.90359e-06,1.6361e-06,0,0,0,0,0,0,0,0 +4785000,0.979253,-0.00676557,-0.012645,0.202135,-0.00128328,0.0065367,-0.129245,0.00161631,0.00241869,-0.131235,-2.25928e-05,-5.67428e-05,-7.9865e-07,-1.26228e-05,7.83249e-06,-0.000839672,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00244157,0.000793262,0.000789067,0.0573032,0.323071,0.323116,0.100378,0.128218,0.128221,0.142837,3.51643e-08,3.51872e-08,9.99118e-07,3.89596e-06,3.89614e-06,1.54527e-06,0,0,0,0,0,0,0,0 +4885000,0.979242,-0.00668918,-0.012662,0.202188,-0.000657602,0.00510409,-0.125741,0.00152599,0.00299534,-0.131566,-2.26016e-05,-5.67426e-05,-7.98362e-07,-1.31966e-05,8.35009e-06,-0.000864971,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00253955,0.000842826,0.000838399,0.0595698,0.379955,0.380002,0.100264,0.167176,0.167182,0.146771,3.51644e-08,3.51873e-08,9.99119e-07,3.89593e-06,3.89612e-06,1.47919e-06,0,0,0,0,0,0,0,0 +4985000,0.979245,-0.00669973,-0.012601,0.202178,-0.000388414,0.00486673,-0.118913,0.0008243,0.00207164,-0.127451,-2.23019e-05,-5.7084e-05,-8.20682e-07,-1.42905e-05,8.70132e-06,-0.000897753,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00263781,0.000694955,0.00069015,0.0618853,0.29036,0.290391,0.0975811,0.121712,0.121716,0.145352,2.8125e-08,2.81415e-08,9.99099e-07,3.88855e-06,3.88875e-06,1.39413e-06,0,0,0,0,0,0,0,0 +5085000,0.979231,-0.00655487,-0.0125218,0.202256,-6.97556e-05,0.00578396,-0.114624,0.000827377,0.00257818,-0.123483,-2.23119e-05,-5.70854e-05,-8.20367e-07,-1.49916e-05,9.32752e-06,-0.000928498,0.202688,0.0101969,0.433398,0,0,0,0,0,0.0027407,0.000735848,0.000730861,0.0642471,0.340043,0.340079,0.0948884,0.157469,0.157474,0.143941,2.81251e-08,2.81416e-08,9.99099e-07,3.88852e-06,3.88872e-06,1.31296e-06,0,0,0,0,0,0,0,0 +5185000,0.97922,-0.00644305,-0.0125256,0.202312,-0.00311749,0.00712929,-0.111563,0.000335848,0.00194935,-0.121168,-2.20379e-05,-5.7298e-05,-8.40287e-07,-1.58388e-05,9.54329e-06,-0.000955032,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00284494,0.000612832,0.000607213,0.0666564,0.26182,0.26186,0.0921538,0.115743,0.115746,0.142468,2.26324e-08,2.26412e-08,9.9908e-07,3.88131e-06,3.88153e-06,1.23528e-06,0,0,0,0,0,0,0,0 +5285000,0.979211,-0.00632405,-0.012494,0.202361,-0.00277811,0.00889483,-0.101023,5.59439e-05,0.00276561,-0.114763,-2.20479e-05,-5.73004e-05,-8.39943e-07,-1.65856e-05,1.02052e-05,-0.000987656,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00295136,0.000646902,0.000641033,0.0691146,0.305059,0.305103,0.0893932,0.148641,0.148646,0.140935,2.26324e-08,2.26413e-08,9.9908e-07,3.88128e-06,3.8815e-06,1.16119e-06,0,0,0,0,0,0,0,0 +5385000,0.979213,-0.00627203,-0.0124803,0.202351,-0.005568,0.00995511,-0.0965693,-0.00024743,0.0022454,-0.109581,-2.17222e-05,-5.74196e-05,-8.64591e-07,-1.73797e-05,1.0352e-05,-0.00101584,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00305786,0.00054414,0.000537709,0.0716213,0.236528,0.236576,0.0866628,0.110252,0.110256,0.139413,1.83264e-08,1.83283e-08,9.99059e-07,3.87432e-06,3.87456e-06,1.09109e-06,0,0,0,0,0,0,0,0 +5485000,0.979212,-0.00627007,-0.0125421,0.202356,-0.00552518,0.0135262,-0.0935062,-0.000835442,0.00340271,-0.109992,-2.17273e-05,-5.74211e-05,-8.6439e-07,-1.77662e-05,1.06932e-05,-0.00103266,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00316713,0.000572786,0.000566044,0.0741763,0.274583,0.274633,0.0860529,0.140589,0.140596,0.142824,1.83265e-08,1.83284e-08,9.99059e-07,3.87431e-06,3.87455e-06,1.04099e-06,0,0,0,0,0,0,0,0 +5585000,0.97922,-0.0063522,-0.0125711,0.202312,-0.00587118,0.0149121,-0.0857373,-0.000834167,0.00297005,-0.102359,-2.12965e-05,-5.74839e-05,-8.99279e-07,-1.85293e-05,1.0678e-05,-0.00106223,0.202688,0.0101969,0.433398,0,0,0,0,0,0.0032765,0.000486746,0.000479515,0.0767795,0.214276,0.214309,0.0832859,0.105201,0.105205,0.14115,1.49338e-08,1.49315e-08,9.99034e-07,3.86765e-06,3.8679e-06,9.773e-07,0,0,0,0,0,0,0,0 +5685000,0.979239,-0.00631529,-0.012461,0.202225,-0.00619541,0.0178395,-0.0858768,-0.0014946,0.00453737,-0.101798,-2.13013e-05,-5.74855e-05,-8.99082e-07,-1.88942e-05,1.10006e-05,-0.00107809,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00338674,0.000510523,0.000503247,0.0794338,0.247916,0.247948,0.0805416,0.133244,0.133251,0.13943,1.49339e-08,1.49316e-08,9.99034e-07,3.86762e-06,3.86788e-06,9.17104e-07,0,0,0,0,0,0,0,0 +5785000,0.979251,-0.00627087,-0.0124401,0.202172,-0.00557335,0.017488,-0.0801386,-0.00126327,0.00385099,-0.0958059,-2.07678e-05,-5.75356e-05,-9.43992e-07,-1.95278e-05,1.06688e-05,-0.00110249,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00349949,0.00043806,0.000430259,0.0821334,0.194755,0.194769,0.077865,0.100548,0.100552,0.137732,1.22468e-08,1.22436e-08,9.99005e-07,3.86129e-06,3.86155e-06,8.606e-07,0,0,0,0,0,0,0,0 +5885000,0.979244,-0.00619666,-0.0124931,0.202204,-0.00371633,0.0190133,-0.0768142,-0.00170988,0.00571718,-0.0972443,-2.07711e-05,-5.75367e-05,-9.43854e-07,-1.97722e-05,1.08864e-05,-0.00111312,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00361773,0.00045845,0.000450204,0.0848793,0.224318,0.224323,0.0752282,0.126533,0.126538,0.135998,1.22469e-08,1.22437e-08,9.99005e-07,3.86127e-06,3.86154e-06,8.07379e-07,0,0,0,0,0,0,0,0 +5985000,0.979248,-0.0061322,-0.0126015,0.202182,-0.00347781,0.0208752,-0.0702985,-0.00205141,0.00770478,-0.0914818,-2.07779e-05,-5.75386e-05,-9.43547e-07,-2.02643e-05,1.13273e-05,-0.0011346,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00373607,0.000479563,0.000470753,0.0876749,0.257147,0.25715,0.0726704,0.158753,0.158761,0.134292,1.2247e-08,1.22438e-08,9.99005e-07,3.86125e-06,3.86153e-06,7.57571e-07,0,0,0,0,0,0,0,0 +6085000,0.979284,-0.00623375,-0.012543,0.202007,-0.00364786,0.0187115,-0.0671349,-0.001566,0.00643415,-0.089724,-2.0199e-05,-5.76264e-05,-9.9088e-07,-2.07209e-05,1.0633e-05,-0.0011483,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00384998,0.000414636,0.000405605,0.090523,0.203535,0.203537,0.0701643,0.120376,0.12038,0.13256,1.01069e-08,1.01062e-08,9.98978e-07,3.85526e-06,3.85554e-06,7.10771e-07,0,0,0,0,0,0,0,0 +6185000,0.979282,-0.00624802,-0.0124959,0.202019,-0.00480247,0.0209768,-0.0658291,-0.00194522,0.00844789,-0.0891871,-2.02026e-05,-5.76273e-05,-9.90737e-07,-2.09814e-05,1.0868e-05,-0.00115974,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00397346,0.000432241,0.000423094,0.0934137,0.232616,0.23262,0.0693659,0.150155,0.150159,0.135286,1.0107e-08,1.01063e-08,9.98978e-07,3.85526e-06,3.85554e-06,6.7759e-07,0,0,0,0,0,0,0,0 +6285000,0.97927,-0.00631807,-0.0125227,0.202071,-0.00588718,0.0193039,-0.0669331,-0.00166566,0.00691913,-0.0929434,-1.96228e-05,-5.77329e-05,-1.03586e-06,-2.12716e-05,9.90353e-06,-0.00116416,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00410003,0.000377491,0.000367914,0.0963488,0.18525,0.185255,0.0669273,0.114726,0.114729,0.13345,8.39428e-09,8.39756e-09,9.98952e-07,3.84961e-06,3.8499e-06,6.35849e-07,0,0,0,0,0,0,0,0 +6385000,0.979273,-0.00625606,-0.0124583,0.202067,-0.00515756,0.0215354,-0.0663407,-0.00226495,0.00895163,-0.0943446,-1.96252e-05,-5.77335e-05,-1.03578e-06,-2.14494e-05,1.00643e-05,-0.00117199,0.202688,0.0101969,0.433398,0,0,0,0,0,0.00422699,0.000392449,0.000382675,0.099336,0.211037,0.211035,0.0645803,0.142315,0.142319,0.131656,8.39438e-09,8.39766e-09,9.98952e-07,3.8496e-06,3.84989e-06,5.96932e-07,0,0,0,0,0,0,0,0 +6485000,0.981889,-0.00647844,-0.0123765,0.188944,-0.00671791,0.0165561,-0.0627291,-0.00191067,0.00711801,-0.0912945,-1.90675e-05,-5.78161e-05,-1.51257e-06,-2.19396e-05,9.22645e-06,-0.00118578,0.204236,0.00198353,0.433474,0,0,0,0,0,0.000285637,0.000323115,0.000322505,0.00672877,0.156179,0.156184,0.0622996,0.109324,0.109325,0.129852,7.0174e-09,7.02515e-09,9.98769e-07,3.84429e-06,3.84459e-06,5.60485e-07,0,0,0,0,0,0,0,0 +6585000,0.98187,-0.00642864,-0.0123315,0.189044,-0.00767397,0.0183505,-0.0640584,-0.00261048,0.00881912,-0.0931733,-1.90716e-05,-5.78143e-05,-1.61834e-06,-2.20839e-05,9.35715e-06,-0.00119216,0.204236,0.00198353,0.433474,0,0,0,0,0,0.000127947,0.000322923,0.000322688,0.00301064,0.159086,0.159091,0.0600878,0.133265,0.133267,0.128043,7.01644e-09,7.0242e-09,9.96611e-07,3.84429e-06,3.84459e-06,5.26387e-07,0,0,0,0,0,0,0,0 +6685000,0.981846,-0.00632032,-0.0123026,0.189175,-0.0113461,0.0213203,-0.0656394,-0.0036151,0.0108163,-0.0930877,-1.91145e-05,-5.77728e-05,-3.53323e-06,-2.229e-05,9.54564e-06,-0.00120136,0.204236,0.00198353,0.433474,0,0,0,0,0,8.34481e-05,0.000323495,0.000323365,0.00196688,0.165634,0.16564,0.0579677,0.160178,0.160181,0.126281,7.00924e-09,7.01701e-09,9.90286e-07,3.84427e-06,3.84457e-06,4.9464e-07,0,0,0,0,0,0,0,0 +6785000,0.981848,-0.00634563,-0.0122356,0.189169,-0.0105414,0.0234806,-0.0625458,-0.00475703,0.0130233,-0.0924851,-1.91216e-05,-5.77691e-05,-3.72674e-06,-2.25022e-05,9.73674e-06,-0.00121077,0.204236,0.00198353,0.433474,0,0,0,0,0,6.77697e-05,0.000324505,0.000324419,0.00160685,0.176127,0.176134,0.0572233,0.190717,0.190721,0.128569,7.00507e-09,7.01283e-09,9.81492e-07,3.84426e-06,3.84457e-06,4.72234e-07,0,0,0,0,0,0,0,0 +6885000,0.98186,-0.00614474,-0.0121461,0.189118,-0.0109364,0.0233655,-0.0593466,-0.00581921,0.0152862,-0.0913952,-1.91169e-05,-5.77734e-05,-3.56289e-06,-2.27152e-05,9.92212e-06,-0.0012202,0.204236,0.00198353,0.433474,0,0,0,0,0,5.51278e-05,0.000325843,0.000325786,0.00131984,0.190109,0.190117,0.0551965,0.224579,0.224584,0.126744,6.98911e-09,6.99688e-09,9.62796e-07,3.84425e-06,3.84456e-06,4.44074e-07,0,0,0,0,0,0,0,0 +6985000,0.981936,-0.00608975,-0.0121033,0.188726,-0.0121208,0.0249679,-0.0558087,-0.00701166,0.0177126,-0.0887607,-1.9049e-05,-5.78453e-05,-3.31786e-07,-2.29615e-05,1.01283e-05,-0.00123099,0.204236,0.00198353,0.433474,0,0,0,0,0,4.77857e-05,0.000327539,0.000327503,0.00115962,0.208177,0.208186,0.0532402,0.26309,0.263096,0.124927,6.97565e-09,6.98338e-09,9.34892e-07,3.84425e-06,3.84456e-06,4.17754e-07,0,0,0,0,0,0,0,0 +7085000,0.981925,-0.00597387,-0.0120025,0.188796,-0.0133209,0.0303683,-0.0558136,-0.00828785,0.020523,-0.0898077,-1.90401e-05,-5.78496e-05,-1.51796e-07,-2.30896e-05,1.02394e-05,-0.00123667,0.204236,0.00198353,0.433474,0,0,0,0,0,4.33862e-05,0.000329521,0.0003295,0.00106913,0.229582,0.229593,0.0513716,0.305567,0.305576,0.123163,6.94742e-09,6.95514e-09,8.97955e-07,3.84425e-06,3.84456e-06,3.93264e-07,0,0,0,0,0,0,0,0 +7185000,0.981891,-0.0058969,-0.0120669,0.188969,-0.0147468,0.0329429,-0.0544926,-0.0097525,0.0237379,-0.0916544,-1.91056e-05,-5.77856e-05,-3.05904e-06,-2.31889e-05,1.03346e-05,-0.00124127,0.204236,0.00198353,0.433474,0,0,0,0,0,4.06371e-05,0.000331882,0.000331869,0.00101877,0.255229,0.255242,0.0495705,0.354349,0.35436,0.12141,6.92518e-09,6.93283e-09,8.52004e-07,3.84425e-06,3.84456e-06,3.70376e-07,0,0,0,0,0,0,0,0 +7285000,0.981923,-0.00586313,-0.0120703,0.188803,-0.0147817,0.0366399,-0.0506414,-0.0112494,0.0271176,-0.0872669,-1.90432e-05,-5.78414e-05,-5.50711e-07,-2.34499e-05,1.05572e-05,-0.00125281,0.204236,0.00198353,0.433474,0,0,0,0,0,3.89225e-05,0.000334428,0.000334424,0.00099239,0.283901,0.283916,0.0478519,0.407908,0.407921,0.119711,6.8851e-09,6.89272e-09,7.99123e-07,3.84423e-06,3.84455e-06,3.49075e-07,0,0,0,0,0,0,0,0 +7385000,0.981965,-0.00578043,-0.0120513,0.18859,-0.0172311,0.0401091,-0.0475611,-0.0128193,0.0310596,-0.0840221,-1.8997e-05,-5.78909e-05,1.67844e-06,-2.36658e-05,1.07277e-05,-0.00126241,0.204236,0.00198353,0.433474,0,0,0,0,0,3.77521e-05,0.00033743,0.000337433,0.000978577,0.317176,0.317194,0.0461972,0.470158,0.470175,0.118026,6.85684e-09,6.86436e-09,7.4077e-07,3.84423e-06,3.84455e-06,3.29163e-07,0,0,0,0,0,0,0,0 +7485000,0.982053,-0.0057293,-0.0120778,0.188132,-0.0155967,0.0437521,-0.0433128,-0.0143474,0.0351298,-0.0805164,-1.88071e-05,-5.80681e-05,9.68367e-06,-2.38811e-05,1.09096e-05,-0.00127166,0.204236,0.00198353,0.433474,0,0,0,0,0,3.86292e-05,0.000340442,0.000340447,0.00101655,0.352909,0.352929,0.04558,0.537955,0.537975,0.119882,6.81535e-09,6.82285e-09,6.94892e-07,3.84413e-06,3.84446e-06,3.15093e-07,0,0,0,0,0,0,0,0 +7585000,0.982099,-0.00580421,-0.0120379,0.187888,-0.0154714,0.0467018,-0.0392542,-0.0158969,0.0396315,-0.0744986,-1.875e-05,-5.81289e-05,1.24342e-05,-2.41345e-05,1.10991e-05,-0.001283,0.204236,0.00198353,0.433474,0,0,0,0,0,3.7853e-05,0.000344067,0.000344083,0.00100954,0.393827,0.39385,0.0440148,0.617736,0.617762,0.118167,6.78537e-09,6.79277e-09,6.33022e-07,3.84413e-06,3.84446e-06,2.97431e-07,0,0,0,0,0,0,0,0 +7685000,0.982093,-0.00581189,-0.0120973,0.187917,-0.0164535,0.0509804,-0.0376728,-0.0173915,0.0442863,-0.06811,-1.87782e-05,-5.80813e-05,1.0243e-05,-2.43782e-05,1.13723e-05,-0.00129415,0.204236,0.00198353,0.433474,0,0,0,0,0,3.71355e-05,0.000347379,0.0003474,0.00100172,0.436468,0.436494,0.0425233,0.703444,0.703474,0.116507,6.73119e-09,6.73855e-09,5.72497e-07,3.84383e-06,3.84416e-06,2.8098e-07,0,0,0,0,0,0,0,0 +7785000,0.982062,-0.00568406,-0.0120998,0.188085,-0.015569,0.0534196,-0.0393496,-0.0190276,0.049429,-0.0721496,-1.88609e-05,-5.79984e-05,6.48886e-06,-2.43676e-05,1.13774e-05,-0.00129385,0.204236,0.00198353,0.433474,0,0,0,0,0,3.64084e-05,0.000351611,0.000351634,0.000990818,0.48508,0.485108,0.0410895,0.805639,0.805675,0.114868,6.70306e-09,6.71033e-09,5.14448e-07,3.84383e-06,3.84417e-06,2.65589e-07,0,0,0,0,0,0,0,0 +7885000,0.982032,-0.00569312,-0.0121715,0.188235,-0.0176103,0.0581241,-0.0389938,-0.0206023,0.0544995,-0.0748663,-1.88719e-05,-5.79565e-05,4.52584e-06,-2.43912e-05,1.15543e-05,-0.00129507,0.204236,0.00198353,0.433474,0,0,0,0,0,3.56549e-05,0.000355027,0.000355055,0.000976397,0.533811,0.533842,0.0397122,0.913175,0.913218,0.113249,6.64553e-09,6.65274e-09,4.60071e-07,3.84315e-06,3.84349e-06,2.51188e-07,0,0,0,0,0,0,0,0 +7985000,0.982038,-0.0056192,-0.0120809,0.188213,-0.0180873,0.060924,-0.0350841,-0.0224226,0.0604372,-0.0712407,-1.88586e-05,-5.79719e-05,5.23488e-06,-2.45557e-05,1.16584e-05,-0.00130265,0.204236,0.00198353,0.433474,0,0,0,0,0,3.48451e-05,0.00035984,0.000359873,0.000959401,0.590006,0.59004,0.0383999,1.04337,1.04342,0.111683,6.62147e-09,6.62859e-09,4.10385e-07,3.84315e-06,3.84349e-06,2.3776e-07,0,0,0,0,0,0,0,0 +8085000,0.981937,-0.0054824,-0.0120802,0.188745,-0.0178545,0.0657528,-0.0353724,-0.0242297,0.0667215,-0.073659,-1.90631e-05,-5.77674e-05,-4.02119e-06,-2.457e-05,1.16966e-05,-0.00130378,0.204236,0.00198353,0.433474,0,0,0,0,0,3.549e-05,0.000364984,0.000365017,0.000982686,0.650272,0.650311,0.0379066,1.19067,1.19073,0.113289,6.60496e-09,6.61201e-09,3.76225e-07,3.84316e-06,3.8435e-06,2.2827e-07,0,0,0,0,0,0,0,0 +8185000,0.981876,-0.00552366,-0.0120089,0.189064,-0.0180154,0.0718099,-0.0318228,-0.0257505,0.0728353,-0.0691237,-1.91184e-05,-5.76725e-05,-8.41538e-06,-2.47269e-05,1.20626e-05,-0.0013116,0.204236,0.00198353,0.433474,0,0,0,0,0,3.45472e-05,0.000368475,0.000368517,0.000959126,0.707917,0.70796,0.03667,1.34083,1.3409,0.111709,6.5466e-09,6.55357e-09,3.34744e-07,3.84183e-06,3.84218e-06,2.16319e-07,0,0,0,0,0,0,0,0 +8285000,0.981852,-0.00548678,-0.011993,0.189189,-0.0165085,0.0763787,-0.0292469,-0.0275044,0.0802422,-0.0677769,-1.91688e-05,-5.7623e-05,-1.06451e-05,-2.48121e-05,1.21166e-05,-0.0013157,0.204236,0.00198353,0.433474,0,0,0,0,0,3.35594e-05,0.000374163,0.000374209,0.000933811,0.775773,0.775821,0.0354823,1.52603,1.52611,0.110153,6.52871e-09,6.5356e-09,2.97748e-07,3.84184e-06,3.84219e-06,2.05121e-07,0,0,0,0,0,0,0,0 +8385000,0.981837,-0.0054441,-0.0119884,0.189268,-0.019483,0.078655,-0.0275327,-0.0288612,0.0867519,-0.064235,-1.91148e-05,-5.7625e-05,-1.07435e-05,-2.49197e-05,1.25887e-05,-0.00132161,0.204236,0.00198353,0.433474,0,0,0,0,0,3.2603e-05,0.000377142,0.000377192,0.00090789,0.83727,0.837319,0.0343509,1.70753,1.70761,0.10865,6.46685e-09,6.47368e-09,2.65119e-07,3.83955e-06,3.83991e-06,1.94661e-07,0,0,0,0,0,0,0,0 +8485000,0.981901,-0.00533444,-0.011979,0.188941,-0.0206796,0.083675,-0.0280411,-0.0308198,0.0948335,-0.0682725,-1.89951e-05,-5.77447e-05,-5.3328e-06,-2.49008e-05,1.25648e-05,-0.00132043,0.204236,0.00198353,0.433474,0,0,0,0,0,3.1635e-05,0.000383349,0.000383401,0.00088134,0.912662,0.912714,0.0332647,1.93752,1.93762,0.107169,6.45294e-09,6.45969e-09,2.36302e-07,3.83956e-06,3.83992e-06,1.84853e-07,0,0,0,0,0,0,0,0 +8585000,0.981882,-0.00528972,-0.0120858,0.189034,-0.0202341,0.0864127,-0.0228553,-0.0322845,0.101502,-0.0630938,-1.896e-05,-5.77138e-05,-7.01809e-06,-2.50054e-05,1.32329e-05,-0.00132728,0.204236,0.00198353,0.433474,0,0,0,0,0,3.06506e-05,0.000385434,0.000385485,0.000855092,0.975762,0.975815,0.0322295,2.15159,2.1517,0.105739,6.3863e-09,6.39297e-09,2.11033e-07,3.83593e-06,3.83629e-06,1.7568e-07,0,0,0,0,0,0,0,0 +8685000,0.981911,-0.00531062,-0.0121691,0.188876,-0.0211061,0.0897471,-0.0240663,-0.0343853,0.110305,-0.064805,-1.89285e-05,-5.77455e-05,-5.58375e-06,-2.50173e-05,1.32348e-05,-0.00132777,0.204236,0.00198353,0.433474,0,0,0,0,0,2.96832e-05,0.000392118,0.000392174,0.000828952,1.0585,1.05855,0.0312353,2.43324,2.43335,0.10433,6.37558e-09,6.3822e-09,1.88793e-07,3.83594e-06,3.8363e-06,1.6707e-07,0,0,0,0,0,0,0,0 +8785000,0.981864,-0.00527613,-0.0121366,0.189124,-0.0204678,0.0918803,-0.0230421,-0.0356776,0.116603,-0.0614419,-1.89029e-05,-5.76888e-05,-8.56724e-06,-2.5051e-05,1.41299e-05,-0.00133264,0.204236,0.00198353,0.433474,0,0,0,0,0,2.98368e-05,0.00039289,0.000392949,0.00083438,1.12094,1.12099,0.030861,2.67847,2.67859,0.10569,6.30529e-09,6.31184e-09,1.73895e-07,3.83054e-06,3.8309e-06,1.60959e-07,0,0,0,0,0,0,0,0 +8885000,0.981924,-0.00531526,-0.0121254,0.188811,-0.0209866,0.0966772,-0.019703,-0.0377379,0.126203,-0.0558249,-1.88233e-05,-5.77701e-05,-4.8519e-06,-2.5188e-05,1.41465e-05,-0.00133918,0.204236,0.00198353,0.433474,0,0,0,0,0,2.88772e-05,0.000400001,0.000400067,0.000807594,1.21039,1.21045,0.029925,3.01829,3.01842,0.104278,6.29677e-09,6.30327e-09,1.56162e-07,3.83055e-06,3.83091e-06,1.53257e-07,0,0,0,0,0,0,0,0 +8985000,0.982004,-0.00525927,-0.0120522,0.188404,-0.0220806,0.0994866,-0.0177309,-0.0387428,0.13191,-0.0574814,-1.85995e-05,-5.7894e-05,1.54465e-07,-2.50946e-05,1.53036e-05,-0.00133929,0.204236,0.00198353,0.433474,0,0,0,0,0,2.79604e-05,0.000399022,0.000399091,0.000781928,1.26831,1.26837,0.0290329,3.28958,3.28971,0.102915,6.21745e-09,6.22386e-09,1.40606e-07,3.82296e-06,3.82333e-06,1.46036e-07,0,0,0,0,0,0,0,0 +9085000,0.982093,-0.00526313,-0.0121145,0.187934,-0.0225522,0.105242,-0.0190724,-0.0409818,0.142154,-0.057186,-1.85007e-05,-5.79935e-05,4.66402e-06,-2.51333e-05,1.52952e-05,-0.00134099,0.204236,0.00198353,0.433474,0,0,0,0,0,2.70479e-05,0.000406509,0.000406582,0.000757141,1.36411,1.36417,0.0281759,3.69314,3.69328,0.101574,6.21087e-09,6.21725e-09,1.26885e-07,3.82297e-06,3.82334e-06,1.39249e-07,0,0,0,0,0,0,0,0 +9185000,0.982151,-0.0052836,-0.0121574,0.187628,-0.0195151,0.105329,-0.0171859,-0.0415151,0.147206,-0.0570211,-1.82965e-05,-5.80806e-05,7.84428e-06,-2.50193e-05,1.68065e-05,-0.00134255,0.204236,0.00198353,0.433474,0,0,0,0,0,2.61845e-05,0.000403398,0.000403473,0.000733257,1.41391,1.41397,0.0273519,3.98094,3.98108,0.100256,6.12493e-09,6.13122e-09,1.14765e-07,3.81281e-06,3.81318e-06,1.32856e-07,0,0,0,0,0,0,0,0 +9285000,0.982168,-0.0051221,-0.0119784,0.187556,-0.0181976,0.109998,-0.0154924,-0.0433632,0.158085,-0.0543297,-1.82883e-05,-5.80895e-05,8.27472e-06,-2.50851e-05,1.67982e-05,-0.00134589,0.204236,0.00198353,0.433474,0,0,0,0,0,2.53557e-05,0.0004112,0.000411281,0.000710585,1.51488,1.51493,0.0265665,4.45248,4.45263,0.0989822,6.11983e-09,6.12609e-09,1.04078e-07,3.81282e-06,3.81319e-06,1.26864e-07,0,0,0,0,0,0,0,0 +9385000,0.9821,-0.00506046,-0.0120227,0.187911,-0.0177845,0.109844,-0.0139561,-0.0430996,0.161622,-0.054116,-1.82228e-05,-5.80213e-05,4.21292e-06,-2.48891e-05,1.87055e-05,-0.0013471,0.204236,0.00198353,0.433474,0,0,0,0,0,2.53504e-05,0.000405656,0.000405735,0.000711588,1.5522,1.55225,0.026278,4.74235,4.74249,0.100199,6.02892e-09,6.03506e-09,9.68743e-08,3.79982e-06,3.8002e-06,1.226e-07,0,0,0,0,0,0,0,0 +9485000,0.982118,-0.00507867,-0.0120927,0.187808,-0.0190364,0.112775,-0.0116974,-0.0450022,0.172932,-0.0501836,-1.82185e-05,-5.80262e-05,4.47882e-06,-2.4963e-05,1.86837e-05,-0.00135097,0.204236,0.00198353,0.433474,0,0,0,0,0,2.4553e-05,0.00041372,0.000413804,0.000689595,1.65745,1.6575,0.0255376,5.28415,5.28429,0.098927,6.0248e-09,6.03092e-09,8.82128e-08,3.79983e-06,3.80021e-06,1.1721e-07,0,0,0,0,0,0,0,0 +9585000,0.982012,-0.00516136,-0.0120766,0.188363,-0.0190346,0.110026,-0.0122881,-0.0444524,0.17424,-0.0531192,-1.81522e-05,-5.7944e-05,-4.57772e-07,-2.46447e-05,2.0998e-05,-0.00134961,0.204236,0.00198353,0.433474,0,0,0,0,0,2.38167e-05,0.000405565,0.000405653,0.000668556,1.67807,1.67811,0.0248254,5.55715,5.55727,0.0976767,5.92771e-09,5.93371e-09,8.05019e-08,3.78388e-06,3.78425e-06,1.12118e-07,0,0,0,0,0,0,0,0 +9685000,0.981984,-0.00514183,-0.0120303,0.188512,-0.0200522,0.114025,-0.00910858,-0.0463406,0.185714,-0.0506954,-1.81958e-05,-5.79006e-05,-2.38868e-06,-2.4689e-05,2.0981e-05,-0.00135213,0.204236,0.00198353,0.433474,0,0,0,0,0,2.31075e-05,0.000413831,0.000413926,0.000648675,1.78624,1.78627,0.0241462,6.16923,6.16934,0.0964686,5.92447e-09,5.93046e-09,7.3643e-08,3.78389e-06,3.78426e-06,1.07341e-07,0,0,0,0,0,0,0,0 +9785000,0.981887,-0.00518167,-0.0119883,0.189016,-0.0180425,0.1127,-0.00967546,-0.0452136,0.18493,-0.0510662,-1.81142e-05,-5.78224e-05,-7.32283e-06,-2.43277e-05,2.36484e-05,-0.00135251,0.204236,0.00198353,0.433474,0,0,0,0,0,2.2433e-05,0.000403084,0.000403182,0.000629687,1.78641,1.78643,0.0234927,6.40305,6.40313,0.0952811,5.82411e-09,5.82998e-09,6.7508e-08,3.76505e-06,3.76542e-06,1.0282e-07,0,0,0,0,0,0,0,0 +9885000,0.981911,-0.0051365,-0.0119281,0.188899,-0.016704,0.115547,-0.00802724,-0.0469959,0.19626,-0.0511951,-1.80817e-05,-5.78549e-05,-5.84327e-06,-2.43389e-05,2.36401e-05,-0.00135304,0.204236,0.00198353,0.433474,0,0,0,0,0,2.18246e-05,0.000411504,0.000411608,0.000611693,1.89635,1.89637,0.0228687,7.08289,7.08295,0.0941332,5.82154e-09,5.8274e-09,6.20241e-08,3.76506e-06,3.76543e-06,9.85762e-08,0,0,0,0,0,0,0,0 +9985000,0.981815,-0.00520213,-0.012008,0.189389,-0.0142201,0.111076,-0.00698529,-0.0450886,0.192822,-0.0522498,-1.79636e-05,-5.78056e-05,-9.65403e-06,-2.38906e-05,2.663e-05,-0.00135282,0.204236,0.00198353,0.433474,0,0,0,0,0,2.12383e-05,0.000398378,0.000398481,0.000594507,1.873,1.87301,0.0222678,7.25389,7.25392,0.0930046,5.71993e-09,5.72567e-09,5.70961e-08,3.74364e-06,3.74401e-06,9.45521e-08,0,0,0,0,0,0,0,0 +10085000,0.981761,-0.00512882,-0.0121663,0.189662,-0.0159439,0.111897,-0.00584383,-0.0465781,0.204075,-0.0506796,-1.80143e-05,-5.77549e-05,-1.19291e-05,-2.3912e-05,2.66142e-05,-0.00135427,0.204236,0.00198353,0.433474,0,0,0,0,0,2.12281e-05,0.000406914,0.000407018,0.00059402,1.98338,1.98337,0.0220544,7.9964,7.9964,0.0940749,5.71839e-09,5.72413e-09,5.37259e-08,3.74365e-06,3.74402e-06,9.1693e-08,0,0,0,0,0,0,0,0 +10185000,0.981645,-0.00507622,-0.0120876,0.190266,-0.0187963,0.11571,-0.00419983,-0.0482927,0.215525,-0.0507364,-1.8109e-05,-5.76601e-05,-1.62157e-05,-2.39107e-05,2.66197e-05,-0.00135456,0.204236,0.00198353,0.433474,0,0,0,0,0,2.06863e-05,0.000415729,0.00041584,0.000577601,2.09764,2.09762,0.0214879,8.80021,8.80017,0.0929513,5.7165e-09,5.72223e-09,4.96235e-08,3.74366e-06,3.74403e-06,8.80642e-08,0,0,0,0,0,0,0,0 +10285000,0.981699,-0.00520671,-0.0120089,0.189988,-0.0173973,0.110738,-0.00529337,-0.0461438,0.208806,-0.0506702,-1.78458e-05,-5.77527e-05,-1.37208e-05,-2.34102e-05,2.98319e-05,-0.00135486,0.204236,0.00198353,0.433474,0,0,0,0,0,2.01603e-05,0.000400414,0.000400528,0.000562048,2.04473,2.0447,0.0209459,8.88011,8.88003,0.0918641,5.61597e-09,5.62159e-09,4.59246e-08,3.72015e-06,3.72051e-06,8.46257e-08,0,0,0,0,0,0,0,0 +10385000,0.981738,-0.00519836,-0.0119041,0.189793,0.00653465,0.00501298,-0.00293876,0.000745655,0.000164722,-0.0490327,-1.78069e-05,-5.77916e-05,-1.19402e-05,-2.34308e-05,2.9807e-05,-0.00135599,0.204236,0.00198353,0.433474,0,0,0,0,0,1.96615e-05,0.000409305,0.000409427,0.000547196,0.0358862,0.0358861,0.0374558,0.125282,0.125282,0.0850707,5.61444e-09,5.62006e-09,4.25735e-08,3.72016e-06,3.72052e-06,8.15499e-08,0,0,0,0,0,0,0,0 +10485000,0.981682,-0.00508565,-0.0118535,0.19009,0.00611072,0.00776216,-0.00186049,0.00137025,0.000800856,-0.0445979,-1.78556e-05,-5.7743e-05,-1.41005e-05,-2.34744e-05,2.97587e-05,-0.00135891,0.204236,0.00198353,0.433474,0,0,0,0,0,1.91802e-05,0.000418477,0.000418603,0.000533012,0.0405088,0.0405083,0.0375587,0.126294,0.126294,0.0794337,5.61306e-09,5.61868e-09,3.95316e-08,3.72017e-06,3.72053e-06,7.89521e-08,0,0,0,0,0,0,0,0 +10585000,0.981728,-0.00504354,-0.0117113,0.189862,0.0037397,0.00937921,-0.000542056,0.000911144,-0.0025292,-0.043769,-1.77811e-05,-5.79899e-05,-1.16115e-05,-2.08437e-05,2.99791e-05,-0.00135938,0.204236,0.00198353,0.433474,0,0,0,0,0,1.8741e-05,0.00042057,0.000420697,0.000519522,0.0416552,0.0416542,0.0352684,0.0849745,0.0849745,0.0751036,5.58287e-09,5.5884e-09,3.67715e-08,3.71471e-06,3.71507e-06,7.67241e-08,0,0,0,0,0,0,0,0 +10685000,0.981727,-0.00498132,-0.0117428,0.189867,0.00333121,0.0104081,-0.000417031,0.00125761,-0.00154425,-0.0429539,-1.77849e-05,-5.79861e-05,-1.17755e-05,-2.08513e-05,2.99701e-05,-0.0013599,0.204236,0.00198353,0.433474,0,0,0,0,0,1.87175e-05,0.000430159,0.000430289,0.00051881,0.0519577,0.0519553,0.0353113,0.087071,0.0870709,0.0733618,5.58204e-09,5.58757e-09,3.48653e-08,3.71472e-06,3.71508e-06,7.52606e-08,0,0,0,0,0,0,0,0 +10785000,0.981726,-0.0051323,-0.0117879,0.189866,0.0033092,0.00952152,0.000469193,0.00105805,-0.00124853,-0.0401543,-1.74574e-05,-5.81875e-05,-1.17578e-05,-1.81919e-05,3.41574e-05,-0.00136153,0.204236,0.00198353,0.433474,0,0,0,0,0,1.82725e-05,0.000414348,0.000414467,0.000505957,0.0538676,0.0538648,0.0331825,0.0663379,0.0663379,0.0707325,5.47877e-09,5.48403e-09,3.25186e-08,3.69743e-06,3.69778e-06,7.35161e-08,0,0,0,0,0,0,0,0 +10885000,0.981792,-0.00509675,-0.0118278,0.189523,0.00282172,0.0125441,0.000686631,0.00136398,-0.000203162,-0.0396064,-1.73906e-05,-5.82543e-05,-8.71419e-06,-1.82066e-05,3.41458e-05,-0.0013618,0.204236,0.00198353,0.433474,0,0,0,0,0,1.78696e-05,0.000423977,0.000424099,0.000493645,0.0685106,0.0685064,0.0330565,0.0697511,0.0697509,0.0692017,5.47784e-09,5.4831e-09,3.03731e-08,3.69744e-06,3.69779e-06,7.20042e-08,0,0,0,0,0,0,0,0 +10985000,0.981802,-0.0052299,-0.0118895,0.189462,0.000498838,0.0174565,0.00270698,0.00105665,0.00027154,-0.0368788,-1.71163e-05,-5.84223e-05,-8.49547e-06,-1.6169e-05,3.73771e-05,-0.00136286,0.204236,0.00198353,0.433474,0,0,0,0,0,1.74487e-05,0.000388369,0.000388471,0.000481941,0.0666055,0.0666029,0.031042,0.0568488,0.0568486,0.0676403,5.29336e-09,5.29821e-09,2.84122e-08,3.66998e-06,3.67032e-06,7.06573e-08,0,0,0,0,0,0,0,0 +11085000,0.981724,-0.00534017,-0.0118722,0.189867,0.000283639,0.022513,0.00459693,0.00107086,0.00221242,-0.034299,-1.71623e-05,-5.83767e-05,-1.05827e-05,-1.61754e-05,3.73624e-05,-0.00136399,0.204236,0.00198353,0.433474,0,0,0,0,0,1.70769e-05,0.000397625,0.000397735,0.000470709,0.0835401,0.0835369,0.0307747,0.0617397,0.0617394,0.0671434,5.2926e-09,5.29746e-09,2.66132e-08,3.66999e-06,3.67033e-06,6.94914e-08,0,0,0,0,0,0,0,0 +11185000,0.981713,-0.00564516,-0.0118829,0.189913,0.00132811,0.0210086,0.00782428,0.0020014,0.00158956,-0.0297353,-1.6524e-05,-5.83604e-05,-1.11478e-05,-1.6097e-05,4.47329e-05,-0.00136542,0.204236,0.00198353,0.433474,0,0,0,0,0,1.6687e-05,0.000350262,0.000350354,0.000460014,0.0753308,0.0753285,0.0288707,0.0520582,0.0520579,0.0661807,5.05824e-09,5.06271e-09,2.49631e-08,3.63967e-06,3.63999e-06,6.84428e-08,0,0,0,0,0,0,0,0 +11285000,0.981703,-0.00563915,-0.0119139,0.189964,-0.000342065,0.0227662,0.00889751,0.0020083,0.00383224,-0.0299693,-1.65225e-05,-5.8362e-05,-1.10816e-05,-1.60919e-05,4.47407e-05,-0.00136494,0.204236,0.00198353,0.433474,0,0,0,0,0,1.63451e-05,0.000358888,0.000358985,0.000449736,0.0925545,0.0925507,0.028481,0.0583033,0.0583029,0.0663152,5.05762e-09,5.06211e-09,2.34441e-08,3.63968e-06,3.64e-06,6.75381e-08,0,0,0,0,0,0,0,0 +11385000,0.981708,-0.00582383,-0.0118615,0.189936,-0.00148901,0.0190483,0.0079895,0.0015476,0.00240567,-0.0318598,-1.5945e-05,-5.86058e-05,-1.07197e-05,-1.35103e-05,5.06535e-05,-0.00136373,0.204236,0.00198353,0.433474,0,0,0,0,0,1.63135e-05,0.000310529,0.000310603,0.000448999,0.0788067,0.0788041,0.0268409,0.0497497,0.0497495,0.0667606,4.8159e-09,4.81998e-09,2.23833e-08,3.61333e-06,3.61364e-06,6.69143e-08,0,0,0,0,0,0,0,0 +11485000,0.981758,-0.00572914,-0.0118339,0.18968,-0.00373912,0.0200278,0.0096714,0.00123479,0.00438229,-0.0286997,-1.59159e-05,-5.86339e-05,-9.38692e-06,-1.35289e-05,5.06364e-05,-0.00136466,0.204236,0.00198353,0.433474,0,0,0,0,0,1.59679e-05,0.000318479,0.000318556,0.000439191,0.0949818,0.0949778,0.0263736,0.057018,0.0570175,0.0672682,4.81538e-09,4.81949e-09,2.10656e-08,3.61334e-06,3.61365e-06,6.61892e-08,0,0,0,0,0,0,0,0 +11585000,0.981772,-0.00605112,-0.0118087,0.189598,-0.00132038,0.0157354,0.0101724,0.00125393,0.00259425,-0.0274096,-1.53748e-05,-5.87701e-05,-8.76742e-06,-1.23027e-05,5.55047e-05,-0.00136537,0.204236,0.00198353,0.433474,0,0,0,0,0,1.5634e-05,0.00027594,0.000276001,0.000429796,0.0780781,0.0780757,0.0247174,0.0486972,0.048697,0.0667359,4.59275e-09,4.5965e-09,1.98497e-08,3.594e-06,3.59429e-06,6.55361e-08,0,0,0,0,0,0,0,0 +11685000,0.981806,-0.00600621,-0.0117525,0.189428,-0.00167709,0.0192982,0.0119246,0.00111165,0.00434096,-0.0272065,-1.53503e-05,-5.8794e-05,-7.63324e-06,-1.23077e-05,5.55058e-05,-0.00136502,0.204236,0.00198353,0.433474,0,0,0,0,0,1.53257e-05,0.000283304,0.000283368,0.000420768,0.0925708,0.0925682,0.0241858,0.0566145,0.056614,0.0674167,4.59231e-09,4.5961e-09,1.87241e-08,3.59401e-06,3.5943e-06,6.49732e-08,0,0,0,0,0,0,0,0 +11785000,0.981876,-0.00635709,-0.0117057,0.189056,-0.00240596,0.0143298,0.0127426,0.000938125,0.000868891,-0.0244923,-1.46125e-05,-5.90741e-05,-5.1935e-06,-1.0399e-05,6.0874e-05,-0.00136556,0.204236,0.00198353,0.433474,0,0,0,0,0,1.5022e-05,0.000248839,0.000248892,0.000412069,0.0748586,0.0748573,0.022662,0.0482457,0.0482455,0.0669067,4.39781e-09,4.40131e-09,1.76806e-08,3.58141e-06,3.5817e-06,6.44676e-08,0,0,0,0,0,0,0,0 +11885000,0.981879,-0.00643182,-0.0116036,0.189045,-0.000362865,0.0153721,0.0117852,0.000728617,0.00230854,-0.023192,-1.46127e-05,-5.9074e-05,-5.20202e-06,-1.03993e-05,6.0874e-05,-0.00136556,0.204236,0.00198353,0.433474,0,0,0,0,0,1.4728e-05,0.000255754,0.000255812,0.000403754,0.0876376,0.0876359,0.0220969,0.0565037,0.0565033,0.0676283,4.39746e-09,4.401e-09,1.67138e-08,3.58142e-06,3.58171e-06,6.40311e-08,0,0,0,0,0,0,0,0 +11985000,0.981913,-0.00661508,-0.0117112,0.188853,0.00245183,0.0146658,0.0109204,0.00221881,0.000554225,-0.0257476,-1.43116e-05,-5.89708e-05,-4.35069e-06,-1.09451e-05,6.30184e-05,-0.00136469,0.204236,0.00198353,0.433474,0,0,0,0,0,1.46904e-05,0.000228827,0.000228876,0.000403114,0.0705114,0.0705105,0.0208927,0.0480619,0.0480617,0.0682423,4.2288e-09,4.23212e-09,1.60342e-08,3.57411e-06,3.57439e-06,6.37338e-08,0,0,0,0,0,0,0,0 +12085000,0.981911,-0.0065265,-0.0117642,0.188863,0.00358203,0.0150384,0.0135223,0.00252489,0.00200475,-0.0190243,-1.43066e-05,-5.89748e-05,-4.13246e-06,-1.09496e-05,6.29995e-05,-0.00136623,0.204236,0.00198353,0.433474,0,0,0,0,0,1.44195e-05,0.000235421,0.000235471,0.00039513,0.0816741,0.0816728,0.0203269,0.05644,0.0564396,0.0689442,4.22851e-09,4.23186e-09,1.51835e-08,3.57412e-06,3.5744e-06,6.33844e-08,0,0,0,0,0,0,0,0 +12185000,0.981909,-0.00646618,-0.0117382,0.188878,0.00340635,0.0134402,0.0128712,0.00188157,0.00235067,-0.0174029,-1.42575e-05,-5.90865e-05,-4.64377e-06,-1.02938e-05,6.32917e-05,-0.00136636,0.204236,0.00198353,0.433474,0,0,0,0,0,1.4132e-05,0.000214651,0.000214693,0.000387447,0.0658705,0.0658694,0.0190777,0.0479839,0.0479837,0.0683253,4.07986e-09,4.08301e-09,1.43911e-08,3.57033e-06,3.57061e-06,6.30702e-08,0,0,0,0,0,0,0,0 +12285000,0.981908,-0.00651192,-0.0117261,0.188885,0.000631363,0.0126157,0.0112952,0.00209478,0.00364591,-0.0168048,-1.4257e-05,-5.9087e-05,-4.62092e-06,-1.02938e-05,6.32934e-05,-0.0013662,0.204236,0.00198353,0.433474,0,0,0,0,0,1.38757e-05,0.000221025,0.00022107,0.00038006,0.0756936,0.0756917,0.0185247,0.0563371,0.0563368,0.068931,4.07961e-09,4.0828e-09,1.36533e-08,3.57034e-06,3.57062e-06,6.27983e-08,0,0,0,0,0,0,0,0 +12385000,0.981932,-0.00662791,-0.0116665,0.188758,-2.89892e-05,0.00921001,0.0117978,0.00174868,0.00215687,-0.0196993,-1.40094e-05,-5.92008e-05,-4.37662e-06,-9.89117e-06,6.40053e-05,-0.00136535,0.204236,0.00198353,0.433474,0,0,0,0,0,1.36097e-05,0.000204907,0.000204946,0.000372938,0.0613782,0.0613767,0.0174135,0.0479294,0.0479293,0.0682427,3.94464e-09,3.94765e-09,1.29644e-08,3.56866e-06,3.56893e-06,6.25514e-08,0,0,0,0,0,0,0,0 +12485000,0.981923,-0.00662331,-0.0116743,0.188806,2.02907e-06,0.0103774,0.0156785,0.00175485,0.00311882,-0.0176679,-1.40063e-05,-5.92036e-05,-4.23346e-06,-9.8907e-06,6.40027e-05,-0.00136549,0.204236,0.00198353,0.433474,0,0,0,0,0,1.33813e-05,0.000211135,0.000211176,0.000366072,0.0700421,0.0700404,0.0168903,0.0561668,0.0561665,0.068727,3.94444e-09,3.94748e-09,1.23216e-08,3.56867e-06,3.56894e-06,6.23382e-08,0,0,0,0,0,0,0,0 +12585000,0.981909,-0.00677224,-0.0116526,0.188875,0.00367778,0.00412898,0.0173517,0.00324217,0.000166769,-0.0163824,-1.3556e-05,-5.91604e-05,-4.29705e-06,-9.76567e-06,6.43474e-05,-0.0013654,0.204236,0.00198353,0.433474,0,0,0,0,0,1.31525e-05,0.000198476,0.000198513,0.000359435,0.0572555,0.0572541,0.0159109,0.0478619,0.0478618,0.067973,3.81811e-09,3.82097e-09,1.172e-08,3.56789e-06,3.56816e-06,6.21403e-08,0,0,0,0,0,0,0,0 +12685000,0.981921,-0.0067408,-0.0116672,0.18881,0.00358965,0.00258687,0.0175037,0.00354935,0.000501806,-0.0134595,-1.35526e-05,-5.91634e-05,-4.14233e-06,-9.76299e-06,6.43428e-05,-0.00136563,0.204236,0.00198353,0.433474,0,0,0,0,0,1.3128e-05,0.000204607,0.000204645,0.000358887,0.0650644,0.0650622,0.0155917,0.055934,0.0559337,0.0695161,3.81801e-09,3.8209e-09,1.1294e-08,3.5679e-06,3.56817e-06,6.20142e-08,0,0,0,0,0,0,0,0 +12785000,0.982021,-0.00696544,-0.0115723,0.18829,0.0052559,-0.000399923,0.0187098,0.00395211,-0.00290418,-0.0118849,-1.30121e-05,-5.91415e-05,-1.90198e-06,-8.99202e-06,6.34116e-05,-0.00136563,0.204236,0.00198353,0.433474,0,0,0,0,0,1.28928e-05,0.000194391,0.000194427,0.000352515,0.0536512,0.0536499,0.0147262,0.0477647,0.0477645,0.0686788,3.69556e-09,3.69828e-09,1.07574e-08,3.56713e-06,3.5674e-06,6.18457e-08,0,0,0,0,0,0,0,0 +12885000,0.98209,-0.0069454,-0.0115053,0.187935,0.00479607,-0.0015775,0.0195668,0.00448966,-0.00300359,-0.00853858,-1.29839e-05,-5.91676e-05,-5.91049e-07,-8.99424e-06,6.34023e-05,-0.00136589,0.204236,0.00198353,0.433474,0,0,0,0,0,1.26665e-05,0.000200452,0.000200491,0.000346385,0.060757,0.0607551,0.0142914,0.0556475,0.0556473,0.0689182,3.69543e-09,3.69818e-09,1.02547e-08,3.56714e-06,3.56741e-06,6.17059e-08,0,0,0,0,0,0,0,0 +12985000,0.982154,-0.00695126,-0.0114941,0.187597,0.0036154,0.000174283,0.0199646,0.00340614,-0.00236699,-0.00700837,-1.30344e-05,-5.92778e-05,5.17915e-07,-9.12939e-06,6.34114e-05,-0.00136583,0.204236,0.00198353,0.433474,0,0,0,0,0,1.24412e-05,0.000191947,0.000191981,0.000340449,0.0505515,0.0505502,0.0135401,0.0476347,0.0476346,0.0680381,3.57345e-09,3.57605e-09,9.78247e-09,3.56562e-06,3.5659e-06,6.15605e-08,0,0,0,0,0,0,0,0 +13085000,0.982197,-0.00695674,-0.0114167,0.187376,0.00442327,0.000532613,0.0184096,0.00380283,-0.0022877,-0.00700004,-1.30052e-05,-5.93052e-05,1.88002e-06,-9.14786e-06,6.34163e-05,-0.0013655,0.204236,0.00198353,0.433474,0,0,0,0,0,1.22473e-05,0.000197953,0.000197991,0.000334683,0.0571253,0.0571238,0.0131554,0.0553211,0.0553208,0.0681527,3.57335e-09,3.57598e-09,9.33848e-09,3.56563e-06,3.56591e-06,6.1445e-08,0,0,0,0,0,0,0,0 +13185000,0.982228,-0.0069846,-0.0113785,0.187216,0.000967259,-0.00122016,0.0175565,0.000930215,-0.00348727,-0.00600757,-1.28717e-05,-5.95435e-05,2.72765e-06,-9.55879e-06,6.24935e-05,-0.00136539,0.204236,0.00198353,0.433474,0,0,0,0,0,1.20509e-05,0.000190584,0.000190617,0.000329123,0.0479522,0.047951,0.0125083,0.047474,0.0474739,0.067245,3.44907e-09,3.45156e-09,8.92122e-09,3.56275e-06,3.56303e-06,6.13125e-08,0,0,0,0,0,0,0,0 +13285000,0.98224,-0.00699207,-0.0113615,0.187152,-0.00015311,-0.00189658,0.0158118,0.00090324,-0.00362843,-0.00535112,-1.28693e-05,-5.95459e-05,2.8436e-06,-9.56617e-06,6.24988e-05,-0.00136523,0.204236,0.00198353,0.433474,0,0,0,0,0,1.20253e-05,0.000196538,0.000196573,0.000328656,0.0541177,0.054116,0.012311,0.0549689,0.0549687,0.0684177,3.44903e-09,3.45154e-09,8.62451e-09,3.56276e-06,3.56304e-06,6.1241e-08,0,0,0,0,0,0,0,0 +13385000,0.982237,-0.00694661,-0.01148,0.187164,-0.000548158,-0.000581622,0.0149006,0.000737505,-0.00279654,-0.00542078,-1.29273e-05,-5.95216e-05,2.59739e-06,-9.4912e-06,6.26598e-05,-0.00136497,0.204236,0.00198353,0.433474,0,0,0,0,0,1.1828e-05,0.000189874,0.000189904,0.000323298,0.0458032,0.045802,0.0117494,0.0472886,0.0472885,0.0674645,3.32048e-09,3.32283e-09,8.24876e-09,3.55797e-06,3.55825e-06,6.11108e-08,0,0,0,0,0,0,0,0 +13485000,0.982246,-0.00691389,-0.0114402,0.187119,-6.92133e-06,0.00146475,0.0156895,0.000708472,-0.00270524,-0.00661705,-1.29231e-05,-5.95258e-05,2.79049e-06,-9.51203e-06,6.26745e-05,-0.00136457,0.204236,0.00198353,0.433474,0,0,0,0,0,1.16443e-05,0.000195767,0.000195799,0.000318099,0.0516368,0.0516355,0.0114676,0.0546031,0.0546029,0.0673939,3.32042e-09,3.3228e-09,7.89436e-09,3.55798e-06,3.55826e-06,6.10237e-08,0,0,0,0,0,0,0,0 +13585000,0.982225,-0.00693393,-0.0115505,0.187225,0.00422555,0.000941114,0.0170928,0.00367788,-0.00232698,-0.00840079,-1.27576e-05,-5.91418e-05,2.54471e-06,-6.76163e-06,6.12797e-05,-0.00136411,0.204236,0.00198353,0.433474,0,0,0,0,0,1.147e-05,0.000189497,0.000189527,0.000313066,0.0440271,0.044026,0.0109906,0.0470861,0.0470859,0.0664402,3.18646e-09,3.1887e-09,7.56018e-09,3.55092e-06,3.55121e-06,6.08913e-08,0,0,0,0,0,0,0,0 +13685000,0.982274,-0.00686672,-0.0114653,0.186976,0.00357589,-0.000278251,0.0167173,0.00405883,-0.00229593,-0.00594714,-1.27439e-05,-5.91542e-05,3.18678e-06,-6.76043e-06,6.12738e-05,-0.00136421,0.204236,0.00198353,0.433474,0,0,0,0,0,1.12861e-05,0.000195315,0.000195346,0.000308199,0.0496452,0.0496436,0.0107592,0.0542352,0.054235,0.0663022,3.18642e-09,3.18868e-09,7.24446e-09,3.55093e-06,3.55122e-06,6.08121e-08,0,0,0,0,0,0,0,0 +13785000,0.982261,-0.00682353,-0.0116259,0.187032,0.010623,0.00267672,0.0168655,0.00770647,-0.000347579,-0.00633492,-1.27708e-05,-5.8579e-05,2.88672e-06,-1.82035e-06,6.12744e-05,-0.00136389,0.204236,0.00198353,0.433474,0,0,0,0,0,1.11152e-05,0.000189189,0.000189218,0.000303478,0.042638,0.0426369,0.0103573,0.0468746,0.0468745,0.065359,3.04638e-09,3.0485e-09,6.94626e-09,3.5413e-06,3.5416e-06,6.06713e-08,0,0,0,0,0,0,0,0 +13885000,0.982309,-0.00674293,-0.0115964,0.186785,0.0117157,0.0038894,0.0181482,0.00879315,6.31451e-06,-0.00394347,-1.27495e-05,-5.85984e-05,3.88649e-06,-1.82517e-06,6.12643e-05,-0.00136399,0.204236,0.00198353,0.433474,0,0,0,0,0,1.09534e-05,0.000194913,0.000194943,0.000298892,0.0480778,0.0480766,0.0101736,0.0538788,0.0538787,0.0651708,3.04635e-09,3.04849e-09,6.66411e-09,3.54131e-06,3.54161e-06,6.05962e-08,0,0,0,0,0,0,0,0 +13985000,0.982335,-0.00682745,-0.0113409,0.186664,0.0120546,0.00461868,0.0171856,0.00687198,-0.00155704,-0.00357534,-1.25491e-05,-5.89976e-05,4.53975e-06,-5.15984e-06,5.93974e-05,-0.00136377,0.204236,0.00198353,0.433474,0,0,0,0,0,1.0937e-05,0.000188735,0.000188764,0.000298484,0.0415555,0.041555,0.00993786,0.0466629,0.0466628,0.0652964,2.90007e-09,2.90207e-09,6.46235e-09,3.5289e-06,3.5292e-06,6.04621e-08,0,0,0,0,0,0,0,0 +14085000,0.98226,-0.00681138,-0.0112795,0.187062,0.00940668,0.000546951,0.0190191,0.00803762,-0.0013177,-0.00504835,-1.25824e-05,-5.89677e-05,2.96458e-06,-5.17691e-06,5.94245e-05,-0.00136332,0.204236,0.00198353,0.433474,0,0,0,0,0,1.07805e-05,0.000194342,0.000194374,0.000294045,0.0468639,0.0468624,0.00979589,0.0535425,0.0535423,0.0650662,2.90006e-09,2.90207e-09,6.20586e-09,3.52891e-06,3.52921e-06,6.03886e-08,0,0,0,0,0,0,0,0 +14185000,0.982212,-0.00680287,-0.0112256,0.187314,0.00744477,0.00168169,0.0180022,0.0075411,-0.00102447,-0.00726568,-1.26202e-05,-5.89731e-05,1.98068e-06,-5.2212e-06,5.95071e-05,-0.00136245,0.204236,0.00198353,0.433474,0,0,0,0,0,1.06275e-05,0.000187984,0.000188013,0.000289741,0.0407137,0.0407125,0.00951234,0.0464582,0.0464581,0.0641412,2.74805e-09,2.74992e-09,5.96291e-09,3.51368e-06,3.51399e-06,6.02151e-08,0,0,0,0,0,0,0,0 +14285000,0.982215,-0.00672367,-0.011219,0.187303,0.00852583,0.00146325,0.0168661,0.00820547,-0.000927557,-0.00354478,-1.2618e-05,-5.89748e-05,2.0903e-06,-5.19857e-06,5.94914e-05,-0.00136273,0.204236,0.00198353,0.433474,0,0,0,0,0,1.0483e-05,0.000193452,0.000193481,0.000285554,0.0459647,0.0459633,0.00941134,0.0532335,0.0532333,0.0638897,2.74804e-09,2.74993e-09,5.73243e-09,3.51369e-06,3.514e-06,6.01404e-08,0,0,0,0,0,0,0,0 +14385000,0.982234,-0.00683546,-0.0111686,0.187201,0.00955364,-0.00153765,0.0169257,0.00789751,-0.00232215,2.72944e-05,-1.23776e-05,-5.9091e-05,2.59251e-06,-6.12307e-06,5.68137e-05,-0.00136289,0.204236,0.00198353,0.433474,0,0,0,0,0,1.03411e-05,0.0001868,0.000186828,0.000281475,0.0401042,0.0401029,0.00917802,0.0462658,0.0462657,0.0629935,2.59103e-09,2.59278e-09,5.51352e-09,3.49556e-06,3.49588e-06,5.99442e-08,0,0,0,0,0,0,0,0 +14485000,0.982204,-0.00693391,-0.0111382,0.187358,0.00765531,-0.00109426,0.0206872,0.00868204,-0.00246269,0.00230626,-1.23944e-05,-5.90756e-05,1.78988e-06,-6.11304e-06,5.68103e-05,-0.00136294,0.204236,0.00198353,0.433474,0,0,0,0,0,1.01972e-05,0.000192101,0.000192132,0.000277529,0.0452533,0.0452517,0.00911393,0.0529566,0.0529564,0.0627331,2.59104e-09,2.5928e-09,5.30583e-09,3.49557e-06,3.49589e-06,5.98657e-08,0,0,0,0,0,0,0,0 +14585000,0.982194,-0.00702415,-0.010952,0.187419,0.00595352,-0.00121728,0.019337,0.00554609,-0.00337922,0.000177455,-1.23822e-05,-5.9562e-05,1.6027e-06,-1.16171e-05,5.65117e-05,-0.00136219,0.204236,0.00198353,0.433474,0,0,0,0,0,1.0182e-05,0.000185148,0.000185176,0.000277176,0.0396141,0.0396131,0.00900853,0.0460912,0.0460911,0.0628548,2.43083e-09,2.43244e-09,5.15685e-09,3.4749e-06,3.47523e-06,5.96667e-08,0,0,0,0,0,0,0,0 +14685000,0.982224,-0.00699535,-0.0110096,0.187259,0.00535579,-0.00104471,0.0191106,0.00610346,-0.00347482,0.00068151,-1.23733e-05,-5.95704e-05,2.02492e-06,-1.16411e-05,5.6528e-05,-0.00136198,0.204236,0.00198353,0.433474,0,0,0,0,0,1.00439e-05,0.000190261,0.00019029,0.000273348,0.0447308,0.0447297,0.00897647,0.0527148,0.0527146,0.0625878,2.43085e-09,2.43247e-09,4.96675e-09,3.47491e-06,3.47524e-06,5.95836e-08,0,0,0,0,0,0,0,0 +14785000,0.982276,-0.0069201,-0.0109981,0.186992,0.00692592,0.00530459,0.01886,0.00496368,0.00133223,0.00264221,-1.30802e-05,-5.94579e-05,2.73577e-06,-9.86422e-06,6.51326e-05,-0.0013621,0.204236,0.00198353,0.433474,0,0,0,0,0,9.90375e-06,0.000182977,0.000183004,0.000269619,0.039251,0.0392504,0.00882156,0.0459366,0.0459364,0.0617488,2.26888e-09,2.27036e-09,4.78576e-09,3.45187e-06,3.4522e-06,5.93327e-08,0,0,0,0,0,0,0,0 +14885000,0.982325,-0.00684358,-0.0109254,0.186738,0.00565133,0.00352922,0.0224609,0.00558019,0.00177642,0.00361226,-1.30649e-05,-5.94719e-05,3.46692e-06,-9.88754e-06,6.51491e-05,-0.00136192,0.204236,0.00198353,0.433474,0,0,0,0,0,9.77143e-06,0.00018788,0.000187908,0.000265998,0.0442906,0.0442896,0.00881943,0.052508,0.0525078,0.0614928,2.2689e-09,2.2704e-09,4.61365e-09,3.45188e-06,3.45221e-06,5.92416e-08,0,0,0,0,0,0,0,0 +14985000,0.982339,-0.00701271,-0.0107917,0.186668,0.00498926,0.00156079,0.025258,0.00444584,-3.0925e-06,0.005032,-1.28393e-05,-5.9753e-05,3.82492e-06,-1.33019e-05,6.24562e-05,-0.00136121,0.204236,0.00198353,0.433474,0,0,0,0,0,9.64821e-06,0.000180315,0.000180342,0.000262457,0.0389067,0.038906,0.00869708,0.0458029,0.0458027,0.0607007,2.10732e-09,2.10868e-09,4.44958e-09,3.42698e-06,3.42732e-06,5.89591e-08,0,0,0,0,0,0,0,0 +15085000,0.982342,-0.00695105,-0.0108793,0.186649,0.00504926,0.0025365,0.0291447,0.0049579,0.00016875,0.00748806,-1.28398e-05,-5.97526e-05,3.79955e-06,-1.33081e-05,6.24598e-05,-0.00136116,0.204236,0.00198353,0.433474,0,0,0,0,0,9.52577e-06,0.000184991,0.000185019,0.000259023,0.0438876,0.0438868,0.00872146,0.0523324,0.0523321,0.0604631,2.10736e-09,2.10873e-09,4.29337e-09,3.42698e-06,3.42733e-06,5.88578e-08,0,0,0,0,0,0,0,0 +15185000,0.98234,-0.00709157,-0.0109179,0.186652,0.00361244,0.00122891,0.0295467,0.0039391,-5.44978e-05,0.00808106,-1.28321e-05,-5.99072e-05,3.67718e-06,-1.53113e-05,6.23462e-05,-0.00136046,0.204236,0.00198353,0.433474,0,0,0,0,0,9.40375e-06,0.000177207,0.000177233,0.00025567,0.0386078,0.0386071,0.00862643,0.045689,0.0456889,0.059719,1.94814e-09,1.94939e-09,4.14429e-09,3.40071e-06,3.40107e-06,5.85415e-08,0,0,0,0,0,0,0,0 +15285000,0.982369,-0.0071886,-0.0109496,0.186496,0.00355194,0.000786953,0.0293872,0.00432434,8.79218e-05,0.00796149,-1.28199e-05,-5.99188e-05,4.25705e-06,-1.53746e-05,6.2394e-05,-0.0013599,0.204236,0.00198353,0.433474,0,0,0,0,0,9.39266e-06,0.000181644,0.000181671,0.000255369,0.0435475,0.0435467,0.00874596,0.0521872,0.052187,0.0604043,1.9482e-09,1.94945e-09,4.03702e-09,3.40072e-06,3.40107e-06,5.84595e-08,0,0,0,0,0,0,0,0 +15385000,0.982336,-0.00726681,-0.0109491,0.186664,0.0044555,0.00294353,0.0290566,0.00347239,0.000126878,0.00722589,-1.28574e-05,-6.0033e-05,3.85004e-06,-1.70462e-05,6.28504e-05,-0.00135875,0.204236,0.00198353,0.433474,0,0,0,0,0,9.28139e-06,0.000173692,0.000173718,0.000252103,0.0383279,0.0383277,0.00867121,0.0455942,0.0455941,0.0596873,1.793e-09,1.79413e-09,3.89962e-09,3.37344e-06,3.37381e-06,5.8108e-08,0,0,0,0,0,0,0,0 +15485000,0.982338,-0.00730251,-0.0109116,0.186656,0.00354045,0.000815132,0.0290914,0.00386346,0.000350172,0.00815187,-1.2854e-05,-6.00365e-05,4.00622e-06,-1.70932e-05,6.28818e-05,-0.00135837,0.204236,0.00198353,0.433474,0,0,0,0,0,9.17393e-06,0.00017788,0.000177907,0.000248928,0.0431963,0.0431957,0.00873826,0.0520679,0.0520677,0.0594974,1.79305e-09,1.79419e-09,3.76854e-09,3.37345e-06,3.37382e-06,5.79829e-08,0,0,0,0,0,0,0,0 +15585000,0.982345,-0.00749857,-0.0109316,0.186607,0.00734449,-0.00280811,0.0287024,0.00588669,-0.00372847,0.00716804,-1.2115e-05,-5.99985e-05,4.37132e-06,-1.66789e-05,5.28669e-05,-0.00135749,0.204236,0.00198353,0.433474,0,0,0,0,0,9.06783e-06,0.000169837,0.000169856,0.00024582,0.0380212,0.0380213,0.00868208,0.0455157,0.0455157,0.0588298,1.6435e-09,1.64444e-09,3.64315e-09,3.34558e-06,3.34595e-06,5.75942e-08,0,0,0,0,0,0,0,0 +15685000,0.982384,-0.00746255,-0.0109234,0.186403,0.00916407,-0.00582846,0.0291122,0.00669458,-0.00416107,0.0083162,-1.2109e-05,-6.00118e-05,4.85402e-06,-1.69336e-05,5.31163e-05,-0.00135712,0.204236,0.00198353,0.433474,0,0,0,0,0,8.95555e-06,0.000173774,0.000173787,0.000242798,0.0428028,0.042803,0.00876562,0.0519683,0.0519683,0.0586684,1.64358e-09,1.64445e-09,3.52328e-09,3.34556e-06,3.34594e-06,5.74524e-08,0,0,0,0,0,0,0,0 +15785000,0.982432,-0.00746246,-0.0107983,0.186158,0.00606624,-0.00593545,0.0285185,0.00517216,-0.0033315,0.00954973,-1.2331e-05,-6.01928e-05,5.525e-06,-1.95275e-05,5.6637e-05,-0.00135619,0.204236,0.00198353,0.433474,0,0,0,0,0,8.84561e-06,0.000165729,0.000165738,0.000239852,0.0376743,0.0376744,0.00872385,0.0454506,0.0454506,0.058049,1.50104e-09,1.50177e-09,3.40867e-09,3.31762e-06,3.318e-06,5.70254e-08,0,0,0,0,0,0,0,0 +15885000,0.982402,-0.00750699,-0.0108487,0.186315,0.00479257,-0.00380152,0.0296857,0.00565118,-0.00382276,0.00966885,-1.23361e-05,-6.01829e-05,5.09811e-06,-1.94386e-05,5.65e-05,-0.00135558,0.204236,0.00198353,0.433474,0,0,0,0,0,8.83594e-06,0.000169413,0.000169417,0.000239586,0.042352,0.0423524,0.00889012,0.051883,0.0518831,0.0587794,1.50112e-09,1.50181e-09,3.32603e-09,3.31762e-06,3.318e-06,5.69098e-08,0,0,0,0,0,0,0,0 +15985000,0.982411,-0.00732016,-0.0107882,0.186277,0.00322879,-0.00238127,0.0262232,0.00450983,-0.00298258,0.00747064,-1.24829e-05,-6.02739e-05,4.9981e-06,-2.10002e-05,5.87012e-05,-0.00135346,0.204236,0.00198353,0.433474,0,0,0,0,0,8.72632e-06,0.000161451,0.00016145,0.000236722,0.0372772,0.0372777,0.00885769,0.0453949,0.045395,0.0581893,1.36664e-09,1.36722e-09,3.21987e-09,3.29e-06,3.29039e-06,5.64451e-08,0,0,0,0,0,0,0,0 +16085000,0.982414,-0.00728144,-0.0107782,0.186264,0.00175912,-0.00339212,0.0247812,0.00468859,-0.00328661,0.00899808,-1.24908e-05,-6.02679e-05,4.62069e-06,-2.10696e-05,5.87457e-05,-0.00135322,0.204236,0.00198353,0.433474,0,0,0,0,0,8.61688e-06,0.000164882,0.000164882,0.00023393,0.0418676,0.041868,0.00896715,0.0518071,0.0518072,0.0580982,1.36669e-09,1.36729e-09,3.11821e-09,3.29001e-06,3.2904e-06,5.62697e-08,0,0,0,0,0,0,0,0 +16185000,0.982401,-0.0071868,-0.0106631,0.186343,-0.00205128,-0.00173265,0.023672,0.00241078,-0.00249641,0.00587122,-1.26966e-05,-6.04728e-05,4.1716e-06,-2.44195e-05,6.17655e-05,-0.00135138,0.204236,0.00198353,0.433474,0,0,0,0,0,8.51392e-06,0.000157061,0.00015706,0.0002312,0.0368231,0.0368234,0.00894247,0.0453451,0.0453452,0.0575535,1.24087e-09,1.2414e-09,3.02082e-09,3.26297e-06,3.26337e-06,5.57661e-08,0,0,0,0,0,0,0,0 +16285000,0.982402,-0.007236,-0.0105949,0.186339,-0.00166302,-0.0030308,0.0232346,0.00220449,-0.00274835,0.00727097,-1.26946e-05,-6.04763e-05,4.30906e-06,-2.44977e-05,6.18342e-05,-0.00135115,0.204236,0.00198353,0.433474,0,0,0,0,0,8.42402e-06,0.000160249,0.000160247,0.000228521,0.0412884,0.0412888,0.00906107,0.0517337,0.0517338,0.0575008,1.24094e-09,1.24146e-09,2.92746e-09,3.26297e-06,3.26337e-06,5.55702e-08,0,0,0,0,0,0,0,0 +16385000,0.98242,-0.00719289,-0.010618,0.186242,0.000827748,-0.00237902,0.0238684,0.00328251,-0.00215773,0.00720881,-1.26823e-05,-6.0274e-05,4.69471e-06,-2.13715e-05,6.17376e-05,-0.00135023,0.204236,0.00198353,0.433474,0,0,0,0,0,8.33361e-06,0.000152653,0.000152651,0.000225909,0.0363004,0.0363008,0.00904132,0.0452976,0.0452977,0.0569987,1.12432e-09,1.12479e-09,2.83795e-09,3.2369e-06,3.23731e-06,5.50284e-08,0,0,0,0,0,0,0,0 +16485000,0.98242,-0.0072932,-0.0106041,0.18624,0.00328925,-0.00367964,0.025728,0.00348481,-0.00252615,0.0106187,-1.26845e-05,-6.02706e-05,4.55748e-06,-2.12979e-05,6.16752e-05,-0.00135047,0.204236,0.00198353,0.433474,0,0,0,0,0,8.24042e-06,0.000155608,0.000155604,0.000223358,0.0406267,0.0406273,0.00916662,0.0516579,0.0516581,0.0569839,1.1244e-09,1.12484e-09,2.75206e-09,3.23689e-06,3.23731e-06,5.48109e-08,0,0,0,0,0,0,0,0 +16585000,0.98242,-0.00727523,-0.0106021,0.186239,0.00722557,-0.0045118,0.0291642,0.00305377,-0.00199866,0.0113306,-1.28003e-05,-6.03038e-05,4.48303e-06,-2.18616e-05,6.34243e-05,-0.00134965,0.204236,0.00198353,0.433474,0,0,0,0,0,8.22639e-06,0.000148298,0.00014829,0.00022313,0.0357014,0.0357022,0.00921601,0.0452487,0.0452488,0.057331,1.01715e-09,1.01751e-09,2.6899e-09,3.21203e-06,3.21245e-06,5.42904e-08,0,0,0,0,0,0,0,0 +16685000,0.982439,-0.00733136,-0.0105372,0.186144,0.00849057,-0.00811626,0.0294629,0.00383568,-0.00260853,0.0127406,-1.27966e-05,-6.03102e-05,4.7362e-06,-2.20149e-05,6.35585e-05,-0.00134923,0.204236,0.00198353,0.433474,0,0,0,0,0,8.13828e-06,0.00015103,0.00015102,0.000220639,0.039897,0.0398977,0.00934667,0.051575,0.0515753,0.0573536,1.01723e-09,1.01756e-09,2.60992e-09,3.21202e-06,3.21245e-06,5.40546e-08,0,0,0,0,0,0,0,0 +16785000,0.982464,-0.00716856,-0.0104161,0.186025,0.00962572,-0.00795806,0.0282334,0.00300744,-0.00191344,0.0119099,-1.30203e-05,-6.04119e-05,4.87977e-06,-2.3768e-05,6.72486e-05,-0.00134759,0.204236,0.00198353,0.433474,0,0,0,0,0,8.04535e-06,0.000144052,0.000144037,0.000218213,0.0350852,0.0350861,0.00932776,0.0451961,0.0451963,0.0569139,9.19219e-10,9.19481e-10,2.53313e-09,3.18857e-06,3.189e-06,5.34397e-08,0,0,0,0,0,0,0,0 +16885000,0.982512,-0.00713514,-0.0105085,0.185765,0.00843859,-0.00786582,0.0295205,0.00390505,-0.00268987,0.0111326,-1.30114e-05,-6.04226e-05,5.36666e-06,-2.39812e-05,6.74074e-05,-0.00134652,0.204236,0.00198353,0.433474,0,0,0,0,0,7.95514e-06,0.000146574,0.000146557,0.000215838,0.039133,0.0391339,0.00946057,0.0514846,0.0514849,0.0569723,9.19294e-10,9.19553e-10,2.45933e-09,3.18856e-06,3.189e-06,5.31813e-08,0,0,0,0,0,0,0,0 +16985000,0.982515,-0.0071502,-0.0105435,0.185747,0.00852049,-0.00809368,0.0296558,0.00366942,-0.00202311,0.0101654,-1.31203e-05,-6.02929e-05,5.45234e-06,-2.18188e-05,6.91464e-05,-0.00134521,0.204236,0.00198353,0.433474,0,0,0,0,0,7.87368e-06,0.00013994,0.000139925,0.000213504,0.0344133,0.0344139,0.00943831,0.0451378,0.045138,0.0565605,8.30129e-10,8.30363e-10,2.38834e-09,3.16654e-06,3.16699e-06,5.25313e-08,0,0,0,0,0,0,0,0 +17085000,0.982508,-0.00725047,-0.0104774,0.185784,0.00947783,-0.0104111,0.0298447,0.0045762,-0.00296639,0.0100115,-1.31224e-05,-6.02903e-05,5.30029e-06,-2.18991e-05,6.91614e-05,-0.00134426,0.204236,0.00198353,0.433474,0,0,0,0,0,7.79253e-06,0.000142266,0.000142248,0.000211225,0.0383263,0.038327,0.00957165,0.051383,0.0513834,0.0566521,8.30214e-10,8.30428e-10,2.32014e-09,3.16654e-06,3.16699e-06,5.22501e-08,0,0,0,0,0,0,0,0 +17185000,0.982462,-0.00737198,-0.0103673,0.186029,0.00880158,-0.0153008,0.0309812,0.00295791,-0.00668155,0.0126805,-1.29832e-05,-6.04489e-05,4.80357e-06,-2.43211e-05,6.66695e-05,-0.00134367,0.204236,0.00198353,0.433474,0,0,0,0,0,7.78756e-06,0.000135995,0.000135976,0.000211018,0.0337144,0.0337149,0.00961585,0.0450719,0.0450722,0.0570765,7.49484e-10,7.4965e-10,2.2707e-09,3.14596e-06,3.14642e-06,5.16446e-08,0,0,0,0,0,0,0,0 +17285000,0.982431,-0.00732578,-0.0103647,0.186196,0.00926423,-0.0157799,0.03048,0.00385139,-0.00820786,0.0132218,-1.29905e-05,-6.04391e-05,4.32378e-06,-2.42684e-05,6.6555e-05,-0.00134291,0.204236,0.00198353,0.433474,0,0,0,0,0,7.70978e-06,0.000138138,0.000138116,0.000208792,0.0374891,0.0374899,0.00974929,0.0512697,0.05127,0.0572019,7.49569e-10,7.4972e-10,2.20694e-09,3.14595e-06,3.14642e-06,5.13453e-08,0,0,0,0,0,0,0,0 +17385000,0.982476,-0.00720687,-0.0103753,0.18596,0.00647498,-0.0159343,0.0304999,0.00530424,-0.00514767,0.013831,-1.33429e-05,-6.01724e-05,4.66408e-06,-1.99976e-05,7.25676e-05,-0.00134164,0.204236,0.00198353,0.433474,0,0,0,0,0,7.6235e-06,0.000132238,0.000132214,0.000206618,0.0329968,0.032997,0.00971615,0.0449984,0.0449986,0.0568327,6.7673e-10,6.76839e-10,2.14552e-09,3.12684e-06,3.12732e-06,5.06355e-08,0,0,0,0,0,0,0,0 +17485000,0.982465,-0.0072052,-0.0104296,0.186015,0.0042275,-0.0166956,0.0299829,0.00577406,-0.0067534,0.0143525,-1.3346e-05,-6.01687e-05,4.46292e-06,-2.00497e-05,7.25636e-05,-0.00134085,0.204236,0.00198353,0.433474,0,0,0,0,0,7.54818e-06,0.000134212,0.000134184,0.000204486,0.0366298,0.0366299,0.00984654,0.0511438,0.0511441,0.0569856,6.76815e-10,6.76913e-10,2.08642e-09,3.12684e-06,3.12732e-06,5.03146e-08,0,0,0,0,0,0,0,0 +17585000,0.982468,-0.00712317,-0.0102993,0.18601,0.00066066,-0.0129101,0.0290001,0.00212634,-0.00505268,0.0125165,-1.37306e-05,-6.04065e-05,4.42884e-06,-2.42359e-05,7.90601e-05,-0.00133879,0.204236,0.00198353,0.433474,0,0,0,0,0,7.47297e-06,0.00012868,0.000128651,0.000202395,0.032262,0.0322622,0.00980684,0.044916,0.0449163,0.0566371,6.11288e-10,6.11349e-10,2.02946e-09,3.10915e-06,3.10964e-06,5e-08,0,0,0,0,0,0,0,0 +17685000,0.982497,-0.00721753,-0.0102192,0.185857,-0.000342294,-0.0134214,0.0302952,0.00216261,-0.00639154,0.014886,-1.373e-05,-6.04074e-05,4.46898e-06,-2.42769e-05,7.909e-05,-0.00133859,0.204236,0.00198353,0.433474,0,0,0,0,0,7.39155e-06,0.000130496,0.000130466,0.000200358,0.0357488,0.035749,0.00993321,0.051005,0.0510053,0.056814,6.11374e-10,6.11426e-10,1.97461e-09,3.10914e-06,3.10964e-06,5e-08,0,0,0,0,0,0,0,0 +17785000,0.982542,-0.00718016,-0.0102093,0.18562,0.00205751,-0.0116445,0.0300814,0.00310963,-0.00553492,0.0185215,-1.39335e-05,-6.0194e-05,4.56608e-06,-2.05816e-05,8.26443e-05,-0.00133862,0.204236,0.00198353,0.433474,0,0,0,0,0,7.30587e-06,0.000125327,0.000125296,0.000198366,0.0315147,0.0315149,0.00988619,0.0448245,0.0448248,0.0564822,5.52564e-10,5.5259e-10,1.92171e-09,3.09284e-06,3.09335e-06,5e-08,0,0,0,0,0,0,0,0 +17885000,0.982552,-0.00712689,-0.0103178,0.185567,0.00433892,-0.013875,0.0295622,0.00348593,-0.0068277,0.0235392,-1.39329e-05,-6.01943e-05,4.60208e-06,-2.04956e-05,8.25977e-05,-0.00133929,0.204236,0.00198353,0.433474,0,0,0,0,0,7.29563e-06,0.000127001,0.000126967,0.000198191,0.0348764,0.0348767,0.0100835,0.0508535,0.0508539,0.0574939,5.52654e-10,5.52674e-10,1.8833e-09,3.09284e-06,3.09335e-06,5.0002e-08,0,0,0,0,0,0,0,0 +17985000,0.982559,-0.00691385,-0.0103017,0.185536,0.00327296,-0.00759305,0.0292915,0.00276224,-0.00143499,0.0236664,-1.44952e-05,-6.00524e-05,4.51376e-06,-1.8201e-05,9.22898e-05,-0.00133823,0.204236,0.00198353,0.433474,0,0,0,0,0,7.2223e-06,0.000122177,0.000122143,0.000196232,0.030768,0.0307681,0.0100278,0.0447239,0.0447242,0.0571655,4.99936e-10,4.99949e-10,1.83364e-09,3.07781e-06,3.07833e-06,5.0001e-08,0,0,0,0,0,0,0,0 +18085000,0.982559,-0.00699732,-0.0102652,0.185537,0.0034856,-0.0080819,0.0289513,0.00317505,-0.0022499,0.0231135,-1.44956e-05,-6.00521e-05,4.47513e-06,-1.83376e-05,9.23567e-05,-0.00133705,0.204236,0.00198353,0.433474,0,0,0,0,0,7.15534e-06,0.000123718,0.000123684,0.00019431,0.0339876,0.0339877,0.0101456,0.05069,0.0506903,0.0573849,5.00016e-10,5.00036e-10,1.78575e-09,3.0778e-06,3.07833e-06,5.0001e-08,0,0,0,0,0,0,0,0 +18185000,0.982603,-0.00700918,-0.0103105,0.185301,0.00332394,-0.00698142,0.029684,0.00374417,-0.00167484,0.021486,-1.45615e-05,-5.99658e-05,4.94687e-06,-1.67849e-05,9.36811e-05,-0.00133518,0.204236,0.00198353,0.433474,0,0,0,0,0,7.086e-06,0.00011923,0.000119196,0.000192426,0.0300072,0.0300072,0.0100822,0.0446143,0.0446145,0.0570658,4.52843e-10,4.52861e-10,1.73951e-09,3.06401e-06,3.06455e-06,5.0001e-08,0,0,0,0,0,0,0,0 +18285000,0.982601,-0.00704352,-0.0102843,0.185311,0.00415077,-0.0076689,0.0289837,0.00405762,-0.00239501,0.0205782,-1.45616e-05,-5.99663e-05,4.94149e-06,-1.69823e-05,9.38016e-05,-0.00133382,0.204236,0.00198353,0.433474,0,0,0,0,0,7.02266e-06,0.000120652,0.000120616,0.000190574,0.0330976,0.0330976,0.0101934,0.0505132,0.0505135,0.0572929,4.52931e-10,4.52944e-10,1.69486e-09,3.06401e-06,3.06455e-06,5e-08,0,0,0,0,0,0,0,0 +18385000,0.982579,-0.00696683,-0.0103148,0.185431,0.00474095,-0.00683974,0.0287649,0.00567698,-0.00181799,0.0201993,-1.45997e-05,-5.97953e-05,4.73835e-06,-1.42267e-05,9.45287e-05,-0.0013326,0.204236,0.00198353,0.433474,0,0,0,0,0,6.96246e-06,0.000116485,0.00011645,0.000188756,0.0292593,0.0292592,0.0101225,0.0444953,0.0444955,0.0569798,4.10759e-10,4.10771e-10,1.65175e-09,3.05138e-06,3.05194e-06,5e-08,0,0,0,0,0,0,0,0 +18485000,0.982588,-0.00700021,-0.01033,0.185381,0.00765384,-0.00648932,0.0284746,0.00638359,-0.00249281,0.0228676,-1.45966e-05,-5.97975e-05,4.88772e-06,-1.41811e-05,9.44872e-05,-0.00133257,0.204236,0.00198353,0.433474,0,0,0,0,0,6.95672e-06,0.000117796,0.000117761,0.000188597,0.0322275,0.0322275,0.0103089,0.0503263,0.0503265,0.0580515,4.10845e-10,4.10864e-10,1.62042e-09,3.05138e-06,3.05195e-06,5.0002e-08,0,0,0,0,0,0,0,0 +18585000,0.982562,-0.00683331,-0.0102008,0.185529,0.00628587,-0.00600948,0.0281425,0.00512789,-0.00195847,0.0245279,-1.47173e-05,-5.98708e-05,4.68936e-06,-1.56845e-05,9.66681e-05,-0.00133167,0.204236,0.00198353,0.433474,0,0,0,0,0,6.89956e-06,0.000113929,0.000113894,0.000186817,0.0285254,0.0285253,0.0102298,0.0443684,0.0443685,0.0577324,3.73153e-10,3.7317e-10,1.57982e-09,3.03982e-06,3.0404e-06,5.0002e-08,0,0,0,0,0,0,0,0 +18685000,0.982576,-0.00681463,-0.0101511,0.185457,0.00591262,-0.00498708,0.0266861,0.00574368,-0.00251058,0.0239998,-1.47161e-05,-5.98722e-05,4.74626e-06,-1.58376e-05,9.67572e-05,-0.00133052,0.204236,0.00198353,0.433474,0,0,0,0,0,6.83651e-06,0.00011514,0.000115105,0.000185075,0.0313743,0.0313742,0.0103307,0.0501293,0.0501294,0.0579815,3.73235e-10,3.73261e-10,1.54058e-09,3.03982e-06,3.0404e-06,5.0001e-08,0,0,0,0,0,0,0,0 +18785000,0.982578,-0.00675154,-0.0100468,0.185456,0.00483403,-0.00488518,0.0260349,0.00576331,-0.00204355,0.0207263,-1.4772e-05,-5.98454e-05,4.71475e-06,-1.57689e-05,9.79977e-05,-0.00132756,0.204236,0.00198353,0.433474,0,0,0,0,0,6.77603e-06,0.000111552,0.000111518,0.000183366,0.027799,0.0277988,0.010245,0.0442335,0.0442336,0.0576628,3.39548e-10,3.39571e-10,1.50266e-09,3.02923e-06,3.02983e-06,5.0001e-08,0,0,0,0,0,0,0,0 +18885000,0.982571,-0.00670526,-0.0100598,0.185496,0.00390462,-0.00453041,0.0245736,0.00616888,-0.00257542,0.0177622,-1.47761e-05,-5.98432e-05,4.52053e-06,-1.61298e-05,9.82378e-05,-0.00132555,0.204236,0.00198353,0.433474,0,0,0,0,0,6.7161e-06,0.000112672,0.000112638,0.000181689,0.0305302,0.0305299,0.01034,0.0499224,0.0499226,0.0579145,3.39632e-10,3.39662e-10,1.46597e-09,3.02923e-06,3.02983e-06,5e-08,0,0,0,0,0,0,0,0 +18985000,0.982549,-0.00668848,-0.0100971,0.185607,0.00235053,-0.0046715,0.0250809,0.00507122,-0.00207256,0.0205783,-1.48519e-05,-5.98816e-05,4.45862e-06,-1.68943e-05,9.96185e-05,-0.0013251,0.204236,0.00198353,0.433474,0,0,0,0,0,6.66514e-06,0.000109351,0.000109317,0.000180035,0.0270896,0.0270893,0.0102483,0.0440913,0.0440914,0.0575943,3.09531e-10,3.09558e-10,1.4305e-09,3.01957e-06,3.02019e-06,5e-08,0,0,0,0,0,0,0,0 +19085000,0.982555,-0.00676229,-0.0101058,0.185577,0.00036582,-0.00475033,0.0256186,0.00524798,-0.00250885,0.0168187,-1.48502e-05,-5.98837e-05,4.54349e-06,-1.72102e-05,9.98044e-05,-0.00132284,0.204236,0.00198353,0.433474,0,0,0,0,0,6.61032e-06,0.000110388,0.000110354,0.000178415,0.0297033,0.0297028,0.0103376,0.0497079,0.049708,0.057846,3.09616e-10,3.0965e-10,1.39617e-09,3.01957e-06,3.0202e-06,5e-08,0,0,0,0,0,0,0,0 +19185000,0.982529,-0.00665707,-0.0102321,0.185707,-0.00101009,-0.00470996,0.025638,0.00435798,-0.0020735,0.0168619,-1.49177e-05,-5.98831e-05,4.21872e-06,-1.75024e-05,0.000101075,-0.00132182,0.204236,0.00198353,0.433474,0,0,0,0,0,6.60399e-06,0.000107316,0.00010728,0.000178275,0.0263911,0.0263906,0.010323,0.0439425,0.0439426,0.0583618,2.82713e-10,2.82742e-10,1.37116e-09,3.01077e-06,3.01141e-06,5.0002e-08,0,0,0,0,0,0,0,0 +19285000,0.982527,-0.00659639,-0.0101841,0.185723,-0.00211091,-0.00464648,0.0259948,0.00423451,-0.00254379,0.0169504,-1.49204e-05,-5.98812e-05,4.08624e-06,-1.76785e-05,0.000101194,-0.00132092,0.204236,0.00198353,0.433474,0,0,0,0,0,6.54736e-06,0.000108277,0.000108242,0.000176691,0.0289049,0.0289044,0.0104086,0.0494857,0.0494858,0.0586184,2.828e-10,2.82834e-10,1.33873e-09,3.01077e-06,3.01142e-06,5.0001e-08,0,0,0,0,0,0,0,0 +19385000,0.982523,-0.00667547,-0.0100737,0.185747,-0.00211502,-0.00122291,0.0276647,0.00361915,-0.000759565,0.0157351,-1.5042e-05,-5.98363e-05,3.89801e-06,-1.71951e-05,0.000103579,-0.00131908,0.204236,0.00198353,0.433474,0,0,0,0,0,6.48995e-06,0.000105432,0.000105397,0.000175138,0.0257103,0.0257099,0.0103056,0.0437874,0.0437874,0.0582808,2.5873e-10,2.58761e-10,1.30733e-09,3.00275e-06,3.00341e-06,5.0001e-08,0,0,0,0,0,0,0,0 +19485000,0.982478,-0.0067255,-0.00997598,0.185988,-0.00305125,-0.00118075,0.0269493,0.00332012,-0.000878415,0.0154896,-1.50486e-05,-5.98314e-05,3.56865e-06,-1.74598e-05,0.000103769,-0.00131797,0.204236,0.00198353,0.433474,0,0,0,0,0,6.44433e-06,0.000106325,0.000106291,0.0001736,0.0281276,0.0281271,0.0103863,0.0492565,0.0492565,0.0585329,2.58818e-10,2.58853e-10,1.27691e-09,3.00275e-06,3.00342e-06,5.0001e-08,0,0,0,0,0,0,0,0 +19585000,0.982456,-0.00667508,-0.0100909,0.186103,-0.00482994,-0.00399351,0.0283754,0.00388359,-0.00194302,0.0156404,-1.49628e-05,-5.97696e-05,3.44764e-06,-1.65417e-05,0.000102247,-0.00131671,0.204236,0.00198353,0.433474,0,0,0,0,0,6.39697e-06,0.000103691,0.000103657,0.00017209,0.0250561,0.0250556,0.0102783,0.0436266,0.0436266,0.0581845,2.37269e-10,2.37301e-10,1.24743e-09,2.99544e-06,2.99612e-06,5e-08,0,0,0,0,0,0,0,0 +19685000,0.982471,-0.00669431,-0.0101057,0.186024,-0.00618696,-0.0027755,0.0276332,0.00336878,-0.0022878,0.0155195,-1.49602e-05,-5.9772e-05,3.579e-06,-1.66701e-05,0.000102314,-0.00131561,0.204236,0.00198353,0.433474,0,0,0,0,0,6.34555e-06,0.000104522,0.000104488,0.000170614,0.0273793,0.0273788,0.0103544,0.0490224,0.0490224,0.0584304,2.37358e-10,2.37394e-10,1.21888e-09,2.99543e-06,2.99612e-06,5e-08,0,0,0,0,0,0,0,0 +19785000,0.982457,-0.00677639,-0.0101225,0.186091,-0.00645937,-0.00143639,0.0264499,0.00579645,-0.00185559,0.0125322,-1.49336e-05,-5.96214e-05,3.42864e-06,-1.43112e-05,0.000102022,-0.00131323,0.204236,0.00198353,0.433474,0,0,0,0,0,6.34029e-06,0.000102083,0.000102048,0.000170488,0.0244283,0.0244279,0.010329,0.0434614,0.0434614,0.0589372,2.18051e-10,2.18083e-10,1.19807e-09,2.98877e-06,2.98947e-06,5.0002e-08,0,0,0,0,0,0,0,0 +19885000,0.982433,-0.00678343,-0.010212,0.186214,-0.00618996,-0.000829388,0.0262025,0.00510741,-0.00192705,0.0113582,-1.49387e-05,-5.96175e-05,3.17008e-06,-1.45928e-05,0.000102215,-0.00131185,0.204236,0.00198353,0.433474,0,0,0,0,0,6.29211e-06,0.000102858,0.000102823,0.000169037,0.0266605,0.0266601,0.0104026,0.0487848,0.0487847,0.0591828,2.1814e-10,2.18176e-10,1.17103e-09,2.98877e-06,2.98947e-06,5.0002e-08,0,0,0,0,0,0,0,0 +19985000,0.982453,-0.00680129,-0.0103508,0.186101,-0.00627363,-0.000757968,0.0236683,0.00546943,-0.000507604,0.00773342,-1.49816e-05,-5.95055e-05,3.20568e-06,-1.2842e-05,0.000103292,-0.00130885,0.204236,0.00198353,0.433474,0,0,0,0,0,6.2376e-06,0.000100598,0.000100562,0.000167617,0.0238234,0.023823,0.0102875,0.0432927,0.0432927,0.0588117,2.00818e-10,2.00851e-10,1.1448e-09,2.98269e-06,2.98341e-06,5.0001e-08,0,0,0,0,0,0,0,0 +20085000,0.982463,-0.00680671,-0.0103626,0.186046,-0.00574571,-0.0031682,0.0237429,0.00484484,-0.000730036,0.0109206,-1.49826e-05,-5.95047e-05,3.15781e-06,-1.28129e-05,0.000103278,-0.00130914,0.204236,0.00198353,0.433474,0,0,0,0,0,6.18568e-06,0.000101321,0.000101285,0.000166221,0.025975,0.0259745,0.0103575,0.0485445,0.0485444,0.0590488,2.00908e-10,2.00944e-10,1.11937e-09,2.98269e-06,2.98341e-06,5.0001e-08,0,0,0,0,0,0,0,0 +20185000,0.982444,-0.00680957,-0.0104673,0.186141,-0.00472139,-0.00141223,0.0245402,0.00589915,-0.00053115,0.0104957,-1.49882e-05,-5.94342e-05,2.89409e-06,-1.17068e-05,0.00010339,-0.00130781,0.204236,0.00198353,0.433474,0,0,0,0,0,6.13746e-06,9.92213e-05,9.91853e-05,0.000164843,0.0238183,0.0238184,0.0102416,0.0431298,0.0431298,0.0586716,1.85346e-10,1.85378e-10,1.09469e-09,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +20285000,0.982455,-0.00680106,-0.0104965,0.186078,-0.00778446,-0.00166577,0.0248531,0.00530418,-0.000609968,0.0112085,-1.49902e-05,-5.94327e-05,2.79188e-06,-1.17068e-05,0.00010339,-0.00130716,0.204236,0.00198353,0.433474,0,0,0,0,0,6.08543e-06,9.98979e-05,9.98617e-05,0.000163496,0.0272802,0.0272813,0.0103093,0.0483724,0.0483724,0.0588998,1.85436e-10,1.85471e-10,1.07075e-09,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +20385000,0.98245,-0.0067524,-0.010501,0.186107,-0.00843871,-0.000735874,0.0238797,0.00626648,-0.000433844,0.0106705,-1.4975e-05,-5.93632e-05,2.9422e-06,-1.17068e-05,0.00010339,-0.00130538,0.204236,0.00198353,0.433474,0,0,0,0,0,6.04569e-06,9.62525e-05,9.6217e-05,0.000162158,0.0260463,0.0260487,0.0101922,0.0430173,0.0430173,0.0585171,1.70751e-10,1.70784e-10,1.04751e-09,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +20485000,0.982467,-0.00676426,-0.0104724,0.186018,-0.012743,-0.00163776,0.0245008,0.00518039,-0.000529465,0.0103219,-1.4977e-05,-5.93616e-05,2.83814e-06,-1.17068e-05,0.00010339,-0.00130435,0.204236,0.00198353,0.433474,0,0,0,0,0,6.03335e-06,9.68678e-05,9.68324e-05,0.000162053,0.0305052,0.0305095,0.0103442,0.0483288,0.0483289,0.0596114,1.70844e-10,1.70879e-10,1.03055e-09,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +20585000,0.982503,-0.00673907,-0.010515,0.185827,-0.0119467,-0.00251883,0.0241496,0.00629391,-0.000443311,0.00872163,-1.49449e-05,-5.92672e-05,3.14329e-06,-1.17068e-05,0.00010339,-0.00130246,0.204236,0.00198353,0.433474,0,0,0,0,0,5.98524e-06,9.12057e-05,9.11725e-05,0.000160748,0.0294048,0.0294104,0.0102246,0.0429926,0.0429927,0.059212,1.57237e-10,1.57269e-10,1.00848e-09,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +20685000,0.982493,-0.00666373,-0.0105091,0.185883,-0.0139437,-0.00145793,0.0251058,0.00504191,-0.000601392,0.00911347,-1.49503e-05,-5.92627e-05,2.86811e-06,-1.17068e-05,0.00010339,-0.00130171,0.204236,0.00198353,0.433474,0,0,0,0,0,5.93773e-06,9.17465e-05,9.17131e-05,0.000159466,0.0346382,0.0346467,0.0102883,0.0484383,0.0484387,0.059428,1.57328e-10,1.57363e-10,9.87053e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +20785000,0.982516,-0.00620512,-0.0104855,0.185781,-0.0151911,0.000824651,0.0127782,0.00431071,-0.000466799,0.00773877,-1.49375e-05,-5.92087e-05,2.9301e-06,-1.17068e-05,0.00010339,-0.00130007,0.204236,0.00198353,0.433474,0,0,0,0,0,5.88917e-06,8.42251e-05,8.4194e-05,0.000158205,0.033174,0.0331834,0.0101682,0.0430749,0.0430752,0.0590238,1.45199e-10,1.45233e-10,9.66232e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +20885000,0.98257,0.00265275,-0.00680217,0.185751,-0.0214647,0.0126764,-0.100677,0.0024105,0.000235829,0.00218082,-1.49378e-05,-5.92082e-05,2.91335e-06,-1.17068e-05,0.00010339,-0.00129934,0.204236,0.00198353,0.433474,0,0,0,0,0,5.84183e-06,8.46748e-05,8.4643e-05,0.000156986,0.0396171,0.0396305,0.0102279,0.0487308,0.0487316,0.0592248,1.45291e-10,1.45326e-10,9.46002e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +20985000,0.982568,0.00630694,-0.00315246,0.185772,-0.030567,0.0294501,-0.241955,0.00207306,0.000627162,-0.0112836,-1.48368e-05,-5.91391e-05,2.86378e-06,-1.17068e-05,0.00010339,-0.00130235,0.204236,0.00198353,0.433474,0,0,0,0,0,5.80009e-06,7.55996e-05,7.55857e-05,0.000155768,0.0378912,0.0379042,0.0101063,0.0432896,0.0432902,0.0588166,1.3489e-10,1.34925e-10,9.26348e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +21085000,0.982507,0.00488208,-0.00339822,0.18613,-0.0438853,0.0457179,-0.359652,-0.00164393,0.00443934,-0.0406344,-1.48382e-05,-5.91377e-05,2.79136e-06,-1.17068e-05,0.00010339,-0.00130259,0.204236,0.00198353,0.433474,0,0,0,0,0,5.81302e-06,7.59797e-05,7.59632e-05,0.000155645,0.0447638,0.04478,0.0102524,0.0492539,0.0492553,0.0598972,1.34985e-10,1.3502e-10,9.11999e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +21185000,0.982457,0.00183861,-0.00517075,0.186408,-0.0445193,0.0470878,-0.484798,-0.000399704,0.00269932,-0.0745033,-1.45576e-05,-5.90352e-05,2.88773e-06,-1.17068e-05,0.00010339,-0.00131034,0.204236,0.00198353,0.433474,0,0,0,0,0,5.78859e-06,6.60343e-05,6.60184e-05,0.000154415,0.041503,0.041517,0.010131,0.0436348,0.0436357,0.0594733,1.26492e-10,1.26532e-10,8.93287e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +21285000,0.982409,-0.000373085,-0.00654888,0.186628,-0.0442694,0.0503561,-0.614874,-0.00486516,0.00758705,-0.130652,-1.45616e-05,-5.90314e-05,2.67701e-06,-1.17068e-05,0.00010339,-0.00130994,0.204236,0.00198353,0.433474,0,0,0,0,0,5.75494e-06,6.63391e-05,6.632e-05,0.000153214,0.0484806,0.0484979,0.0101912,0.0499005,0.0499025,0.0596613,1.26585e-10,1.26625e-10,8.75098e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +21385000,0.982365,-0.00193332,-0.00734787,0.18682,-0.0375957,0.0454933,-0.739248,-0.00325806,0.00985494,-0.192424,-1.44543e-05,-5.89251e-05,2.62646e-06,-1.17068e-05,0.00010339,-0.00131593,0.204236,0.00198353,0.433474,0,0,0,0,0,5.72427e-06,5.64187e-05,5.64046e-05,0.000152033,0.043759,0.0437734,0.0100728,0.0440523,0.0440535,0.0592351,1.20026e-10,1.20071e-10,8.57406e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +21485000,0.982342,-0.00277675,-0.00779169,0.186913,-0.0325636,0.0423803,-0.874665,-0.00684009,0.0142807,-0.277026,-1.44516e-05,-5.89272e-05,2.7524e-06,-1.17068e-05,0.00010339,-0.0013145,0.204236,0.00198353,0.433474,0,0,0,0,0,5.6942e-06,5.66544e-05,5.66399e-05,0.000150871,0.050512,0.0505298,0.0101337,0.0505742,0.0505766,0.0594147,1.20119e-10,1.20165e-10,8.40204e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +21585000,0.982347,-0.00322015,-0.00780259,0.186877,-0.0241824,0.0376651,-0.998001,-0.00591694,0.015198,-0.362465,-1.43865e-05,-5.88945e-05,2.86455e-06,-1.17068e-05,0.00010339,-0.00132223,0.204236,0.00198353,0.433474,0,0,0,0,0,5.65601e-06,4.74485e-05,4.74392e-05,0.000149737,0.0446372,0.0446519,0.0100178,0.0444823,0.0444838,0.0589872,1.15284e-10,1.15333e-10,8.23469e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +21685000,0.982341,-0.00356835,-0.00765409,0.186911,-0.0211249,0.0336195,-1.1314,-0.00817921,0.0188035,-0.476583,-1.43826e-05,-5.88973e-05,3.04363e-06,-1.17068e-05,0.00010339,-0.00131948,0.204236,0.00198353,0.433474,0,0,0,0,0,5.62467e-06,4.76302e-05,4.76218e-05,0.000148615,0.0509325,0.0509504,0.0100785,0.0511892,0.0511919,0.0591593,1.15377e-10,1.15428e-10,8.07186e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +21785000,0.98236,-0.003915,-0.00786754,0.186792,-0.0115175,0.0283447,-1.25922,-0.00101069,0.0169131,-0.589607,-1.42684e-05,-5.88026e-05,3.31016e-06,-1.17068e-05,0.00010339,-0.00132625,0.204236,0.00198353,0.433474,0,0,0,0,0,5.62137e-06,3.95286e-05,3.95237e-05,0.000148522,0.0443505,0.0443649,0.0100489,0.0448763,0.044878,0.0596064,1.11942e-10,1.11994e-10,7.95281e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +21885000,0.982354,-0.00420067,-0.0079846,0.186816,-0.00781665,0.024101,-1.38038,-0.0019998,0.0195775,-0.729159,-1.42715e-05,-5.87987e-05,3.12421e-06,-1.17068e-05,0.00010339,-0.00132372,0.204236,0.00198353,0.433474,0,0,0,0,0,5.58022e-06,3.96723e-05,3.96673e-05,0.000147429,0.0500483,0.0500657,0.0101109,0.0516889,0.0516917,0.0597765,1.12036e-10,1.12089e-10,7.79749e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +21985000,0.982374,-0.00481476,-0.00819258,0.186686,-0.00698659,0.0196362,-1.36848,0.00162279,0.0161158,-0.864402,-1.41847e-05,-5.87773e-05,3.20314e-06,-1.17068e-05,0.00010339,-0.00132823,0.204236,0.00198353,0.433474,0,0,0,0,0,5.53808e-06,3.28005e-05,3.27978e-05,0.000146352,0.0425442,0.0425581,0.00999543,0.0451908,0.0451926,0.0593358,1.09657e-10,1.09711e-10,7.64633e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +22085000,0.982369,-0.0055526,-0.00898465,0.186655,-0.00389274,0.0159326,-1.34917,0.00101434,0.0178476,-1.00622,-1.41808e-05,-5.878e-05,3.38302e-06,-1.17068e-05,0.00010339,-0.00132593,0.204236,0.00198353,0.433474,0,0,0,0,0,5.50573e-06,3.29194e-05,3.29153e-05,0.000145281,0.0469929,0.0470093,0.0100575,0.0519677,0.0519707,0.0594997,1.09751e-10,1.09806e-10,7.49912e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +22185000,0.982387,-0.0059194,-0.00922995,0.186535,0.00195959,0.0115843,-1.36411,0.00742242,0.013033,-1.14751,-1.4075e-05,-5.87322e-05,3.51212e-06,-1.17068e-05,0.00010339,-0.00132375,0.204236,0.00198353,0.433474,0,0,0,0,0,5.46655e-06,2.73393e-05,2.73361e-05,0.000144233,0.0400486,0.0400623,0.00994352,0.0453948,0.0453967,0.0590547,1.0814e-10,1.08196e-10,7.3557e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +22285000,0.982375,-0.00664019,-0.00947102,0.186565,0.0079251,0.0064082,-1.36213,0.00789813,0.013971,-1.29006,-1.40766e-05,-5.87296e-05,3.40176e-06,-1.17068e-05,0.00010339,-0.00132159,0.204236,0.00198353,0.433474,0,0,0,0,0,5.42994e-06,2.74396e-05,2.74368e-05,0.0001432,0.0440664,0.0440829,0.0100066,0.0520811,0.0520844,0.0592129,1.08235e-10,1.08291e-10,7.21607e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +22385000,0.982353,-0.00700796,-0.00953751,0.186662,0.00977618,-0.00322171,-1.36406,0.0131861,0.0040829,-1.43447,-1.39544e-05,-5.87052e-05,3.23341e-06,-1.17068e-05,0.00010339,-0.0013178,0.204236,0.00198353,0.433474,0,0,0,0,0,5.42668e-06,2.29104e-05,2.29077e-05,0.000143115,0.0375454,0.0375594,0.00997972,0.0454871,0.0454893,0.0596518,1.07155e-10,1.07211e-10,7.11395e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +22485000,0.982326,-0.0071759,-0.00997172,0.186777,0.0143154,-0.00978733,-1.3688,0.0143788,0.00341417,-1.57581,-1.39583e-05,-5.87007e-05,3.00964e-06,-1.17068e-05,0.00010339,-0.00131615,0.204236,0.00198353,0.433474,0,0,0,0,0,5.39221e-06,2.30019e-05,2.29972e-05,0.000142098,0.0411339,0.0411508,0.0100441,0.0520436,0.0520471,0.0598098,1.0725e-10,1.07307e-10,6.98052e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +22585000,0.98231,-0.00702634,-0.0106081,0.186827,0.0229868,-0.0167997,-1.3686,0.0260038,-0.0047903,-1.7187,-1.38447e-05,-5.86385e-05,3.12068e-06,-1.17068e-05,0.00010339,-0.00131354,0.204236,0.00198353,0.433474,0,0,0,0,0,5.36357e-06,1.93351e-05,1.93271e-05,0.000141088,0.0351244,0.0351393,0.00993168,0.0454805,0.0454828,0.059356,1.06533e-10,1.06589e-10,6.85044e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +22685000,0.982287,-0.00695469,-0.0108049,0.186944,0.0253736,-0.0218182,-1.37203,0.0284117,-0.00676839,-1.86258,-1.38452e-05,-5.86368e-05,3.0664e-06,-1.17068e-05,0.00010339,-0.00131114,0.204236,0.00198353,0.433474,0,0,0,0,0,5.33466e-06,1.94216e-05,1.94121e-05,0.000140096,0.0383048,0.0383226,0.00999584,0.0518829,0.0518867,0.0595098,1.06628e-10,1.06685e-10,6.72372e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +22785000,0.982312,-0.00689225,-0.0111472,0.186793,0.0292576,-0.0285744,-1.3762,0.0370213,-0.016089,-2.0106,-1.37506e-05,-5.85873e-05,2.91173e-06,-1.17068e-05,0.00010339,-0.00130672,0.204236,0.00198353,0.433474,0,0,0,0,0,5.289e-06,1.64517e-05,1.64399e-05,0.000139133,0.0328175,0.0328336,0.00988517,0.0453898,0.0453924,0.0590591,1.06159e-10,1.06216e-10,6.60013e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +22885000,0.982386,-0.00707244,-0.0114775,0.186378,0.0326395,-0.0335913,-1.37804,0.040079,-0.019116,-2.15489,-1.37472e-05,-5.85895e-05,3.06744e-06,-1.17068e-05,0.00010339,-0.0013044,0.204236,0.00198353,0.433474,0,0,0,0,0,5.23966e-06,1.65384e-05,1.65252e-05,0.00013819,0.0356441,0.0356636,0.00995003,0.0516221,0.0516263,0.0592093,1.06255e-10,1.06312e-10,6.4797e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +22985000,0.982458,-0.00699156,-0.011802,0.185978,0.0351774,-0.0380251,-1.38245,0.0485465,-0.0291142,-2.30719,-1.36576e-05,-5.85492e-05,3.21026e-06,-1.17068e-05,0.00010339,-0.00129872,0.204236,0.00198353,0.433474,0,0,0,0,0,5.19075e-06,1.41291e-05,1.41132e-05,0.000137258,0.030643,0.0306611,0.00984065,0.0452277,0.0452305,0.0587621,1.05957e-10,1.06014e-10,6.3622e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +23085000,0.982521,-0.00700096,-0.0121226,0.185623,0.0393608,-0.0433082,-1.37975,0.0522568,-0.03321,-2.44652,-1.36578e-05,-5.85488e-05,3.19651e-06,-1.17068e-05,0.00010339,-0.0012983,0.204236,0.00198353,0.433474,0,0,0,0,0,5.16975e-06,1.42188e-05,1.42011e-05,0.000137202,0.0331598,0.0331816,0.00999111,0.0512792,0.0512838,0.0597898,1.06054e-10,1.06111e-10,6.27625e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +23185000,0.982559,-0.00696955,-0.0123022,0.185411,0.0450699,-0.0438826,-1.38312,0.0631447,-0.0431564,-2.59393,-1.35903e-05,-5.8501e-05,3.04923e-06,-1.17068e-05,0.00010339,-0.00129416,0.204236,0.00198353,0.433474,0,0,0,0,0,5.12318e-06,1.22593e-05,1.22398e-05,0.000136283,0.0286173,0.0286383,0.00988124,0.0450052,0.0450084,0.0593331,1.05873e-10,1.05931e-10,6.16376e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23285000,0.982594,-0.00743766,-0.0124296,0.185203,0.0494232,-0.048997,-1.37902,0.067796,-0.0478403,-2.7382,-1.35892e-05,-5.85013e-05,3.09192e-06,-1.17068e-05,0.00010339,-0.00129199,0.204236,0.00198353,0.433474,0,0,0,0,0,5.08335e-06,1.23526e-05,1.2333e-05,0.000135373,0.0308665,0.030892,0.0099483,0.0508709,0.0508762,0.0594821,1.05969e-10,1.06027e-10,6.05409e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23385000,0.98261,-0.00735348,-0.012552,0.185113,0.0544139,-0.0494696,-1.38053,0.0784959,-0.0517512,-2.87912,-1.35519e-05,-5.84595e-05,2.8671e-06,-1.17068e-05,0.00010339,-0.00129075,0.204236,0.00198353,0.433474,0,0,0,0,0,5.04196e-06,1.0755e-05,1.07336e-05,0.000134475,0.0267462,0.0267706,0.00984028,0.0447322,0.044736,0.0590297,1.0587e-10,1.05928e-10,5.94702e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23485000,0.982626,-0.00743825,-0.0128185,0.185005,0.058467,-0.0514604,-1.38215,0.0840971,-0.0568237,-3.02286,-1.35495e-05,-5.84611e-05,2.98192e-06,-1.17068e-05,0.00010339,-0.00128877,0.204236,0.00198353,0.433474,0,0,0,0,0,5.01022e-06,1.08549e-05,1.08318e-05,0.000133582,0.0287826,0.0288124,0.00990653,0.0504113,0.0504174,0.0591712,1.05966e-10,1.06024e-10,5.84255e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +23585000,0.982642,-0.00769686,-0.0127206,0.184916,0.0599625,-0.054174,-1.38172,0.0908358,-0.0671305,-3.16891,-1.35104e-05,-5.84454e-05,3.01921e-06,-1.17068e-05,0.00010339,-0.00128615,0.204236,0.00198353,0.433474,0,0,0,0,0,4.97708e-06,9.54796e-06,9.52422e-06,0.000132702,0.0250361,0.0250651,0.00979956,0.0444179,0.0444224,0.0587232,1.05923e-10,1.05982e-10,5.74058e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +23685000,0.982636,-0.00832253,-0.0132147,0.184887,0.0584872,-0.056986,-1.28571,0.0967697,-0.0727488,-3.30693,-1.3509e-05,-5.84464e-05,3.08596e-06,-1.17068e-05,0.00010339,-0.00128508,0.204236,0.00198353,0.433474,0,0,0,0,0,4.97533e-06,9.65613e-06,9.63123e-06,0.000132632,0.0267092,0.0267431,0.0099501,0.0499077,0.049915,0.0597477,1.06021e-10,1.06079e-10,5.66599e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +23785000,0.982596,-0.010053,-0.0158996,0.184803,0.0545375,-0.0535103,-0.968528,0.106573,-0.0767986,-3.42998,-1.34852e-05,-5.84283e-05,3.25073e-06,-1.17068e-05,0.00010339,-0.00128088,0.204236,0.00198353,0.433474,0,0,0,0,0,4.94744e-06,8.60094e-06,8.56817e-06,0.000131747,0.0228691,0.0228999,0.00984018,0.0440527,0.0440581,0.0592908,1.06017e-10,1.06075e-10,5.56822e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +23885000,0.982507,-0.01339,-0.0200308,0.184659,0.0499965,-0.0539852,-0.537897,0.11176,-0.0821223,-3.50839,-1.34853e-05,-5.84279e-05,3.23997e-06,-1.17068e-05,0.00010339,-0.00127981,0.204236,0.00198353,0.433474,0,0,0,0,0,4.91363e-06,8.73305e-06,8.6901e-06,0.000130868,0.0238529,0.023887,0.00990534,0.0492722,0.0492807,0.0594331,1.06113e-10,1.06172e-10,5.47278e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +23985000,0.982454,-0.0155491,-0.0224306,0.184496,0.0509134,-0.0519752,-0.153542,0.120074,-0.0840734,-3.57671,-1.34845e-05,-5.84168e-05,3.19485e-06,-1.17068e-05,0.00010339,-0.00125708,0.204236,0.00198353,0.433474,0,0,0,0,0,4.87719e-06,7.9022e-06,7.8525e-06,0.00013001,0.020512,0.0205429,0.00979893,0.0435946,0.0436011,0.0589816,1.06137e-10,1.06196e-10,5.37959e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +24085000,0.982496,-0.0151877,-0.0215022,0.184413,0.0571434,-0.0604457,0.0908838,0.125419,-0.0896556,-3.58011,-1.34866e-05,-5.84144e-05,3.07161e-06,-1.17068e-05,0.00010339,-0.00125632,0.204236,0.00198353,0.433474,0,0,0,0,0,4.84184e-06,8.01839e-06,7.97135e-06,0.00012919,0.0216492,0.021685,0.00986767,0.0485382,0.0485482,0.0591228,1.06234e-10,1.06293e-10,5.28857e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +24185000,0.982607,-0.012323,-0.0177562,0.184434,0.0674906,-0.0647723,0.0834058,0.133117,-0.0939599,-3.59632,-1.34894e-05,-5.8413e-05,3.12274e-06,-1.17068e-05,0.00010339,-0.00123813,0.204236,0.00198353,0.433474,0,0,0,0,0,4.81483e-06,7.32406e-06,7.28339e-06,0.000128393,0.0192339,0.0192704,0.00976603,0.043079,0.0430868,0.0586771,1.06277e-10,1.06335e-10,5.19967e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +24285000,0.982696,-0.00988063,-0.0142723,0.184409,0.0709342,-0.0685666,0.0582986,0.140075,-0.100676,-3.59252,-1.34893e-05,-5.84131e-05,3.13067e-06,-1.17068e-05,0.00010339,-0.0012372,0.204236,0.00198353,0.433474,0,0,0,0,0,4.78576e-06,7.44153e-06,7.40643e-06,0.000127602,0.0206211,0.0206664,0.00983376,0.0478583,0.0478703,0.058818,1.06374e-10,1.06432e-10,5.11283e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +24385000,0.982745,-0.00890605,-0.0131871,0.184281,0.0648436,-0.0630213,0.0747054,0.147239,-0.101227,-3.58891,-1.34972e-05,-5.84085e-05,3.23889e-06,-1.17068e-05,0.00010339,-0.00123641,0.204236,0.00198353,0.433474,0,0,0,0,0,4.77997e-06,6.87373e-06,6.83823e-06,0.00012755,0.0183707,0.0184159,0.00980922,0.0425852,0.0425945,0.0592414,1.06425e-10,1.06483e-10,5.04921e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +24485000,0.98276,-0.00911982,-0.0132554,0.184184,0.0595511,-0.0591904,0.0729292,0.153446,-0.107329,-3.58103,-1.34932e-05,-5.84122e-05,3.44557e-06,-1.17068e-05,0.00010339,-0.00123656,0.204236,0.00198353,0.433474,0,0,0,0,0,4.75469e-06,7.0138e-06,6.97668e-06,0.000126747,0.0196447,0.0196998,0.00987473,0.0472214,0.0472358,0.0593856,1.06522e-10,1.06581e-10,4.96581e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +24585000,0.98272,-0.00974827,-0.0133556,0.184359,0.0563285,-0.0546178,0.0683106,0.157704,-0.104271,-3.57545,-1.35151e-05,-5.84058e-05,3.41458e-06,-1.17068e-05,0.00010339,-0.00123567,0.204236,0.00198353,0.433474,0,0,0,0,0,4.7356e-06,6.54277e-06,6.50421e-06,0.000125947,0.0175877,0.0176432,0.00976872,0.0421177,0.0421292,0.0589355,1.06572e-10,1.0663e-10,4.88431e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +24685000,0.982705,-0.010258,-0.0131887,0.184426,0.0533422,-0.0539103,0.0675583,0.163238,-0.109632,-3.56862,-1.35157e-05,-5.84052e-05,3.38056e-06,-1.17068e-05,0.00010339,-0.00123565,0.204236,0.00198353,0.433474,0,0,0,0,0,4.71188e-06,6.69092e-06,6.65191e-06,0.000125164,0.0187896,0.0188565,0.00983563,0.0466216,0.0466392,0.059079,1.06669e-10,1.06727e-10,4.80465e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +24785000,0.982727,-0.0103393,-0.012545,0.184347,0.0503741,-0.0510412,0.059843,0.165972,-0.105638,-3.5663,-1.35409e-05,-5.84013e-05,3.38093e-06,-1.17068e-05,0.00010339,-0.00123504,0.204236,0.00198353,0.433474,0,0,0,0,0,4.68243e-06,6.29439e-06,6.25462e-06,0.000124397,0.016886,0.0169529,0.00973029,0.0416727,0.0416869,0.0586279,1.0671e-10,1.06767e-10,4.72675e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +24885000,0.982723,-0.010175,-0.0120348,0.184413,0.0477765,-0.0544301,0.0496343,0.170889,-0.110912,-3.56308,-1.35402e-05,-5.84021e-05,3.42018e-06,-1.17068e-05,0.00010339,-0.00123425,0.204236,0.00198353,0.433474,0,0,0,0,0,4.66119e-06,6.45053e-06,6.40927e-06,0.000123634,0.0180383,0.0181181,0.00979825,0.0460534,0.0460751,0.0587708,1.06807e-10,1.06864e-10,4.65063e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +24985000,0.982704,-0.00989264,-0.0117931,0.184545,0.0397785,-0.0497364,0.0421824,0.171313,-0.102522,-3.56073,-1.358e-05,-5.83916e-05,3.39564e-06,-1.17068e-05,0.00010339,-0.00123408,0.204236,0.00198353,0.433474,0,0,0,0,0,4.66424e-06,6.11881e-06,6.07512e-06,0.000123576,0.0162702,0.016349,0.00977494,0.041248,0.0412655,0.0591923,1.06829e-10,1.06885e-10,4.59489e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +25085000,0.982702,-0.01022,-0.0118448,0.184533,0.0358464,-0.0491579,0.0392115,0.174985,-0.107496,-3.56244,-1.35813e-05,-5.83905e-05,3.33447e-06,-1.17068e-05,0.00010339,-0.00123207,0.204236,0.00198353,0.433474,0,0,0,0,0,4.63716e-06,6.28518e-06,6.23936e-06,0.000122827,0.017366,0.0174593,0.00984348,0.0455139,0.0455404,0.059339,1.06926e-10,1.06983e-10,4.52169e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +25185000,0.982657,-0.0103891,-0.011686,0.184773,0.0312315,-0.0427612,0.0393938,0.175754,-0.099758,-3.56011,-1.36135e-05,-5.83703e-05,3.20906e-06,-1.17068e-05,0.00010339,-0.00123097,0.204236,0.00198353,0.433474,0,0,0,0,0,4.61977e-06,6.00523e-06,5.95704e-06,0.000122078,0.0157138,0.0158063,0.00973718,0.0408411,0.0408627,0.0588828,1.06918e-10,1.06974e-10,4.45007e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25285000,0.982617,-0.010532,-0.0110432,0.185016,0.0254657,-0.0441576,0.0343054,0.178553,-0.104077,-3.55744,-1.36174e-05,-5.83663e-05,2.99489e-06,-1.17068e-05,0.00010339,-0.00123064,0.204236,0.00198353,0.433474,0,0,0,0,0,4.60039e-06,6.17826e-06,6.12914e-06,0.000121342,0.0167744,0.0168831,0.00980578,0.0449994,0.0450318,0.0590291,1.07016e-10,1.07071e-10,4.38005e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25385000,0.982615,-0.0105978,-0.0108347,0.185036,0.0178087,-0.0371354,0.0326986,0.175042,-0.0934827,-3.55835,-1.36668e-05,-5.83496e-05,2.95507e-06,-1.17068e-05,0.00010339,-0.00122887,0.204236,0.00198353,0.433474,0,0,0,0,0,4.57604e-06,5.94115e-06,5.88938e-06,0.000120619,0.0152356,0.0153429,0.00970021,0.0404509,0.0404776,0.0585768,1.06968e-10,1.07022e-10,4.31154e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +25485000,0.982605,-0.010634,-0.010534,0.185102,0.011743,-0.0364302,0.0319333,0.176444,-0.0971501,-3.5569,-1.36688e-05,-5.83476e-05,2.84839e-06,-1.17068e-05,0.00010339,-0.00122826,0.204236,0.00198353,0.433474,0,0,0,0,0,4.55234e-06,6.12339e-06,6.0692e-06,0.000119906,0.016262,0.0163874,0.00976895,0.0445104,0.0445499,0.0587229,1.07066e-10,1.0712e-10,4.24453e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +25585000,0.982592,-0.0108015,-0.0103446,0.185174,0.00712977,-0.0328382,0.0339042,0.173219,-0.0895191,-3.55513,-1.36876e-05,-5.83284e-05,2.71886e-06,-1.17068e-05,0.00010339,-0.00122765,0.204236,0.00198353,0.433474,0,0,0,0,0,4.52846e-06,5.92122e-06,5.8645e-06,0.000119201,0.0148231,0.0149462,0.00966516,0.0400783,0.0401108,0.0582745,1.06966e-10,1.07019e-10,4.17894e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +25685000,0.982599,-0.0102717,-0.0100401,0.185185,0.00580011,-0.032536,0.0231596,0.173832,-0.0928098,-3.55508,-1.36878e-05,-5.83282e-05,2.71089e-06,-1.17068e-05,0.00010339,-0.00122665,0.204236,0.00198353,0.433474,0,0,0,0,0,4.52694e-06,6.11218e-06,6.05231e-06,0.000119154,0.0158372,0.0159794,0.00981832,0.0440479,0.0440955,0.0592865,1.07065e-10,1.07117e-10,4.13093e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +25785000,0.982612,-0.0100056,-0.00932076,0.185164,-0.00479712,-0.0248295,0.0221365,0.167347,-0.0839844,-3.55783,-1.37188e-05,-5.83039e-05,2.65928e-06,-1.17068e-05,0.00010339,-0.00122474,0.204236,0.00198353,0.433474,0,0,0,0,0,4.50143e-06,5.93677e-06,5.87461e-06,0.000118462,0.0144898,0.014629,0.00971154,0.0397247,0.0397641,0.0588287,1.06901e-10,1.06952e-10,4.06777e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25885000,0.982585,-0.0100607,-0.00936525,0.185306,-0.0116767,-0.0229928,0.0246746,0.166452,-0.0863431,-3.55647,-1.37237e-05,-5.82988e-05,2.39036e-06,-1.17068e-05,0.00010339,-0.00122439,0.204236,0.00198353,0.433474,0,0,0,0,0,4.47747e-06,6.13554e-06,6.06983e-06,0.000117776,0.0154769,0.0156381,0.00978199,0.0436132,0.0436703,0.0589791,1.06999e-10,1.07049e-10,4.00598e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +25985000,0.982575,-0.0101245,-0.00950665,0.185349,-0.0197186,-0.0169223,0.0180014,0.156055,-0.0777592,-3.55676,-1.37518e-05,-5.83021e-05,2.29128e-06,-1.17068e-05,0.00010339,-0.00122344,0.204236,0.00198353,0.433474,0,0,0,0,0,4.45414e-06,5.98396e-06,5.91495e-06,0.000117096,0.0142159,0.0143728,0.00967785,0.0393912,0.0394386,0.0585251,1.06758e-10,1.06807e-10,3.94546e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +26085000,0.982596,-0.00981798,-0.00945939,0.185253,-0.0250353,-0.0165639,0.0164879,0.153762,-0.0794154,-3.55701,-1.37507e-05,-5.83032e-05,2.35047e-06,-1.17068e-05,0.00010339,-0.00122274,0.204236,0.00198353,0.433474,0,0,0,0,0,4.4295e-06,6.18993e-06,6.11657e-06,0.000116427,0.015198,0.0153788,0.00974876,0.0432082,0.0432761,0.0586706,1.06856e-10,1.06905e-10,3.88622e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +26185000,0.982584,-0.00973701,-0.00995811,0.185296,-0.0316793,-0.0110421,0.012414,0.144144,-0.0733272,-3.55996,-1.37306e-05,-5.82762e-05,2.36968e-06,-1.17068e-05,0.00010339,-0.00122077,0.204236,0.00198353,0.433474,0,0,0,0,0,4.40997e-06,6.05554e-06,5.97808e-06,0.00011576,0.014005,0.01418,0.00964535,0.0390799,0.0391363,0.0582205,1.06525e-10,1.06571e-10,3.8282e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +26285000,0.982581,-0.00979499,-0.0102693,0.185291,-0.0334152,-0.010031,0.00658046,0.140847,-0.0744037,-3.56089,-1.3733e-05,-5.82735e-05,2.23383e-06,-1.17068e-05,0.00010339,-0.00122011,0.204236,0.00198353,0.433474,0,0,0,0,0,4.40462e-06,6.26988e-06,6.18892e-06,0.000115719,0.0149897,0.0151891,0.00980077,0.042835,0.0429147,0.0592361,1.06623e-10,1.0667e-10,3.78576e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +26385000,0.982608,-0.00923292,-0.0102198,0.185179,-0.0389842,-0.00362259,0.00985153,0.128305,-0.0673219,-3.5608,-1.37243e-05,-5.82829e-05,2.1246e-06,-1.17068e-05,0.00010339,-0.00122008,0.204236,0.00198353,0.433474,0,0,0,0,0,4.37521e-06,6.14601e-06,6.0615e-06,0.000115072,0.0138523,0.014044,0.00969721,0.038793,0.0388592,0.0587768,1.06187e-10,1.06231e-10,3.72983e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +26485000,0.982612,-0.00898028,-0.0101102,0.18518,-0.0423544,-0.000922594,0.0190572,0.124241,-0.0675705,-3.55952,-1.37265e-05,-5.82806e-05,2.00446e-06,-1.17068e-05,0.00010339,-0.00122003,0.204236,0.00198353,0.433474,0,0,0,0,0,4.35071e-06,6.36528e-06,6.27667e-06,0.000114429,0.0148249,0.0150438,0.0097706,0.0424939,0.0425869,0.0589279,1.06285e-10,1.06329e-10,3.67507e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +26585000,0.982594,-0.00843697,-0.010359,0.185286,-0.0438433,0.00618307,0.0198704,0.114723,-0.0613415,-3.55924,-1.36813e-05,-5.82425e-05,1.86364e-06,-1.17068e-05,0.00010339,-0.00121813,0.204236,0.00198353,0.433474,0,0,0,0,0,4.33023e-06,6.24977e-06,6.15769e-06,0.000113788,0.0137429,0.0139524,0.00966849,0.0385305,0.0386079,0.0584729,1.05733e-10,1.05775e-10,3.62141e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +26685000,0.982584,-0.00830949,-0.0100688,0.185363,-0.0458672,0.0107762,0.019109,0.110223,-0.0604911,-3.55756,-1.36851e-05,-5.82384e-05,1.65506e-06,-1.17068e-05,0.00010339,-0.00121802,0.204236,0.00198353,0.433474,0,0,0,0,0,4.30705e-06,6.47466e-06,6.37913e-06,0.000113159,0.0147299,0.0149686,0.00974262,0.0421867,0.042294,0.058625,1.05831e-10,1.05873e-10,3.56887e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +26785000,0.982599,-0.00810477,-0.00953023,0.185319,-0.0518773,0.0141031,0.0181845,0.0984533,-0.0559139,-3.55969,-1.36059e-05,-5.8227e-05,1.5422e-06,-1.17068e-05,0.00010339,-0.00121578,0.204236,0.00198353,0.433474,0,0,0,0,0,4.28173e-06,6.36087e-06,6.26496e-06,0.000112539,0.0136926,0.0139202,0.00964061,0.0382948,0.0383842,0.0581744,1.0515e-10,1.05189e-10,3.51738e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +26885000,0.982618,-0.00749458,-0.00961902,0.185238,-0.0577987,0.016598,0.0138823,0.0929128,-0.0543807,-3.55881,-1.36048e-05,-5.82279e-05,1.59415e-06,-1.17068e-05,0.00010339,-0.00121551,0.204236,0.00198353,0.433474,0,0,0,0,0,4.25972e-06,6.59233e-06,6.49121e-06,0.000111923,0.0146924,0.0149513,0.00971418,0.0419159,0.0420386,0.0583275,1.05248e-10,1.05287e-10,3.46695e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +26985000,0.982607,-0.00696774,-0.010078,0.18529,-0.0643385,0.0220925,0.0123475,0.080953,-0.0489485,-3.56264,-1.35353e-05,-5.82002e-05,1.48842e-06,-1.17068e-05,0.00010339,-0.00121276,0.204236,0.00198353,0.433474,0,0,0,0,0,4.2577e-06,6.48157e-06,6.37902e-06,0.000111883,0.0136923,0.0139362,0.00969262,0.0380885,0.0381901,0.058731,1.04427e-10,1.04463e-10,3.43e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +27085000,0.982601,-0.00678451,-0.0104041,0.185313,-0.0669315,0.0292158,0.0162653,0.0742048,-0.0463274,-3.56579,-1.35361e-05,-5.81975e-05,1.40217e-06,-1.17068e-05,0.00010339,-0.00121108,0.204236,0.00198353,0.433474,0,0,0,0,0,4.23653e-06,6.71855e-06,6.61108e-06,0.000111273,0.014697,0.014973,0.0097683,0.0416833,0.0418216,0.0588897,1.04525e-10,1.04561e-10,3.38132e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27185000,0.982601,-0.00681733,-0.0102963,0.185316,-0.0724811,0.0339415,0.0179217,0.0641088,-0.0409758,-3.56762,-1.34483e-05,-5.81613e-05,1.32114e-06,-1.17068e-05,0.00010339,-0.00120904,0.204236,0.00198353,0.433474,0,0,0,0,0,4.21486e-06,6.60254e-06,6.49571e-06,0.000110671,0.0137207,0.0139808,0.009666,0.0379109,0.0380258,0.0584348,1.03553e-10,1.03588e-10,3.33358e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27285000,0.982602,-0.00697216,-0.0112147,0.185251,-0.0792858,0.0394816,0.120822,0.0564782,-0.0372856,-3.56554,-1.34486e-05,-5.81595e-05,1.26736e-06,-1.17068e-05,0.00010339,-0.00120794,0.204236,0.00198353,0.433474,0,0,0,0,0,4.19165e-06,6.84542e-06,6.73259e-06,0.000110076,0.0146495,0.0149405,0.00974075,0.0414849,0.0416399,0.0585946,1.03651e-10,1.03686e-10,3.28682e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27385000,0.98256,-0.00827913,-0.0136577,0.185259,-0.0834766,0.0446946,0.437353,0.047604,-0.0307127,-3.54621,-1.33577e-05,-5.80411e-05,1.21077e-06,-1.17068e-05,0.00010339,-0.00120205,0.204236,0.00198353,0.433474,0,0,0,0,0,4.17176e-06,6.7334e-06,6.61667e-06,0.000109476,0.0134305,0.0136943,0.00963889,0.03775,0.0378782,0.05814,1.02541e-10,1.02574e-10,3.24092e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +27485000,0.982503,-0.00970659,-0.0156287,0.185336,-0.0863795,0.0492538,0.756466,0.0389838,-0.0259723,-3.48836,-1.33605e-05,-5.80369e-05,1.03079e-06,-1.17068e-05,0.00010339,-0.00120096,0.204236,0.00198353,0.433474,0,0,0,0,0,4.15168e-06,6.98383e-06,6.8596e-06,0.000108885,0.0141611,0.0144487,0.00971513,0.0412662,0.0414366,0.0583009,1.02639e-10,1.02672e-10,3.19599e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +27585000,0.982522,-0.00963521,-0.0145479,0.18533,-0.0815915,0.051888,0.861938,0.030655,-0.0220415,-3.42605,-1.3208e-05,-5.79503e-05,9.78107e-07,-1.17068e-05,0.00010339,-0.0011847,0.204236,0.00198353,0.433474,0,0,0,0,0,4.14894e-06,6.86929e-06,6.75121e-06,0.000108853,0.0131991,0.0134629,0.00969971,0.0375752,0.0377154,0.0587088,1.01461e-10,1.01492e-10,3.16306e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +27685000,0.982578,-0.00848232,-0.0116492,0.185292,-0.0786752,0.0483979,0.768926,0.0225671,-0.0169296,-3.34772,-1.32069e-05,-5.79482e-05,9.57957e-07,-1.17068e-05,0.00010339,-0.00118326,0.204236,0.00198353,0.433474,0,0,0,0,0,4.12792e-06,7.10886e-06,6.99381e-06,0.00010829,0.0143047,0.0146054,0.00978008,0.0410654,0.04125,0.0588765,1.01559e-10,1.01589e-10,3.11965e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +27785000,0.9826,-0.00714744,-0.0100772,0.185322,-0.0768944,0.0449537,0.756718,0.0174056,-0.0149564,-3.27297,-1.30413e-05,-5.78609e-05,9.58523e-07,-1.17068e-05,0.00010339,-0.00118281,0.204236,0.00198353,0.433474,0,0,0,0,0,4.11042e-06,6.98245e-06,6.87144e-06,0.000107723,0.013459,0.0137401,0.0096813,0.0374313,0.0375837,0.0584225,1.00214e-10,1.00241e-10,3.07702e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27885000,0.982589,-0.00675054,-0.0101515,0.185391,-0.0838388,0.0508346,0.798323,0.00927916,-0.0101845,-3.19815,-1.30409e-05,-5.78585e-05,9.12342e-07,-1.17068e-05,0.00010339,-0.00118155,0.204236,0.00198353,0.433474,0,0,0,0,0,4.09372e-06,7.2338e-06,7.11838e-06,0.000107159,0.0144686,0.0147841,0.00975704,0.0409278,0.0411276,0.0585918,1.00312e-10,1.00339e-10,3.03528e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +27985000,0.982582,-0.00717959,-0.0105155,0.185392,-0.0843187,0.0524283,0.786254,0.00462651,-0.00871735,-3.12645,-1.28383e-05,-5.77369e-05,8.66221e-07,-1.17068e-05,0.00010339,-0.00117505,0.204236,0.00198353,0.433474,0,0,0,0,0,4.07469e-06,7.09959e-06,6.98703e-06,0.000106599,0.0136229,0.0139157,0.00965748,0.0373308,0.0374954,0.0581432,9.88046e-11,9.88278e-11,2.99427e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +28085000,0.982596,-0.00750619,-0.0105246,0.185305,-0.0882002,0.0527104,0.792339,-0.00399612,-0.00341715,-3.04861,-1.28363e-05,-5.77383e-05,9.50808e-07,-1.17068e-05,0.00010339,-0.00117469,0.204236,0.00198353,0.433474,0,0,0,0,0,4.05602e-06,7.35291e-06,7.2373e-06,0.000106048,0.0146886,0.0150177,0.00973489,0.0408369,0.0410515,0.0583136,9.89024e-11,9.8925e-11,2.95412e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +28185000,0.982592,-0.00698947,-0.0108151,0.185332,-0.087744,0.0486567,0.79858,-0.00974671,-0.00322666,-2.97334,-1.26294e-05,-5.76483e-05,9.03247e-07,-1.17068e-05,0.00010339,-0.00117047,0.204236,0.00198353,0.433474,0,0,0,0,0,4.03817e-06,7.20355e-06,7.09015e-06,0.000105501,0.0138193,0.0141223,0.00963711,0.0372681,0.0374443,0.0578704,9.72284e-11,9.72462e-11,2.91466e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +28285000,0.982605,-0.00646888,-0.0111045,0.185263,-0.0932902,0.0515472,0.799037,-0.0188506,0.00186123,-2.89643,-1.26266e-05,-5.76478e-05,9.65134e-07,-1.17068e-05,0.00010339,-0.00116936,0.204236,0.00198353,0.433474,0,0,0,0,0,4.03651e-06,7.46005e-06,7.34274e-06,0.00010547,0.0149149,0.0152528,0.00979482,0.0407909,0.0410187,0.0588967,9.73264e-11,9.73442e-11,2.88585e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +28385000,0.982587,-0.00648767,-0.0117334,0.185322,-0.0931505,0.0540912,0.800542,-0.0226659,0.00467224,-2.82239,-1.24366e-05,-5.74749e-05,1.02633e-06,-1.17068e-05,0.00010339,-0.00116467,0.204236,0.00198353,0.433474,0,0,0,0,0,4.02318e-06,7.29501e-06,7.18067e-06,0.000104924,0.0140364,0.0143455,0.00969444,0.0372406,0.0374271,0.0584459,9.54926e-11,9.5505e-11,2.84769e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +28485000,0.982578,-0.00679973,-0.0122313,0.185326,-0.0950391,0.0568853,0.801466,-0.0322128,0.0102572,-2.74767,-1.24346e-05,-5.74705e-05,9.76594e-07,-1.17068e-05,0.00010339,-0.00116274,0.204236,0.00198353,0.433474,0,0,0,0,0,4.00501e-06,7.55201e-06,7.4336e-06,0.000104391,0.0151511,0.0154968,0.00977297,0.040785,0.0410257,0.0586235,9.55898e-11,9.56021e-11,2.81031e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +28585000,0.982605,-0.0068881,-0.0122114,0.185179,-0.087928,0.0518812,0.79929,-0.0345618,0.00779392,-2.67078,-1.21361e-05,-5.73355e-05,1.01236e-06,-1.17068e-05,0.00010339,-0.00115869,0.204236,0.00198353,0.433474,0,0,0,0,0,3.98349e-06,7.36802e-06,7.25498e-06,0.000103866,0.0142574,0.0145716,0.00967581,0.0372445,0.0374408,0.0581783,9.36052e-11,9.3611e-11,2.77356e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +28685000,0.982593,-0.00667833,-0.0115986,0.185288,-0.0881599,0.0522619,0.799865,-0.043515,0.0130851,-2.59571,-1.21343e-05,-5.73309e-05,9.52338e-07,-1.17068e-05,0.00010339,-0.00115687,0.204236,0.00198353,0.433474,0,0,0,0,0,3.96912e-06,7.62216e-06,7.50749e-06,0.000103343,0.0153934,0.0157442,0.009754,0.0408158,0.041068,0.0583518,9.37021e-11,9.37079e-11,2.73755e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +28785000,0.982605,-0.00603984,-0.0114063,0.185257,-0.0833651,0.0519699,0.798826,-0.0450668,0.0148642,-2.52235,-1.19377e-05,-5.71396e-05,1.02022e-06,-1.17068e-05,0.00010339,-0.00115121,0.204236,0.00198353,0.433474,0,0,0,0,0,3.9531e-06,7.42009e-06,7.31072e-06,0.000102826,0.0144721,0.0147893,0.0096561,0.0372762,0.037481,0.0579124,9.15783e-11,9.15763e-11,2.70216e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +28885000,0.982627,-0.00585619,-0.0111452,0.185163,-0.0876941,0.0532708,0.797888,-0.0537101,0.0201579,-2.44605,-1.19344e-05,-5.71379e-05,1.06426e-06,-1.17068e-05,0.00010339,-0.00114992,0.204236,0.00198353,0.433474,0,0,0,0,0,3.95013e-06,7.67546e-06,7.56459e-06,0.000102801,0.0156312,0.015983,0.00981493,0.0408788,0.0411397,0.0589479,9.16759e-11,9.16737e-11,2.67634e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +28985000,0.982607,-0.00563022,-0.0113705,0.185263,-0.082738,0.049484,0.797439,-0.0522168,0.0192696,-2.37349,-1.16635e-05,-5.69321e-05,1.05898e-06,-1.17068e-05,0.00010339,-0.00114364,0.204236,0.00198353,0.433474,0,0,0,0,0,3.9373e-06,7.45673e-06,7.35096e-06,0.000102286,0.0146804,0.0149967,0.00971538,0.0373323,0.0375434,0.0585009,8.94288e-11,8.94175e-11,2.64209e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +29085000,0.982601,-0.00551227,-0.0114163,0.185296,-0.0859413,0.0512262,0.796773,-0.0608126,0.0243111,-2.29675,-1.16618e-05,-5.69292e-05,1.03561e-06,-1.17068e-05,0.00010339,-0.00114256,0.204236,0.00198353,0.433474,0,0,0,0,0,3.92169e-06,7.71087e-06,7.60206e-06,0.00010178,0.0158541,0.0162063,0.00979265,0.0409664,0.041235,0.0586807,8.95254e-11,8.95138e-11,2.6085e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +29185000,0.982622,-0.00545509,-0.0116376,0.185174,-0.0809956,0.0489444,0.791432,-0.0575717,0.023704,-2.22686,-1.1394e-05,-5.66817e-05,1.10691e-06,-1.17068e-05,0.00010339,-0.00113504,0.204236,0.00198353,0.433474,0,0,0,0,0,3.90308e-06,7.47519e-06,7.37192e-06,0.000101281,0.0148766,0.0151916,0.00969297,0.0374069,0.0376235,0.0582392,8.71735e-11,8.71513e-11,2.57549e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +29285000,0.982599,-0.00569696,-0.0116782,0.185285,-0.0828469,0.054377,0.793417,-0.0658134,0.0289424,-2.15017,-1.13917e-05,-5.668e-05,1.12421e-06,-1.17068e-05,0.00010339,-0.00113412,0.204236,0.00198353,0.433474,0,0,0,0,0,3.89178e-06,7.72732e-06,7.62171e-06,0.000100781,0.016062,0.016412,0.00976967,0.0410746,0.0413489,0.058419,8.727e-11,8.72474e-11,2.54311e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +29385000,0.982602,-0.00614804,-0.0111924,0.185283,-0.0773536,0.0527676,0.7958,-0.0629515,0.0299221,-2.07407,-1.1168e-05,-5.64714e-05,1.16353e-06,-1.17068e-05,0.00010339,-0.00112993,0.204236,0.00198353,0.433474,0,0,0,0,0,3.87696e-06,7.47386e-06,7.37656e-06,0.000100291,0.0150461,0.0153576,0.00967063,0.0374963,0.0377166,0.0579829,8.48331e-11,8.47988e-11,2.51129e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +29485000,0.982608,-0.00619461,-0.0110629,0.185258,-0.079775,0.0530877,0.796592,-0.0708692,0.0352721,-1.99763,-1.1163e-05,-5.64712e-05,1.28135e-06,-1.17068e-05,0.00010339,-0.00112878,0.204236,0.00198353,0.433474,0,0,0,0,0,3.86369e-06,7.72317e-06,7.62371e-06,9.98039e-05,0.0162435,0.0165897,0.0097473,0.0411968,0.0414746,0.0581626,8.49295e-11,8.48947e-11,2.48007e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +29585000,0.982619,-0.00611344,-0.011081,0.1852,-0.0738503,0.0502529,0.798636,-0.0670426,0.0344522,-1.91838,-1.09093e-05,-5.62722e-05,1.35082e-06,-1.17068e-05,0.00010339,-0.00112622,0.204236,0.00198353,0.433474,0,0,0,0,0,3.86287e-06,7.45743e-06,7.36481e-06,9.9779e-05,0.0151988,0.015504,0.00972877,0.0375964,0.037818,0.058577,8.24303e-11,8.23825e-11,2.45724e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +29685000,0.982638,-0.00617608,-0.0108758,0.18511,-0.078362,0.048905,0.793921,-0.0747994,0.0395071,-1.84392,-1.0903e-05,-5.62696e-05,1.44502e-06,-1.17068e-05,0.00010339,-0.00112433,0.204236,0.00198353,0.433474,0,0,0,0,0,3.8467e-06,7.70366e-06,7.60918e-06,9.93008e-05,0.0164104,0.0167494,0.00980556,0.0413291,0.0416077,0.0587617,8.25265e-11,8.24781e-11,2.42699e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +29785000,0.982641,-0.00603091,-0.0113965,0.18507,-0.0729939,0.0410603,0.790367,-0.0690005,0.0370632,-1.7708,-1.06487e-05,-5.60425e-05,1.55136e-06,-1.17068e-05,0.00010339,-0.00111876,0.204236,0.00198353,0.433474,0,0,0,0,0,3.83288e-06,7.42555e-06,7.33525e-06,9.88238e-05,0.0153342,0.0156341,0.00970537,0.0377021,0.0379241,0.0583228,7.99834e-11,7.99204e-11,2.39725e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +29885000,0.982639,-0.0055234,-0.0117847,0.185071,-0.0734235,0.0412499,0.786159,-0.0764625,0.0412301,-1.69916,-1.06409e-05,-5.60378e-05,1.63564e-06,-1.17068e-05,0.00010339,-0.00111614,0.204236,0.00198353,0.433474,0,0,0,0,0,3.82005e-06,7.66995e-06,7.57537e-06,9.83515e-05,0.0165509,0.0168835,0.00978285,0.0414658,0.0417439,0.0585069,8.00796e-11,8.00159e-11,2.36806e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +29985000,0.98263,-0.00562652,-0.0118417,0.18511,-0.0674259,0.036193,0.783189,-0.0710992,0.036868,-1.62871,-1.03637e-05,-5.58538e-05,1.64661e-06,-1.17068e-05,0.00010339,-0.00110971,0.204236,0.00198353,0.433474,0,0,0,0,0,3.80665e-06,7.37954e-06,7.2903e-06,9.78842e-05,0.0154417,0.0157351,0.00968183,0.0378106,0.0380316,0.0580676,7.75139e-11,7.74342e-11,2.33936e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +30085000,0.982624,-0.00577924,-0.0119885,0.185128,-0.0675414,0.0364279,0.780635,-0.0780018,0.0405873,-1.55533,-1.03626e-05,-5.58461e-05,1.50697e-06,-1.17068e-05,0.00010339,-0.0011079,0.204236,0.00198353,0.433474,0,0,0,0,0,3.78856e-06,7.61938e-06,7.52754e-06,9.74268e-05,0.0166605,0.0169858,0.00975877,0.0416023,0.0418783,0.0582507,7.76101e-11,7.75297e-11,2.31119e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +30185000,0.982596,-0.00576122,-0.0119948,0.185281,-0.0601793,0.0330536,0.780516,-0.0704535,0.0394127,-1.48262,-1.01971e-05,-5.56128e-05,1.39521e-06,-1.17068e-05,0.00010339,-0.00110319,0.204236,0.00198353,0.433474,0,0,0,0,0,3.79034e-06,7.32035e-06,7.23437e-06,9.74026e-05,0.0155223,0.0158073,0.0097397,0.0379187,0.0381367,0.0586693,7.5043e-11,7.49457e-11,2.29062e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +30285000,0.982578,-0.00579157,-0.0119986,0.185372,-0.0594672,0.032578,0.780156,-0.0765915,0.0427894,-1.41085,-1.01916e-05,-5.56069e-05,1.39857e-06,-1.17068e-05,0.00010339,-0.00110089,0.204236,0.00198353,0.433474,0,0,0,0,0,3.77898e-06,7.55575e-06,7.46742e-06,9.69441e-05,0.0167387,0.0170547,0.00981766,0.0417353,0.0420069,0.0588569,7.51391e-11,7.50411e-11,2.2633e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +30385000,0.982563,-0.00576485,-0.011903,0.185459,-0.0508885,0.0269348,0.777721,-0.0675583,0.0403694,-1.34222,-9.98964e-06,-5.53597e-05,1.53542e-06,-1.17068e-05,0.00010339,-0.00109422,0.204236,0.00198353,0.433474,0,0,0,0,0,3.77116e-06,7.24874e-06,7.16505e-06,9.64868e-05,0.0155737,0.0158522,0.0097157,0.0380217,0.0382362,0.0584139,7.2588e-11,7.24719e-11,2.23644e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +30485000,0.982587,-0.00578084,-0.0120453,0.185322,-0.0536314,0.0265204,0.778062,-0.0729668,0.0431731,-1.27106,-9.98206e-06,-5.53555e-05,1.62268e-06,-1.17068e-05,0.00010339,-0.00109177,0.204236,0.00198353,0.433474,0,0,0,0,0,3.75427e-06,7.48016e-06,7.39359e-06,9.60429e-05,0.0167868,0.0170958,0.00979185,0.0418594,0.0421261,0.0586001,7.26842e-11,7.25675e-11,2.21006e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +30585000,0.982599,-0.00608124,-0.0123208,0.18523,-0.0477447,0.023695,0.777549,-0.0650705,0.0398631,-1.19897,-9.79182e-06,-5.51592e-05,1.72441e-06,-1.17068e-05,0.00010339,-0.00108701,0.204236,0.00198353,0.433474,0,0,0,0,0,3.73951e-06,7.16907e-06,7.08603e-06,9.56003e-05,0.0155988,0.0158713,0.00968885,0.0381175,0.0383278,0.0581612,7.01662e-11,7.00307e-11,2.18411e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +30685000,0.982613,-0.00645381,-0.0125603,0.185128,-0.046167,0.0218053,0.775793,-0.0700701,0.0422741,-1.12857,-9.78548e-06,-5.51526e-05,1.73214e-06,-1.17068e-05,0.00010339,-0.00108432,0.204236,0.00198353,0.433474,0,0,0,0,0,3.72201e-06,7.39611e-06,7.31045e-06,9.51653e-05,0.0168094,0.0171122,0.00976618,0.0419725,0.0422336,0.0583458,7.02626e-11,7.01264e-11,2.15863e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +30785000,0.982635,-0.00616755,-0.0122636,0.185043,-0.0380854,0.0169032,0.77388,-0.0623517,0.0421037,-1.05879,-9.72361e-06,-5.49646e-05,1.71423e-06,-1.17068e-05,0.00010339,-0.00107937,0.204236,0.00198353,0.433474,0,0,0,0,0,3.70427e-06,7.0805e-06,6.99833e-06,9.47368e-05,0.0156031,0.0158707,0.00966506,0.0382043,0.0384098,0.0579108,6.77918e-11,6.76364e-11,2.13357e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +30885000,0.98262,-0.00553506,-0.0121295,0.185148,-0.0377573,0.0131337,0.770952,-0.0662449,0.0437278,-0.986924,-9.72024e-06,-5.49588e-05,1.6723e-06,-1.17068e-05,0.00010339,-0.00107742,0.204236,0.00198353,0.433474,0,0,0,0,0,3.70622e-06,7.30279e-06,7.21812e-06,9.47166e-05,0.0168113,0.0171071,0.00982382,0.0420741,0.0423282,0.0589502,6.78892e-11,6.77333e-11,2.11531e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +30985000,0.982615,-0.00569306,-0.0120646,0.185173,-0.0297914,0.00812403,0.772202,-0.0557408,0.0375443,-0.917578,-9.52639e-06,-5.47737e-05,1.6576e-06,-1.17068e-05,0.00010339,-0.00107214,0.204236,0.00198353,0.433474,0,0,0,0,0,3.69269e-06,6.98608e-06,6.90435e-06,9.42876e-05,0.0155858,0.0158482,0.0097198,0.0382815,0.0384813,0.058506,6.54774e-11,6.53018e-11,2.09099e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +31085000,0.982571,-0.0058395,-0.0121816,0.185394,-0.0279858,0.00559146,0.770494,-0.0587071,0.0382142,-0.844351,-9.52463e-06,-5.4769e-05,1.59929e-06,-1.17068e-05,0.00010339,-0.00107072,0.204236,0.00198353,0.433474,0,0,0,0,0,3.68493e-06,7.20343e-06,7.11882e-06,9.38569e-05,0.0167827,0.0170749,0.00979748,0.0421601,0.0424079,0.058693,6.55741e-11,6.53978e-11,2.06709e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +31185000,0.982581,-0.00597914,-0.0123167,0.185329,-0.02305,0.00212203,0.77154,-0.0499741,0.0344031,-0.774728,-9.4189e-06,-5.46194e-05,1.73365e-06,-1.17068e-05,0.00010339,-0.00106654,0.204236,0.00198353,0.433474,0,0,0,0,0,3.67268e-06,6.88738e-06,6.80463e-06,9.34346e-05,0.0155463,0.0158065,0.00969299,0.0383463,0.0385411,0.0582522,6.32314e-11,6.30355e-11,2.04358e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +31285000,0.982596,-0.00624212,-0.0124005,0.185238,-0.020007,-0.000833519,0.774751,-0.0523018,0.0345936,-0.703966,-9.41246e-06,-5.46157e-05,1.80518e-06,-1.17068e-05,0.00010339,-0.00106413,0.204236,0.00198353,0.433474,0,0,0,0,0,3.65803e-06,7.09986e-06,7.01423e-06,9.30186e-05,0.0167267,0.0170169,0.00976995,0.0422304,0.0424721,0.058432,6.33284e-11,6.31319e-11,2.02047e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +31385000,0.982602,-0.00602498,-0.0121943,0.185227,-0.0137528,-0.00666912,0.773529,-0.0434017,0.03023,-0.63155,-9.33263e-06,-5.45008e-05,1.72507e-06,-1.17068e-05,0.00010339,-0.0010603,0.204236,0.00198353,0.433474,0,0,0,0,0,3.64182e-06,6.78481e-06,6.70072e-06,9.26097e-05,0.0154861,0.0157457,0.00966657,0.0383984,0.0385884,0.0579947,6.10634e-11,6.08475e-11,1.99774e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +31485000,0.98258,-0.00577347,-0.0125136,0.185328,-0.0134037,-0.0107086,0.769752,-0.0448933,0.0293551,-0.557095,-9.33132e-06,-5.44982e-05,1.70045e-06,-1.17068e-05,0.00010339,-0.00105933,0.204236,0.00198353,0.433474,0,0,0,0,0,3.64423e-06,6.99393e-06,6.90629e-06,9.25901e-05,0.0166661,0.0169543,0.00982548,0.0422858,0.0425211,0.0590365,6.11613e-11,6.09449e-11,1.98119e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +31585000,0.9826,-0.00559374,-0.0129657,0.185197,-0.00867143,-0.0115525,0.772907,-0.0338479,0.0265992,-0.486042,-9.28285e-06,-5.43349e-05,1.77739e-06,-1.17068e-05,0.00010339,-0.00105528,0.204236,0.00198353,0.433474,0,0,0,0,0,3.62859e-06,6.683e-06,6.59484e-06,9.21834e-05,0.0154154,0.0156745,0.00971873,0.0384387,0.0386239,0.0585893,5.89782e-11,5.87426e-11,1.95912e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +31685000,0.982621,-0.00558507,-0.0134399,0.185051,-0.0105897,-0.0133216,0.768578,-0.035118,0.025391,-0.417481,-9.27504e-06,-5.43309e-05,1.8776e-06,-1.17068e-05,0.00010339,-0.00105211,0.204236,0.00198353,0.433474,0,0,0,0,0,3.61339e-06,6.8871e-06,6.79414e-06,9.17799e-05,0.0165793,0.0168692,0.00979415,0.0423239,0.0425543,0.0587704,5.90756e-11,5.88395e-11,1.93741e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +31785000,0.98263,-0.00577781,-0.0140827,0.184948,-0.00133842,-0.0147934,0.767863,-0.0235689,0.0256351,-0.346605,-9.30204e-06,-5.41451e-05,1.95477e-06,-1.17068e-05,0.00010339,-0.00104845,0.204236,0.00198353,0.433474,0,0,0,0,0,3.59899e-06,6.58045e-06,6.48672e-06,9.13788e-05,0.0153316,0.0155937,0.00968962,0.0384658,0.0386473,0.0583261,5.6979e-11,5.67244e-11,1.91605e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +31885000,0.982635,-0.00554715,-0.0138836,0.184946,0.00251226,-0.0177284,0.765934,-0.0237654,0.0240554,-0.278319,-9.29591e-06,-5.41406e-05,2.00598e-06,-1.17068e-05,0.00010339,-0.00104537,0.204236,0.00198353,0.433474,0,0,0,0,0,3.58736e-06,6.77814e-06,6.68087e-06,9.09816e-05,0.0164797,0.0167736,0.0097671,0.042347,0.0425734,0.0585053,5.70768e-11,5.68217e-11,1.89505e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +31985000,0.982622,-0.00575015,-0.0134337,0.185045,0.0103385,-0.017047,0.762048,-0.0121778,0.022859,-0.212513,-9.30368e-06,-5.39917e-05,1.95622e-06,-1.17068e-05,0.00010339,-0.00104,0.204236,0.00198353,0.433474,0,0,0,0,0,3.57618e-06,6.47326e-06,6.37789e-06,9.05876e-05,0.015235,0.0155024,0.00966194,0.0384809,0.0386595,0.058064,5.50686e-11,5.47957e-11,1.87438e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +32085000,0.982635,-0.00612982,-0.0130681,0.18499,0.0107162,-0.0211253,0.763793,-0.0113197,0.0210982,-0.142617,-9.30034e-06,-5.39879e-05,1.95433e-06,-1.17068e-05,0.00010339,-0.00103763,0.204236,0.00198353,0.433474,0,0,0,0,0,3.56157e-06,6.66597e-06,6.56807e-06,9.02006e-05,0.0163657,0.0166657,0.00973802,0.0423548,0.0425784,0.0582413,5.51666e-11,5.48934e-11,1.85406e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +32185000,0.982623,-0.00632995,-0.013326,0.185026,0.0152113,-0.022598,0.763156,-0.000650383,0.0218117,-0.0742406,-9.37556e-06,-5.38634e-05,1.93002e-06,-1.17068e-05,0.00010339,-0.00103345,0.204236,0.00198353,0.433474,0,0,0,0,0,3.56164e-06,6.36904e-06,6.27183e-06,9.01849e-05,0.0151252,0.0153975,0.00971311,0.0384848,0.0386609,0.0586503,5.32485e-11,5.29585e-11,1.83927e-10,2.97712e-06,2.97785e-06,5.0002e-08,0,0,0,0,0,0,0,0 +32285000,0.982635,-0.00624685,-0.013582,0.184945,0.0171315,-0.0265261,0.761065,0.000698499,0.0194306,-0.00622197,-9.37035e-06,-5.38601e-05,1.98583e-06,-1.17068e-05,0.00010339,-0.00103041,0.204236,0.00198353,0.433474,0,0,0,0,0,3.548e-06,6.55903e-06,6.45668e-06,8.98002e-05,0.0162446,0.0165508,0.00979077,0.0423487,0.0425699,0.0588309,5.33467e-11,5.30564e-11,1.81951e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +32385000,0.982612,-0.00628977,-0.0136819,0.185058,0.0236835,-0.0260285,0.759019,0.0114447,0.0187386,0.0655202,-9.42822e-06,-5.37694e-05,1.94447e-06,-1.17068e-05,0.00010339,-0.00102729,0.204236,0.00198353,0.433474,0,0,0,0,0,3.53794e-06,6.26685e-06,6.16408e-06,8.94153e-05,0.0150106,0.0152919,0.00968401,0.0384766,0.0386519,0.058382,5.15175e-11,5.12114e-11,1.80007e-10,2.97712e-06,2.97785e-06,5.0001e-08,0,0,0,0,0,0,0,0 +32485000,0.982628,-0.00919897,-0.0116311,0.184991,0.0492413,-0.0894199,-0.114456,0.0153349,0.0113321,0.0729831,-9.42685e-06,-5.37654e-05,1.89286e-06,-1.17068e-05,0.00010339,-0.0010268,0.204236,0.00198353,0.433474,0,0,0,0,0,3.52202e-06,6.44678e-06,6.3497e-06,8.90424e-05,0.0170111,0.0173512,0.00958522,0.0423885,0.0426107,0.0585532,5.16161e-11,5.13094e-11,1.78094e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +32585000,0.982635,-0.00920822,-0.0115925,0.184955,0.0489181,-0.0893854,-0.116898,0.0266317,0.0100204,0.0534587,-9.60682e-06,-5.36667e-05,1.97406e-06,-1.17068e-05,0.00010339,-0.0010268,0.204236,0.00198353,0.433474,0,0,0,0,0,3.51055e-06,6.14006e-06,6.04346e-06,8.86641e-05,0.0156581,0.0159697,0.00920981,0.0385239,0.0387002,0.0580621,4.97886e-11,4.94653e-11,1.76209e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +32685000,0.982637,-0.00919682,-0.0114659,0.184957,0.0458288,-0.0958108,-0.119218,0.0312753,0.000810827,0.0376049,-9.6057e-06,-5.36647e-05,1.95921e-06,-1.17068e-05,0.00010339,-0.0010268,0.204236,0.00198353,0.433474,0,0,0,0,0,3.49804e-06,6.32041e-06,6.219e-06,8.82934e-05,0.0167836,0.0171334,0.0090233,0.0424501,0.042675,0.0581551,4.98874e-11,4.95636e-11,1.74356e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +32785000,0.982636,-0.00909605,-0.0115503,0.184961,0.0441283,-0.0933375,-0.120828,0.0403032,0.000934272,0.0210709,-9.81502e-06,-5.3576e-05,2.03854e-06,-1.17068e-05,0.00010339,-0.0010268,0.204236,0.00198353,0.433474,0,0,0,0,0,3.49975e-06,6.02417e-06,5.92481e-06,8.82772e-05,0.0154497,0.015768,0.00875532,0.0385653,0.0387436,0.0584681,4.81597e-11,4.78202e-11,1.73008e-10,2.97712e-06,2.97785e-06,5e-08,0,0,0,0,0,0,0,0 +32885000,0.982653,-0.0090727,-0.0116244,0.184865,0.0451581,-0.101079,-0.122639,0.0447264,-0.00877191,0.00630319,-9.81341e-06,-5.35758e-05,2.07673e-06,-1.17068e-05,0.00010339,-0.0010268,0.204236,0.00198353,0.433474,0,0,0,0,0,3.48569e-06,6.20076e-06,6.09607e-06,8.79116e-05,0.0165549,0.0169117,0.00858685,0.0424743,0.0427028,0.0584917,4.82586e-11,4.79186e-11,1.71207e-10,2.97712e-06,2.97785e-06,5.0003e-08,0,0,0,0,0,0,0,0 +32985000,0.982661,-0.00902819,-0.0116073,0.184826,0.0430782,-0.0992671,-0.122565,0.0519263,-0.0107432,-0.00804921,-9.98989e-06,-5.35159e-05,2.18024e-06,-1.17068e-05,0.00010339,-0.00102684,0.204236,0.00198353,0.433474,0,0,0,0,0,3.47505e-06,5.91351e-06,5.81094e-06,8.75434e-05,0.0152376,0.0155644,0.00828078,0.0385769,0.0387592,0.0579087,4.66279e-11,4.62732e-11,1.6943e-10,2.97712e-06,2.97785e-06,5.00129e-08,0,0,0,0,0,0,0,0 +33085000,0.982662,-0.00900353,-0.0116442,0.184819,0.040958,-0.104714,-0.120789,0.0562533,-0.0209388,-0.0177059,-9.99064e-06,-5.35168e-05,2.17909e-06,-1.17068e-05,0.00010339,-0.00102684,0.204236,0.00198353,0.433474,0,0,0,0,0,3.46295e-06,6.08603e-06,5.97823e-06,8.71828e-05,0.0163203,0.0166862,0.00814501,0.0424644,0.0426988,0.0578719,4.67269e-11,4.63718e-11,1.67685e-10,2.97712e-06,2.97785e-06,5.00229e-08,0,0,0,0,0,0,0,0 +33185000,0.982668,-0.0089286,-0.0115896,0.184794,0.0380633,-0.103915,-0.120081,0.0619492,-0.0221233,-0.0255782,-1.01763e-05,-5.34641e-05,2.15759e-06,-1.17068e-05,0.00010339,-0.00102711,0.204236,0.00198353,0.433474,0,0,0,0,0,3.44947e-06,5.80905e-06,5.70425e-06,8.68244e-05,0.0150276,0.015362,0.007888,0.0385633,0.0387508,0.0572668,4.51906e-11,4.48216e-11,1.65964e-10,2.97712e-06,2.97785e-06,5.00304e-08,0,0,0,0,0,0,0,0 +33285000,0.98269,-0.00900885,-0.0116197,0.184673,0.0367364,-0.107897,-0.120305,0.0657166,-0.0327611,-0.0351755,-1.01747e-05,-5.34676e-05,2.27696e-06,-1.17068e-05,0.00010339,-0.00102712,0.204236,0.00198353,0.433474,0,0,0,0,0,3.43733e-06,5.97785e-06,5.86808e-06,8.64704e-05,0.0160927,0.0164668,0.00778817,0.0424268,0.0426682,0.057182,4.52896e-11,4.49203e-11,1.64273e-10,2.97712e-06,2.97785e-06,5.00403e-08,0,0,0,0,0,0,0,0 +33385000,0.982702,-0.00892379,-0.0116855,0.184607,0.0329765,-0.101062,-0.118885,0.0682008,-0.0280524,-0.0455466,-1.0451e-05,-5.34086e-05,2.33269e-06,-1.18363e-05,0.000101938,-0.00102746,0.204236,0.00198353,0.433474,0,0,0,0,0,3.42492e-06,5.71137e-06,5.6052e-06,8.61174e-05,0.0150877,0.0154291,0.00757647,0.0385294,0.038723,0.0565654,4.3843e-11,4.3461e-11,1.62605e-10,2.97709e-06,2.97782e-06,5.00418e-08,0,0,0,0,0,0,0,0 +33485000,0.982705,-0.00891644,-0.0116565,0.184594,0.0299327,-0.105614,-0.119166,0.0713059,-0.0383584,-0.0573691,-1.04506e-05,-5.3409e-05,2.35203e-06,-1.18372e-05,0.000101939,-0.00102746,0.204236,0.00198353,0.433474,0,0,0,0,0,3.42475e-06,5.87729e-06,5.76717e-06,8.61083e-05,0.0169964,0.0173753,0.00757168,0.0423769,0.0426253,0.0572529,4.39423e-11,4.35601e-11,1.61398e-10,2.9771e-06,2.97783e-06,5.00515e-08,0,0,0,0,0,0,0,0 +33585000,0.982732,-0.00877226,-0.0116359,0.184461,0.0267631,-0.101824,-0.116224,0.0730352,-0.0346377,-0.0649629,-1.06853e-05,-5.33608e-05,2.46456e-06,-1.44884e-05,7.65637e-05,-0.00102818,0.204236,0.00198353,0.433474,0,0,0,0,0,3.41191e-06,5.62185e-06,5.51592e-06,8.57598e-05,0.0169729,0.0173138,0.00739897,0.0384959,0.0386952,0.0566171,4.25853e-11,4.21912e-11,1.59774e-10,2.96258e-06,2.9633e-06,5.00436e-08,0,0,0,0,0,0,0,0 +33685000,0.982742,-0.00877507,-0.0116441,0.184408,0.0239944,-0.106488,-0.118145,0.0756969,-0.0451293,-0.0744545,-1.0685e-05,-5.33628e-05,2.51548e-06,-1.44759e-05,7.65519e-05,-0.00102822,0.204236,0.00198353,0.433474,0,0,0,0,0,3.40033e-06,5.78403e-06,5.67334e-06,8.54155e-05,0.0199572,0.0203365,0.00736552,0.042385,0.0426412,0.0564691,4.26843e-11,4.229e-11,1.58179e-10,2.96259e-06,2.96331e-06,5.00523e-08,0,0,0,0,0,0,0,0 +33785000,0.982755,-0.00869537,-0.0116375,0.184343,0.0195904,-0.100494,-0.11306,0.0781953,-0.0401645,-0.0820043,-1.09153e-05,-5.32922e-05,2.51753e-06,-2.26966e-05,2.88105e-05,-0.00102908,0.204236,0.00198353,0.433474,0,0,0,0,0,3.38679e-06,5.54594e-06,5.43987e-06,8.50741e-05,0.0204556,0.020785,0.00722918,0.0385292,0.0387338,0.0558421,4.14336e-11,4.10287e-11,1.56605e-10,2.91153e-06,2.91224e-06,5.00314e-08,0,0,0,0,0,0,0,0 +33885000,0.982771,-0.00874392,-0.0116152,0.184254,0.0172745,-0.102047,-0.112944,0.0801056,-0.0503898,-0.0902454,-1.09143e-05,-5.32954e-05,2.6191e-06,-2.26508e-05,2.87644e-05,-0.00102917,0.204236,0.00198353,0.433474,0,0,0,0,0,3.37569e-06,5.70523e-06,5.5947e-06,8.47351e-05,0.0243678,0.0247321,0.00722525,0.0425683,0.0428296,0.0556771,4.15326e-11,4.11275e-11,1.55058e-10,2.91153e-06,2.91225e-06,5.00384e-08,0,0,0,0,0,0,0,0 +33985000,0.982766,-0.00862185,-0.0117349,0.184282,0.0147054,-0.0906475,-0.10994,0.0812002,-0.0423503,-0.0949387,-1.11593e-05,-5.32154e-05,2.60838e-06,-4.63715e-05,-4.47352e-05,-0.00103029,0.204236,0.00198353,0.433474,0,0,0,0,0,3.36488e-06,5.4957e-06,5.38938e-06,8.43972e-05,0.0248338,0.0251345,0.00712175,0.0387167,0.0389227,0.0550684,4.04197e-11,4.00053e-11,1.53532e-10,2.81062e-06,2.81134e-06,5.00049e-08,0,0,0,0,0,0,0,0 +34085000,0.982772,-0.00856746,-0.0117581,0.18425,0.0123634,-0.0951862,-0.109345,0.0827278,-0.051724,-0.102744,-1.116e-05,-5.32173e-05,2.63084e-06,-4.62414e-05,-4.48515e-05,-0.00103042,0.204236,0.00198353,0.433474,0,0,0,0,0,3.36425e-06,5.65336e-06,5.54316e-06,8.43907e-05,0.0294702,0.0297973,0.00719854,0.0430246,0.0432836,0.0556688,4.05189e-11,4.01045e-11,1.52429e-10,2.81062e-06,2.81135e-06,5.00106e-08,0,0,0,0,0,0,0,0 +34185000,0.982774,-0.00851571,-0.0117801,0.184238,0.00802194,-0.0820174,-0.107552,0.0839748,-0.0435718,-0.105839,-1.13615e-05,-5.31519e-05,2.69221e-06,-6.81831e-05,-0.000125118,-0.00103142,0.204236,0.00198353,0.433474,0,0,0,0,0,3.35436e-06,5.48432e-06,5.37788e-06,8.40557e-05,0.0293323,0.0295865,0.00712155,0.0391142,0.0393146,0.0550703,3.95761e-11,3.91539e-11,1.50944e-10,2.65805e-06,2.6588e-06,5.00035e-08,0,0,0,0,0,0,0,0 +34285000,0.98278,-0.00841638,-0.0118587,0.184205,0.00903711,-0.0849214,-0.106766,0.0849571,-0.0520017,-0.11399,-1.13611e-05,-5.31543e-05,2.76257e-06,-6.80441e-05,-0.000125253,-0.00103156,0.204236,0.00198353,0.433474,0,0,0,0,0,3.34443e-06,5.64005e-06,5.52905e-06,8.37251e-05,0.0344348,0.0347103,0.00717027,0.043779,0.0440281,0.0549044,3.9675e-11,3.92527e-11,1.49482e-10,2.65804e-06,2.6588e-06,5.00036e-08,0,0,0,0,0,0,0,0 +34385000,0.982807,-0.00832584,-0.0118523,0.184068,0.00525989,-0.0690006,-0.102256,0.0842466,-0.042816,-0.118378,-1.15319e-05,-5.31094e-05,2.8045e-06,-9.08538e-05,-0.000208521,-0.00103332,0.204236,0.00198353,0.433474,0,0,0,0,0,3.33041e-06,5.52142e-06,5.41306e-06,8.34006e-05,0.0332581,0.0334589,0.00711916,0.0397167,0.0399052,0.0543401,3.89219e-11,3.84935e-11,1.48041e-10,2.46325e-06,2.46407e-06,5.0001e-08,0,0,0,0,0,0,0,0 +34485000,0.982814,-0.00842162,-0.0118046,0.18403,0.00348116,-0.0715852,-0.10102,0.0849147,-0.0500041,-0.122781,-1.15325e-05,-5.31134e-05,2.88056e-06,-9.03716e-05,-0.000208964,-0.00103375,0.204236,0.00198353,0.433474,0,0,0,0,0,3.32069e-06,5.67624e-06,5.56398e-06,8.30756e-05,0.0385674,0.0387831,0.00718953,0.0447797,0.0450095,0.0541885,3.90208e-11,3.85924e-11,1.46623e-10,2.46323e-06,2.46406e-06,5e-08,0,0,0,0,0,0,0,0 +34585000,0.982823,-0.00833915,-0.0116051,0.183997,0.0027806,-0.0561772,0.644549,0.0841761,-0.0415566,-0.0986137,-1.16553e-05,-5.30797e-05,2.90924e-06,-0.000111509,-0.000277478,-0.00103546,0.204236,0.00198353,0.433474,0,0,0,0,0,3.30967e-06,5.61149e-06,5.50108e-06,8.27547e-05,0.0358371,0.035972,0.00716121,0.040452,0.0406218,0.0536628,3.84569e-11,3.8024e-11,1.45225e-10,2.24283e-06,2.24376e-06,5e-08,0,0,0,0,0,0,0,0 +34685000,0.982834,-0.00833304,-0.0113307,0.183958,0.00248116,-0.0530313,1.63504,0.084366,-0.0469874,0.0134936,-1.16541e-05,-5.30793e-05,2.93463e-06,-0.000111736,-0.000277283,-0.00103528,0.204236,0.00198353,0.433474,0,0,0,0,0,3.29867e-06,5.76624e-06,5.65227e-06,8.24372e-05,0.0407003,0.0408266,0.00725105,0.0458078,0.046008,0.0535321,3.85559e-11,3.81229e-11,1.43849e-10,2.24281e-06,2.24374e-06,5e-08,0,0,0,0,0,0,0,0 +34785000,0.982844,-0.00821583,-0.0109656,0.183931,-0.00314714,-0.0357618,2.60191,0.0796183,-0.0369435,0.175975,-1.17536e-05,-5.30722e-05,2.94825e-06,-0.000127745,-0.000334588,-0.00100953,0.204236,0.00198353,0.433474,0,0,0,0,0,3.29788e-06,5.76905e-06,5.65562e-06,8.24328e-05,0.0371847,0.0372545,0.00729059,0.041191,0.0413361,0.0537641,3.82087e-11,3.77726e-11,1.42854e-10,2.00846e-06,2.00948e-06,5.0002e-08,0,0,0,0,0,0,0,0 +34885000,0.982854,-0.00819718,-0.0106726,0.183895,-0.00393548,-0.0318316,3.58742,0.0785792,-0.0400332,0.46539,-1.17458e-05,-5.30635e-05,2.97014e-06,-0.000130364,-0.000332251,-0.00100736,0.204236,0.00198353,0.433474,0,0,0,0,0,3.28697e-06,5.92527e-06,5.80826e-06,8.21183e-05,0.0420439,0.042107,0.00739764,0.046766,0.04693,0.0536569,3.83077e-11,3.78716e-11,1.41513e-10,2.00842e-06,2.00945e-06,5.0001e-08,0,0,0,0,0,0,0,0 diff --git a/src/lib/ecl/test/replay_data/ekf_gsf_reset.csv b/src/modules/ekf2/test/replay_data/ekf_gsf_reset.csv similarity index 100% rename from src/lib/ecl/test/replay_data/ekf_gsf_reset.csv rename to src/modules/ekf2/test/replay_data/ekf_gsf_reset.csv diff --git a/src/lib/ecl/test/replay_data/iris_gps.csv b/src/modules/ekf2/test/replay_data/iris_gps.csv similarity index 100% rename from src/lib/ecl/test/replay_data/iris_gps.csv rename to src/modules/ekf2/test/replay_data/iris_gps.csv diff --git a/src/lib/ecl/test/sensor_simulator/.gitignore b/src/modules/ekf2/test/sensor_simulator/.gitignore similarity index 100% rename from src/lib/ecl/test/sensor_simulator/.gitignore rename to src/modules/ekf2/test/sensor_simulator/.gitignore diff --git a/src/lib/ecl/test/sensor_simulator/CMakeLists.txt b/src/modules/ekf2/test/sensor_simulator/CMakeLists.txt similarity index 100% rename from src/lib/ecl/test/sensor_simulator/CMakeLists.txt rename to src/modules/ekf2/test/sensor_simulator/CMakeLists.txt diff --git a/src/lib/ecl/test/sensor_simulator/airspeed.cpp b/src/modules/ekf2/test/sensor_simulator/airspeed.cpp similarity index 80% rename from src/lib/ecl/test/sensor_simulator/airspeed.cpp rename to src/modules/ekf2/test/sensor_simulator/airspeed.cpp index 6b7e35979e..520aca024e 100644 --- a/src/lib/ecl/test/sensor_simulator/airspeed.cpp +++ b/src/modules/ekf2/test/sensor_simulator/airspeed.cpp @@ -5,7 +5,7 @@ namespace sensor_simulator namespace sensor { -Airspeed::Airspeed(std::shared_ptr ekf):Sensor(ekf) +Airspeed::Airspeed(std::shared_ptr ekf): Sensor(ekf) { } @@ -15,8 +15,7 @@ Airspeed::~Airspeed() void Airspeed::send(uint64_t time) { - if(_true_airspeed_data > FLT_EPSILON && _indicated_airspeed_data > FLT_EPSILON) - { + if (_true_airspeed_data > FLT_EPSILON && _indicated_airspeed_data > FLT_EPSILON) { airspeedSample airspeed_sample; airspeed_sample.time_us = time; airspeed_sample.eas2tas = _true_airspeed_data / _indicated_airspeed_data; diff --git a/src/lib/ecl/test/sensor_simulator/airspeed.h b/src/modules/ekf2/test/sensor_simulator/airspeed.h similarity index 96% rename from src/lib/ecl/test/sensor_simulator/airspeed.h rename to src/modules/ekf2/test/sensor_simulator/airspeed.h index 79dcd87ebd..0ac4aa5c89 100644 --- a/src/lib/ecl/test/sensor_simulator/airspeed.h +++ b/src/modules/ekf2/test/sensor_simulator/airspeed.h @@ -35,7 +35,8 @@ * Feeds Ekf with airspeed data * @author Kamil Ritz */ -#pragma once +#ifndef EKF_AIRSPEED_H +#define EKF_AIRSPEED_H #include "sensor.h" @@ -62,3 +63,4 @@ private: } // namespace sensor } // namespace sensor_simulator +#endif // !EKF_AIRSPEED_H diff --git a/src/lib/ecl/test/sensor_simulator/baro.cpp b/src/modules/ekf2/test/sensor_simulator/baro.cpp similarity index 85% rename from src/lib/ecl/test/sensor_simulator/baro.cpp rename to src/modules/ekf2/test/sensor_simulator/baro.cpp index 75a25a7cd4..94c1884f16 100644 --- a/src/lib/ecl/test/sensor_simulator/baro.cpp +++ b/src/modules/ekf2/test/sensor_simulator/baro.cpp @@ -5,7 +5,7 @@ namespace sensor_simulator namespace sensor { -Baro::Baro(std::shared_ptr ekf):Sensor(ekf) +Baro::Baro(std::shared_ptr ekf): Sensor(ekf) { } diff --git a/src/lib/ecl/test/sensor_simulator/baro.h b/src/modules/ekf2/test/sensor_simulator/baro.h similarity index 97% rename from src/lib/ecl/test/sensor_simulator/baro.h rename to src/modules/ekf2/test/sensor_simulator/baro.h index fbe5a9c597..9ce6ac551e 100644 --- a/src/lib/ecl/test/sensor_simulator/baro.h +++ b/src/modules/ekf2/test/sensor_simulator/baro.h @@ -35,7 +35,8 @@ * Feeds Ekf with Mag data * @author Kamil Ritz */ -#pragma once +#ifndef EKF_BARO_H +#define EKF_BARO_H #include "sensor.h" @@ -61,3 +62,4 @@ private: } // namespace sensor } // namespace sensor_simulator +#endif // !EKF_BARO_H diff --git a/src/lib/ecl/test/sensor_simulator/convertULogToSensorData.py b/src/modules/ekf2/test/sensor_simulator/convertULogToSensorData.py similarity index 100% rename from src/lib/ecl/test/sensor_simulator/convertULogToSensorData.py rename to src/modules/ekf2/test/sensor_simulator/convertULogToSensorData.py diff --git a/src/lib/ecl/test/sensor_simulator/createSensorDataFile.py b/src/modules/ekf2/test/sensor_simulator/createSensorDataFile.py similarity index 100% rename from src/lib/ecl/test/sensor_simulator/createSensorDataFile.py rename to src/modules/ekf2/test/sensor_simulator/createSensorDataFile.py diff --git a/src/lib/ecl/test/sensor_simulator/ekf_logger.cpp b/src/modules/ekf2/test/sensor_simulator/ekf_logger.cpp similarity index 67% rename from src/lib/ecl/test/sensor_simulator/ekf_logger.cpp rename to src/modules/ekf2/test/sensor_simulator/ekf_logger.cpp index 4ff9f7beca..3fed179244 100644 --- a/src/lib/ecl/test/sensor_simulator/ekf_logger.cpp +++ b/src/modules/ekf2/test/sensor_simulator/ekf_logger.cpp @@ -1,8 +1,8 @@ #include "ekf_logger.h" EkfLogger::EkfLogger(std::shared_ptr ekf): -_ekf{ekf}, -_ekf_wrapper(ekf) + _ekf{ekf}, + _ekf_wrapper(ekf) { } @@ -16,62 +16,58 @@ void EkfLogger::setFilePath(std::string file_path) void EkfLogger::writeStateToFile() { - if(!_file_opened) - { + if (!_file_opened) { _file.open(_file_path); _file_opened = true; _file << "Timestamp"; - if(_state_logging_enabled) - { - for(int i = 0; i < 24; i++) - { + + if (_state_logging_enabled) { + for (int i = 0; i < 24; i++) { _file << ",state[" << i << "]"; } } - if(_variance_logging_enabled) - { - for(int i = 0; i < 24; i++) - { + + if (_variance_logging_enabled) { + for (int i = 0; i < 24; i++) { _file << ",variance[" << i << "]"; } } + _file << std::endl; } - if (_file) - { + if (_file) { writeState(); - } - else - { + + } else { std::cerr << "Can not write to output file" << std::endl; - std::exit(-1); + system_exit(-1); } } void EkfLogger::writeState() { - if(_state_logging_enabled) - { + if (_state_logging_enabled) { uint64_t time = _ekf->get_imu_sample_delayed().time_us; _file << time; - if(_state_logging_enabled) - { + + if (_state_logging_enabled) { matrix::Vector state = _ekf->getStateAtFusionHorizonAsVector(); - for(int i = 0; i < 24; i++) - { + + for (int i = 0; i < 24; i++) { _file << "," << state(i); } } - if(_variance_logging_enabled) - { + + if (_variance_logging_enabled) { matrix::Vector variance = _ekf->covariances_diagonal(); - for(int i = 0; i < 24; i++) - { + + for (int i = 0; i < 24; i++) { _file << "," << variance(i); } } + _file << std::endl; } } diff --git a/src/lib/ecl/test/sensor_simulator/ekf_logger.h b/src/modules/ekf2/test/sensor_simulator/ekf_logger.h similarity index 87% rename from src/lib/ecl/test/sensor_simulator/ekf_logger.h rename to src/modules/ekf2/test/sensor_simulator/ekf_logger.h index e23cde194a..824b8bbdab 100644 --- a/src/lib/ecl/test/sensor_simulator/ekf_logger.h +++ b/src/modules/ekf2/test/sensor_simulator/ekf_logger.h @@ -35,7 +35,8 @@ * Class to write EKF state to file * @author Kamil Ritz */ -#pragma once +#ifndef EKF_EKF_LOGGER_H +#define EKF_EKF_LOGGER_H #include "EKF/ekf.h" #include "EKF/estimator_interface.h" @@ -50,10 +51,10 @@ public: ~EkfLogger(); void setFilePath(std::string file_path); - void enableStateLogging(){ _state_logging_enabled = true; }; - void disableStateLogging(){ _state_logging_enabled = false; }; - void enableVarianceLogging(){ _variance_logging_enabled = true; }; - void disableVarianceLogging(){ _variance_logging_enabled = false; }; + void enableStateLogging() { _state_logging_enabled = true; }; + void disableStateLogging() { _state_logging_enabled = false; }; + void enableVarianceLogging() { _variance_logging_enabled = true; }; + void disableVarianceLogging() { _variance_logging_enabled = false; }; void writeStateToFile(); @@ -72,3 +73,4 @@ private: void writeState(); }; +#endif // !EKF_EKF_LOGGER_H diff --git a/src/lib/ecl/test/sensor_simulator/ekf_wrapper.cpp b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp similarity index 98% rename from src/lib/ecl/test/sensor_simulator/ekf_wrapper.cpp rename to src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp index ed8890eb0a..e90e01282f 100644 --- a/src/lib/ecl/test/sensor_simulator/ekf_wrapper.cpp +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.cpp @@ -1,7 +1,7 @@ #include "ekf_wrapper.h" EkfWrapper::EkfWrapper(std::shared_ptr ekf): -_ekf{ekf} + _ekf{ekf} { _ekf_params = _ekf->getParamHandle(); } @@ -235,5 +235,5 @@ int EkfWrapper::getQuaternionResetCounter() const matrix::Vector3f EkfWrapper::getDeltaVelBiasVariance() const { - return _ekf->covariances_diagonal().slice<3, 1>(13,0); + return _ekf->covariances_diagonal().slice<3, 1>(13, 0); } diff --git a/src/lib/ecl/test/sensor_simulator/ekf_wrapper.h b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h similarity index 97% rename from src/lib/ecl/test/sensor_simulator/ekf_wrapper.h rename to src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h index c7ef60ec4d..80b4cc0644 100644 --- a/src/lib/ecl/test/sensor_simulator/ekf_wrapper.h +++ b/src/modules/ekf2/test/sensor_simulator/ekf_wrapper.h @@ -35,7 +35,8 @@ * Wrapper class for Ekf object to set behavior or check status * @author Kamil Ritz */ -#pragma once +#ifndef EKF_EKF_WRAPPER_H +#define EKF_EKF_WRAPPER_H #include #include "EKF/ekf.h" @@ -113,6 +114,7 @@ private: std::shared_ptr _ekf; // Pointer to Ekf internal param struct - parameters* _ekf_params; + parameters *_ekf_params; }; +#endif // !EKF_EKF_WRAPPER_H diff --git a/src/lib/ecl/test/sensor_simulator/flow.cpp b/src/modules/ekf2/test/sensor_simulator/flow.cpp similarity index 85% rename from src/lib/ecl/test/sensor_simulator/flow.cpp rename to src/modules/ekf2/test/sensor_simulator/flow.cpp index 2ef66d019d..400cb66b70 100644 --- a/src/lib/ecl/test/sensor_simulator/flow.cpp +++ b/src/modules/ekf2/test/sensor_simulator/flow.cpp @@ -5,7 +5,7 @@ namespace sensor_simulator namespace sensor { -Flow::Flow(std::shared_ptr ekf):Sensor(ekf) +Flow::Flow(std::shared_ptr ekf): Sensor(ekf) { } @@ -19,7 +19,7 @@ void Flow::send(uint64_t time) _ekf->setOpticalFlowData(_flow_data); } -void Flow::setData(const flowSample& flow) +void Flow::setData(const flowSample &flow) { _flow_data = flow; diff --git a/src/lib/ecl/test/sensor_simulator/flow.h b/src/modules/ekf2/test/sensor_simulator/flow.h similarity index 95% rename from src/lib/ecl/test/sensor_simulator/flow.h rename to src/modules/ekf2/test/sensor_simulator/flow.h index 9dca908093..4820fedfd8 100644 --- a/src/lib/ecl/test/sensor_simulator/flow.h +++ b/src/modules/ekf2/test/sensor_simulator/flow.h @@ -35,7 +35,8 @@ * Feeds Ekf with optical flow data * @author Kamil Ritz */ -#pragma once +#ifndef EKF_FLOW_H +#define EKF_FLOW_H #include "sensor.h" @@ -50,7 +51,7 @@ public: Flow(std::shared_ptr ekf); ~Flow(); - void setData(const flowSample& flow); + void setData(const flowSample &flow); flowSample dataAtRest(); private: @@ -62,3 +63,4 @@ private: } // namespace sensor } // namespace sensor_simulator +#endif // !EKF_FLOW_H diff --git a/src/lib/ecl/test/sensor_simulator/gps.cpp b/src/modules/ekf2/test/sensor_simulator/gps.cpp similarity index 89% rename from src/lib/ecl/test/sensor_simulator/gps.cpp rename to src/modules/ekf2/test/sensor_simulator/gps.cpp index 40229b786c..47bd63f71f 100644 --- a/src/lib/ecl/test/sensor_simulator/gps.cpp +++ b/src/modules/ekf2/test/sensor_simulator/gps.cpp @@ -5,7 +5,7 @@ namespace sensor_simulator namespace sensor { -Gps::Gps(std::shared_ptr ekf):Sensor(ekf) +Gps::Gps(std::shared_ptr ekf): Sensor(ekf) { } @@ -22,6 +22,7 @@ void Gps::send(const uint64_t time) if (fabsf(_gps_pos_rate(0)) > FLT_EPSILON || fabsf(_gps_pos_rate(1)) > FLT_EPSILON) { stepHorizontalPositionByMeters(Vector2f(_gps_pos_rate) * dt); } + if (fabsf(_gps_pos_rate(2)) > FLT_EPSILON) { stepHeightByMeters(-_gps_pos_rate(2) * dt); } @@ -29,7 +30,7 @@ void Gps::send(const uint64_t time) _ekf->setGpsData(_gps_data); } -void Gps::setData(const gps_message& gps) +void Gps::setData(const gps_message &gps) { _gps_data = gps; } @@ -49,16 +50,18 @@ void Gps::setLongitude(const int32_t lon) _gps_data.lon = lon; } -void Gps::setVelocity(const Vector3f& vel) +void Gps::setVelocity(const Vector3f &vel) { _gps_data.vel_ned = vel; } -void Gps::setYaw(const float yaw) { +void Gps::setYaw(const float yaw) +{ _gps_data.yaw = yaw; } -void Gps::setYawOffset(const float yaw_offset) { +void Gps::setYawOffset(const float yaw_offset) +{ _gps_data.yaw_offset = yaw_offset; } @@ -77,7 +80,7 @@ void Gps::setPdop(const float pdop) _gps_data.pdop = pdop; } -void Gps::setPositionRateNED(const Vector3f& rate) +void Gps::setPositionRateNED(const Vector3f &rate) { _gps_pos_rate = rate; } diff --git a/src/lib/ecl/test/sensor_simulator/gps.h b/src/modules/ekf2/test/sensor_simulator/gps.h similarity index 93% rename from src/lib/ecl/test/sensor_simulator/gps.h rename to src/modules/ekf2/test/sensor_simulator/gps.h index d5d50860fe..f21087879f 100644 --- a/src/lib/ecl/test/sensor_simulator/gps.h +++ b/src/modules/ekf2/test/sensor_simulator/gps.h @@ -35,7 +35,8 @@ * Feeds Ekf with Gps data * @author Kamil Ritz */ -#pragma once +#ifndef EKF_GPS_H +#define EKF_GPS_H #include "sensor.h" @@ -50,14 +51,14 @@ public: Gps(std::shared_ptr ekf); ~Gps(); - void setData(const gps_message& gps); + void setData(const gps_message &gps); void stepHeightByMeters(const float hgt_change); void stepHorizontalPositionByMeters(const Vector2f hpos_change); - void setPositionRateNED(const Vector3f& rate); + void setPositionRateNED(const Vector3f &rate); void setAltitude(const int32_t alt); void setLatitude(const int32_t lat); void setLongitude(const int32_t lon); - void setVelocity(const Vector3f& vel); + void setVelocity(const Vector3f &vel); void setYaw(const float yaw); void setYawOffset(const float yaw); void setFixType(const int fix_type); @@ -75,3 +76,4 @@ private: } // namespace sensor } // namespace sensor_simulator +#endif // EKF_GPS_H diff --git a/src/lib/ecl/test/sensor_simulator/imu.cpp b/src/modules/ekf2/test/sensor_simulator/imu.cpp similarity index 75% rename from src/lib/ecl/test/sensor_simulator/imu.cpp rename to src/modules/ekf2/test/sensor_simulator/imu.cpp index 78d13f7a80..bcde2038ff 100644 --- a/src/lib/ecl/test/sensor_simulator/imu.cpp +++ b/src/modules/ekf2/test/sensor_simulator/imu.cpp @@ -5,7 +5,7 @@ namespace sensor_simulator namespace sensor { -Imu::Imu(std::shared_ptr ekf):Sensor(ekf) +Imu::Imu(std::shared_ptr ekf): Sensor(ekf) { } @@ -26,18 +26,18 @@ void Imu::send(uint64_t time) _ekf->setIMUData(imu_sample); } -void Imu::setData(const Vector3f& accel, const Vector3f& gyro) +void Imu::setData(const Vector3f &accel, const Vector3f &gyro) { setAccelData(accel); setGyroData(gyro); } -void Imu::setAccelData(const Vector3f& accel) +void Imu::setAccelData(const Vector3f &accel) { _accel_data = accel; } -void Imu::setGyroData(const Vector3f& gyro) +void Imu::setGyroData(const Vector3f &gyro) { _gyro_data = gyro; } diff --git a/src/lib/ecl/test/sensor_simulator/imu.h b/src/modules/ekf2/test/sensor_simulator/imu.h similarity index 91% rename from src/lib/ecl/test/sensor_simulator/imu.h rename to src/modules/ekf2/test/sensor_simulator/imu.h index bdd2632b92..9921b60fe4 100644 --- a/src/lib/ecl/test/sensor_simulator/imu.h +++ b/src/modules/ekf2/test/sensor_simulator/imu.h @@ -35,7 +35,8 @@ * Feeds Ekf with Imu data * @author Kamil Ritz */ -#pragma once +#ifndef EKF_IMU_H +#define EKF_IMU_H #include "sensor.h" @@ -50,9 +51,9 @@ public: Imu(std::shared_ptr ekf); ~Imu(); - void setData(const Vector3f& accel, const Vector3f& gyro); - void setAccelData(const Vector3f& accel); - void setGyroData(const Vector3f& gyro); + void setData(const Vector3f &accel, const Vector3f &gyro); + void setAccelData(const Vector3f &accel); + void setGyroData(const Vector3f &gyro); private: Vector3f _accel_data; @@ -64,3 +65,4 @@ private: } // namespace sensor } // namespace sensor_simulator +#endif // EKF_IMU_H diff --git a/src/lib/ecl/test/sensor_simulator/mag.cpp b/src/modules/ekf2/test/sensor_simulator/mag.cpp similarity index 74% rename from src/lib/ecl/test/sensor_simulator/mag.cpp rename to src/modules/ekf2/test/sensor_simulator/mag.cpp index 482af9c179..6a407b9c65 100644 --- a/src/lib/ecl/test/sensor_simulator/mag.cpp +++ b/src/modules/ekf2/test/sensor_simulator/mag.cpp @@ -5,7 +5,7 @@ namespace sensor_simulator namespace sensor { -Mag::Mag(std::shared_ptr ekf):Sensor(ekf) +Mag::Mag(std::shared_ptr ekf): Sensor(ekf) { } @@ -18,7 +18,7 @@ void Mag::send(uint64_t time) _ekf->setMagData(magSample{time, _mag_data}); } -void Mag::setData(const Vector3f& mag) +void Mag::setData(const Vector3f &mag) { _mag_data = mag; } diff --git a/src/lib/ecl/test/sensor_simulator/mag.h b/src/modules/ekf2/test/sensor_simulator/mag.h similarity index 95% rename from src/lib/ecl/test/sensor_simulator/mag.h rename to src/modules/ekf2/test/sensor_simulator/mag.h index 8b659ff672..5cfed8b892 100644 --- a/src/lib/ecl/test/sensor_simulator/mag.h +++ b/src/modules/ekf2/test/sensor_simulator/mag.h @@ -35,7 +35,8 @@ * Feeds Ekf with Mag data * @author Kamil Ritz */ -#pragma once +#ifndef EKF_MAG_H +#define EKF_MAG_H #include "sensor.h" @@ -50,7 +51,7 @@ public: Mag(std::shared_ptr ekf); ~Mag(); - void setData(const Vector3f& mag); + void setData(const Vector3f &mag); private: Vector3f _mag_data; @@ -61,3 +62,4 @@ private: } // namespace sensor } // namespace sensor_simulator +#endif // !EKF_MAG_H diff --git a/src/lib/ecl/test/sensor_simulator/range_finder.cpp b/src/modules/ekf2/test/sensor_simulator/range_finder.cpp similarity index 90% rename from src/lib/ecl/test/sensor_simulator/range_finder.cpp rename to src/modules/ekf2/test/sensor_simulator/range_finder.cpp index 489bdd3304..2cfdf2e2e0 100644 --- a/src/lib/ecl/test/sensor_simulator/range_finder.cpp +++ b/src/modules/ekf2/test/sensor_simulator/range_finder.cpp @@ -5,7 +5,7 @@ namespace sensor_simulator namespace sensor { -RangeFinder::RangeFinder(std::shared_ptr ekf):Sensor(ekf) +RangeFinder::RangeFinder(std::shared_ptr ekf): Sensor(ekf) { } diff --git a/src/lib/ecl/test/sensor_simulator/range_finder.h b/src/modules/ekf2/test/sensor_simulator/range_finder.h similarity index 96% rename from src/lib/ecl/test/sensor_simulator/range_finder.h rename to src/modules/ekf2/test/sensor_simulator/range_finder.h index ab126311c8..24025bdcfc 100644 --- a/src/lib/ecl/test/sensor_simulator/range_finder.h +++ b/src/modules/ekf2/test/sensor_simulator/range_finder.h @@ -35,7 +35,8 @@ * Feeds Ekf with range finder data * @author Kamil Ritz */ -#pragma once +#ifndef EKF_RANGE_FINDER_H +#define EKF_RANGE_FINDER_H #include "sensor.h" @@ -63,3 +64,4 @@ private: } // namespace sensor } // namespace sensor_simulator +#endif // !EKF_RANGE_FINDER_H diff --git a/src/lib/ecl/test/sensor_simulator/sensor.cpp b/src/modules/ekf2/test/sensor_simulator/sensor.cpp similarity index 95% rename from src/lib/ecl/test/sensor_simulator/sensor.cpp rename to src/modules/ekf2/test/sensor_simulator/sensor.cpp index dea0974b1b..67a29bb881 100644 --- a/src/lib/ecl/test/sensor_simulator/sensor.cpp +++ b/src/modules/ekf2/test/sensor_simulator/sensor.cpp @@ -13,8 +13,7 @@ Sensor::~Sensor() void Sensor::update(uint64_t time) { - if(should_send(time)) - { + if (should_send(time)) { send(time); _time_last_data_sent = time; } diff --git a/src/lib/ecl/test/sensor_simulator/sensor.h b/src/modules/ekf2/test/sensor_simulator/sensor.h similarity index 92% rename from src/lib/ecl/test/sensor_simulator/sensor.h rename to src/modules/ekf2/test/sensor_simulator/sensor.h index 813287fb75..271960eb47 100644 --- a/src/lib/ecl/test/sensor_simulator/sensor.h +++ b/src/modules/ekf2/test/sensor_simulator/sensor.h @@ -36,7 +36,8 @@ * @author Kamil Ritz */ -#pragma once +#ifndef EKF_SENSOR_H +#define EKF_SENSOR_H #include "EKF/ekf.h" #include @@ -54,13 +55,13 @@ public: void update(uint64_t time); - void setRateHz(uint32_t rate){ _update_period = uint32_t(1000000)/rate; } + void setRateHz(uint32_t rate) { _update_period = uint32_t(1000000) / rate; } bool isRunning() const { return _is_running; } - void start(){ _is_running = true; } + void start() { _is_running = true; } - void stop(){ _is_running = false; } + void stop() { _is_running = false; } bool should_send(uint64_t time) const; @@ -82,3 +83,4 @@ protected: }; } // namespace sensor_simulator +#endif // !EKF_SENSOR_H diff --git a/src/lib/ecl/test/sensor_simulator/sensor_simulator.cpp b/src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp similarity index 79% rename from src/lib/ecl/test/sensor_simulator/sensor_simulator.cpp rename to src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp index fbb4c1ed4c..346a32e7c7 100644 --- a/src/lib/ecl/test/sensor_simulator/sensor_simulator.cpp +++ b/src/modules/ekf2/test/sensor_simulator/sensor_simulator.cpp @@ -35,23 +35,26 @@ void SensorSimulator::loadSensorDataFromFile(std::string file_name) getline(file, timestamp, ','); - if (!timestamp.compare("")){ // empty line at end of file + if (!timestamp.compare("")) { // empty line at end of file break; } + sensor_sample.timestamp = std::stoul(timestamp); - if(_replay_data.size() > 0) { + if (_replay_data.size() > 0) { sensor_info last_sample = _replay_data.back(); - if (sensor_sample.timestamp < last_sample.timestamp) - { + + if (sensor_sample.timestamp < last_sample.timestamp) { std::cout << "Timestamps not sorted ascendingly" << std::endl; - exit(-1); + system_exit(-1); } } getline(file, sensor_type, ','); + if (!sensor_type.compare("imu")) { sensor_sample.sensor_type = sensor_info::IMU; + } else if (!sensor_type.compare("mag")) { sensor_sample.sensor_type = sensor_info::MAG; @@ -78,28 +81,33 @@ void SensorSimulator::loadSensorDataFromFile(std::string file_name) } else { std::cout << "Sensor type in file unknown" << std::endl; - exit(-1); + system_exit(-1); } getline(file, sensor_data); std::stringstream ss(sensor_data); int8_t i = 0; - while( ss.good() ) - { - if(i>=10){ + + while (ss.good()) { + if (i >= 10) { std::cout << "sensor data bigger than expected" << std::endl; - exit(-1); + system_exit(-1); } + std::string value_string; - getline( ss, value_string, ',' ); - if(!value_string.compare("")){ + getline(ss, value_string, ','); + + if (!value_string.compare("")) { continue; } + sensor_sample.sensor_data[i] = std::stod(value_string); i++; } + _replay_data.emplace_back(sensor_sample); } + file.close(); _has_replay_data = true; } @@ -122,7 +130,7 @@ void SensorSimulator::setSensorDataToDefault() _baro.setData(122.2f); _flow.setData(_flow.dataAtRest()); _gps.setData(_gps.getDefaultGpsData()); - _imu.setData(Vector3f{0.0f,0.0f,-CONSTANTS_ONE_G}, Vector3f{0.0f,0.0f,0.0f}); + _imu.setData(Vector3f{0.0f, 0.0f, -CONSTANTS_ONE_G}, Vector3f{0.0f, 0.0f, 0.0f}); _mag.setData(Vector3f{0.2f, 0.0f, 0.4f}); _rng.setData(0.2f, 100); _vio.setData(_vio.dataAtRest()); @@ -137,7 +145,7 @@ void SensorSimulator::startBasicSensor() void SensorSimulator::runSeconds(float duration_seconds) { - runMicroseconds( uint32_t(duration_seconds * 1e6f) ); + runMicroseconds(uint32_t(duration_seconds * 1e6f)); } void SensorSimulator::runMicroseconds(uint32_t duration) @@ -145,8 +153,7 @@ void SensorSimulator::runMicroseconds(uint32_t duration) // simulate in 1000us steps const uint64_t start_time = _time; - for(;_time < start_time + (uint64_t)duration; _time+=1000) - { + for (; _time < start_time + (uint64_t)duration; _time += 1000) { bool update_imu = _imu.should_send(_time); updateSensors(); @@ -171,27 +178,26 @@ void SensorSimulator::updateSensors() void SensorSimulator::runReplaySeconds(float duration_seconds) { - runReplayMicroseconds( uint32_t(duration_seconds * 1e6f) ); + runReplayMicroseconds(uint32_t(duration_seconds * 1e6f)); } void SensorSimulator::runReplayMicroseconds(uint32_t duration) { - if(!_has_replay_data) { + if (!_has_replay_data) { std::cout << "Can not run replay without replay data" << std::endl; - exit(-1); + system_exit(-1); } + // simulate in 1000us steps const uint64_t start_time = _time; - for(;_time < start_time + duration; _time+=1000) - { + for (; _time < start_time + duration; _time += 1000) { setSensorDataFromReplayData(); bool update_imu = _imu.should_send(_time); updateSensors(); - if(update_imu) - { + if (update_imu) { _ekf->update(); } } @@ -199,40 +205,43 @@ void SensorSimulator::runReplayMicroseconds(uint32_t duration) void SensorSimulator::setSensorDataFromReplayData() { - if(_replay_data.size() > 0) { + if (_replay_data.size() > 0) { sensor_info sample = _replay_data[_current_replay_data_index]; - while(sample.timestamp < _time) - { + + while (sample.timestamp < _time) { setSingleReplaySample(sample); - if(_current_replay_data_index < _replay_data.size()) - { + + if (_current_replay_data_index < _replay_data.size()) { _current_replay_data_index ++; + } else { break; } + sample = _replay_data[_current_replay_data_index]; } + } else { std::cerr << "Loaded replay data empty. Likely could not load replay data" << std::endl; - exit(-1); + system_exit(-1); } } -void SensorSimulator::setSingleReplaySample(const sensor_info& sample) +void SensorSimulator::setSingleReplaySample(const sensor_info &sample) { if (sample.sensor_type == sensor_info::IMU) { Vector3f accel{(float) sample.sensor_data[0], - (float) sample.sensor_data[1], - (float) sample.sensor_data[2]}; + (float) sample.sensor_data[1], + (float) sample.sensor_data[2]}; Vector3f gyro{(float) sample.sensor_data[3], - (float) sample.sensor_data[4], - (float) sample.sensor_data[5]}; + (float) sample.sensor_data[4], + (float) sample.sensor_data[5]}; _imu.setData(accel, gyro); } else if (sample.sensor_type == sensor_info::MAG) { Vector3f mag{(float) sample.sensor_data[0], - (float) sample.sensor_data[1], - (float) sample.sensor_data[2]}; + (float) sample.sensor_data[1], + (float) sample.sensor_data[2]}; _mag.setData(mag); } else if (sample.sensor_type == sensor_info::BARO) { @@ -247,18 +256,18 @@ void SensorSimulator::setSingleReplaySample(const sensor_info& sample) (float) sample.sensor_data[5])); } else if (sample.sensor_type == sensor_info::AIRSPEED) { - _airspeed.setData((float) sample.sensor_data[0], (float) sample.sensor_data[1]); + _airspeed.setData((float) sample.sensor_data[0], (float) sample.sensor_data[1]); } else if (sample.sensor_type == sensor_info::RANGE) { - _rng.setData((float) sample.sensor_data[0], (float) sample.sensor_data[1]); + _rng.setData((float) sample.sensor_data[0], (float) sample.sensor_data[1]); } else if (sample.sensor_type == sensor_info::FLOW) { flowSample flow_sample; flow_sample.flow_xy_rad = Vector2f(sample.sensor_data[0], - sample.sensor_data[1]); + sample.sensor_data[1]); flow_sample.gyro_xyz = Vector3f(sample.sensor_data[2], - sample.sensor_data[3], - sample.sensor_data[4]); + sample.sensor_data[3], + sample.sensor_data[4]); flow_sample.quality = sample.sensor_data[5]; _flow.setData(flow_sample); @@ -272,12 +281,12 @@ void SensorSimulator::setSingleReplaySample(const sensor_info& sample) // _vio.setData((float) sample.sensor_data[0], (float) sample.sensor_data[1]); } else if (sample.sensor_type == sensor_info::LANDING_STATUS) { - bool landed = sample.sensor_data[0]; + bool landed = fabsf(sample.sensor_data[0]) <= 0.f; _ekf->set_in_air_status(!landed); } else { printf("Unknown sensor type, can not set replay sample"); - exit(-1); + system_exit(-1); } } @@ -295,14 +304,14 @@ void SensorSimulator::setGpsLongitude(const double longitude) void SensorSimulator::setGpsAltitude(const float altitude) { - int32_t alt = static_cast(altitude * 1e3); + int32_t alt = static_cast(altitude * 1e3f); _gps.setAltitude(alt); } void SensorSimulator::setImuBias(Vector3f accel_bias, Vector3f gyro_bias) { - _imu.setData(Vector3f{0.0f,0.0f,-CONSTANTS_ONE_G} + accel_bias, - Vector3f{0.0f,0.0f,0.0f} + gyro_bias); + _imu.setData(Vector3f{0.0f, 0.0f, -CONSTANTS_ONE_G} + accel_bias, + Vector3f{0.0f, 0.0f, 0.0f} + gyro_bias); } void SensorSimulator::simulateOrientation(Quatf orientation) @@ -313,6 +322,6 @@ void SensorSimulator::simulateOrientation(Quatf orientation) const Vector3f sensed_gravity_body = R_bodyToWorld.transpose() * world_sensed_gravity; const Vector3f body_mag_field = R_bodyToWorld.transpose() * world_mag_field; - _imu.setData(sensed_gravity_body, Vector3f{0.0f,0.0f,0.0f}); + _imu.setData(sensed_gravity_body, Vector3f{0.0f, 0.0f, 0.0f}); _mag.setData(body_mag_field); } diff --git a/src/lib/ecl/test/sensor_simulator/sensor_simulator.h b/src/modules/ekf2/test/sensor_simulator/sensor_simulator.h similarity index 96% rename from src/lib/ecl/test/sensor_simulator/sensor_simulator.h rename to src/modules/ekf2/test/sensor_simulator/sensor_simulator.h index 37e1ed2be2..52f2721077 100644 --- a/src/lib/ecl/test/sensor_simulator/sensor_simulator.h +++ b/src/modules/ekf2/test/sensor_simulator/sensor_simulator.h @@ -40,7 +40,8 @@ * @author Kamil Ritz */ -#pragma once +#ifndef EKF_SENSOR_SIMULATOR_H +#define EKF_SENSOR_SIMULATOR_H #include #include @@ -125,7 +126,7 @@ private: void setSensorDataToDefault(); void setSensorDataFromReplayData(); void setSensorRateToDefault(); - void setSingleReplaySample(const sensor_info& sample); + void setSingleReplaySample(const sensor_info &sample); void startBasicSensor(); void updateSensors(); @@ -139,3 +140,4 @@ private: uint64_t _time {0}; // microseconds }; +#endif // !EKF_SENSOR_SIMULATOR_H diff --git a/src/lib/ecl/test/sensor_simulator/vio.cpp b/src/modules/ekf2/test/sensor_simulator/vio.cpp similarity index 71% rename from src/lib/ecl/test/sensor_simulator/vio.cpp rename to src/modules/ekf2/test/sensor_simulator/vio.cpp index cf8fd52e34..dff8be228c 100644 --- a/src/lib/ecl/test/sensor_simulator/vio.cpp +++ b/src/modules/ekf2/test/sensor_simulator/vio.cpp @@ -5,7 +5,7 @@ namespace sensor_simulator namespace sensor { -Vio::Vio(std::shared_ptr ekf):Sensor(ekf) +Vio::Vio(std::shared_ptr ekf): Sensor(ekf) { } @@ -19,22 +19,22 @@ void Vio::send(uint64_t time) _ekf->setExtVisionData(_vio_data); } -void Vio::setData(const extVisionSample& vio_data) +void Vio::setData(const extVisionSample &vio_data) { _vio_data = vio_data; } -void Vio::setVelocityVariance(const Vector3f& velVar) +void Vio::setVelocityVariance(const Vector3f &velVar) { setVelocityCovariance(matrix::diag(velVar)); } -void Vio::setVelocityCovariance(const Matrix3f& velCov) +void Vio::setVelocityCovariance(const Matrix3f &velCov) { _vio_data.velCov = velCov; } -void Vio::setPositionVariance(const Vector3f& posVar) +void Vio::setPositionVariance(const Vector3f &posVar) { _vio_data.posVar = posVar; } @@ -44,17 +44,17 @@ void Vio::setAngularVariance(float angVar) _vio_data.angVar = angVar; } -void Vio::setVelocity(const Vector3f& vel) +void Vio::setVelocity(const Vector3f &vel) { _vio_data.vel = vel; } -void Vio::setPosition(const Vector3f& pos) +void Vio::setPosition(const Vector3f &pos) { _vio_data.pos = pos; } -void Vio::setOrientation(const Quatf& quat) +void Vio::setOrientation(const Quatf &quat) { _vio_data.quat = quat; } @@ -76,7 +76,7 @@ extVisionSample Vio::dataAtRest() vio_data.vel = Vector3f{0.0f, 0.0f, 0.0f};; vio_data.quat = Quatf{1.0f, 0.0f, 0.0f, 0.0f}; vio_data.posVar = Vector3f{0.1f, 0.1f, 0.1f}; - vio_data.velCov = matrix::eye() * 0.1f; + vio_data.velCov = matrix::eye() * 0.1f; vio_data.angVar = 0.05f; vio_data.vel_frame = velocity_frame_t::LOCAL_FRAME_FRD; return vio_data; diff --git a/src/lib/ecl/test/sensor_simulator/vio.h b/src/modules/ekf2/test/sensor_simulator/vio.h similarity index 85% rename from src/lib/ecl/test/sensor_simulator/vio.h rename to src/modules/ekf2/test/sensor_simulator/vio.h index bcae46d4eb..d37364d651 100644 --- a/src/lib/ecl/test/sensor_simulator/vio.h +++ b/src/modules/ekf2/test/sensor_simulator/vio.h @@ -35,7 +35,8 @@ * Feeds Ekf external vision data * @author Kamil Ritz */ -#pragma once +#ifndef EKF_VIO_H +#define EKF_VIO_H #include "sensor.h" @@ -50,14 +51,14 @@ public: Vio(std::shared_ptr ekf); ~Vio(); - void setData(const extVisionSample& vio_data); - void setVelocityVariance(const Vector3f& velVar); - void setVelocityCovariance(const Matrix3f& velCov); - void setPositionVariance(const Vector3f& posVar); + void setData(const extVisionSample &vio_data); + void setVelocityVariance(const Vector3f &velVar); + void setVelocityCovariance(const Matrix3f &velCov); + void setPositionVariance(const Vector3f &posVar); void setAngularVariance(float angVar); - void setVelocity(const Vector3f& vel); - void setPosition(const Vector3f& pos); - void setOrientation(const Quatf& quat); + void setVelocity(const Vector3f &vel); + void setPosition(const Vector3f &pos); + void setOrientation(const Quatf &quat); void setVelocityFrameToLocal(); void setVelocityFrameToBody(); @@ -72,3 +73,4 @@ private: } // namespace sensor } // namespace sensor_simulator +#endif // !EKF_VIO_H diff --git a/src/lib/ecl/test/test_EKF_airspeed.cpp b/src/modules/ekf2/test/test_EKF_airspeed.cpp similarity index 87% rename from src/lib/ecl/test/test_EKF_airspeed.cpp rename to src/modules/ekf2/test/test_EKF_airspeed.cpp index 6be558d839..0480267107 100644 --- a/src/lib/ecl/test/test_EKF_airspeed.cpp +++ b/src/modules/ekf2/test/test_EKF_airspeed.cpp @@ -42,14 +42,15 @@ #include "sensor_simulator/ekf_wrapper.h" -class EkfAirspeedTest : public ::testing::Test { - public: +class EkfAirspeedTest : public ::testing::Test +{ +public: EkfAirspeedTest(): ::testing::Test(), - _ekf{std::make_shared()}, - _sensor_simulator(_ekf), - _ekf_wrapper(_ekf), - _quat_sim(Eulerf(0.0f, 0.0f, math::radians(45.0f))) {}; + _ekf{std::make_shared()}, + _sensor_simulator(_ekf), + _ekf_wrapper(_ekf), + _quat_sim(Eulerf(0.0f, 0.0f, math::radians(45.0f))) {}; std::shared_ptr _ekf; SensorSimulator _sensor_simulator; @@ -73,7 +74,7 @@ class EkfAirspeedTest : public ::testing::Test { TEST_F(EkfAirspeedTest, testWindVelocityEstimation) { - const Vector3f simulated_velocity_earth(0.0f,1.5f,0.0f); + const Vector3f simulated_velocity_earth(0.0f, 1.5f, 0.0f); const Vector2f airspeed_body(0.4f, 0.0f); _ekf_wrapper.enableExternalVisionVelocityFusion(); _sensor_simulator._vio.setVelocity(simulated_velocity_earth); @@ -94,24 +95,26 @@ TEST_F(EkfAirspeedTest, testWindVelocityEstimation) const Dcmf R_to_earth_sim(_quat_sim); EXPECT_TRUE(matrix::isEqual(vel, simulated_velocity_earth)); - const Vector3f vel_wind_expected = simulated_velocity_earth - R_to_earth_sim * (Vector3f(airspeed_body(0), airspeed_body(1), 0.0f)); - EXPECT_TRUE(matrix::isEqual(vel_wind_earth, Vector2f(vel_wind_expected.slice<2,1>(0,0)))); + const Vector3f vel_wind_expected = simulated_velocity_earth - R_to_earth_sim * (Vector3f(airspeed_body(0), + airspeed_body(1), 0.0f)); + EXPECT_TRUE(matrix::isEqual(vel_wind_earth, Vector2f(vel_wind_expected.slice<2, 1>(0, 0)))); EXPECT_NEAR(height_before_pressure_correction, 0.0f, 1e-5f); // Apply height correction const float static_pressure_coef_xp = 1.0f; const float static_pressure_coef_yp = -1.0f; // not used as wind direction is along x axis - parameters* _params = _ekf->getParamHandle(); + parameters *_params = _ekf->getParamHandle(); _params->static_pressure_coef_xp = static_pressure_coef_xp; _params->static_pressure_coef_yp = static_pressure_coef_yp; - float expected_height_difference = 0.5f * static_pressure_coef_xp * airspeed_body(0) * airspeed_body(0) / CONSTANTS_ONE_G; + float expected_height_difference = 0.5f * static_pressure_coef_xp * airspeed_body(0) * airspeed_body( + 0) / CONSTANTS_ONE_G; _sensor_simulator.runSeconds(20); const float height_after_pressure_correction = _ekf->getPosition()(2); // height increase means that state z decrease due to z axis pointing down const float expected_height_after_pressure_correction = height_before_pressure_correction - - expected_height_difference; + expected_height_difference; EXPECT_NEAR(height_after_pressure_correction, expected_height_after_pressure_correction, 1e-3f); diff --git a/src/lib/ecl/test/test_EKF_basics.cpp b/src/modules/ekf2/test/test_EKF_basics.cpp similarity index 95% rename from src/lib/ecl/test/test_EKF_basics.cpp rename to src/modules/ekf2/test/test_EKF_basics.cpp index fce4bf1c4f..9eeebfd2f1 100644 --- a/src/lib/ecl/test/test_EKF_basics.cpp +++ b/src/modules/ekf2/test/test_EKF_basics.cpp @@ -39,12 +39,13 @@ #include "sensor_simulator/sensor_simulator.h" #include "sensor_simulator/ekf_wrapper.h" -class EkfBasicsTest : public ::testing::Test { - public: +class EkfBasicsTest : public ::testing::Test +{ +public: EkfBasicsTest(): ::testing::Test(), _ekf{std::make_shared()}, - _ekf_wrapper(_ekf) , + _ekf_wrapper(_ekf), _sensor_simulator(_ekf) { }; @@ -180,10 +181,10 @@ TEST_F(EkfBasicsTest, accelBiasEstimation) { // GIVEN: initialized EKF with default IMU, baro and mag input // WHEN: Added more sensor measurements with accel bias and gps measurements - const Vector3f accel_bias_sim = {0.0f,0.0f,0.1f}; + const Vector3f accel_bias_sim = {0.0f, 0.0f, 0.1f}; _sensor_simulator.startGps(); - _sensor_simulator.setImuBias(accel_bias_sim, Vector3f(0.0f,0.0f,0.0f)); + _sensor_simulator.setImuBias(accel_bias_sim, Vector3f(0.0f, 0.0f, 0.0f)); _ekf->set_min_required_gps_health_time(1e6); _sensor_simulator.runSeconds(30); @@ -195,13 +196,13 @@ TEST_F(EkfBasicsTest, accelBiasEstimation) // THEN: EKF should stay or converge to zero EXPECT_TRUE(matrix::isEqual(pos, zero, 0.05f)) - << "pos = " << pos(0) << ", " << pos(1) << ", " << pos(2); + << "pos = " << pos(0) << ", " << pos(1) << ", " << pos(2); EXPECT_TRUE(matrix::isEqual(vel, zero, 0.02f)) - << "vel = " << vel(0) << ", " << vel(1) << ", " << vel(2); + << "vel = " << vel(0) << ", " << vel(1) << ", " << vel(2); EXPECT_TRUE(matrix::isEqual(accel_bias, accel_bias_sim, 0.01f)) - << "accel_bias = " << accel_bias(0) << ", " << accel_bias(1) << ", " << accel_bias(2); + << "accel_bias = " << accel_bias(0) << ", " << accel_bias(1) << ", " << accel_bias(2); EXPECT_TRUE(matrix::isEqual(gyro_bias, zero, 0.001f)) - << "gyro_bias = " << gyro_bias(0) << ", " << gyro_bias(1) << ", " << gyro_bias(2); + << "gyro_bias = " << gyro_bias(0) << ", " << gyro_bias(1) << ", " << gyro_bias(2); } TEST_F(EkfBasicsTest, reset_ekf_global_origin_gps_initialized) diff --git a/src/lib/ecl/test/test_EKF_externalVision.cpp b/src/modules/ekf2/test/test_EKF_externalVision.cpp similarity index 96% rename from src/lib/ecl/test/test_EKF_externalVision.cpp rename to src/modules/ekf2/test/test_EKF_externalVision.cpp index a1c5e7c9b8..84449045db 100644 --- a/src/lib/ecl/test/test_EKF_externalVision.cpp +++ b/src/modules/ekf2/test/test_EKF_externalVision.cpp @@ -43,13 +43,14 @@ #include "test_helper/reset_logging_checker.h" -class EkfExternalVisionTest : public ::testing::Test { - public: +class EkfExternalVisionTest : public ::testing::Test +{ +public: EkfExternalVisionTest(): ::testing::Test(), - _ekf{std::make_shared()}, - _sensor_simulator(_ekf), - _ekf_wrapper(_ekf) {}; + _ekf{std::make_shared()}, + _sensor_simulator(_ekf), + _ekf_wrapper(_ekf) {}; std::shared_ptr _ekf; SensorSimulator _sensor_simulator; @@ -139,7 +140,7 @@ TEST_F(EkfExternalVisionTest, visionVelocityResetWithAlignment) // Heading of drone in EKF frame is 0° // WHEN: Vision frame is rotate +90°. The reported heading is -90° - Quatf vision_to_ekf(Eulerf(0.0f,0.0f,math::radians(-90.0f))); + Quatf vision_to_ekf(Eulerf(0.0f, 0.0f, math::radians(-90.0f))); _sensor_simulator._vio.setOrientation(vision_to_ekf.inversed()); _ekf_wrapper.enableExternalVisionAlignment(); @@ -188,7 +189,7 @@ TEST_F(EkfExternalVisionTest, visionHorizontalPositionResetWithAlignment) // Heading of drone in EKF frame is 0° // WHEN: Vision frame is rotate +90°. The reported heading is -90° - Quatf vision_to_ekf(Eulerf(0.0f,0.0f,math::radians(-90.0f))); + Quatf vision_to_ekf(Eulerf(0.0f, 0.0f, math::radians(-90.0f))); _sensor_simulator._vio.setOrientation(vision_to_ekf.inversed()); _ekf_wrapper.enableExternalVisionAlignment(); @@ -212,7 +213,7 @@ TEST_F(EkfExternalVisionTest, visionVarianceCheck) const Vector3f velVar_init = _ekf->getVelocityVariance(); EXPECT_NEAR(velVar_init(0), velVar_init(1), 0.0001); - _sensor_simulator._vio.setVelocityVariance(Vector3f{2.0f,0.01f,0.01f}); + _sensor_simulator._vio.setVelocityVariance(Vector3f{2.0f, 0.01f, 0.01f}); _ekf_wrapper.enableExternalVisionVelocityFusion(); _sensor_simulator.startExternalVision(); _sensor_simulator.runSeconds(4); @@ -228,13 +229,13 @@ TEST_F(EkfExternalVisionTest, visionAlignment) // Heading of drone in EKF frame is 0° // WHEN: Vision frame is rotate +90°. The reported heading is -90° - Quatf externalVisionFrameOffset(Eulerf(0.0f,0.0f,math::radians(90.0f))); + Quatf externalVisionFrameOffset(Eulerf(0.0f, 0.0f, math::radians(90.0f))); _sensor_simulator._vio.setOrientation(externalVisionFrameOffset.inversed()); _ekf_wrapper.enableExternalVisionAlignment(); // Simulate high uncertainty on vision x axis which is in this case // the y EKF frame axis - _sensor_simulator._vio.setVelocityVariance(Vector3f{2.0f,0.01f,0.01f}); + _sensor_simulator._vio.setVelocityVariance(Vector3f{2.0f, 0.01f, 0.01f}); _ekf_wrapper.enableExternalVisionVelocityFusion(); _sensor_simulator.startExternalVision(); @@ -269,7 +270,8 @@ TEST_F(EkfExternalVisionTest, velocityFrameBody) _sensor_simulator._vio.setVelocityFrameToBody(); float vel_cov_data [9] = {2.0f, 0.0f, 0.0f, 0.0f, 0.01f, 0.0f, - 0.0f, 0.0f, 0.01f}; + 0.0f, 0.0f, 0.01f + }; const Matrix3f vel_cov_body(vel_cov_data); const Vector3f vel_body(1.0f, 0.0f, 0.0f); _sensor_simulator._vio.setVelocityCovariance(vel_cov_body); @@ -304,7 +306,8 @@ TEST_F(EkfExternalVisionTest, velocityFrameLocal) _sensor_simulator._vio.setVelocityFrameToLocal(); float vel_cov_data [9] = {2.0f, 0.0f, 0.0f, 0.0f, 0.01f, 0.0f, - 0.0f, 0.0f, 0.01f}; + 0.0f, 0.0f, 0.01f + }; const Matrix3f vel_cov_earth(vel_cov_data); const Vector3f vel_earth(1.0f, 0.0f, 0.0f); _sensor_simulator._vio.setVelocityCovariance(vel_cov_earth); diff --git a/src/lib/ecl/test/test_EKF_flow.cpp b/src/modules/ekf2/test/test_EKF_flow.cpp similarity index 87% rename from src/lib/ecl/test/test_EKF_flow.cpp rename to src/modules/ekf2/test/test_EKF_flow.cpp index a40f4203a0..2532c60620 100644 --- a/src/lib/ecl/test/test_EKF_flow.cpp +++ b/src/modules/ekf2/test/test_EKF_flow.cpp @@ -43,13 +43,14 @@ #include "test_helper/reset_logging_checker.h" -class EkfFlowTest : public ::testing::Test { - public: +class EkfFlowTest : public ::testing::Test +{ +public: EkfFlowTest(): ::testing::Test(), - _ekf{std::make_shared()}, - _sensor_simulator(_ekf), - _ekf_wrapper(_ekf) {}; + _ekf{std::make_shared()}, + _sensor_simulator(_ekf), + _ekf_wrapper(_ekf) {}; std::shared_ptr _ekf; SensorSimulator _sensor_simulator; @@ -74,7 +75,8 @@ class EkfFlowTest : public ::testing::Test { void startRangeFinderFusion(float distance); void startZeroFlowFusion(); - void setFlowFromHorizontalVelocityAndDistance(flowSample &flow_sample, const Vector2f &simulated_horz_velocity, float estimated_distance_to_ground); + void setFlowFromHorizontalVelocityAndDistance(flowSample &flow_sample, const Vector2f &simulated_horz_velocity, + float estimated_distance_to_ground); }; void EkfFlowTest::startRangeFinderFusion(float distance) @@ -92,10 +94,11 @@ void EkfFlowTest::startZeroFlowFusion() _sensor_simulator.startFlow(); } -void EkfFlowTest::setFlowFromHorizontalVelocityAndDistance(flowSample &flow_sample, const Vector2f &simulated_horz_velocity, float estimated_distance_to_ground) +void EkfFlowTest::setFlowFromHorizontalVelocityAndDistance(flowSample &flow_sample, + const Vector2f &simulated_horz_velocity, float estimated_distance_to_ground) { flow_sample.flow_xy_rad = - Vector2f( simulated_horz_velocity(1) * flow_sample.dt / estimated_distance_to_ground, + Vector2f(simulated_horz_velocity(1) * flow_sample.dt / estimated_distance_to_ground, -simulated_horz_velocity(0) * flow_sample.dt / estimated_distance_to_ground); } @@ -122,16 +125,16 @@ TEST_F(EkfFlowTest, resetToFlowVelocityInAir) _sensor_simulator._flow.setData(flow_sample); _ekf_wrapper.enableFlowFusion(); _sensor_simulator.startFlow(); - // Let it reset but not fuse more measurements. We actually need to send 2 - // samples to get a reset because the first one cannot be used as the gyro - // compensation needs to be accumulated between two samples. + // Let it reset but not fuse more measurements. We actually need to send 2 + // samples to get a reset because the first one cannot be used as the gyro + // compensation needs to be accumulated between two samples. _sensor_simulator.runSeconds(0.14); // THEN: estimated velocity should match simulated velocity const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity()); EXPECT_TRUE(isEqual(estimated_horz_velocity, simulated_horz_velocity)) - << "estimated vel = " << estimated_horz_velocity(0) << ", " - << estimated_horz_velocity(1); + << "estimated vel = " << estimated_horz_velocity(0) << ", " + << estimated_horz_velocity(1); // AND: the reset in velocity should be saved correctly reset_logging_checker.capturePostResetState(); @@ -162,7 +165,7 @@ TEST_F(EkfFlowTest, resetToFlowVelocityOnGround) // THEN: estimated velocity should match simulated velocity const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity()); EXPECT_TRUE(isEqual(estimated_horz_velocity, Vector2f(0.f, 0.f))) - << estimated_horz_velocity(0) << ", " << estimated_horz_velocity(1); + << estimated_horz_velocity(0) << ", " << estimated_horz_velocity(1); // AND: the reset in velocity should be saved correctly reset_logging_checker.capturePostResetState(); @@ -189,16 +192,16 @@ TEST_F(EkfFlowTest, inAirConvergence) _sensor_simulator._flow.setData(flow_sample); _ekf_wrapper.enableFlowFusion(); _sensor_simulator.startFlow(); - // Let it reset but not fuse more measurements. We actually need to send 2 - // samples to get a reset because the first one cannot be used as the gyro - // compensation needs to be accumulated between two samples. + // Let it reset but not fuse more measurements. We actually need to send 2 + // samples to get a reset because the first one cannot be used as the gyro + // compensation needs to be accumulated between two samples. _sensor_simulator.runSeconds(0.14); // THEN: estimated velocity should match simulated velocity Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity()); EXPECT_TRUE(isEqual(estimated_horz_velocity, simulated_horz_velocity)) - << "estimated vel = " << estimated_horz_velocity(0) << ", " - << estimated_horz_velocity(1); + << "estimated vel = " << estimated_horz_velocity(0) << ", " + << estimated_horz_velocity(1); // AND: when the velocity changes simulated_horz_velocity = Vector2f(0.8f, -0.5f); @@ -210,9 +213,9 @@ TEST_F(EkfFlowTest, inAirConvergence) // This takes a bit of time because the data is inconsistent with IMU measurements estimated_horz_velocity = Vector2f(_ekf->getVelocity()); EXPECT_NEAR(estimated_horz_velocity(0), simulated_horz_velocity(0), 0.05f) - << "estimated vel = " << estimated_horz_velocity(0); + << "estimated vel = " << estimated_horz_velocity(0); EXPECT_NEAR(estimated_horz_velocity(1), simulated_horz_velocity(1), 0.05f) - << estimated_horz_velocity(1); + << estimated_horz_velocity(1); } TEST_F(EkfFlowTest, yawMotionCorrectionWithAutopilotGyroData) @@ -245,9 +248,9 @@ TEST_F(EkfFlowTest, yawMotionCorrectionWithAutopilotGyroData) // and the velocity estimate stays 0 const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity()); EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.01f) - << "estimated vel = " << estimated_horz_velocity(0); + << "estimated vel = " << estimated_horz_velocity(0); EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.01f) - << "estimated vel = " << estimated_horz_velocity(1); + << "estimated vel = " << estimated_horz_velocity(1); } TEST_F(EkfFlowTest, yawMotionCorrectionWithFlowGyroData) @@ -281,7 +284,7 @@ TEST_F(EkfFlowTest, yawMotionCorrectionWithFlowGyroData) // and the velocity estimate stays 0 const Vector2f estimated_horz_velocity = Vector2f(_ekf->getVelocity()); EXPECT_NEAR(estimated_horz_velocity(0), 0.f, 0.01f) - << "estimated vel = " << estimated_horz_velocity(0); + << "estimated vel = " << estimated_horz_velocity(0); EXPECT_NEAR(estimated_horz_velocity(1), 0.f, 0.01f) - << "estimated vel = " << estimated_horz_velocity(1); + << "estimated vel = " << estimated_horz_velocity(1); } diff --git a/src/lib/ecl/test/test_EKF_fusionLogic.cpp b/src/modules/ekf2/test/test_EKF_fusionLogic.cpp similarity index 98% rename from src/lib/ecl/test/test_EKF_fusionLogic.cpp rename to src/modules/ekf2/test/test_EKF_fusionLogic.cpp index 9430efbe55..6bdee14a06 100644 --- a/src/lib/ecl/test/test_EKF_fusionLogic.cpp +++ b/src/modules/ekf2/test/test_EKF_fusionLogic.cpp @@ -42,13 +42,14 @@ #include "sensor_simulator/ekf_wrapper.h" -class EkfFusionLogicTest : public ::testing::Test { - public: +class EkfFusionLogicTest : public ::testing::Test +{ +public: EkfFusionLogicTest(): ::testing::Test(), - _ekf{std::make_shared()}, - _sensor_simulator(_ekf), - _ekf_wrapper(_ekf) {}; + _ekf{std::make_shared()}, + _sensor_simulator(_ekf), + _ekf_wrapper(_ekf) {}; std::shared_ptr _ekf; SensorSimulator _sensor_simulator; @@ -296,7 +297,7 @@ TEST_F(EkfFusionLogicTest, doVisionHeadingFusion) EXPECT_FALSE(_ekf_wrapper.isIntendingExternalVisionHeadingFusion()); EXPECT_FALSE(_ekf->local_position_is_valid()); EXPECT_FALSE(_ekf->global_position_is_valid()); - // THEN: Yaw state shoud be reset to mag + // THEN: Yaw state shoud be reset to mag EXPECT_TRUE(_ekf_wrapper.isIntendingMagHeadingFusion()); EXPECT_EQ(_ekf_wrapper.getQuaternionResetCounter(), initial_quat_reset_counter + 2); } @@ -347,6 +348,7 @@ TEST_F(EkfFusionLogicTest, doRangeHeightFusion) EXPECT_TRUE(_ekf_wrapper.isIntendingRangeHeightFusion()); const float dt = 8e-3f; + for (int i = 0; i < 5; i++) { _sensor_simulator.runSeconds(dt); // THEN: EKF should intend to fuse range height, even if diff --git a/src/lib/ecl/test/test_EKF_gps.cpp b/src/modules/ekf2/test/test_EKF_gps.cpp similarity index 92% rename from src/lib/ecl/test/test_EKF_gps.cpp rename to src/modules/ekf2/test/test_EKF_gps.cpp index fd311d5005..4c23166ad3 100644 --- a/src/lib/ecl/test/test_EKF_gps.cpp +++ b/src/modules/ekf2/test/test_EKF_gps.cpp @@ -42,13 +42,14 @@ #include "sensor_simulator/ekf_wrapper.h" #include "test_helper/reset_logging_checker.h" -class EkfGpsTest : public ::testing::Test { - public: +class EkfGpsTest : public ::testing::Test +{ +public: EkfGpsTest(): ::testing::Test(), - _ekf{std::make_shared()}, - _sensor_simulator(_ekf), - _ekf_wrapper(_ekf) {}; + _ekf{std::make_shared()}, + _sensor_simulator(_ekf), + _ekf_wrapper(_ekf) {}; std::shared_ptr _ekf; SensorSimulator _sensor_simulator; @@ -101,10 +102,8 @@ TEST_F(EkfGpsTest, resetToGpsVelocity) const Vector3f simulated_velocity(0.5f, 1.0f, -0.3f); _sensor_simulator._gps.setVelocity(simulated_velocity); const uint64_t dt_us = 1e5; - _sensor_simulator._gps.stepHorizontalPositionByMeters( - Vector2f(simulated_velocity) * dt_us * 1e-6); - _sensor_simulator._gps.stepHeightByMeters( - simulated_velocity(2) * dt_us * 1e-6); + _sensor_simulator._gps.stepHorizontalPositionByMeters(Vector2f(simulated_velocity) * dt_us * 1e-6); + _sensor_simulator._gps.stepHeightByMeters(simulated_velocity(2) * dt_us * 1e-6f); _sensor_simulator.runMicroseconds(dt_us); // THEN: a reset to GPS velocity should be done @@ -138,5 +137,5 @@ TEST_F(EkfGpsTest, resetToGpsPosition) // THEN: a reset to the new GPS position should be done const Vector3f estimated_position = _ekf->getPosition(); EXPECT_TRUE(isEqual(estimated_position, - previous_position + simulated_position_change, 1e-2f)); + previous_position + simulated_position_change, 1e-2f)); } diff --git a/src/lib/ecl/test/test_EKF_gps_yaw.cpp b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp similarity index 97% rename from src/lib/ecl/test/test_EKF_gps_yaw.cpp rename to src/modules/ekf2/test/test_EKF_gps_yaw.cpp index ecf6acf91a..c67200170d 100644 --- a/src/lib/ecl/test/test_EKF_gps_yaw.cpp +++ b/src/modules/ekf2/test/test_EKF_gps_yaw.cpp @@ -42,13 +42,14 @@ #include "sensor_simulator/ekf_wrapper.h" #include "test_helper/reset_logging_checker.h" -class EkfGpsHeadingTest : public ::testing::Test { - public: +class EkfGpsHeadingTest : public ::testing::Test +{ +public: EkfGpsHeadingTest(): ::testing::Test(), - _ekf{std::make_shared()}, - _sensor_simulator(_ekf), - _ekf_wrapper(_ekf) {}; + _ekf{std::make_shared()}, + _sensor_simulator(_ekf), + _ekf_wrapper(_ekf) {}; std::shared_ptr _ekf; SensorSimulator _sensor_simulator; @@ -93,7 +94,7 @@ void EkfGpsHeadingTest::checkConvergence(float truth, float tolerance) { const float yaw_est = _ekf_wrapper.getYawAngle(); EXPECT_NEAR(yaw_est, truth, math::radians(tolerance)) - << "yaw est: " << math::degrees(yaw_est) << "gps yaw: " << math::degrees(truth); + << "yaw est: " << math::degrees(yaw_est) << "gps yaw: " << math::degrees(truth); } TEST_F(EkfGpsHeadingTest, fusionStartWithReset) diff --git a/src/lib/ecl/test/test_EKF_imuSampling.cpp b/src/modules/ekf2/test/test_EKF_imuSampling.cpp similarity index 73% rename from src/lib/ecl/test/test_EKF_imuSampling.cpp rename to src/modules/ekf2/test/test_EKF_imuSampling.cpp index 3a98f727d0..c7642adf70 100644 --- a/src/lib/ecl/test/test_EKF_imuSampling.cpp +++ b/src/modules/ekf2/test/test_EKF_imuSampling.cpp @@ -36,9 +36,9 @@ #include "EKF/ekf.h" #include "EKF/imu_down_sampler.hpp" -class EkfImuSamplingTest : public ::testing::TestWithParam> +class EkfImuSamplingTest : public ::testing::TestWithParam> { - public: +public: Ekf _ekf{}; @@ -67,7 +67,7 @@ TEST_P(EkfImuSamplingTest, imuSamplingAtMultipleRates) uint32_t dt_us = std::get<0>(GetParam()) * (_ekf.FILTER_UPDATE_PERIOD_MS * 1000); uint32_t expected_dt_us = std::get<1>(GetParam()) * (_ekf.FILTER_UPDATE_PERIOD_MS * 1000); - Vector3f ang_vel= std::get<2>(GetParam()); + Vector3f ang_vel = std::get<2>(GetParam()); Vector3f accel = std::get<3>(GetParam()); imuSample imu_sample; imu_sample.delta_ang_dt = dt_us * 1.0e-6f; @@ -77,8 +77,8 @@ TEST_P(EkfImuSamplingTest, imuSamplingAtMultipleRates) // The higher the imu rate is the more measurements we have to set before reaching the FILTER_UPDATE_PERIOD int n_samples = 0; - for(int i = 0; i<(int)20/std::get<0>(GetParam()); ++i) - { + + for (int i = 0; i < (int)20 / std::get<0>(GetParam()); ++i) { n_samples++; imu_sample.time_us = _t_us; _ekf.setIMUData(imu_sample); @@ -93,37 +93,39 @@ TEST_P(EkfImuSamplingTest, imuSamplingAtMultipleRates) // WHEN: downsampling the imu measurement // THEN: the delta vel should be accumulated correctly // Allow for accumulation of rounding error with each sample - EXPECT_TRUE(matrix::isEqual(ang_vel, imu_sample_buffered.delta_ang/imu_sample_buffered.delta_ang_dt, float(n_samples) * 1e-7f)); - EXPECT_TRUE(matrix::isEqual(accel, imu_sample_buffered.delta_vel/imu_sample_buffered.delta_vel_dt, float(n_samples) * 1e-7f)); + EXPECT_TRUE(matrix::isEqual(ang_vel, imu_sample_buffered.delta_ang / imu_sample_buffered.delta_ang_dt, + float(n_samples) * 1e-7f)); + EXPECT_TRUE(matrix::isEqual(accel, imu_sample_buffered.delta_vel / imu_sample_buffered.delta_vel_dt, + float(n_samples) * 1e-7f)); } INSTANTIATE_TEST_SUITE_P(imuSamplingAtMultipleRates, - EkfImuSamplingTest, - ::testing::Values( - std::make_tuple(1.0f, 1.0f,Vector3f{0.0f,0.0f,0.0f},Vector3f{-0.46f,0.87f,0.20f}), - std::make_tuple(0.5f, 1.0f,Vector3f{0.0f,0.0f,0.0f},Vector3f{-0.46f,0.87f,0.20f}), - std::make_tuple(1.6f, 1.6f,Vector3f{0.0f,0.0f,0.0f},Vector3f{-0.46f,0.87f,0.20f}), - std::make_tuple(0.333f,1.0f,Vector3f{0.0f,0.0f,0.0f},Vector3f{-0.46f,0.87f,0.20f}), - std::make_tuple(1.0f, 1.0f,Vector3f{1.0f,0.0f,0.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(0.5f, 1.0f,Vector3f{1.0f,0.0f,0.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(1.6f, 1.6f,Vector3f{1.0f,0.0f,0.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(0.333f,1.0f,Vector3f{1.0f,0.0f,0.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(1.0f, 1.0f,Vector3f{0.0f,1.0f,0.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(0.5f, 1.0f,Vector3f{0.0f,1.0f,0.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(1.6f, 1.6f,Vector3f{0.0f,1.0f,0.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(0.333f,1.0f,Vector3f{0.0f,1.0f,0.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(1.0f, 1.0f,Vector3f{0.0f,0.0f,1.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(0.5f, 1.0f,Vector3f{0.0f,0.0f,1.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(1.6f, 1.6f,Vector3f{0.0f,0.0f,1.0f},Vector3f{0.0f,0.0f,0.0f}), - std::make_tuple(0.333f,1.0f,Vector3f{0.0f,0.0f,1.0f},Vector3f{0.0f,0.0f,0.0f}) - )); + EkfImuSamplingTest, + ::testing::Values( + std::make_tuple(1.0f, 1.0f, Vector3f{0.0f, 0.0f, 0.0f}, Vector3f{-0.46f, 0.87f, 0.20f}), + std::make_tuple(0.5f, 1.0f, Vector3f{0.0f, 0.0f, 0.0f}, Vector3f{-0.46f, 0.87f, 0.20f}), + std::make_tuple(1.6f, 1.6f, Vector3f{0.0f, 0.0f, 0.0f}, Vector3f{-0.46f, 0.87f, 0.20f}), + std::make_tuple(0.333f, 1.0f, Vector3f{0.0f, 0.0f, 0.0f}, Vector3f{-0.46f, 0.87f, 0.20f}), + std::make_tuple(1.0f, 1.0f, Vector3f{1.0f, 0.0f, 0.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(0.5f, 1.0f, Vector3f{1.0f, 0.0f, 0.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(1.6f, 1.6f, Vector3f{1.0f, 0.0f, 0.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(0.333f, 1.0f, Vector3f{1.0f, 0.0f, 0.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(1.0f, 1.0f, Vector3f{0.0f, 1.0f, 0.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(0.5f, 1.0f, Vector3f{0.0f, 1.0f, 0.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(1.6f, 1.6f, Vector3f{0.0f, 1.0f, 0.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(0.333f, 1.0f, Vector3f{0.0f, 1.0f, 0.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(1.0f, 1.0f, Vector3f{0.0f, 0.0f, 1.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(0.5f, 1.0f, Vector3f{0.0f, 0.0f, 1.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(1.6f, 1.6f, Vector3f{0.0f, 0.0f, 1.0f}, Vector3f{0.0f, 0.0f, 0.0f}), + std::make_tuple(0.333f, 1.0f, Vector3f{0.0f, 0.0f, 1.0f}, Vector3f{0.0f, 0.0f, 0.0f}) + )); TEST_F(EkfImuSamplingTest, accelDownSampling) { ImuDownSampler sampler(0.008f); - Vector3f ang_vel{0.0f,0.0f,0.0f}; - Vector3f accel{-0.46f,0.87f,0.0f}; + Vector3f ang_vel{0.0f, 0.0f, 0.0f}; + Vector3f accel{-0.46f, 0.87f, 0.0f}; imuSample input_sample; input_sample.delta_ang_dt = 0.004f; input_sample.delta_ang = ang_vel * input_sample.delta_ang_dt; @@ -150,8 +152,8 @@ TEST_F(EkfImuSamplingTest, gyroDownSampling) { ImuDownSampler sampler(0.008f); - Vector3f ang_vel{0.0f,0.0f,1.0f}; - Vector3f accel{0.0f,0.0f,0.0f}; + Vector3f ang_vel{0.0f, 0.0f, 1.0f}; + Vector3f accel{0.0f, 0.0f, 0.0f}; imuSample input_sample; input_sample.delta_ang_dt = 0.004f; @@ -175,7 +177,7 @@ TEST_F(EkfImuSamplingTest, gyroDownSampling) EXPECT_TRUE(matrix::isEqual(ang_vel * 0.008f, output_sample.delta_ang, 1e-10f)); EXPECT_TRUE(matrix::isEqual(accel * 0.008f, output_sample.delta_vel, 1e-10f)); - ang_vel = Vector3f{0.0f,1.0f,0.0f}; + ang_vel = Vector3f{0.0f, 1.0f, 0.0f}; input_sample.delta_ang = ang_vel * input_sample.delta_ang_dt; input_sample.delta_vel = accel * input_sample.delta_vel_dt; @@ -194,7 +196,7 @@ TEST_F(EkfImuSamplingTest, gyroDownSampling) EXPECT_TRUE(matrix::isEqual(ang_vel * 0.008f, output_sample.delta_ang, 1e-10f)); EXPECT_TRUE(matrix::isEqual(accel * 0.008f, output_sample.delta_vel, 1e-10f)); - ang_vel = Vector3f{1.0f,0.0f,0.0f}; + ang_vel = Vector3f{1.0f, 0.0f, 0.0f}; input_sample.delta_ang = ang_vel * input_sample.delta_ang_dt; input_sample.delta_vel = accel * input_sample.delta_vel_dt; diff --git a/src/lib/ecl/test/test_EKF_initialization.cpp b/src/modules/ekf2/test/test_EKF_initialization.cpp similarity index 91% rename from src/lib/ecl/test/test_EKF_initialization.cpp rename to src/modules/ekf2/test/test_EKF_initialization.cpp index 9f2b20c6e0..05f41606fb 100644 --- a/src/lib/ecl/test/test_EKF_initialization.cpp +++ b/src/modules/ekf2/test/test_EKF_initialization.cpp @@ -38,12 +38,13 @@ #include "sensor_simulator/sensor_simulator.h" #include "sensor_simulator/ekf_wrapper.h" -class EkfInitializationTest : public ::testing::Test { - public: +class EkfInitializationTest : public ::testing::Test +{ +public: EkfInitializationTest(): ::testing::Test(), - _ekf{std::make_shared()}, - _sensor_simulator(_ekf), - _ekf_wrapper(_ekf) {}; + _ekf{std::make_shared()}, + _sensor_simulator(_ekf), + _ekf_wrapper(_ekf) {}; std::shared_ptr _ekf; SensorSimulator _sensor_simulator; @@ -67,10 +68,10 @@ class EkfInitializationTest : public ::testing::Test { const Quatf quat_est = _ekf->getQuaternion(); const float precision = 0.0002f; // TODO: this is only required for the pitch90 test to pass EXPECT_TRUE(matrix::isEqual(quat_est, true_quaternion, precision)) - << "quat est = " << quat_est(0) << ", " << quat_est(1) << ", " - << quat_est(2) << ", " << quat_est(3) - << "\nquat true = " << true_quaternion(0) << ", " << true_quaternion(1) << ", " - << true_quaternion(2) << ", " << true_quaternion(3); + << "quat est = " << quat_est(0) << ", " << quat_est(1) << ", " + << quat_est(2) << ", " << quat_est(3) + << "\nquat true = " << true_quaternion(0) << ", " << true_quaternion(1) << ", " + << true_quaternion(2) << ", " << true_quaternion(3); } void validStateAfterOrientationInitialization() @@ -95,9 +96,9 @@ class EkfInitializationTest : public ::testing::Test { const Vector3f vel = _ekf->getVelocity(); EXPECT_TRUE(matrix::isEqual(pos, Vector3f{}, 0.002f)) - << "pos = " << pos(0) << ", " << pos(1) << ", " << pos(2); + << "pos = " << pos(0) << ", " << pos(1) << ", " << pos(2); EXPECT_TRUE(matrix::isEqual(vel, Vector3f{}, 0.003f)) - << "vel = " << vel(0) << ", " << vel(1) << ", " << vel(2); + << "vel = " << vel(0) << ", " << vel(1) << ", " << vel(2); } void velocityAndPositionVarianceBigEnoughAfterOrientationInitialization() @@ -122,7 +123,7 @@ class EkfInitializationTest : public ::testing::Test { const Vector3f dvel_bias_var = _ekf_wrapper.getDeltaVelBiasVariance(); const Vector3f accel_bias = _ekf->getAccelBias(); - for (int i = 0; i < 3; i++){ + for (int i = 0; i < 3; i++) { if (fabsf(R_to_earth(2, i)) > 0.8f) { // Highly observable, the variance decreases EXPECT_LT(dvel_bias_var(i), 4.0e-6f) << "axis " << i; @@ -160,32 +161,40 @@ TEST_F(EkfInitializationTest, gyroBias) // THEN: the vertical accel bias should not be affected Vector3f accel_bias; - for (int i = 0; i < 100; i++) { + + for (int ii = 0; ii < 100; ii++) { _sensor_simulator.runSeconds(0.5); accel_bias = _ekf->getAccelBias(); + if (fabsf(accel_bias(2)) > 0.3f) { // Print state covariance and correlation matrices for debugging const matrix::SquareMatrix P = _ekf->covariances(); printf("State covariance:\n"); + for (int i = 0; i <= 15; i++) { for (int j = 0; j <= 15; j++) { - printf("%.3fe-9 ", ((double)P(i, j))*1e9); + printf("%.3fe-9 ", ((double)P(i, j)) * 1e9); } + printf("\n"); } printf("State correlation:\n"); printf("\t0\t1\t2\t3\t4\t5\t6\t7\t8\t9\t10\t11\t12\t13\t14\t15\n"); + for (uint8_t i = 0; i <= 15; i++) { printf("%d| ", i); - for (uint8_t j = 0; j <= 15; j++) { - double corr = sqrt(abs(P(i, i) * P(j, j))); - if (corr > 0.0) corr = double(abs(P(i, j))) / corr; + for (uint8_t j = 0; j <= 15; j++) { + double corr = sqrt(abs(P(i, i) * P(j, j))); + + if (corr > 0.0) { corr = double(abs(P(i, j))) / corr; } + printf("%.3f\t", corr); } + printf("\n"); } diff --git a/src/lib/ecl/test/test_EKF_measurementSampling.cpp b/src/modules/ekf2/test/test_EKF_measurementSampling.cpp similarity index 95% rename from src/lib/ecl/test/test_EKF_measurementSampling.cpp rename to src/modules/ekf2/test/test_EKF_measurementSampling.cpp index d053d0d17c..fe16477be6 100644 --- a/src/lib/ecl/test/test_EKF_measurementSampling.cpp +++ b/src/modules/ekf2/test/test_EKF_measurementSampling.cpp @@ -37,9 +37,9 @@ class EkfMeasurementSamplingTest : public ::testing::Test { - public: +public: EkfMeasurementSamplingTest(): ::testing::Test(), - _ekf{std::make_shared()}{}; + _ekf{std::make_shared()} {}; std::shared_ptr _ekf; @@ -58,18 +58,19 @@ TEST_F(EkfMeasurementSamplingTest, baroDownSampling) int baro_rate_Hz = 10000; uint64_t time = 0; float baro_data = 1.0f; - for(int i = 0; i < 2 * baro_rate_Hz; i++) - { - if(i % 100 == 0) - { + + for (int i = 0; i < 2 * baro_rate_Hz; i++) { + if (i % 100 == 0) { // send imu data at a 100 times lower rate imu_sample.time_us = time; _ekf->setIMUData(imu_sample); } + _ekf->setBaroData(baroSample{time, baro_data}); baro_data *= -1.0f; time += 1000000 / baro_rate_Hz; } + _ekf->update(); // THEN: average and buffered baro dato should be close to zero diff --git a/src/lib/ecl/test/test_EKF_ringbuffer.cpp b/src/modules/ekf2/test/test_EKF_ringbuffer.cpp similarity index 91% rename from src/lib/ecl/test/test_EKF_ringbuffer.cpp rename to src/modules/ekf2/test/test_EKF_ringbuffer.cpp index fc26d9187b..0839a9ea18 100644 --- a/src/lib/ecl/test/test_EKF_ringbuffer.cpp +++ b/src/modules/ekf2/test/test_EKF_ringbuffer.cpp @@ -41,11 +41,12 @@ struct sample { }; -class EkfRingBufferTest : public ::testing::Test { - public: +class EkfRingBufferTest : public ::testing::Test +{ +public: sample _x, _y, _z; - RingBuffer* _buffer; + RingBuffer *_buffer; void SetUp() override { @@ -118,11 +119,11 @@ TEST_F(EkfRingBufferTest, popSample) // WHEN: when calling "pop_first_older_than" // THEN: we should get the first sample from the head that is older - EXPECT_EQ(true, _buffer->pop_first_older_than(_x.time_us+1, &pop)); + EXPECT_EQ(true, _buffer->pop_first_older_than(_x.time_us + 1, &pop)); EXPECT_EQ(_x.time_us, pop.time_us); - EXPECT_EQ(true, _buffer->pop_first_older_than(_y.time_us+10, &pop)); + EXPECT_EQ(true, _buffer->pop_first_older_than(_y.time_us + 10, &pop)); EXPECT_EQ(_y.time_us, pop.time_us); - EXPECT_EQ(true, _buffer->pop_first_older_than(_z.time_us+100, &pop)); + EXPECT_EQ(true, _buffer->pop_first_older_than(_z.time_us + 100, &pop)); EXPECT_EQ(_z.time_us, pop.time_us); // TODO: When changing the order of popping sample it does not behave as expected, fix this } @@ -137,8 +138,8 @@ TEST_F(EkfRingBufferTest, askingForTooNewSample) sample pop = {}; // WHEN: all buffered samples are older by 0.1s than your query timestamp // THEN: should get no sample returned - EXPECT_EQ(true, _buffer->pop_first_older_than(_z.time_us+99000, &pop)); - EXPECT_EQ(false, _buffer->pop_first_older_than(_y.time_us+100000, &pop)); + EXPECT_EQ(true, _buffer->pop_first_older_than(_z.time_us + 99000, &pop)); + EXPECT_EQ(false, _buffer->pop_first_older_than(_y.time_us + 100000, &pop)); } TEST_F(EkfRingBufferTest, reallocateBuffer) diff --git a/src/lib/ecl/test/test_EKF_terrain_estimator.cpp b/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp similarity index 96% rename from src/lib/ecl/test/test_EKF_terrain_estimator.cpp rename to src/modules/ekf2/test/test_EKF_terrain_estimator.cpp index 6bc6b22134..1fd6ae336e 100644 --- a/src/lib/ecl/test/test_EKF_terrain_estimator.cpp +++ b/src/modules/ekf2/test/test_EKF_terrain_estimator.cpp @@ -41,13 +41,14 @@ #include "sensor_simulator/sensor_simulator.h" #include "sensor_simulator/ekf_wrapper.h" -class EkfTerrainTest : public ::testing::Test { - public: +class EkfTerrainTest : public ::testing::Test +{ +public: EkfTerrainTest(): ::testing::Test(), - _ekf{std::make_shared()}, - _sensor_simulator(_ekf), - _ekf_wrapper(_ekf) {}; + _ekf{std::make_shared()}, + _sensor_simulator(_ekf), + _ekf_wrapper(_ekf) {}; std::shared_ptr _ekf; SensorSimulator _sensor_simulator; @@ -87,7 +88,7 @@ class EkfTerrainTest : public ::testing::Test { // Configure optical flow simulator data flowSample flow_sample = _sensor_simulator._flow.dataAtRest(); flow_sample.flow_xy_rad = - Vector2f( simulated_velocity(1) * flow_sample.dt / flow_height, + Vector2f(simulated_velocity(1) * flow_sample.dt / flow_height, -simulated_velocity(0) * flow_sample.dt / flow_height); _sensor_simulator._flow.setData(flow_sample); const float max_flow_rate = 5.f; diff --git a/src/lib/ecl/test/test_EKF_utils.cpp b/src/modules/ekf2/test/test_EKF_utils.cpp similarity index 93% rename from src/lib/ecl/test/test_EKF_utils.cpp rename to src/modules/ekf2/test/test_EKF_utils.cpp index 81df57446b..99cf67d860 100644 --- a/src/lib/ecl/test/test_EKF_utils.cpp +++ b/src/modules/ekf2/test/test_EKF_utils.cpp @@ -46,8 +46,8 @@ TEST(eclPowfTest, compareToStandardImplementation) { - std::vector exponents = {-3,-2,-1,-0,0,1,2,3}; - std::vector bases = {-INFINITY, -11.1f,-0.5f, -0.f, 0.f, 0.5f, 11.1f, INFINITY}; + std::vector exponents = {-3, -2, -1, -0, 0, 1, 2, 3}; + std::vector bases = {-INFINITY, -11.1f, -0.5f, -0.f, 0.f, 0.5f, 11.1f, INFINITY}; for (auto const exponent : exponents) { for (auto const basis : bases) { @@ -59,12 +59,12 @@ TEST(eclPowfTest, compareToStandardImplementation) TEST(euler312YawTest, fromQuaternion) { - matrix::Quatf q1(3.5f,2.4f,-0.5f,-3.f); + matrix::Quatf q1(3.5f, 2.4f, -0.5f, -3.f); q1.normalize(); const matrix::Eulerf euler1(q1); EXPECT_FLOAT_EQ(euler1(2), getEuler321Yaw(q1)); - matrix::Quatf q2(0.f,0,-1.f,0.f); + matrix::Quatf q2(0.f, 0, -1.f, 0.f); q2.normalize(); const matrix::Eulerf euler2(q2); EXPECT_FLOAT_EQ(euler2(2), getEuler321Yaw(q2)); diff --git a/src/lib/ecl/test/test_EKF_withReplayData.cpp b/src/modules/ekf2/test/test_EKF_withReplayData.cpp similarity index 83% rename from src/lib/ecl/test/test_EKF_withReplayData.cpp rename to src/modules/ekf2/test/test_EKF_withReplayData.cpp index f9b686e4f3..b9ee8cea15 100644 --- a/src/lib/ecl/test/test_EKF_withReplayData.cpp +++ b/src/modules/ekf2/test/test_EKF_withReplayData.cpp @@ -39,13 +39,14 @@ #include "sensor_simulator/ekf_wrapper.h" #include "sensor_simulator/ekf_logger.h" -class EkfReplayTest : public ::testing::Test { - public: +class EkfReplayTest : public ::testing::Test +{ +public: EkfReplayTest(): ::testing::Test(), - _ekf{std::make_shared()}, - _sensor_simulator(_ekf), - _ekf_wrapper(_ekf), - _ekf_logger(_ekf) {}; + _ekf{std::make_shared()}, + _sensor_simulator(_ekf), + _ekf_wrapper(_ekf), + _ekf_logger(_ekf) {}; std::shared_ptr _ekf; SensorSimulator _sensor_simulator; @@ -55,8 +56,8 @@ class EkfReplayTest : public ::testing::Test { TEST_F(EkfReplayTest, irisGps) { - _sensor_simulator.loadSensorDataFromFile("../../../test/replay_data/iris_gps.csv"); - _ekf_logger.setFilePath("../../../test/change_indication/iris_gps.csv"); + _sensor_simulator.loadSensorDataFromFile(TEST_DATA_PATH"/replay_data/iris_gps.csv"); + _ekf_logger.setFilePath(TEST_DATA_PATH"/change_indication/iris_gps.csv"); // Start simulation and enable fusion of additional sensor types here // By default the IMU, Baro and Mag sensor simulators are already running @@ -64,8 +65,8 @@ TEST_F(EkfReplayTest, irisGps) _ekf_wrapper.enableGpsFusion(); uint8_t logging_rate_hz = 10; - for(int i = 0; i < 35 * logging_rate_hz; ++i) - { + + for (int i = 0; i < 35 * logging_rate_hz; ++i) { _sensor_simulator.runReplaySeconds(1.0f / logging_rate_hz); _ekf_logger.writeStateToFile(); } @@ -73,8 +74,8 @@ TEST_F(EkfReplayTest, irisGps) TEST_F(EkfReplayTest, ekfGsfReset) { - _sensor_simulator.loadSensorDataFromFile("../../../test/replay_data/ekf_gsf_reset.csv"); - _ekf_logger.setFilePath("../../../test/change_indication/ekf_gsf_reset.csv"); + _sensor_simulator.loadSensorDataFromFile(TEST_DATA_PATH"/replay_data/ekf_gsf_reset.csv"); + _ekf_logger.setFilePath(TEST_DATA_PATH"/change_indication/ekf_gsf_reset.csv"); // Start simulation and enable fusion of additional sensor types here // By default the IMU, Baro and Mag sensor simulators are already running @@ -85,8 +86,8 @@ TEST_F(EkfReplayTest, ekfGsfReset) params->gps_pos_innov_gate = 1.f; uint8_t logging_rate_hz = 10; - for(int i = 0; i < 39 * logging_rate_hz; ++i) - { + + for (int i = 0; i < 39 * logging_rate_hz; ++i) { _sensor_simulator.runReplaySeconds(1.0f / logging_rate_hz); _ekf_logger.writeStateToFile(); } diff --git a/src/lib/ecl/test/test_SensorRangeFinder.cpp b/src/modules/ekf2/test/test_SensorRangeFinder.cpp similarity index 99% rename from src/lib/ecl/test/test_SensorRangeFinder.cpp rename to src/modules/ekf2/test/test_SensorRangeFinder.cpp index 901af5fd09..2e10f69357 100644 --- a/src/lib/ecl/test/test_SensorRangeFinder.cpp +++ b/src/modules/ekf2/test/test_SensorRangeFinder.cpp @@ -42,7 +42,8 @@ using matrix::Dcmf; using matrix::Eulerf; using namespace estimator::sensor; -class SensorRangeFinderTest : public ::testing::Test { +class SensorRangeFinderTest : public ::testing::Test +{ public: // Setup the Ekf with synthetic measurements void SetUp() override @@ -73,16 +74,21 @@ void SensorRangeFinderTest::updateSensorAtRate(uint64_t duration_us, uint64_t dt rangeSample new_sample = _good_sample; uint64_t t_now_us = _good_sample.time_us; + for (int i = 0; i < int(duration_us / dt_update_us); i++) { t_now_us += dt_update_us; + if ((i % int(dt_sensor_us / dt_update_us)) == 0) { new_sample.rng += 0.2f; // update the range to not trigger the stuck detection + if (new_sample.rng > _max_range) { new_sample.rng = _min_range; } + new_sample.time_us = t_now_us; _range_finder.setSample(new_sample); } + _range_finder.runChecks(t_now_us, attitude); } } @@ -213,15 +219,18 @@ TEST_F(SensorRangeFinderTest, rangeStuck) const uint64_t dt = 3e5; const uint64_t stuck_timeout = 11e6; new_sample.quality = 0; + for (int i = 0; i < int(stuck_timeout / dt); i++) { _range_finder.setSample(new_sample); _range_finder.runChecks(new_sample.time_us, attitude); new_sample.time_us += dt; } + EXPECT_FALSE(_range_finder.isDataHealthy()); EXPECT_FALSE(_range_finder.isHealthy()); new_sample.quality = 100; + // we need a few sample to pass the hysteresis check for (int i = 0; i < int(2e6 / dt); i++) { _range_finder.setSample(new_sample); @@ -270,6 +279,7 @@ TEST_F(SensorRangeFinderTest, qualityHysteresis) // AND: we need to put enough good data to pass the hysteresis const uint64_t dt = 3e5; const uint64_t hyst_time = 1e6; + for (int i = 0; i < int(hyst_time / dt) + 2; i++) { _range_finder.setSample(new_sample); _range_finder.runChecks(new_sample.time_us, attitude); diff --git a/src/lib/ecl/test/test_helper/CMakeLists.txt b/src/modules/ekf2/test/test_helper/CMakeLists.txt similarity index 100% rename from src/lib/ecl/test/test_helper/CMakeLists.txt rename to src/modules/ekf2/test/test_helper/CMakeLists.txt diff --git a/src/lib/ecl/test/test_helper/reset_logging_checker.cpp b/src/modules/ekf2/test/test_helper/reset_logging_checker.cpp similarity index 77% rename from src/lib/ecl/test/test_helper/reset_logging_checker.cpp rename to src/modules/ekf2/test/test_helper/reset_logging_checker.cpp index d02b4a4bc3..5fb48153c8 100644 --- a/src/lib/ecl/test/test_helper/reset_logging_checker.cpp +++ b/src/modules/ekf2/test/test_helper/reset_logging_checker.cpp @@ -1,7 +1,8 @@ #include "reset_logging_checker.h" // call immediately after state reset -void ResetLoggingChecker::capturePreResetState() { +void ResetLoggingChecker::capturePreResetState() +{ float a[2]; float b; uint8_t c; @@ -19,7 +20,8 @@ void ResetLoggingChecker::capturePreResetState() { } // call immediately after state reset -void ResetLoggingChecker::capturePostResetState() { +void ResetLoggingChecker::capturePostResetState() +{ float a[2]; float b; uint8_t c; @@ -42,40 +44,46 @@ void ResetLoggingChecker::capturePostResetState() { position_after_reset = _ekf->getPosition(); } -bool ResetLoggingChecker::isVelocityDeltaLoggedCorrectly(float accuracy) { +bool ResetLoggingChecker::isVelocityDeltaLoggedCorrectly(float accuracy) +{ const Vector3f measured_delta_velocity = velocity_after_reset - - velocity_before_reset; + velocity_before_reset; return matrix::isEqual(logged_delta_velocity, - measured_delta_velocity, - accuracy); + measured_delta_velocity, + accuracy); } -bool ResetLoggingChecker::isHorizontalVelocityResetCounterIncreasedBy(int offset) { +bool ResetLoggingChecker::isHorizontalVelocityResetCounterIncreasedBy(int offset) +{ return horz_vel_reset_counter_after_reset == - horz_vel_reset_counter_before_reset + offset; + horz_vel_reset_counter_before_reset + offset; } -bool ResetLoggingChecker::isVerticalVelocityResetCounterIncreasedBy(int offset) { +bool ResetLoggingChecker::isVerticalVelocityResetCounterIncreasedBy(int offset) +{ return vert_vel_reset_counter_after_reset == - vert_vel_reset_counter_before_reset + offset; + vert_vel_reset_counter_before_reset + offset; } -bool ResetLoggingChecker::isPositionDeltaLoggedCorrectly(float accuracy) { +bool ResetLoggingChecker::isPositionDeltaLoggedCorrectly(float accuracy) +{ const Vector3f measured_delta_position = position_after_reset - - position_before_reset; + position_before_reset; return matrix::isEqual(logged_delta_position, - measured_delta_position, - accuracy); + measured_delta_position, + accuracy); } -bool ResetLoggingChecker::isHorizontalPositionResetCounterIncreasedBy(int offset) { +bool ResetLoggingChecker::isHorizontalPositionResetCounterIncreasedBy(int offset) +{ return horz_pos_reset_counter_after_reset == - horz_pos_reset_counter_before_reset + offset; + horz_pos_reset_counter_before_reset + offset; } -bool ResetLoggingChecker::isVerticalPositionResetCounterIncreasedBy(int offset) { +bool ResetLoggingChecker::isVerticalPositionResetCounterIncreasedBy(int offset) +{ return vert_pos_reset_counter_after_reset == - vert_pos_reset_counter_before_reset + offset; + vert_pos_reset_counter_before_reset + offset; } diff --git a/src/lib/ecl/test/test_helper/reset_logging_checker.h b/src/modules/ekf2/test/test_helper/reset_logging_checker.h similarity index 95% rename from src/lib/ecl/test/test_helper/reset_logging_checker.h rename to src/modules/ekf2/test/test_helper/reset_logging_checker.h index a1c4fccc50..965a636371 100644 --- a/src/lib/ecl/test/test_helper/reset_logging_checker.h +++ b/src/modules/ekf2/test/test_helper/reset_logging_checker.h @@ -37,12 +37,14 @@ * @author Kamil Ritz */ -#pragma once +#ifndef EKF_RESET_LOGGING_CHECKER_H +#define EKF_RESET_LOGGING_CHECKER_H #include #include "EKF/ekf.h" -class ResetLoggingChecker { +class ResetLoggingChecker +{ public: ResetLoggingChecker(std::shared_ptr ekf) : _ekf(ekf) {} @@ -84,3 +86,4 @@ private: Vector3f logged_delta_velocity; Vector3f logged_delta_position; }; +#endif // !EKF_RESET_LOGGING_CHECKER_H diff --git a/src/modules/sensors/vehicle_gps_position/CMakeLists.txt b/src/modules/sensors/vehicle_gps_position/CMakeLists.txt index eb1aeb461b..12b625ead6 100644 --- a/src/modules/sensors/vehicle_gps_position/CMakeLists.txt +++ b/src/modules/sensors/vehicle_gps_position/CMakeLists.txt @@ -43,4 +43,4 @@ target_link_libraries(vehicle_gps_position px4_work_queue ) -px4_add_functional_gtest(SRC gps_blending_test.cpp LINKLIBS vehicle_gps_position) +px4_add_unit_gtest(SRC gps_blending_test.cpp LINKLIBS vehicle_gps_position)