From d52a8d96a9de0f35525ae7ddf82457f0e706db20 Mon Sep 17 00:00:00 2001
From: Alberto Nidasio <alberto.nidasio@skywarder.eu>
Date: Sun, 17 Jul 2022 11:43:27 +0000
Subject: [PATCH] [Parafoil] Updated implementation to match the main computer

---
 .vscode/c_cpp_properties.json                 |    64 +-
 .vscode/settings.json                         |    21 +-
 CMakeLists.txt                                |    43 +-
 cmake/dependencies.cmake                      |    30 +-
 skyward-boardcore                             |     2 +-
 src/boards/Parafoil/Actuators/Actuators.cpp   |   150 +
 src/boards/Parafoil/Actuators/Actuators.h     |    77 +
 .../lynx_airspeed_data.h => BoardScheduler.h} |    30 +-
 .../{Configs/XbeeConfig.h => Buses.h}         |    40 +-
 .../ActuatorsConfigs.h}                       |    61 +-
 src/boards/Parafoil/Configs/MavlinkConfig.h   |    44 -
 src/boards/Parafoil/Configs/NASConfig.h       |    60 +
 src/boards/Parafoil/Configs/RadioConfig.h     |    36 +-
 src/boards/Parafoil/Configs/SensorsConfig.h   |    13 +-
 src/boards/Parafoil/Configs/WingConfig.h      |    53 +-
 src/boards/Parafoil/Control/NASController.h   |   146 -
 .../Parafoil/FlightModeManager/FMM.scxml      |    10 -
 ...MMController.cpp => FlightModeManager.cpp} |   104 +-
 .../{FMMController.h => FlightModeManager.h}  |    29 +-
 .../{FMMData.h => FlightModeManagerData.h}    |    17 +-
 src/boards/Parafoil/Main/Radio.cpp            |   387 -
 src/boards/Parafoil/Main/Radio.h              |   195 -
 src/boards/Parafoil/Main/Sensors.cpp          |   303 -
 src/boards/Parafoil/Main/Sensors.h            |   142 -
 .../NASController.cpp                         |   162 +-
 .../Parafoil/NASController/NASController.h    |    68 +
 src/boards/Parafoil/ParafoilTest.h            |   270 -
 src/boards/Parafoil/ParafoilTestStatus.h      |    77 -
 src/boards/Parafoil/Radio/Radio.cpp           |   418 +
 src/boards/Parafoil/Radio/Radio.h             |   103 +
 src/boards/Parafoil/Sensors/Sensors.cpp       |   246 +
 .../Algorithms.h => Sensors/Sensors.h}        |    77 +-
 .../Parafoil/TMRepository/TMRepository.cpp    |   362 +
 .../Parafoil/TMRepository/TMRepository.h      |    70 +
 .../TelemetriesTelecommands/TMRepository.cpp  |   231 -
 .../TelemetriesTelecommands/TMRepository.h    |   109 -
 .../Parafoil/Wing/AutomaticWingAlgorithm.cpp  |    90 +-
 .../Parafoil/Wing/AutomaticWingAlgorithm.h    |    19 +-
 src/boards/Parafoil/Wing/WingAlgorithm.cpp    |    56 +-
 src/boards/Parafoil/Wing/WingAlgorithm.h      |    45 +-
 src/boards/Parafoil/Wing/WingAlgorithmData.h  |    16 +-
 src/boards/Parafoil/Wing/WingController.cpp   |   106 +-
 src/boards/Parafoil/Wing/WingController.h     |    40 +-
 src/boards/Parafoil/Wing/WingServo.cpp        |    71 -
 src/boards/Parafoil/Wing/WingServo.h          |    92 -
 src/boards/Parafoil/mocksensors/MockGPS.h     |   101 -
 src/boards/Parafoil/mocksensors/MockIMU.h     |    80 -
 .../Parafoil/mocksensors/MockPressureSensor.h |   109 -
 src/boards/Parafoil/mocksensors/MockSensors.h |    29 -
 .../Parafoil/mocksensors/MockSensorsData.h    |    90 -
 .../Parafoil/mocksensors/MockSpeedSensor.h    |    76 -
 .../lynx_flight_data/lynx_airspeed_data.cpp   |   923 -
 .../lynx_flight_data/lynx_gps_data.cpp        | 10979 ---------
 .../lynx_flight_data/lynx_gps_data.h          |    37 -
 .../lynx_flight_data/lynx_imu_data.cpp        | 19421 ----------------
 .../lynx_flight_data/lynx_imu_data.h          |    35 -
 .../lynx_flight_data/lynx_press_data.cpp      |  1462 --
 .../lynx_flight_data/lynx_press_data.h        |    30 -
 .../lynx_pressure_static_data.cpp             |   924 -
 .../lynx_pressure_static_data.h               |    30 -
 .../mocksensors/mock_data/test-mock-data.cpp  | 14664 ------------
 .../mocksensors/mock_data/test-mock-data.h    |    38 -
 .../mock_data/test-mock-sensors.cpp           |    82 -
 src/boards/Payload/Main/Sensors.h             |    13 +-
 src/boards/common/Algorithm.h                 |    65 -
 .../Mavlink.h                                 |    20 +-
 src/boards/common/ServoInterface.h            |   154 -
 src/boards/common/SystemData.h                |    51 -
 src/entrypoints/Parafoil/parafoil-entry.cpp   |   105 +-
 69 files changed, 2079 insertions(+), 52224 deletions(-)
 create mode 100644 src/boards/Parafoil/Actuators/Actuators.cpp
 create mode 100644 src/boards/Parafoil/Actuators/Actuators.h
 rename src/boards/Parafoil/{mocksensors/lynx_flight_data/lynx_airspeed_data.h => BoardScheduler.h} (70%)
 rename src/boards/Parafoil/{Configs/XbeeConfig.h => Buses.h} (64%)
 rename src/boards/Parafoil/{Control/Algorithms.cpp => Configs/ActuatorsConfigs.h} (57%)
 delete mode 100644 src/boards/Parafoil/Configs/MavlinkConfig.h
 create mode 100644 src/boards/Parafoil/Configs/NASConfig.h
 delete mode 100644 src/boards/Parafoil/Control/NASController.h
 delete mode 100644 src/boards/Parafoil/FlightModeManager/FMM.scxml
 rename src/boards/Parafoil/FlightModeManager/{FMMController.cpp => FlightModeManager.cpp} (51%)
 rename src/boards/Parafoil/FlightModeManager/{FMMController.h => FlightModeManager.h} (80%)
 rename src/boards/Parafoil/FlightModeManager/{FMMData.h => FlightModeManagerData.h} (85%)
 delete mode 100644 src/boards/Parafoil/Main/Radio.cpp
 delete mode 100644 src/boards/Parafoil/Main/Radio.h
 delete mode 100644 src/boards/Parafoil/Main/Sensors.cpp
 delete mode 100644 src/boards/Parafoil/Main/Sensors.h
 rename src/boards/Parafoil/{Control => NASController}/NASController.cpp (59%)
 create mode 100644 src/boards/Parafoil/NASController/NASController.h
 delete mode 100644 src/boards/Parafoil/ParafoilTest.h
 delete mode 100644 src/boards/Parafoil/ParafoilTestStatus.h
 create mode 100644 src/boards/Parafoil/Radio/Radio.cpp
 create mode 100644 src/boards/Parafoil/Radio/Radio.h
 create mode 100644 src/boards/Parafoil/Sensors/Sensors.cpp
 rename src/boards/Parafoil/{Control/Algorithms.h => Sensors/Sensors.h} (57%)
 create mode 100644 src/boards/Parafoil/TMRepository/TMRepository.cpp
 create mode 100644 src/boards/Parafoil/TMRepository/TMRepository.h
 delete mode 100644 src/boards/Parafoil/TelemetriesTelecommands/TMRepository.cpp
 delete mode 100644 src/boards/Parafoil/TelemetriesTelecommands/TMRepository.h
 delete mode 100644 src/boards/Parafoil/Wing/WingServo.cpp
 delete mode 100644 src/boards/Parafoil/Wing/WingServo.h
 delete mode 100644 src/boards/Parafoil/mocksensors/MockGPS.h
 delete mode 100644 src/boards/Parafoil/mocksensors/MockIMU.h
 delete mode 100644 src/boards/Parafoil/mocksensors/MockPressureSensor.h
 delete mode 100644 src/boards/Parafoil/mocksensors/MockSensors.h
 delete mode 100644 src/boards/Parafoil/mocksensors/MockSensorsData.h
 delete mode 100644 src/boards/Parafoil/mocksensors/MockSpeedSensor.h
 delete mode 100644 src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_airspeed_data.cpp
 delete mode 100644 src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_gps_data.cpp
 delete mode 100644 src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_gps_data.h
 delete mode 100644 src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_imu_data.cpp
 delete mode 100644 src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_imu_data.h
 delete mode 100644 src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_press_data.cpp
 delete mode 100644 src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_press_data.h
 delete mode 100644 src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_pressure_static_data.cpp
 delete mode 100644 src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_pressure_static_data.h
 delete mode 100644 src/boards/Parafoil/mocksensors/mock_data/test-mock-data.cpp
 delete mode 100644 src/boards/Parafoil/mocksensors/mock_data/test-mock-data.h
 delete mode 100644 src/boards/Parafoil/mocksensors/mock_data/test-mock-sensors.cpp
 delete mode 100644 src/boards/common/Algorithm.h
 rename src/boards/{Parafoil/TelemetriesTelecommands => common}/Mavlink.h (78%)
 delete mode 100644 src/boards/common/ServoInterface.h
 delete mode 100644 src/boards/common/SystemData.h

diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json
index 28ed0329d..69803b1bc 100755
--- a/.vscode/c_cpp_properties.json
+++ b/.vscode/c_cpp_properties.json
@@ -61,7 +61,69 @@
                 "limitSymbolsToIncludedHeaders": true
             },
             "configurationProvider": "ms-vscode.cmake-tools"
+        },
+        {
+            "name": "stm32f429zi_skyward_parafoil",
+            "cStandard": "c11",
+            "cppStandard": "c++11",
+            "compilerPath": "/opt/arm-miosix-eabi/bin/arm-miosix-eabi-g++",
+            "defines": [
+                "DEBUG",
+                "_ARCH_CORTEXM4_STM32F4",
+                "_BOARD_STM32F429ZI_SKYWARD_PARAFOIL",
+                "_MIOSIX_BOARDNAME=stm32f429zi_skyward_parafoil",
+                "HSE_VALUE=8000000",
+                "SYSCLK_FREQ_168MHz=168000000",
+                "_MIOSIX",
+                "__cplusplus=201103L"
+            ],
+            "includePath": [
+                "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil",
+                "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil",
+                "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common",
+                "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/common",
+                "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix",
+                "${workspaceFolder}/skyward-boardcore/libs/mavlink-skyward-lib",
+                "${workspaceFolder}/skyward-boardcore/libs/fmt/include",
+                "${workspaceFolder}/skyward-boardcore/libs/eigen",
+                "${workspaceFolder}/skyward-boardcore/libs/tscpp",
+                "${workspaceFolder}/skyward-boardcore/libs/mavlink-skyward-lib",
+                "${workspaceFolder}/skyward-boardcore/libs",
+                "${workspaceFolder}/skyward-boardcore/src/shared",
+                "${workspaceFolder}/skyward-boardcore/src/tests",
+                "${workspaceFolder}/src/boards",
+                "${workspaceFolder}/src/tests",
+                "${workspaceFolder}/src"
+            ],
+            "browse": {
+                "path": [
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/config/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/stm32f429zi_skyward_parafoil",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/cortexM4_stm32f4/common",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/stdlib_integration",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/arch/common",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/interfaces",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/filesystem",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/kernel",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/util",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/e20",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix/*",
+                    "${workspaceFolder}/skyward-boardcore/libs/miosix-kernel/miosix",
+                    "${workspaceFolder}/skyward-boardcore/libs/mavlink-skyward-lib",
+                    "${workspaceFolder}/skyward-boardcore/libs/eigen",
+                    "${workspaceFolder}/skyward-boardcore/libs/tscpp",
+                    "${workspaceFolder}/skyward-boardcore/libs/mxgui",
+                    "${workspaceFolder}/skyward-boardcore/libs/fmt",
+                    "${workspaceFolder}/skyward-boardcore/src/shared",
+                    "${workspaceFolder}/skyward-boardcore/src/tests",
+                    "${workspaceFolder}/src/boards",
+                    "${workspaceFolder}/src/tests",
+                    "${workspaceFolder}/src"
+                ],
+                "limitSymbolsToIncludedHeaders": true
+            },
+            "configurationProvider": "ms-vscode.cmake-tools"
         }
     ],
     "version": 4
-}
\ No newline at end of file
+}
diff --git a/.vscode/settings.json b/.vscode/settings.json
index ecfd4054d..c3d1fc524 100644
--- a/.vscode/settings.json
+++ b/.vscode/settings.json
@@ -94,15 +94,34 @@
         "matrixfunctions": "cpp"
     },
     "cSpell.words": [
+        "Aeroutils",
+        "baro",
         "Boardcore",
+        "Eigen",
         "Erbetta",
         "Gpio",
+        "GPIOA",
+        "GPIOB",
+        "GPIOC",
+        "GPIOD",
+        "GPIOF",
+        "GPIOG",
         "leds",
         "Luca",
+        "Matteo",
+        "Mavlink",
         "miosix",
+        "MOSI",
+        "Nidasio",
+        "pinouts",
         "Terraneo",
+        "tmrepo",
         "tscpp",
-        "UBXGPS"
+        "Ublox",
+        "UBXGPS",
+        "usart",
+        "wingalgo",
+        "wingctrl"
     ],
     "C_Cpp.errorSquiggles": "Enabled"
 }
diff --git a/CMakeLists.txt b/CMakeLists.txt
index 344016d00..13101e475 100644
--- a/CMakeLists.txt
+++ b/CMakeLists.txt
@@ -24,50 +24,21 @@ enable_testing()
 include(skyward-boardcore/cmake/sbs.cmake)
 
 # -----------------------------------------------------------------------------#
-# Project                                   #
+#                                    Project                                   #
 # -----------------------------------------------------------------------------#
+
 project(SkywardParafoilTest)
 
 # -----------------------------------------------------------------------------#
-# Main Computer                                #
+#                                Parafoil mockup                               #
 # -----------------------------------------------------------------------------#
 
-# add_executable(catch-tests-main
-# src/tests/MainComputer/catch/catch-tests-entry.cpp
-# src/tests/MainComputer/catch/test-airbrakes.cpp
-# src/tests/MainComputer/catch/test-ada.cpp
-# src/tests/MainComputer/catch/test-deployment.cpp
-# src/tests/MainComputer/catch/test-fsr.cpp
-# src/tests/MainComputer/catch/test-nas.cpp
-# ${MAIN_COMPUTER}
-# )
-# target_include_directories(catch-tests-main PRIVATE ${OBSW_INCLUDE_DIRS})
-# target_compile_definitions(catch-tests-main PRIVATE USE_MOCK_PERIPHERALS)
-# sbs_target(catch-tests-main stm32f429zi_skyward_death_stack_x)
-# sbs_catch_test(catch-tests-main)
-
-# -----------------------------------------------------------------------------#
-# Parafoil mockup Computer                              #
-# -----------------------------------------------------------------------------#
-add_executable(parafoil-mockup-entry
-    src/entrypoints/Parafoil/parafoil-entry.cpp
-    ${PARAFOIL_MOCKUP_COMPUTER}
-)
+add_executable(parafoil-mockup-entry src/entrypoints/Parafoil/parafoil-entry.cpp ${PARAFOIL_COMPUTER})
 target_include_directories(parafoil-mockup-entry PRIVATE ${OBSW_INCLUDE_DIRS})
-sbs_target(parafoil-mockup-entry stm32f429zi_stm32f4discovery)
+sbs_target(parafoil-mockup-entry stm32f429zi_skyward_parafoil)
 
 # add_executable(parafoil-test-bme280 src/tests/Parafoil/parafoil-test-bme280.cpp)
-# sbs_target(parafoil-test-bme280 stm32f429zi_stm32f4discovery)
+# sbs_target(parafoil-test-bme280 stm32f429zi_skyward_parafoil)
 
 # add_executable(parafoil-test-ublox-uart src/tests/Parafoil/parafoil-test-ublox-uart.cpp)
-# sbs_target(parafoil-test-ublox-uart stm32f429zi_stm32f4discovery)
-
-# -----------------------------------------------------------------------------#
-# Payload computer                              #
-# -----------------------------------------------------------------------------#
-add_executable(payload-entry
-    src/entrypoints/Payload/payload-entry.cpp
-    ${PAYLOAD_COMPUTER}
-)
-target_include_directories(payload-entry PRIVATE ${OBSW_INCLUDE_DIRS})
-sbs_target(payload-entry stm32f429zi_skyward_death_stack_x)
\ No newline at end of file
+# sbs_target(parafoil-test-ublox-uart stm32f429zi_skyward_parafoil)
diff --git a/cmake/dependencies.cmake b/cmake/dependencies.cmake
index 5f5966924..ef5fb2eb4 100644
--- a/cmake/dependencies.cmake
+++ b/cmake/dependencies.cmake
@@ -23,30 +23,14 @@ set(OBSW_INCLUDE_DIRS
     src/boards
 )
 
-# set(MAIN_COMPUTER
-# src/boards/MainComputer/events/EventStrings.cpp
-# src/boards/MainComputer/Actuators/Actuators.cpp
-# src/boards/MainComputer/AirBrakes/AirBrakesController.cpp
-# src/boards/MainComputer/ApogeeDetectionAlgorithm/ADAController.cpp
-# src/boards/MainComputer/Deployment/DeploymentController.cpp
-# src/boards/MainComputer/NavigationAttitudeSystem/NASController.cpp
-# src/boards/MainComputer/FlightStatsRecorder/FSRController.cpp
-# )
-set(PARAFOIL_MOCKUP_COMPUTER
-    src/boards/Parafoil/Main/Sensors.cpp
-    src/boards/Parafoil/Main/Radio.cpp
-    src/boards/Parafoil/TelemetriesTelecommands/TMRepository.cpp
-    src/boards/Parafoil/Wing/WingServo.cpp
+set(PARAFOIL_COMPUTER
+    src/boards/Parafoil/Actuators/Actuators.cpp
+    src/boards/Parafoil/FlightModeManager/FlightModeManager.cpp
+    src/boards/Parafoil/NASController/NASController.cpp
+    src/boards/Parafoil/Radio/Radio.cpp
+    src/boards/Parafoil/Sensors/Sensors.cpp
+    src/boards/Parafoil/TMRepository/TMRepository.cpp
     src/boards/Parafoil/Wing/WingAlgorithm.cpp
     src/boards/Parafoil/Wing/AutomaticWingAlgorithm.cpp
     src/boards/Parafoil/Wing/WingController.cpp
-    src/boards/Parafoil/FlightModeManager/FMMController.cpp
-    src/boards/Parafoil/Control/Algorithms.cpp
-    src/boards/Parafoil/Control/NASController.cpp
-)
-set(PAYLOAD_COMPUTER
-    src/boards/Payload/Main/Sensors.cpp
-    src/boards/Payload/Main/Radio.cpp
-    src/boards/Payload/TelemetriesTelecommands/TMRepository.cpp
-    src/boards/Payload/Control/NASController.cpp
 )
diff --git a/skyward-boardcore b/skyward-boardcore
index 680203efd..99bcab503 160000
--- a/skyward-boardcore
+++ b/skyward-boardcore
@@ -1 +1 @@
-Subproject commit 680203efd050713021421b82a66748cf7ba53c74
+Subproject commit 99bcab503fbc4b33836a96760cca28a90a55ba61
diff --git a/src/boards/Parafoil/Actuators/Actuators.cpp b/src/boards/Parafoil/Actuators/Actuators.cpp
new file mode 100644
index 000000000..81f932916
--- /dev/null
+++ b/src/boards/Parafoil/Actuators/Actuators.cpp
@@ -0,0 +1,150 @@
+/* Copyright (c) 2021 Skyward Experimental Rocketry
+ * Author: Alberto Nidasio
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include "Actuators.h"
+
+#include <Parafoil/Configs/ActuatorsConfigs.h>
+
+#ifndef COMPILE_FOR_HOST
+#include <interfaces-impl/hwmapping.h>
+#endif
+
+using namespace miosix;
+using namespace Parafoil::ActuatorsConfigs;
+
+namespace Parafoil
+{
+
+bool Actuators::setServo(ServosList servoId, float percentage)
+{
+    switch (servoId)
+    {
+        case PARAFOIL_SERVO1:
+            servo1.setPosition(percentage);
+            break;
+        case PARAFOIL_SERVO2:
+            servo2.setPosition(percentage);
+            break;
+        default:
+            return false;
+    }
+
+    return true;
+}
+
+bool Actuators::setServoAngle(ServosList servoId, float angle)
+{
+    switch (servoId)
+    {
+        case PARAFOIL_SERVO1:
+            servo1.setPosition(angle / SERVO_1_ROTATION);
+            break;
+        case PARAFOIL_SERVO2:
+            servo2.setPosition(angle / SERVO_2_ROTATION);
+            break;
+        default:
+            return false;
+    }
+
+    return true;
+}
+
+bool Actuators::wiggleServo(ServosList servoId)
+{
+    switch (servoId)
+    {
+        case PARAFOIL_SERVO1:
+            servo1.setPosition(1);
+            Thread::sleep(1000);
+            servo1.setPosition(0);
+            break;
+        case PARAFOIL_SERVO2:
+            servo2.setPosition(1);
+            Thread::sleep(1000);
+            servo2.setPosition(0);
+            break;
+        default:
+            return false;
+    }
+
+    return true;
+}
+
+bool Actuators::enableServo(ServosList servoId)
+{
+    switch (servoId)
+    {
+        case PARAFOIL_SERVO1:
+            servo1.enable();
+            break;
+        case PARAFOIL_SERVO2:
+            servo2.enable();
+            break;
+        default:
+            return false;
+    }
+
+    return true;
+}
+
+bool Actuators::disableServo(ServosList servoId)
+{
+    switch (servoId)
+    {
+        case PARAFOIL_SERVO1:
+            servo1.enable();
+            break;
+        case PARAFOIL_SERVO2:
+            servo1.enable();
+            break;
+        default:
+            return false;
+    }
+
+    return true;
+}
+
+float Actuators::getServoPosition(ServosList servoId)
+{
+
+    switch (servoId)
+    {
+        case PARAFOIL_SERVO1:
+            return servo1.getPosition();
+        case PARAFOIL_SERVO2:
+            return servo2.getPosition();
+        default:
+            return 0;
+    }
+
+    return 0;
+}
+
+Actuators::Actuators()
+    : servo1(SERVO_1_TIMER, SERVO_1_PWM_CH, SERVO_1_MIN_PULSE,
+             SERVO_1_MAX_PULSE),
+      servo2(SERVO_2_TIMER, SERVO_2_PWM_CH, SERVO_2_MIN_PULSE,
+             SERVO_2_MAX_PULSE)
+{
+}
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Actuators/Actuators.h b/src/boards/Parafoil/Actuators/Actuators.h
new file mode 100644
index 000000000..8ae12c442
--- /dev/null
+++ b/src/boards/Parafoil/Actuators/Actuators.h
@@ -0,0 +1,77 @@
+/* Copyright (c) 2021 Skyward Experimental Rocketry
+ * Author: Alberto Nidasio
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <Singleton.h>
+#include <actuators/Servo/Servo.h>
+#include <common/Mavlink.h>
+#include <interfaces/gpio.h>
+
+namespace Parafoil
+{
+
+struct Actuators : public Boardcore::Singleton<Actuators>
+{
+    friend class Boardcore::Singleton<Actuators>;
+
+    /**
+     * @brief Moves the specified servo to the given position.
+     *
+     * @param servoId Servo to move.
+     * @param percentage Angle to set [0-1].
+     * @return True if the the angle was set.
+     */
+    bool setServo(ServosList servoId, float percentage);
+
+    /**
+     * @brief Moves the specified servo to the given position.
+     *
+     * @param servoId Servo to move.
+     * @param angle Angle to set [degree].
+     * @return True if the the angle was set.
+     */
+    bool setServoAngle(ServosList servoId, float angle);
+
+    /**
+     * @brief Wiggles the servo for few seconds.
+     *
+     * @param servoId Servo to move.
+     * @return true
+     * @return false
+     */
+    bool wiggleServo(ServosList servoId);
+
+    bool enableServo(ServosList servoId);
+
+    bool disableServo(ServosList servoId);
+
+    float getServoPosition(ServosList servoId);
+
+private:
+    Actuators();
+
+    Boardcore::Servo servo1;
+    Boardcore::Servo servo2;
+};
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_airspeed_data.h b/src/boards/Parafoil/BoardScheduler.h
similarity index 70%
rename from src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_airspeed_data.h
rename to src/boards/Parafoil/BoardScheduler.h
index d0948bffb..4ae0d9346 100644
--- a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_airspeed_data.h
+++ b/src/boards/Parafoil/BoardScheduler.h
@@ -1,5 +1,5 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Authors: Luca Conterio
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Alberto Nidasio
  *
  * Permission is hereby granted, free of charge, to any person obtaining a copy
  * of this software and associated documentation files (the "Software"), to deal
@@ -22,11 +22,23 @@
 
 #pragma once
 
-#include <Common.h>
+#include <Singleton.h>
+#include <scheduler/TaskScheduler.h>
 
-/**
- * Pitot airspeed data from Lynx flight test in Roccaraso.
- * Sampled at 42 Hz (24 ms period).
- */
-static constexpr unsigned AIRSPEED_DATA_SIZE = 5384;
-extern const float AIRSPEED_DATA[AIRSPEED_DATA_SIZE];
\ No newline at end of file
+namespace Parafoil
+{
+
+class BoardScheduler : public Boardcore::Singleton<BoardScheduler>
+{
+    friend Boardcore::Singleton<BoardScheduler>;
+
+public:
+    Boardcore::TaskScheduler& getScheduler() { return scheduler; }
+
+private:
+    BoardScheduler() {}
+
+    Boardcore::TaskScheduler scheduler;
+};
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Configs/XbeeConfig.h b/src/boards/Parafoil/Buses.h
similarity index 64%
rename from src/boards/Parafoil/Configs/XbeeConfig.h
rename to src/boards/Parafoil/Buses.h
index e254ea5a0..1dcc66672 100644
--- a/src/boards/Parafoil/Configs/XbeeConfig.h
+++ b/src/boards/Parafoil/Buses.h
@@ -1,5 +1,5 @@
 /* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
+ * Author: Alberto Nidasio
  *
  * Permission is hereby granted, free of charge, to any person obtaining a copy
  * of this software and associated documentation files (the "Software"), to deal
@@ -22,22 +22,38 @@
 
 #pragma once
 
-#include <radio/Xbee/Xbee.h>
+#include <Singleton.h>
+#include <drivers/spi/SPIBus.h>
+#include <drivers/usart/USART.h>
+#include <miosix.h>
 
 namespace Parafoil
 {
 
-// TODO change the pins to something correct
-static miosix::GpioPin XBEE_CS(GPIOC_BASE, 1);
-static miosix::GpioPin XBEE_ATTN(GPIOF_BASE, 10);  // Interrupt pin
-static miosix::GpioPin XBEE_RESET(GPIOC_BASE, 5);
+struct Buses : public Boardcore::Singleton<Buses>
+{
+    friend class Boardcore::Singleton<Buses>;
+
+    Boardcore::USART usart2;
 
-static miosix::GpioPin XBEE_SCK(GPIOE_BASE, 2);
-static miosix::GpioPin XBEE_MISO(GPIOE_BASE, 5);
-static miosix::GpioPin XBEE_MOSI(GPIOE_BASE, 6);
+    Boardcore::SPIBus spi1;
+    Boardcore::SPIBus spi4;
 
-// Data rate
-static const bool XBEE_80KBPS_DATA_RATE = true;
-static const int XBEE_TIMEOUT           = 5000;  // [ms]
+private:
+#ifndef USE_MOCK_PERIPHERALS
+    Buses()
+        : usart2(USART2, Boardcore::USARTInterface::Baudrate::B115200),
+          spi1(SPI1), spi4(SPI4)
+    {
+        usart2.init();
+    }
+#else
+    Buses()
+        : usart2(USART2, Boardcore::USARTInterface::Baudrate::B115200),
+          spi1({}), spi4({})
+    {
+    }
+#endif
+};
 
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/Control/Algorithms.cpp b/src/boards/Parafoil/Configs/ActuatorsConfigs.h
similarity index 57%
rename from src/boards/Parafoil/Control/Algorithms.cpp
rename to src/boards/Parafoil/Configs/ActuatorsConfigs.h
index d0c4730df..c70939b78 100644
--- a/src/boards/Parafoil/Control/Algorithms.cpp
+++ b/src/boards/Parafoil/Configs/ActuatorsConfigs.h
@@ -1,5 +1,5 @@
 /* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
+ * Author: Alberto Nidasio
  *
  * Permission is hereby granted, free of charge, to any person obtaining a copy
  * of this software and associated documentation files (the "Software"), to deal
@@ -20,50 +20,37 @@
  * THE SOFTWARE.
  */
 
-#include <Parafoil/Control/Algorithms.h>
-#include <Parafoil/ParafoilTest.h>
+#pragma once
 
-using namespace Boardcore;
-using namespace std;
+#include <drivers/timer/PWM.h>
+#include <drivers/timer/TimerUtils.h>
 
 namespace Parafoil
 {
-Algorithms::Algorithms(TaskScheduler* scheduler)
+
+namespace ActuatorsConfigs
 {
-    this->scheduler = scheduler;
 
-    // Init the algorithms
-    NASInit();
-}
+// Servo 1
 
-Algorithms::~Algorithms()
-{
-    // Destroy all the algorithms
-    delete nas;
-}
+static TIM_TypeDef* const SERVO_1_TIMER = TIM4;
+static constexpr Boardcore::TimerUtils::Channel SERVO_1_PWM_CH =
+    Boardcore::TimerUtils::Channel::CHANNEL_2;
 
-bool Algorithms::start()
-{
-    // Start the scheduler
-    return nas->start();
-}
+static constexpr float SERVO_1_ROTATION  = 120;
+static constexpr float SERVO_1_MIN_PULSE = 900;   // [deg]
+static constexpr float SERVO_1_MAX_PULSE = 2100;  // [deg]
 
-void Algorithms::NASInit()
-{
-    // Create the nas
-    nas = new NASController(scheduler);
+// Servo 2
 
-    // Init
-    nas->init();
-}
+static TIM_TypeDef* const SERVO_2_TIMER = TIM10;
+static constexpr Boardcore::TimerUtils::Channel SERVO_2_PWM_CH =
+    Boardcore::TimerUtils::Channel::CHANNEL_1;
 
-/**
- * GETTERS
- */
-NASState Algorithms::getNASLastSample()
-{
-    // Pause the kernel for sync purposes
-    miosix::PauseKernelLock lock;
-    return nas->getLastSample();
-}
-}  // namespace Parafoil
\ No newline at end of file
+static constexpr float SERVO_2_ROTATION  = 120;
+static constexpr float SERVO_2_MIN_PULSE = 2100;  // [deg]
+static constexpr float SERVO_2_MAX_PULSE = 900;   // [deg]
+
+}  // namespace ActuatorsConfigs
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Configs/MavlinkConfig.h b/src/boards/Parafoil/Configs/MavlinkConfig.h
deleted file mode 100644
index 7bda99a2f..000000000
--- a/src/boards/Parafoil/Configs/MavlinkConfig.h
+++ /dev/null
@@ -1,44 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <stdint.h>
-
-#include <cstdio>
-
-namespace Parafoil
-{
-
-// Mavlink Driver queue settings
-static constexpr unsigned int MAV_OUT_QUEUE_LEN = 10;
-static constexpr unsigned int MAV_PKT_SIZE      = 63;
-static constexpr size_t MAV_OUT_BUFFER_MAX_AGE  = 200;
-
-// These two values are taken as is
-static const unsigned int TMTC_MAV_SYSID  = 171;
-static const unsigned int TMTC_MAV_COMPID = 96;
-
-// Min guaranteed sleep time after each packet sent
-static const uint16_t SLEEP_AFTER_SEND = 0;  // [ms]
-
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Configs/NASConfig.h b/src/boards/Parafoil/Configs/NASConfig.h
new file mode 100644
index 000000000..addbff398
--- /dev/null
+++ b/src/boards/Parafoil/Configs/NASConfig.h
@@ -0,0 +1,60 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Alberto Nidasio
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <algorithms/NAS/NASConfig.h>
+
+namespace Parafoil
+{
+
+namespace NASConfig
+{
+
+static constexpr uint32_t UPDATE_PERIOD = 50;  // 50 hz
+
+// Magnetic field in Milan
+Eigen::Vector3f nedMag(0.4747, 0.0276, 0.8797);
+
+static const Boardcore::NASConfig config = {
+    1.0f / UPDATE_PERIOD,  // T
+    0.0001f,               // SIGMA_BETA
+    0.3f,                  // SIGMA_W
+    0.1f,                  // SIGMA_MAG
+    10.0f,                 // SIGMA_GPS
+    4.3f,                  // SIGMA_BAR
+    10.0f,                 // SIGMA_POS
+    10.0f,                 // SIGMA_VEL
+    10.0f,                 // SIGMA_PITOT
+    1.0f,                  // P_POS
+    10.0f,                 // P_POS_VERTICAL
+    1.0f,                  // P_VEL
+    10.0f,                 // P_VEL_VERTICAL
+    0.01f,                 // P_ATT
+    0.01f,                 // P_BIAS
+    6.0f,                  // SATS_NUM
+    nedMag                 // NED_MAG
+};
+
+}  // namespace NASConfig
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Configs/RadioConfig.h b/src/boards/Parafoil/Configs/RadioConfig.h
index 459d378ef..d470f6f4d 100644
--- a/src/boards/Parafoil/Configs/RadioConfig.h
+++ b/src/boards/Parafoil/Configs/RadioConfig.h
@@ -22,20 +22,36 @@
 
 #pragma once
 
-#include <stdint.h>
+#include <common/Mavlink.h>
+
+#include <cstdio>
 
 namespace Parafoil
 {
 
-// TODO: update with the correct values
-static const uint32_t HR_GROUND_UPDATE_PERIOD = 62;  // [ms]
-static const uint32_t HR_FLIGHT_UPDATE_PERIOD = 10;
-static const uint32_t LR_UPDATE_PERIOD        = 100;  // [ms]
-static const uint32_t SD_UPDATE_PERIOD        = 10000;
+namespace RadioConfig
+{
+
+// Mavlink driver template parameters
+constexpr uint32_t RADIO_PKT_LENGTH     = 255;
+constexpr uint32_t RADIO_OUT_QUEUE_SIZE = 10;
+constexpr uint32_t RADIO_MAV_MSG_LENGTH = MAVLINK_MAX_DIALECT_PAYLOAD_SIZE;
+
+// Mavlink driver parameters
+constexpr size_t MAV_OUT_BUFFER_MAX_AGE = 200;
+
+// Mavlink ids
+constexpr uint8_t MAV_SYSTEM_ID    = 171;
+constexpr uint8_t MAV_COMPONENT_ID = 96;
+
+// Periodic telemetries frequency
+constexpr uint32_t FLIGHT_TM_PERIOD = 250;   // [ms]
+constexpr uint32_t STATS_TM_PERIOD  = 2000;  // [ms]
+
+// Periodic telemetries tasks ids
+constexpr uint8_t FLIGHT_TM_TASK_ID = 200;
+constexpr uint8_t STATS_TM_TASK_ID  = 201;
 
-// TODO: define the correct ids for task scheduler
-static const uint8_t RADIO_HR_ID  = 200;
-static const uint8_t RADIO_LR_ID  = 201;
-static const uint8_t SD_UPDATE_ID = 202;
+}  // namespace RadioConfig
 
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/Configs/SensorsConfig.h b/src/boards/Parafoil/Configs/SensorsConfig.h
index 8554bff6a..853cad9be 100644
--- a/src/boards/Parafoil/Configs/SensorsConfig.h
+++ b/src/boards/Parafoil/Configs/SensorsConfig.h
@@ -35,20 +35,14 @@
 namespace Parafoil
 {
 
-// SPI pinouts
-static miosix::GpioPin SCK(GPIOA_BASE, 5);
-static miosix::GpioPin MISO(GPIOB_BASE, 4);
-static miosix::GpioPin MOSI(GPIOA_BASE, 7);
+namespace SensorsConfig
+{
 
 // GPS settings
-// static miosix::GpioPin GPS_CS(GPIOG_BASE, 3);
-static miosix::GpioPin GPS_TX(GPIOD_BASE, 5);
-static miosix::GpioPin GPS_RX(GPIOA_BASE, 3);
 static constexpr unsigned int GPS_SAMPLE_RATE   = 10;
 static constexpr unsigned int GPS_SAMPLE_PERIOD = 1000 / GPS_SAMPLE_RATE;
 
 // IMU MPU9250 settings
-static miosix::GpioPin IMU_CS(GPIOB_BASE, 2);
 static const Boardcore::MPU9250::MPU9250GyroFSR IMU_GYRO_SCALE =
     Boardcore::MPU9250::GYRO_FSR_500DPS;
 static const Boardcore::MPU9250::MPU9250AccelFSR IMU_ACCEL_SCALE =
@@ -57,9 +51,10 @@ static constexpr unsigned short IMU_SAMPLE_RATE = 500;
 static constexpr unsigned int IMU_SAMPLE_PERIOD = 1000 / IMU_SAMPLE_RATE;
 
 // Barometer BME280 settings
-static miosix::GpioPin PRESS_CS(GPIOC_BASE, 11);
 static const Boardcore::BME280::StandbyTime PRESS_SAMPLE_RATE =
     Boardcore::BME280::STB_TIME_0_5;
 static constexpr unsigned int PRESS_SAMPLE_PERIOD = 20;
 
+}  // namespace SensorsConfig
+
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/Configs/WingConfig.h b/src/boards/Parafoil/Configs/WingConfig.h
index efed45f0c..ab7102fb2 100644
--- a/src/boards/Parafoil/Configs/WingConfig.h
+++ b/src/boards/Parafoil/Configs/WingConfig.h
@@ -27,52 +27,25 @@
 
 #include <Eigen/Core>
 
-/**
- * @brief This class defines all the wing configs
- * (E.g. Servos PWM channels, Servos max and min positions, etc..)
- */
 namespace Parafoil
 {
 
-// ALGORITHM CONFIGURATION
-static const uint32_t WING_UPDATE_PERIOD = 100;  // milliseconds
-static const uint8_t WING_CONTROLLER_ID  = 100;  // TODO define a correct ID
-
-// ALGORITHM START AND FLARE ARMING CONSTANTS
-static const float WING_ALGORITHM_ARM_ALTITUDE  = 250;   // [m]
-static const float WING_ALGORITHM_START_ALTITUE = 200;   // [m]
-static const float WING_FLARE_ALTITUDE          = 1275;  // [m]
-
-static float WING_CALIBRATION_PRESSURE    = 101325;  // Pa
-static float WING_CALIBRATION_TEMPERATURE = 300;     // Kelvin
-static uint8_t WING_PRESSURE_MEAN_COUNT   = 20;
-
-// SERVOS CONFIGURATIONS
-static miosix::GpioPin SERVO1PIN(GPIOB_BASE, 7);
-static miosix::GpioPin SERVO2PIN(GPIOF_BASE, 6);
-
-// 16 bit, 45MHz, no DMA timer
-static TIM_TypeDef* WING_SERVO1_TIMER = TIM4;
-static TIM_TypeDef* WING_SERVO2_TIMER = TIM10;
-
-static const Boardcore::TimerUtils::Channel WING_SERVO1_PWM_CHANNEL =
-    Boardcore::TimerUtils::Channel::CHANNEL_2;
-static const Boardcore::TimerUtils::Channel WING_SERVO2_PWM_CHANNEL =
-    Boardcore::TimerUtils::Channel::CHANNEL_1;
+namespace WingConfig
+{
 
-// Servo dependent variables
-static const unsigned int WING_SERVO_MIN_PULSE   = 900;
-static const unsigned int WING_SERVO_MAX_PULSE   = 2100;
-static const unsigned int WING_SERVO_FREQUENCY   = 50;
-static const unsigned int WING_SERVO_MAX_DEGREES = 120;
+// Algorithm configuration
+static constexpr uint32_t WING_UPDATE_PERIOD = 100;  // [ms]
+static constexpr uint8_t WING_CONTROLLER_ID  = 100;  // TODO define a correct ID
 
-static const float WING_SERVO1_MAX_POSITION = 120;  // degrees
-static const float WING_SERVO2_MAX_POSITION = 120;  // degrees
+// Arm, start and flare thresholds
+static constexpr float WING_ALGORITHM_ARM_ALTITUDE   = 250;   // [m]
+static constexpr float WING_ALGORITHM_START_ALTITUDE = 200;   // [m]
+static constexpr float WING_FLARE_ALTITUDE           = 1275;  // [m]
 
-static const float WING_SERVO1_MIN_POSITION = 0;  // degrees
-static const float WING_SERVO2_MIN_POSITION = 0;  // degrees
+static float WING_CALIBRATION_PRESSURE    = 101325;  // [Pa]
+static float WING_CALIBRATION_TEMPERATURE = 300;     // [K]
+static uint8_t WING_PRESSURE_MEAN_COUNT   = 20;
 
-static const float WING_SERVO1_RESET_POSITION = 0;    // degrees
-static const float WING_SERVO2_RESET_POSITION = 120;  // degrees
+}  // namespace WingConfig
 
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/Control/NASController.h b/src/boards/Parafoil/Control/NASController.h
deleted file mode 100644
index 25b6974da..000000000
--- a/src/boards/Parafoil/Control/NASController.h
+++ /dev/null
@@ -1,146 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Alberto Nidasio, Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-#pragma once
-
-#include <algorithms/NAS/NAS.h>
-#include <algorithms/NAS/StateInitializer.h>
-#include <scheduler/TaskScheduler.h>
-
-#include <Eigen/Core>
-#include <functional>
-
-/**
- * USAGE:
- * NASController* nas = new NASController(bind()...);
- *
- * nas->setInitialOrientation({});
- * nas->setInitialPosition({});
- * nas->init();
- * nas->start();
- *
- * nas->getLastSample();
- */
-
-namespace Parafoil
-{
-/**
- * @brief The class expects some parameters that represent the data type
- */
-class NASController
-{
-public:
-    /**
-     * @brief Construct a new NASController object
-     *
-     * @param imuGetter The imu data getter function (done to avoid sync
-     * problems with sensors class)
-     * @param gpsGetter The gps data getter function (done to avoid sync
-     * problems with sensors class)
-     */
-    NASController(Boardcore::TaskScheduler* scheduler,
-                  Boardcore::NASConfig config = getDefaultConfig());
-
-    /**
-     * @brief Destroy the NASController object
-     */
-    ~NASController();
-
-    /**
-     * @brief Method to calculate using triad the initial orientation
-     */
-    void calculateInitialOrientation();
-
-    /**
-     * @brief Method to set the initial gps position
-     */
-    void setInitialPosition(Eigen::Vector2f position);
-
-    /**
-     * @brief Method to initialize the controller
-     */
-    void init();
-
-    /**
-     * @brief Method to start the nas
-     */
-    bool start();
-
-    /**
-     * @brief Method to get the last sample
-     */
-    Boardcore::NASState getLastSample();
-
-    /**
-     * @brief Method to make the nas go forward with the prediction and
-     * correction
-     */
-    void step();
-
-    /**
-     * @brief Default config getter
-     */
-    static Boardcore::NASConfig getDefaultConfig()
-    {
-        Boardcore::NASConfig config;
-
-        config.T              = 0.02f;
-        config.SIGMA_BETA     = 0.0001f;
-        config.SIGMA_W        = 0.3f;
-        config.SIGMA_MAG      = 0.1f;
-        config.SIGMA_GPS      = 10.0f;
-        config.SIGMA_BAR      = 4.3f;
-        config.SIGMA_POS      = 10.0;
-        config.SIGMA_VEL      = 10.0;
-        config.P_POS          = 1.0f;
-        config.P_POS_VERTICAL = 10.0f;
-        config.P_VEL          = 1.0f;
-        config.P_VEL_VERTICAL = 10.0f;
-        config.P_ATT          = 0.01f;
-        config.P_BIAS         = 0.01f;
-        config.SATS_NUM       = 6.0f;
-        // TODO Define what this stuff is
-        config.NED_MAG = Eigen::Vector3f(0.4747, 0.0276, 0.8797);
-
-        return config;
-    }
-
-private:
-    // The NAS filter
-    Boardcore::NAS* nas;
-
-    // The nas config
-    Boardcore::NASConfig config;
-    Eigen::Vector3f initialOrientation;
-    Eigen::Vector2f initialPosition{42.57182024359364, 12.585861994119355};
-
-    // Task scheduler
-    Boardcore::TaskScheduler* scheduler;
-
-    // SD Logger
-    Boardcore::Logger* SDlogger = &Boardcore::Logger::getInstance();
-
-    // Debug logger
-    Boardcore::PrintLogger logger =
-        Boardcore::Logging::getLogger("NASController");
-};
-
-}  // namespace Parafoil
\ No newline at end of file
diff --git a/src/boards/Parafoil/FlightModeManager/FMM.scxml b/src/boards/Parafoil/FlightModeManager/FMM.scxml
deleted file mode 100644
index 0b59b8518..000000000
--- a/src/boards/Parafoil/FlightModeManager/FMM.scxml
+++ /dev/null
@@ -1,10 +0,0 @@
-<scxml version="1.0" xmlns="http://www.w3.org/2005/07/scxml" initial="OnGround">
-    <state id="OnGround">
-        <transition event="FMM.EV_LIFTOFF" target="FlyingState"></transition>
-        <transition event="FMM.EV_TC_TEST_MODE" target="DebugState"></transition>
-    </state>
-    <state id="Flying"></state>
-    <state id="Debug">
-        <transition event="FMM.EV_TC_EXIT_TEST_MODE" target="OnGround"></transition>
-    </state>
-</scxml>
\ No newline at end of file
diff --git a/src/boards/Parafoil/FlightModeManager/FMMController.cpp b/src/boards/Parafoil/FlightModeManager/FlightModeManager.cpp
similarity index 51%
rename from src/boards/Parafoil/FlightModeManager/FMMController.cpp
rename to src/boards/Parafoil/FlightModeManager/FlightModeManager.cpp
index 4de25c2bf..4805fd38e 100644
--- a/src/boards/Parafoil/FlightModeManager/FMMController.cpp
+++ b/src/boards/Parafoil/FlightModeManager/FlightModeManager.cpp
@@ -20,9 +20,10 @@
  * THE SOFTWARE.
  */
 
-#include "FMMController.h"
+#include "FlightModeManager.h"
 
 #include <common/events/Events.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <events/EventBroker.h>
 #include <miosix.h>
 
@@ -30,127 +31,70 @@ using namespace Boardcore;
 
 namespace Parafoil
 {
-FMMController::FMMController() : FSM(&FMMController::state_on_ground)
-{
-    memset(&status, 0, sizeof(FMMControllerStatus));
-    EventBroker::getInstance().subscribe(this, TOPIC_FMM);
-    EventBroker::getInstance().subscribe(this, TOPIC_TMTC);
-}
 
-FMMController::~FMMController()
-{
-    EventBroker::getInstance().unsubscribe(this);
-}
-
-void FMMController::state_on_ground(const Event& ev)
+void FlightModeManager::state_on_ground(const Event& ev)
 {
     switch (ev)
     {
         case EV_ENTRY:
         {
-            // ...
-
-            logStatus(ON_GROUND);
-
-            LOG_DEBUG(logger, "[FMM] entering state on_ground\n");
-            break;
-        }
-        case EV_EXIT:
-        {
-            // ...
-
-            LOG_DEBUG(logger, "[FMM] exiting state on_ground\n");
-            break;
+            return logStatus(FlightModeManagerState::ON_GROUND);
         }
         case EV_LIFTOFF:
         {
-            transition(&FMMController::state_flying);
-            break;
+            return transition(&FlightModeManager::state_flying);
         }
         case EV_TC_TEST_MODE:
         {
-            transition(&FMMController::state_debug);
-            break;
-        }
-        default:
-        {
-            break;
+            return transition(&FlightModeManager::state_debug);
         }
     }
 }
 
-void FMMController::state_flying(const Event& ev)
+void FlightModeManager::state_flying(const Event& ev)
 {
     switch (ev)
     {
         case EV_ENTRY:
         {
-            // ...
-
-            logStatus(FLYING_STATE);
-
-            LOG_DEBUG(logger, "[FMM] entering state flying\n");
-            break;
-        }
-        case EV_EXIT:
-        {
-            // ...
-
-            LOG_DEBUG(logger, "[FMM] exiting state flying\n");
-            break;
-        }
-
-        default:
-        {
-            break;
+            return logStatus(FlightModeManagerState::FLYING_STATE);
         }
     }
 }
 
-void FMMController::state_debug(const Event& ev)
+void FlightModeManager::state_debug(const Event& ev)
 {
     switch (ev)
     {
         case EV_ENTRY:
         {
-            // ...
-
-            logStatus(DEBUG_STATE);
-
-            LOG_DEBUG(logger, "[FMM] entering state debug\n");
-            break;
-        }
-        case EV_EXIT:
-        {
-            // ...
-
-            LOG_DEBUG(logger, "[FMM] exiting state debug\n");
-            break;
+            return logStatus(FlightModeManagerState::DEBUG_STATE);
         }
         case EV_TC_EXIT_TEST_MODE:
         {
-            transition(&FMMController::state_on_ground);
-            break;
-        }
-        default:
-        {
-            break;
+            return transition(&FlightModeManager::state_on_ground);
         }
     }
 }
 
-/* --- LOGGER --- */
+FlightModeManager::FlightModeManager()
+    : FSM(&FlightModeManager::state_on_ground)
+{
+    EventBroker::getInstance().subscribe(this, TOPIC_FMM);
+    EventBroker::getInstance().subscribe(this, TOPIC_TMTC);
+}
 
-void FMMController::logStatus(FMMControllerState state)
+FlightModeManager::~FlightModeManager()
 {
-    status.state = state;
-    logStatus();
+    EventBroker::getInstance().unsubscribe(this);
 }
 
-void FMMController::logStatus()
+void FlightModeManager::logStatus(FlightModeManagerState state)
 {
-    status.timestamp = miosix::getTick();
-    SDlogger->log(status);
+    status.timestamp = TimestampTimer::getTimestamp();
+    status.state     = state;
+
+    Logger::getInstance().log(state);
 }
 
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/FlightModeManager/FMMController.h b/src/boards/Parafoil/FlightModeManager/FlightModeManager.h
similarity index 80%
rename from src/boards/Parafoil/FlightModeManager/FMMController.h
rename to src/boards/Parafoil/FlightModeManager/FlightModeManager.h
index 1f03ed297..ef9b5777c 100644
--- a/src/boards/Parafoil/FlightModeManager/FMMController.h
+++ b/src/boards/Parafoil/FlightModeManager/FlightModeManager.h
@@ -25,31 +25,32 @@
 #include <diagnostic/PrintLogger.h>
 #include <events/FSM.h>
 
-#include "FMMData.h"
+#include "FlightModeManagerData.h"
 
 namespace Parafoil
 {
-/**
- * @brief FMM state machine
- */
-class FMMController : public Boardcore::FSM<FMMController>
+
+class FlightModeManager : public Boardcore::FSM<FlightModeManager>,
+                          public Boardcore::Singleton<FlightModeManager>
 {
-public:
-    FMMController();
-    ~FMMController();
+    friend Boardcore::Singleton<FlightModeManager>;
 
+public:
     void state_on_ground(const Boardcore::Event& ev);
+
     void state_flying(const Boardcore::Event& ev);
+
     void state_debug(const Boardcore::Event& ev);
 
 private:
-    FMMControllerStatus status;
-    Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("FMM");
-    Boardcore::Logger* SDlogger   = &Boardcore::Logger::getInstance();
+    FlightModeManager();
+    ~FlightModeManager();
 
-    /* --- LOGGER --- */
+    FlightModeManagerStatus status;
 
-    void logStatus(FMMControllerState state);
-    void logStatus();
+    Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("fmm");
+
+    void logStatus(FlightModeManagerState state);
 };
+
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/FlightModeManager/FMMData.h b/src/boards/Parafoil/FlightModeManager/FlightModeManagerData.h
similarity index 85%
rename from src/boards/Parafoil/FlightModeManager/FMMData.h
rename to src/boards/Parafoil/FlightModeManager/FlightModeManagerData.h
index 09a17d601..9764943ff 100644
--- a/src/boards/Parafoil/FlightModeManager/FMMData.h
+++ b/src/boards/Parafoil/FlightModeManager/FlightModeManagerData.h
@@ -30,23 +30,18 @@
 namespace Parafoil
 {
 
-/**
- * Enum defining the possibile FSM states.
- */
-enum FMMControllerState : uint8_t
+enum class FlightModeManagerState : uint8_t
 {
-    ON_GROUND = 0,
+    UNINIT = 0,
+    ON_GROUND,
     FLYING_STATE,
     DEBUG_STATE,
 };
 
-/**
- * Structure defining the overall controller status.
- */
-struct FMMControllerStatus
+struct FlightModeManagerStatus
 {
-    long long timestamp;
-    FMMControllerState state;
+    uint64_t timestamp           = 0;
+    FlightModeManagerState state = FlightModeManagerState::UNINIT;
 
     static std::string header() { return "timestamp,state\n"; }
 
diff --git a/src/boards/Parafoil/Main/Radio.cpp b/src/boards/Parafoil/Main/Radio.cpp
deleted file mode 100644
index 1b0c61a52..000000000
--- a/src/boards/Parafoil/Main/Radio.cpp
+++ /dev/null
@@ -1,387 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include <Parafoil/Configs/RadioConfig.h>
-#include <Parafoil/Configs/WingConfig.h>
-#include <Parafoil/Configs/XbeeConfig.h>
-#include <Parafoil/Main/Radio.h>
-#include <Parafoil/ParafoilTest.h>
-#include <Parafoil/TelemetriesTelecommands/TMRepository.h>
-#include <Parafoil/Wing/WingTargetPositionData.h>
-#include <common/events/Topics.h>
-#include <drivers/interrupt/external_interrupts.h>
-#include <drivers/spi/SPIDriver.h>
-#include <radio/Xbee/ATCommands.h>
-#include <utils/AeroUtils/AeroUtils.h>
-
-using std::bind;
-using namespace std::placeholders;
-using namespace Boardcore;
-
-// Xbee ATTN interrupt
-/**
- * @brief We must define the interrupt handler. This calls
- * the message handler which is: handleMavlinkMessage
- */
-void __attribute__((used)) EXTI10_IRQHandlerImpl()
-{
-    using namespace Parafoil;
-
-    /*if (ParafoilTest::getInstance().radio->xbee != nullptr)
-    {
-        ParafoilTest::getInstance().radio->xbee->handleATTNInterrupt();
-    }*/
-    if (ParafoilTest::getInstance().radio->module != nullptr)
-    {
-        ParafoilTest::getInstance().radio->module->handleDioIRQ();
-    }
-}
-
-namespace Parafoil
-{
-
-Radio::Radio(SPIBusInterface& xbee_bus, TaskScheduler* scheduler)
-    : xbee_bus(xbee_bus)
-{
-    // Create a SPI configuration object
-    SPIBusConfig config{};
-
-    // Set the internal scheduler
-    this->scheduler = scheduler;
-
-    // Set the internal telemetry status to low rate
-    this->HRtelemetry = false;
-
-    // Add a clock divider config
-    config.clockDivider = SPI::ClockDivider::DIV_16;
-
-    // Instantiate the xbee object
-    /*xbee = new Xbee::Xbee(xbee_bus, config,
-                          XBEE_CS,
-                          XBEE_ATTN,
-                          XBEE_RESET);*/
-    module = new SX1278(xbee_bus, XBEE_CS);
-
-    // Create the mavlink driver
-    mav_driver =
-        new MavDriver(module, bind(&Radio::handleMavlinkMessage, this, _1, _2),
-                      SLEEP_AFTER_SEND, MAV_OUT_BUFFER_MAX_AGE);
-}
-
-Radio::~Radio()
-{
-    // TODO destruct
-}
-
-void Radio::handleMavlinkMessage(MavDriver* driver,
-                                 const mavlink_message_t& msg)
-{
-    // log status
-    ParafoilTest::getInstance().radio->logStatus();
-
-    LOG_DEBUG(logger, "Message received!");
-
-    // acknowledge
-    sendAck(msg);
-
-    // handle TC
-    switch (msg.msgid)
-    {
-        case MAVLINK_MSG_ID_COMMAND_TC:  // basic command
-        {
-            LOG_DEBUG(logger, "Received NOARG command");
-            uint8_t commandId = mavlink_msg_command_tc_get_command_id(&msg);
-
-            // search for the corresponding event and post it
-            auto it = tcMap.find(commandId);
-            if (it != tcMap.end())
-                EventBroker::getInstance().post(Event{it->second}, TOPIC_TMTC);
-            else
-                LOG_WARN(logger, "Unknown NOARG command {:d}", commandId);
-
-            switch (commandId)
-            {
-                case MAV_CMD_FORCE_REBOOT:
-                    SDlogger->stop();
-                    LOG_INFO(logger, "Received command BOARD_RESET");
-                    miosix::reboot();
-                    break;
-                case MAV_CMD_CLOSE_LOG:
-                    SDlogger->stop();
-                    sendSystemTelemetry(MAV_LOGGER_ID);
-                    LOG_INFO(logger, "Received command CLOSE_LOG");
-                    break;
-                case MAV_CMD_START_LOGGING:
-                    ParafoilTest::getInstance().SDlogger->start();
-                    sendSystemTelemetry(MAV_LOGGER_ID);
-                    LOG_INFO(logger, "Received command START_LOG");
-                    break;
-                case MAV_CMD_TEST_MODE:
-                    // Use the test mode to apply the sequence
-                    ParafoilTest::getInstance().wingController->start();
-                    break;
-                case MAV_CMD_FORCE_LANDING:
-                    // Reset the servo position
-                    ParafoilTest::getInstance().wingController->reset();
-                    break;
-                default:
-                    break;
-            }
-            break;
-        }
-        case MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC:  // tm request
-        {
-            uint8_t tmId = mavlink_msg_system_tm_request_tc_get_tm_id(&msg);
-            LOG_DEBUG(logger, "Received TM request : id = {:d}", tmId);
-
-            // send corresponding telemetry or NACK
-            sendSystemTelemetry(tmId);
-
-            break;
-        }
-        case MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC:
-        {
-            uint8_t tmId = mavlink_msg_sensor_tm_request_tc_get_sensor_id(&msg);
-
-            // Send corresponding telemetry or NACK
-            sendSensorTelemetry(tmId);
-
-            break;
-        }
-        case MAVLINK_MSG_ID_SET_ALGORITHM_TC:
-        {
-            uint8_t algorithmId =
-                mavlink_msg_set_algorithm_tc_get_algorithm_number(&msg);
-
-            // Set the algorithm (invalid cases are checked inside the method)
-            ParafoilTest::getInstance().wingController->selectAlgorithm(
-                algorithmId);
-
-            break;
-        }
-        case MAVLINK_MSG_ID_SET_TARGET_COORDINATES_TC:
-        {
-            float lat =
-                mavlink_msg_set_target_coordinates_tc_get_latitude(&msg);
-            float lon =
-                mavlink_msg_set_target_coordinates_tc_get_longitude(&msg);
-
-            // Set also the barometer reference
-            ParafoilTest::getInstance().sensors->calibrate();
-
-            // Set the target referencing to GPS coordinates
-            UBXGPSData gps =
-                ParafoilTest::getInstance().sensors->getGPSLastSample();
-            if (gps.fix != 0)
-            {
-                auto targetPosition = Boardcore::Aeroutils::geodetic2NED(
-                    Eigen::Vector2f(lat, lon),
-                    Eigen::Vector2f(gps.latitude, gps.longitude));
-
-                ParafoilTest::getInstance().wingController->setTargetPosition(
-                    targetPosition);
-
-                Logger::getInstance().log(WingTargetPositionData{
-                    gps.latitude, gps.longitude, targetPosition(0),
-                    targetPosition(1)});
-
-                // Set also the initial position of the NASController
-                ParafoilTest::getInstance().algorithms->nas->setInitialPosition(
-                    Eigen::Vector2f(gps.latitude, gps.longitude));
-            }
-            break;
-        }
-        case MAVLINK_MSG_ID_RAW_EVENT_TC:  // post a raw event
-        {
-            LOG_DEBUG(logger, "Received RAW_EVENT command");
-
-            // post given event on given topic
-            EventBroker::getInstance().post(
-                {mavlink_msg_raw_event_tc_get_event_id(&msg)},
-                mavlink_msg_raw_event_tc_get_topic_id(&msg));
-            break;
-        }
-        case MAVLINK_MSG_ID_PING_TC:
-        {
-            LOG_DEBUG(logger, "Ping received");
-            break;
-        }
-        default:
-        {
-            LOG_DEBUG(logger, "Received message is not of a known type");
-            break;
-        }
-    }
-
-    // TODO REMOVE THIS ACK DONE BECAUSE OF ACK LOSS
-    sendAck(msg);
-}
-
-bool Radio::sendSystemTelemetry(const uint8_t tm_id)
-{
-    // Enqueue the message
-    bool result =
-        mav_driver->enqueueMsg(TMRepository::getInstance().packSystemTM(tm_id));
-    // TODO log the operation
-    return result;
-}
-
-bool Radio::sendSensorTelemetry(const uint8_t tm_id)
-{
-    // Enqueue the message
-    bool result =
-        mav_driver->enqueueMsg(TMRepository::getInstance().packSensorTM(tm_id));
-    return result;
-}
-
-void Radio::sendHRTelemetry()
-{
-    // sendTelemetry(MAV_HR_TM_ID);
-    // TEST ONLY
-    sendSystemTelemetry(MAV_FLIGHT_ID);
-}
-
-void Radio::sendLRTelemetry()
-{
-    // I send this telemetry if and only if the status is
-    // in low rate telemetry
-    sendSystemTelemetry(MAV_STATS_ID);
-}
-
-void Radio::sendSDLogTelemetry() { sendSystemTelemetry(MAV_LOGGER_ID); }
-
-void Radio::sendServoTelemetry()
-{
-    mavlink_message_t msg;
-    mavlink_servo_tm_t tm;
-
-    tm.servo_id = PARAFOIL_SERVO1;
-    tm.servo_position =
-        ParafoilTest::getInstance().wingController->getServoPosition(
-            PARAFOIL_SERVO1);
-    mavlink_msg_servo_tm_encode(TMTC_MAV_SYSID, TMTC_MAV_COMPID, &msg, &tm);
-    mav_driver->enqueueMsg(msg);
-
-    tm.servo_id = PARAFOIL_SERVO2;
-    tm.servo_position =
-        ParafoilTest::getInstance().wingController->getServoPosition(
-            PARAFOIL_SERVO2);
-    mavlink_msg_servo_tm_encode(TMTC_MAV_SYSID, TMTC_MAV_COMPID, &msg, &tm);
-    mav_driver->enqueueMsg(msg);
-}
-
-void Radio::sendAck(const mavlink_message_t& msg)
-{
-    mavlink_message_t ackMsg;
-    // Pack the ack message based on the received message
-    mavlink_msg_ack_tm_pack(TMTC_MAV_SYSID, TMTC_MAV_COMPID, &ackMsg, msg.msgid,
-                            msg.seq);
-
-    // Put the message in the queue
-    mav_driver->enqueueMsg(ackMsg);
-    // TODO log the thing
-}
-
-void Radio::toggleHRTelemetry()
-{
-    // Lock the kernel to avoid context switch during this toggle
-    miosix::PauseKernelLock kLock;
-    TaskScheduler::function_t HRfunction([=]() { sendHRTelemetry(); });
-    HRtelemetry = !HRtelemetry;
-
-    if (HRtelemetry)
-    {
-        // If we switched to hr telemetry on flight i change the period
-        scheduler->removeTask(RADIO_HR_ID);
-        // Add the same task with a faster period
-        scheduler->addTask(HRfunction, HR_FLIGHT_UPDATE_PERIOD, RADIO_HR_ID);
-    }
-    else
-    {
-        // If we switched to hr telemetry on ground i change the period
-        scheduler->removeTask(RADIO_HR_ID);
-        // Add the same task with a slower period
-        scheduler->addTask(HRfunction, HR_GROUND_UPDATE_PERIOD, RADIO_HR_ID);
-    }
-}
-
-bool Radio::start()
-{
-    // Init the radio module
-    init();
-
-    // Start the mavlink driver
-    bool result = mav_driver->start();
-
-    // Start the scheduler
-    // result &= scheduler -> start();
-
-    return result;
-}
-
-void Radio::logStatus()
-{
-    // TODO log
-}
-
-void Radio::onXbeeFrameReceived(Xbee::APIFrame& frame)
-{
-    // Log the thing
-}
-
-void Radio::init()
-{
-    // Create the lambdas to be called
-    TaskScheduler::function_t HRfunction([=]() { sendHRTelemetry(); });
-    TaskScheduler::function_t LRfunction([=]() { sendLRTelemetry(); });
-    TaskScheduler::function_t SDfunction([=]() { sendSDLogTelemetry(); });
-
-    // Enable external interrupt on F10 pin
-    // TODO for xbee is FALLING
-    enableExternalInterrupt(GPIOF_BASE, 10, InterruptTrigger::RISING_EDGE);
-
-    // Init the radio module with default configs
-    SX1278::Config conf;
-    SX1278::Error initError = module->init(conf);
-
-    // Check if there was an error initalizing the SX1278
-    if (initError != SX1278::Error::NONE)
-    {
-        LOG_ERR(logger, "Error starting the SX1278 radio");
-        return;
-    }
-
-    // Register the LR and HR tasks in the scheduler
-    scheduler->addTask(HRfunction, 250, RADIO_HR_ID);
-    // scheduler->addTask(LRfunction, LR_UPDATE_PERIOD, RADIO_LR_ID);
-    scheduler->addTask(SDfunction, SD_UPDATE_PERIOD, SD_UPDATE_ID);
-    scheduler->addTask([=]() { sendServoTelemetry(); }, 1000);
-
-    // Set the frame receive callback
-    // xbee -> setOnFrameReceivedListener(
-    // bind(&Radio::onXbeeFrameReceived, this, _1));
-
-    // Set the data rate
-    // Xbee::setDataRate(*xbee, XBEE_80KBPS_DATA_RATE, XBEE_TIMEOUT);
-}
-
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Main/Radio.h b/src/boards/Parafoil/Main/Radio.h
deleted file mode 100644
index 5cfc2d11d..000000000
--- a/src/boards/Parafoil/Main/Radio.h
+++ /dev/null
@@ -1,195 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <Parafoil/TelemetriesTelecommands/Mavlink.h>
-#include <common/events/Events.h>
-#include <radio/SX1278/SX1278.h>
-#include <radio/Xbee/Xbee.h>
-#include <scheduler/TaskScheduler.h>
-
-/**
- * @brief This class represents the radio module. It allows the communications
- * between the xbee radio module and the on board software. The main tasks are
- * about sending automatic updates to ground based on the current state (High
- * rate telemetry or Low rate telemetry) and handle the messages from the ground
- * station. To handle the various messages there is an apposit callback method
- * and, to pack the optional reply data we use the TMRepository singleton.
- */
-namespace Parafoil
-{
-
-class Radio
-{
-public:
-    /**
-     * @brief The xbee module driver
-     */
-    // Xbee::Xbee* xbee;
-    Boardcore::SX1278* module;
-
-    /**
-     * @brief Construct a new Radio object
-     *
-     * @param xbee_bus The Xbee SPI bus
-     */
-    Radio(Boardcore::SPIBusInterface& xbee_bus,
-          Boardcore::TaskScheduler* scheduler);
-
-    /**
-     * @brief Destroy the Radio object
-     */
-    ~Radio();
-
-    /**
-     * @brief Method called when a mavlink message is received
-     *
-     * @param msg The parsed message
-     */
-    void handleMavlinkMessage(MavDriver* driver, const mavlink_message_t& msg);
-
-    /**
-     * @brief This method is used to add in send queue
-     * the requested system message. It is necessary to call the
-     * TMrepository to process the actual packet.
-     *
-     * @param tm_id The requested message id
-     * @return boolean that indicates the operation's result
-     */
-    bool sendSystemTelemetry(const uint8_t tm_id);
-
-    /**
-     * @brief This method is used to add in send queue
-     * the requested sensor message. It is necessary to call the
-     * TMrepository to process the actual packet.
-     *
-     * @param tm_id The requested message id
-     * @return boolean that indicates the operation's result
-     */
-    bool sendSensorTelemetry(const uint8_t tm_id);
-
-    /**
-     * @brief Method automatically called by the task
-     * scheduler that sends the high rate telemetry
-     */
-    void sendHRTelemetry();
-
-    /**
-     * @brief Method automatically called by the task
-     * scheduler that sends the high rate telemetry
-     */
-    void sendLRTelemetry();
-
-    /**
-     * @brief Method automatically called by the task
-     * scheduler that sends the SD logger infos
-     */
-    void sendSDLogTelemetry();
-
-    void sendServoTelemetry();
-
-    /**
-     * @brief Every time a message is received we send
-     * an ack message to tell the ground station that we
-     * received the message
-     *
-     * @param msg The message received that we need to ack
-     */
-    void sendAck(const mavlink_message_t& msg);
-
-    /**
-     * @brief Method to change the telemetry rate
-     */
-    void toggleHRTelemetry();
-
-    bool start();
-
-    void logStatus();
-
-private:
-    // 1 to 1 corrispondence of every message to its event
-    const std::map<uint8_t, uint8_t> tcMap = {
-        {MAV_CMD_ARM, EV_TC_ARM},
-        {MAV_CMD_DISARM, EV_TC_DISARM},
-
-        {MAV_CMD_FORCE_LAUNCH, EV_TC_LAUNCH},
-        {MAV_CMD_FORCE_LANDING, EV_TC_LAND},
-
-        {MAV_CMD_FORCE_EXPULSION, EV_TC_NC_OPEN},
-        {MAV_CMD_FORCE_MAIN, EV_TC_CUT_DROGUE},
-
-        {MAV_CMD_START_LOGGING, EV_TC_START_LOG},
-        {MAV_CMD_CLOSE_LOG, EV_TC_CLOSE_LOG},
-
-        {MAV_CMD_FORCE_REBOOT, EV_TC_RESET_BOARD},
-        {MAV_CMD_TEST_MODE, EV_TC_TEST_MODE},
-
-        {MAV_CMD_START_RECORDING, EV_TC_START_RECORDING},
-        {MAV_CMD_STOP_RECORDING, EV_TC_STOP_RECORDING}};
-
-    /**
-     * @brief The mavlink driver
-     */
-    MavDriver* mav_driver;
-
-    /**
-     * @brief SPI bus
-     */
-    Boardcore::SPIBusInterface& xbee_bus;
-
-    /**
-     * @brief Main task scheduler
-     */
-    Boardcore::TaskScheduler* scheduler;
-
-    /**
-     * @brief high rate telemetry status.
-     * false -> LR telemetry
-     * true  -> HR telemetry
-     */
-    bool HRtelemetry;
-
-    /**
-     * @brief Logger
-     */
-    Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("Radio");
-
-    /**
-     * @brief SD logger (pre started because of the ParafoilTest.h main class)
-     */
-    Boardcore::Logger* SDlogger = &Boardcore::Logger::getInstance();
-
-    /**
-     * @brief Radio frame received callback method.
-     * It's used for logging purposes
-     */
-    void onXbeeFrameReceived(Boardcore::Xbee::APIFrame& frame);
-
-    /**
-     * @brief Method to initialize all the variables and objects
-     * and to register the HR and LR tasks into the task scheduler
-     */
-    void init();
-};
-
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Main/Sensors.cpp b/src/boards/Parafoil/Main/Sensors.cpp
deleted file mode 100644
index 650e1f42d..000000000
--- a/src/boards/Parafoil/Main/Sensors.cpp
+++ /dev/null
@@ -1,303 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include "Sensors.h"
-
-#include <Parafoil/Configs/SensorsConfig.h>
-#include <Parafoil/Configs/WingConfig.h>
-#include <Parafoil/ParafoilTest.h>
-#include <Parafoil/TelemetriesTelecommands/TMRepository.h>
-#include <math.h>
-#include <sensors/SensorInfo.h>
-#include <utils/AeroUtils/AeroUtils.h>
-
-using std::bind;
-using namespace Boardcore;
-
-namespace Parafoil
-{
-
-void Sensors::MPU9250init()
-{
-    SPIBusConfig spiConfig{};
-    spiConfig.clockDivider = SPI::ClockDivider::DIV_64;
-    spiConfig.mode         = SPI::Mode::MODE_3;
-    // I create first a new SPISlave with all the settings
-    SPISlave slave{spiInterface, IMU_CS, spiConfig};
-
-    // Instantiate the object
-    imu_mpu9250 =
-        new MPU9250(spiInterface, IMU_CS, spiConfig, IMU_SAMPLE_RATE,
-                    IMU_GYRO_SCALE, IMU_ACCEL_SCALE, SPI::ClockDivider::DIV_16);
-
-    // Bind the information
-    SensorInfo info("MPU9250", IMU_SAMPLE_PERIOD,
-                    bind(&Sensors::MPU9250Callback, this), true);
-
-    // Insert the sensor in the common map
-    sensors_map.emplace(std::make_pair(imu_mpu9250, info));
-
-    // Log the results
-    LOG_INFO(log, "IMU MPU9250 Setup done!");
-}
-
-void Sensors::MPU9250Callback()
-{
-    // Log the sample
-    MPU9250Data d = imu_mpu9250->getLastSample();
-    logger->log(imu_mpu9250->getLastSample());
-    LOG_DEBUG(log, "{:.2f} {:.2f} {:.2f}", d.accelerationX, d.accelerationY,
-              d.accelerationZ);
-}
-
-void Sensors::UbloxGPSinit()
-{
-    // Instantiate the object TODO set the sample rate and stuff
-    gps_ublox = new UBXGPSSerial(256000, GPS_SAMPLE_RATE, 2, "gps", 9600);
-
-    // Bind the information with the callback method
-    SensorInfo info("UbloxGPS", GPS_SAMPLE_PERIOD,
-                    bind(&Sensors::UbloxGPSCallback, this), true);
-
-    // Insert the sensor in the common map
-    sensors_map.emplace(std::make_pair(gps_ublox, info));
-
-    // Log the result
-    LOG_INFO(log, "Ublox GPS Setup done!");
-}
-
-void Sensors::UbloxGPSCallback()
-{
-    // Log the sample
-    UBXGPSData d = gps_ublox->getLastSample();
-    logger->log(gps_ublox->getLastSample());
-    if (d.fix)
-    {
-        LOG_DEBUG(log, "{:.2f} {:.2f}", d.latitude, d.longitude);
-    }
-}
-
-void Sensors::BME280init()
-{
-    // I first create a SPI slave needed to instantiate the sensor
-    SPISlave slave(spiInterface, PRESS_CS, SPIBusConfig{});
-
-    slave.config.clockDivider = SPI::ClockDivider::DIV_16;
-    slave.config.mode         = SPI::Mode::MODE_0;
-
-    auto config                      = BME280::BME280_CONFIG_ALL_ENABLED;
-    config.bits.oversamplingPressure = BME280::OVERSAMPLING_4;
-
-#ifdef MOCK_SENSORS
-    // Instantiate the mock sensor
-    mockPressure = new MockPressureSensor();
-
-    // start the sensor
-    mockPressure->signalLiftoff();
-
-    // Bind the information with the callback method
-    SensorInfo info("BME280", PRESS_SAMPLE_PERIOD,
-                    bind(&Sensors::BME280Callback, this), true);
-    // Insert the sensor in the common map
-    sensors_map.emplace(std::make_pair(mockPressure, info));
-#else
-    // Instantiate the object
-    press_bme280 = new BME280(slave, config);
-
-    // Set the standby time
-    press_bme280->setStandbyTime(PRESS_SAMPLE_RATE);
-
-    // Bind the information with the callback method
-    SensorInfo info("BME280", PRESS_SAMPLE_PERIOD,
-                    bind(&Sensors::BME280Callback, this), true);
-    // Insert the sensor in the common map
-    sensors_map.emplace(std::make_pair(press_bme280, info));
-#endif
-
-    // Log the result
-    LOG_INFO(log, "BME280 Setup done!");
-}
-
-void Sensors::BME280Callback()
-{
-    // Log the sample
-
-#ifdef MOCK_SENSORS
-    // Create the d data but with the mock informations
-    BME280Data d;
-    d.pressure          = mockPressure->getLastSample().pressure;
-    d.pressureTimestamp = 25;
-#else
-    BME280Data d = press_bme280->getLastSample();
-    logger->log(press_bme280->getLastSample());
-#endif
-    LOG_DEBUG(log, "{:.2f} {:.2f} {:.2f}", d.pressure, d.temperature,
-              d.humidity);
-
-    // Here i put the logic for wing procedure start and flare
-    static bool procedureArm = false;
-    static bool flareArm     = false;
-    static uint8_t count     = 0;
-    static Boardcore::Stats pressureMean{};
-    static Boardcore::Stats temperatureMean{};
-
-    // If we reache the needed samples
-    if (count == WING_PRESSURE_MEAN_COUNT)
-    {
-        // In case of calibration needed i calibrate
-        if (needsCalibration)
-        {
-            WING_CALIBRATION_PRESSURE = pressureMean.getStats().mean;
-            WING_CALIBRATION_TEMPERATURE =
-                temperatureMean.getStats().mean + 273.15;
-
-            // Reset the mean values
-            count = 0;
-            pressureMean.reset();
-            temperatureMean.reset();
-
-            // Set calibrated status
-            needsCalibration = false;
-
-            // I don't want to calculate stuff
-            return;
-        }
-
-        // Calculate the height
-        float height = Aeroutils::relAltitude(pressureMean.getStats().mean,
-                                              WING_CALIBRATION_PRESSURE,
-                                              WING_CALIBRATION_TEMPERATURE);
-
-        // Update the radio repository
-        d.pressure    = pressureMean.getStats().mean;
-        d.temperature = temperatureMean.getStats().mean;
-
-        // Decide what the wing should do
-        if (height > WING_ALGORITHM_ARM_ALTITUDE && !procedureArm)
-        {
-            procedureArm = true;
-        }
-
-        if (height < WING_ALGORITHM_START_ALTITUE && procedureArm)
-        {
-            // Disarm the starting command
-            procedureArm = false;
-
-            // Arm the flare command
-            flareArm = true;
-
-            // Start the algorithm
-            ParafoilTest::getInstance().wingController->start();
-        }
-
-        if (height < WING_FLARE_ALTITUDE && flareArm)
-        {
-            // Disarm the starting command
-            flareArm = false;
-
-            // Flare
-            ParafoilTest::getInstance().wingController->flare();
-        }
-
-        // Reset the mean values
-        count = 0;
-        pressureMean.reset();
-        temperatureMean.reset();
-    }
-
-    // Add the current value to the mean and increase the counting
-    pressureMean.add(d.pressure);
-    temperatureMean.add(d.temperature);
-    count++;
-}
-
-Sensors::Sensors(SPIBusInterface& spi, TaskScheduler* scheduler)
-    : spiInterface(spi)
-{
-    // Take the SD logger singleton
-    logger = &Logger::getInstance();
-
-    // Sensor init
-    MPU9250init();
-    miosix::Thread::sleep(200);
-    UbloxGPSinit();
-    miosix::Thread::sleep(200);
-    BME280init();
-    miosix::Thread::sleep(200);
-
-    // Sensor manager instance
-    // At this point sensors_map contains all the initialized sensors
-    // cppcheck-suppress noCopyConstructor
-    // cppcheck-suppress noOperatorEq
-    manager = new SensorManager(sensors_map, scheduler);
-}
-
-Sensors::~Sensors()
-{
-    // Delete the sensors
-    delete (imu_mpu9250);
-    delete (gps_ublox);
-#ifdef MOCK_SENSORS
-    delete (mockPressure);
-#else
-    delete (press_bme280);
-#endif
-
-    // Sensor manager stop and delete
-    manager->stop();
-    delete manager;
-}
-
-bool Sensors::start() { return manager->start(); }
-
-void Sensors::calibrate()
-{
-    miosix::PauseKernelLock kLock;
-    this->needsCalibration = true;
-}
-
-/**
- * GETTERS WITH LOCK
- */
-MPU9250Data Sensors::getMPU9250LastSample()
-{
-    miosix::PauseKernelLock lock;
-    return imu_mpu9250->getLastSample();
-}
-
-BME280Data Sensors::getBME280LastSample()
-{
-    miosix::PauseKernelLock lock;
-#ifdef MOCK_SENSORS
-    return BME280Data();
-#else
-    return press_bme280->getLastSample();
-#endif
-}
-
-UBXGPSData Sensors::getGPSLastSample()
-{
-    miosix::PauseKernelLock lock;
-    return gps_ublox->getLastSample();
-}
-
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Main/Sensors.h b/src/boards/Parafoil/Main/Sensors.h
deleted file mode 100644
index 0e504b1cf..000000000
--- a/src/boards/Parafoil/Main/Sensors.h
+++ /dev/null
@@ -1,142 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-#pragma once
-
-#include <Parafoil/mocksensors/MockPressureSensor.h>
-#include <sensors/BME280/BME280.h>
-#include <sensors/MPU9250/MPU9250.h>
-#include <sensors/SensorManager.h>
-#include <sensors/UBXGPS/UBXGPSSerial.h>
-
-/**
- * This class memorizes all the sensors instances.
- * Every instance is initialized by the constructor. Also every
- * sensor has its own status
- */
-namespace Parafoil
-{
-
-class Sensors
-{
-private:
-    /**
-     * @brief Sensor manager object
-     */
-    Boardcore::SensorManager* manager;
-
-    /**
-     * @brief Sensor map that contains every sensor istance
-     * that needs to be sampled by the sensor manager
-     */
-    Boardcore::SensorManager::SensorMap_t sensors_map;
-
-    /**
-     * @brief SPI interface passed via constructor
-     */
-    Boardcore::SPIBusInterface& spiInterface;
-
-    /**
-     * @brief Sensors serial logger
-     */
-    Boardcore::PrintLogger log = Boardcore::Logging::getLogger("sensors");
-
-    /**
-     * @brief SD logger singleton
-     */
-    Boardcore::Logger* logger;
-
-    /**
-     * @brief boolean that indicates if the sensors need to calibrate
-     */
-    bool needsCalibration = false;
-
-    /**
-     * @brief The MPU9250 IMU init function and
-     * sample callback
-     */
-    void MPU9250init();
-    void MPU9250Callback();
-
-    /**
-     * @brief GPS init function and sample callback
-     */
-    void UbloxGPSinit();
-    void UbloxGPSCallback();
-
-    /**
-     * @brief Barometer BME280 init function and sample callback
-     */
-    void BME280init();
-    void BME280Callback();
-
-public:
-    /**
-     * @brief MPU9250IMU
-     */
-    Boardcore::MPU9250* imu_mpu9250;
-
-    /**
-     * @brief GPS
-     */
-    Boardcore::UBXGPSSerial* gps_ublox;
-
-/**
- * @brief Barometer
- */
-#ifdef MOCK_SENSORS
-    MockPressureSensor* mockPressure;
-#else
-    Boardcore::BME280* press_bme280;
-#endif
-
-    /**
-     * @brief Constructor
-     * @param The spi interface used for the sensors
-     * @param The task scheduler
-     */
-    Sensors(Boardcore::SPIBusInterface& spi,
-            Boardcore::TaskScheduler* scheduler);
-
-    /**
-     * @brief Deconstructor
-     */
-    ~Sensors();
-
-    /**
-     * @brief Starts the sensor manager to sample data
-     * @return boolean that indicates operation's result
-     */
-    bool start();
-
-    /**
-     * @brief Calibrates the sensors that need to
-     */
-    void calibrate();
-
-    /**
-     * @brief Lock getters
-     */
-    Boardcore::MPU9250Data getMPU9250LastSample();
-    Boardcore::BME280Data getBME280LastSample();
-    Boardcore::UBXGPSData getGPSLastSample();
-};
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Control/NASController.cpp b/src/boards/Parafoil/NASController/NASController.cpp
similarity index 59%
rename from src/boards/Parafoil/Control/NASController.cpp
rename to src/boards/Parafoil/NASController/NASController.cpp
index 513fa31ff..22af55f73 100644
--- a/src/boards/Parafoil/Control/NASController.cpp
+++ b/src/boards/Parafoil/NASController/NASController.cpp
@@ -22,98 +22,42 @@
 
 #include "NASController.h"
 
-#include <Parafoil/ParafoilTest.h>
+#include <Parafoil/BoardScheduler.h>
+#include <Parafoil/Configs/NASConfig.h>
+#include <Parafoil/Sensors/Sensors.h>
 #include <sensors/MPU9250/MPU9250Data.h>
 #include <sensors/UBXGPS/UBXGPSData.h>
 
-namespace Parafoil
-{
-
-NASController::NASController(Boardcore::TaskScheduler* scheduler,
-                             Boardcore::NASConfig config)
-{
-    this->scheduler = scheduler;
-    this->config    = config;
-
-    // Create the nas
-    nas = new Boardcore::NAS(config);
-}
-
-NASController::~NASController() { delete nas; }
-
-void NASController::calculateInitialOrientation()
-{
-    // this->initialOrientation = orientation;
-
-    // Mean 10 accelerometer values
-    Eigen::Vector3f accelerometer;
-    Eigen::Vector3f magnetometer;
-    Eigen::Vector3f nedMag(0.4747, 0.0276, 0.8797);
-    Boardcore::StateInitializer state;
-
-    // Mean the values
-    for (int i = 0; i < 10; i++)
-    {
-        Boardcore::MPU9250Data measure =
-            ParafoilTest::getInstance().sensors->getMPU9250LastSample();
-        accelerometer = accelerometer + Eigen::Vector3f(measure.accelerationX,
-                                                        measure.accelerationY,
-                                                        measure.accelerationZ);
-        magnetometer  = magnetometer + Eigen::Vector3f(measure.magneticFieldX,
-                                                       measure.magneticFieldY,
-                                                       measure.magneticFieldZ);
-
-        // Wait for some time
-        miosix::Thread::sleep(100);
-    }
-
-    accelerometer = accelerometer / 10;
-    magnetometer  = magnetometer / 10;
-
-    // Normalize the data
-    accelerometer.normalize();
-    magnetometer.normalize();
-
-    // Triad the initial orientation
-    state.triad(accelerometer, magnetometer, nedMag);
+using namespace std;
+using namespace Boardcore;
 
-    nas->setX(state.getInitX());
-}
-
-void NASController::setInitialPosition(Eigen::Vector2f position)
+namespace Parafoil
 {
-    this->initialPosition = position;
-}
 
 void NASController::init()
 {
     // Set the reference values (whatever they represent)
-    nas->setReferenceValues({0, 0, 0, 110000, 20 + 273.5});
+    nas.setReferenceValues({0, 0, 0, 110000, 20 + 273.5});
 }
 
 bool NASController::start()
 {
-    LOG_DEBUG(logger, "Starting NAS");
-    // Add the update task to the scheduler
-    scheduler->addTask(std::bind(&NASController::step, this), config.T * 1000,
-                       Boardcore::TaskScheduler::Policy::RECOVER);
-
     // Calculate the initial orientation using triad algorithm
     calculateInitialOrientation();
 
-    // Start the scheduler
-    return scheduler->start();
-}
+    // Add the update task to the scheduler
+    BoardScheduler::getInstance().getScheduler().addTask(
+        bind(&NASController::update, this), NASConfig::UPDATE_PERIOD,
+        TaskScheduler::Policy::RECOVER);
 
-Boardcore::NASState NASController::getLastSample() { return nas->getState(); }
+    return true;
+}
 
-void NASController::step()
+void NASController::update()
 {
     // Sample the sensors
-    Boardcore::MPU9250Data imuData =
-        ParafoilTest::getInstance().sensors->getMPU9250LastSample();
-    Boardcore::UBXGPSData gpsData =
-        ParafoilTest::getInstance().sensors->getGPSLastSample();
+    MPU9250Data imuData = Sensors::getInstance().getMpu9250LastSample();
+    UBXGPSData gpsData  = Sensors::getInstance().getUbxGpsLastSample();
 
     // Extrapolate all the data
     Eigen::Vector3f acceleration(imuData.accelerationX, imuData.accelerationY,
@@ -126,7 +70,7 @@ void NASController::step()
 
     // Put the GPS converted data into a 4d vector
     Eigen::Vector2f gpsPos(gpsData.latitude, gpsData.longitude);
-    gpsPos = Boardcore::Aeroutils::geodetic2NED(gpsPos, initialPosition);
+    gpsPos = Aeroutils::geodetic2NED(gpsPos, initialPosition);
     Eigen::Vector2f gpsVel(gpsData.velocityNorth, gpsData.velocityEast);
     Eigen::Vector4f gpsCorrection;
     // cppcheck-suppress constStatement
@@ -145,23 +89,73 @@ void NASController::step()
     }
 
     // Predict step
-    nas->predictGyro(angularVelocity);
+    nas.predictGyro(angularVelocity);
     if (gpsPos[0] < 1e3 && gpsPos[0] > -1e3 && gpsPos[1] < 1e3 &&
         gpsPos[1] > -1e3)
-        nas->predictAcc(acceleration);
+        nas.predictAcc(acceleration);
 
     // Correct step
     magneticField.normalize();
-    nas->correctMag(magneticField);
-    // acceleration.normalize();
-    // nas->correctAcc(acceleration);
+    nas.correctMag(magneticField);
     if (gpsData.fix)
-        nas->correctGPS(gpsCorrection);
-    nas->correctBaro(100000);
+        nas.correctGPS(gpsCorrection);
+    nas.correctBaro(100000);
+
+    NASState nasState = nas.getState();
+
+    Logger::getInstance().log(nasState);
+}
+
+void NASController::calculateInitialOrientation()
+{
+    // Mean 10 accelerometer values
+    Eigen::Vector3f accelerometer;
+    Eigen::Vector3f magnetometer;
+    StateInitializer state;
+
+    // Mean the values
+    for (int i = 0; i < 10; i++)
+    {
+        MPU9250Data data = Sensors::getInstance().getMpu9250LastSample();
+        accelerometer += Eigen::Vector3f(data.accelerationX, data.accelerationY,
+                                         data.accelerationZ);
+        magnetometer += Eigen::Vector3f(
+            data.magneticFieldX, data.magneticFieldY, data.magneticFieldZ);
+
+        // Wait for some time
+        miosix::Thread::sleep(100);
+    }
+
+    accelerometer /= 10;
+    magnetometer /= 10;
 
-    Boardcore::NASState nasState = nas->getState();
-    // TRACE("w%fwa%fab%fbc%fc\n", nasState.qw, nasState.qx, nasState.qy,
-    //   nasState.qz);
-    SDlogger->log(nasState);
+    // Normalize the data
+    accelerometer.normalize();
+    magnetometer.normalize();
+
+    // Triad the initial orientation
+    state.triad(accelerometer, magnetometer, NASConfig::nedMag);
+
+    nas.setX(state.getInitX());
+}
+
+void NASController::setInitialPosition(Eigen::Vector2f position)
+{
+    initialPosition = position;
 }
+
+NASState NASController::getNasState() { return nas.getState(); }
+
+void NASController::setReferenceValues(const ReferenceValues reference)
+{
+    nas.setReferenceValues(reference);
+}
+
+ReferenceValues NASController::getReferenceValues()
+{
+    return nas.getReferenceValues();
+}
+
+NASController::NASController() : nas(NASConfig::config) {}
+
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/NASController/NASController.h b/src/boards/Parafoil/NASController/NASController.h
new file mode 100644
index 000000000..fad190cc9
--- /dev/null
+++ b/src/boards/Parafoil/NASController/NASController.h
@@ -0,0 +1,68 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Alberto Nidasio, Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <algorithms/NAS/NAS.h>
+#include <algorithms/NAS/StateInitializer.h>
+#include <scheduler/TaskScheduler.h>
+
+#include <Eigen/Core>
+#include <functional>
+
+namespace Parafoil
+{
+
+class NASController : public Boardcore::Singleton<NASController>
+{
+    friend Boardcore::Singleton<NASController>;
+
+public:
+    void init();
+
+    bool start();
+
+    void update();
+
+    void calculateInitialOrientation();
+
+    void setInitialPosition(Eigen::Vector2f position);
+
+    Boardcore::NASState getNasState();
+
+    void setReferenceValues(const Boardcore::ReferenceValues reference);
+
+    Boardcore::ReferenceValues getReferenceValues();
+
+private:
+    NASController();
+
+    Boardcore::NAS nas;
+
+    Eigen::Vector3f initialOrientation;
+    Eigen::Vector2f initialPosition{42.571820, 12.585861};
+
+    Boardcore::PrintLogger logger =
+        Boardcore::Logging::getLogger("parafoil.nas");
+};
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/ParafoilTest.h b/src/boards/Parafoil/ParafoilTest.h
deleted file mode 100644
index 518a64126..000000000
--- a/src/boards/Parafoil/ParafoilTest.h
+++ /dev/null
@@ -1,270 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <Parafoil/Control/Algorithms.h>
-#include <Parafoil/FlightModeManager/FMMController.h>
-#include <Parafoil/Main/Radio.h>
-#include <Parafoil/Main/Sensors.h>
-#include <Parafoil/ParafoilTestStatus.h>
-#include <Parafoil/Wing/WingController.h>
-#include <drivers/spi/SPIDriver.h>
-#include <events/EventBroker.h>
-#include <miosix.h>
-
-/**
- * This class is the main singleton that keeps all the project objects.
- * It has all the instances and initializes all of them.
- */
-namespace Parafoil
-{
-
-enum ThreadIds : uint8_t
-{
-    THID_ENTRYPOINT = Boardcore::THID_FIRST_AVAILABLE_ID,
-    THID_FMM_FSM,
-    THID_TMTC_FSM,
-    THID_STATS_FSM,
-    THID_ADA_FSM,
-    THID_NAS_FSM,
-    THID_TASK_SCHEDULER
-};
-
-enum TaskIDs : uint8_t
-{
-    TASK_SCHEDULER_STATS_ID = 0,
-    TASK_SENSORS_6_MS_ID    = 1,
-    TASK_SENSORS_15_MS_ID   = 2,
-    TASK_SENSORS_20_MS_ID   = 3,
-    TASK_SENSORS_24_MS_ID   = 4,
-    TASK_SENSORS_40_MS_ID   = 5,
-    TASK_SENSORS_1000_MS_ID = 6,
-    TASK_ADA_ID             = 7,
-    TASK_NAS_ID             = 9
-};
-
-class ParafoilTest : public Boardcore::Singleton<ParafoilTest>
-{
-    friend class Boardcore::Singleton<ParafoilTest>;
-
-public:
-    /**
-     * @brief Event broker
-     */
-    Boardcore::EventBroker* broker;
-
-    /**
-     * @brief Sensors collection
-     */
-    Sensors* sensors;
-
-    /**
-     * @brief Wing algorithm controller
-     */
-    WingController* wingController;
-
-    /**
-     * @brief Radio that manages the interaction between
-     * the xbee module and mavlink
-     */
-    Radio* radio;
-
-    /**
-     * @brief Algorithms
-     */
-    Algorithms* algorithms;
-
-    /**
-     * @brief Main FSM
-     */
-    FMMController* FMM;
-
-    /**
-     * @brief Task scheduler
-     */
-    Boardcore::TaskScheduler* generalScheduler;
-    Boardcore::TaskScheduler* sensorsScheduler;
-    Boardcore::TaskScheduler* algorithmsScheduler;
-
-    /**
-     * @brief SDlogger singleton for SD
-     */
-    Boardcore::Logger* SDlogger;
-
-    /**
-     * @brief Start method
-     */
-    void start()
-    {
-        // Start the SD logger
-        if (!SDlogger->start())
-        {
-            LOG_ERR(log, "Error starting the logger");
-            status.setError(&ParafoilTestStatus::logger);
-        }
-
-        // Log the logger stats
-        SDlogger->log(SDlogger->getStats());
-
-        if (!generalScheduler->start())
-        {
-            LOG_ERR(log, "Error starting the general purpose scheduler");
-        }
-
-        // Start the broker
-        if (!broker->start())
-        {
-            LOG_ERR(log, "Error starting EventBroker");
-            status.setError(&ParafoilTestStatus::eventBroker);
-        }
-
-        // Start the sensors sampling
-        if (!sensors->start() || !sensorsScheduler->start())
-        {
-            LOG_ERR(log, "Error starting sensors");
-            status.setError(&ParafoilTestStatus::sensors);
-        }
-
-        // Start the main FSM
-        /*if(!FMM -> start())
-        {
-            LOG_ERR(log, "Error starting the main FSM");
-            status.setError(&ParafoilTestStatus::FMM);
-        }*/
-
-        // Start the radio
-        if (!radio->start())
-        {
-            LOG_ERR(log, "Error starting the radio");
-            status.setError(&ParafoilTestStatus::radio);
-        }
-
-        // Start the algorithms
-        if (!algorithms->start())
-        {
-            LOG_ERR(log, "Error starting the algorithms");
-            status.setError(&ParafoilTestStatus::algorithms);
-        }
-
-        // wingController->start();
-
-        // After all the initializations i log the status
-        SDlogger->log(status);
-
-        // Status LED declaration
-        miosix::GpioPin statusLed(GPIOG_BASE, 13);
-        statusLed.mode(miosix::Mode::OUTPUT);
-        statusLed.low();
-
-        // If all is ok i can send the signal to the FSMs
-        if (status.parafoil_test != OK)
-        {
-            LOG_ERR(log, "Initialization failed");
-            // TODO add event to inibit the state machines
-        }
-        else
-        {
-            statusLed.high();
-            LOG_INFO(log, "Initialization ok");
-            // TODO add event to start the state machines
-        }
-    }
-
-private:
-    /**
-     * @brief SDlogger in debug mode
-     */
-    Boardcore::PrintLogger log = Boardcore::Logging::getLogger("ParafoilTest");
-
-    /**
-     * @brief Status memory
-     */
-    ParafoilTestStatus status{};
-
-    /**
-     * @brief Constructor
-     */
-    ParafoilTest()
-    {
-        // Take the singleton instance of SD logger
-        SDlogger = &Boardcore::Logger::getInstance();
-
-        // Store the broker
-        broker = &Boardcore::EventBroker::getInstance();
-
-        // Create the task scheduler
-        generalScheduler    = new Boardcore::TaskScheduler();
-        sensorsScheduler    = new Boardcore::TaskScheduler();
-        algorithmsScheduler = new Boardcore::TaskScheduler();
-        addSchedulerStatsTask();
-
-        // Create the sensors
-        Boardcore::SPIBusInterface* spiInterface1 = new Boardcore::SPIBus(SPI1);
-        sensors = new Sensors(*spiInterface1, sensorsScheduler);
-
-        // Create the wing controller
-        wingController = new WingController(generalScheduler);
-        wingController->addAlgorithm("/sd/servoTerni1.csv");               // 0
-        wingController->addAlgorithm("/sd/servoTerni2.csv");               // 1
-        wingController->addAlgorithm("/sd/servoCorta.csv");                // 2
-        wingController->addAlgorithm("/sd/servoLunga.csv");                // 3
-        wingController->addAlgorithm(new AutomaticWingAlgorithm(0.5, 0));  // 4
-        wingController->addAlgorithm(
-            new AutomaticWingAlgorithm(0.1, 0.01));                        // 5
-        wingController->addAlgorithm(new AutomaticWingAlgorithm(1, 0.1));  // 6
-        wingController->selectAlgorithm(6);
-        // Create the main FSM
-        // FMM = new FMMController();
-
-        // Create a new radio
-        Boardcore::SPIBusInterface* spiInterface4 = new Boardcore::SPIBus(SPI4);
-        radio = new Radio(*spiInterface4, generalScheduler);
-
-        // Create the algorithms
-        algorithms = new Algorithms(algorithmsScheduler);
-    }
-
-    void addSchedulerStatsTask()
-    {
-        // add lambda to log scheduler tasks statistics
-        generalScheduler->addTask(
-            [&]()
-            {
-                std::vector<Boardcore::TaskStatsResult> scheduler_stats =
-                    generalScheduler->getTaskStats();
-
-                for (Boardcore::TaskStatsResult stat : scheduler_stats)
-                {
-                    SDlogger->log(stat);
-                }
-
-                Boardcore::StackLogger::getInstance().updateStack(
-                    THID_TASK_SCHEDULER);
-            },
-            1000,  // 1 hz
-            TASK_SCHEDULER_STATS_ID, Boardcore::TaskScheduler::Policy::SKIP,
-            miosix::getTick());
-    }
-};
-
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/ParafoilTestStatus.h b/src/boards/Parafoil/ParafoilTestStatus.h
deleted file mode 100644
index 1412f647c..000000000
--- a/src/boards/Parafoil/ParafoilTestStatus.h
+++ /dev/null
@@ -1,77 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-/**
- * This class is used to keep track of various main class
- * initialization errors.
- */
-
-#pragma once
-
-#include <ostream>
-#include <string>
-
-namespace Parafoil
-{
-
-enum ParafoilTestComponentStatus
-{
-    ERROR = 0,
-    OK    = 1
-};
-
-struct ParafoilTestStatus
-{
-    // If there is an error, this uint8_t reports it(OR)
-    uint8_t parafoil_test = OK;
-
-    // Specific errors
-    uint8_t logger      = OK;
-    uint8_t eventBroker = OK;
-    uint8_t sensors     = OK;
-    uint8_t FMM         = OK;
-    uint8_t radio       = OK;
-    uint8_t algorithms  = OK;
-
-    /**
-     * @brief Method to set a specific component in an error state
-     */
-    void setError(uint8_t ParafoilTestStatus::*component)
-    {
-        // Put the passed component to error state
-        this->*component = ERROR;
-        // Logic OR
-        parafoil_test = ERROR;
-    }
-
-    static std::string header()
-    {
-        return "logger, eventBorker, sensors, radio, algorithms\n";
-    }
-
-    void print(std::ostream& os) const
-    {
-        os << (int)logger << "," << (int)eventBroker << "," << (int)sensors
-           << "," << (int)radio << "," << (int)algorithms << "\n";
-    }
-};
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Radio/Radio.cpp b/src/boards/Parafoil/Radio/Radio.cpp
new file mode 100644
index 000000000..f9547f122
--- /dev/null
+++ b/src/boards/Parafoil/Radio/Radio.cpp
@@ -0,0 +1,418 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Alberto Nidasio
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include "Radio.h"
+
+#include <Parafoil/Actuators/Actuators.h>
+#include <Parafoil/BoardScheduler.h>
+#include <Parafoil/Buses.h>
+#include <Parafoil/Sensors/Sensors.h>
+#include <Parafoil/TMRepository/TMRepository.h>
+#include <drivers/interrupt/external_interrupts.h>
+#include <events/EventBroker.h>
+#include <radio/Xbee/ATCommands.h>
+
+#include <functional>
+
+using namespace std;
+using namespace miosix;
+using namespace placeholders;
+using namespace Boardcore;
+using namespace Parafoil::RadioConfig;
+
+void __attribute__((used)) EXTI10_IRQHandlerImpl()
+{
+    using namespace Parafoil;
+
+    if (Radio::getInstance().transceiver != nullptr)
+        Radio::getInstance().transceiver->handleDioIRQ();
+}
+
+namespace Parafoil
+{
+
+void Radio::handleMavlinkMessage(MavDriver* driver,
+                                 const mavlink_message_t& msg)
+{
+    switch (msg.msgid)
+    {
+        case MAVLINK_MSG_ID_PING_TC:
+        {
+            // Just send the ack at the end
+            break;
+        }
+        case MAVLINK_MSG_ID_COMMAND_TC:
+        {
+            return handleCommand(msg);
+        }
+        case MAVLINK_MSG_ID_SYSTEM_TM_REQUEST_TC:
+        {
+            SystemTMList tmId = static_cast<SystemTMList>(
+                mavlink_msg_system_tm_request_tc_get_tm_id(&msg));
+
+            // Send multiple packets for the TASK STATS telemetry
+            switch (tmId)
+            {
+                case SystemTMList::MAV_TASK_STATS_ID:
+                {
+                    auto statsVector = BoardScheduler::getInstance()
+                                           .getScheduler()
+                                           .getTaskStats();
+                    uint64_t timestamp = TimestampTimer::getTimestamp();
+
+                    for (auto stats : statsVector)
+                    {
+                        mavlink_message_t msgToSend;
+                        mavlink_task_stats_tm_t tm;
+
+                        tm.timestamp   = timestamp;
+                        tm.task_id     = stats.id;
+                        tm.task_period = stats.period;
+                        tm.task_min    = stats.periodStats.minValue;
+                        tm.task_max    = stats.periodStats.maxValue;
+                        tm.task_mean   = stats.periodStats.mean;
+                        tm.task_stddev = stats.periodStats.stdDev;
+
+                        mavlink_msg_task_stats_tm_encode(
+                            RadioConfig::MAV_SYSTEM_ID,
+                            RadioConfig::MAV_COMPONENT_ID, &msgToSend, &tm);
+
+                        mavDriver->enqueueMsg(msgToSend);
+                    }
+
+                    break;
+                }
+                case SystemTMList::MAV_SENSORS_STATE_ID:
+                {
+                    for (auto sensor : Sensors::getInstance().getSensorsState())
+                    {
+                        mavlink_message_t msgToSend;
+                        mavlink_sensor_state_tm_t tm;
+
+                        sensor.first.copy(tm.sensor_id, sizeof(tm.sensor_id),
+                                          0);
+                        tm.state = sensor.second;
+
+                        mavlink_msg_sensor_state_tm_encode(
+                            RadioConfig::MAV_SYSTEM_ID,
+                            RadioConfig::MAV_COMPONENT_ID, &msgToSend, &tm);
+
+                        mavDriver->enqueueMsg(msgToSend);
+                    }
+
+                    break;
+                }
+                default:
+                {
+                    sendSystemTm(tmId);
+                    break;
+                }
+            }
+
+            LOG_DEBUG(logger, "Received system telemetry request, id: {}",
+                      tmId);
+            break;
+        }
+        case MAVLINK_MSG_ID_SENSOR_TM_REQUEST_TC:
+        {
+            SystemTMList tmId = static_cast<SystemTMList>(
+                mavlink_msg_system_tm_request_tc_get_tm_id(&msg));
+            sendSystemTm(tmId);
+
+            LOG_DEBUG(logger, "Received system telemetry request, id: {}",
+                      tmId);
+            break;
+        }
+        case MAVLINK_MSG_ID_SET_SERVO_ANGLE_TC:
+        {
+            ServosList servoId = static_cast<ServosList>(
+                mavlink_msg_set_servo_angle_tc_get_servo_id(&msg));
+            float angle = mavlink_msg_set_servo_angle_tc_get_angle(&msg);
+
+            LOG_DEBUG(logger,
+                      "Received set servo angle command, servoId: {} angle: {}",
+                      servoId, angle);
+
+            // Move the servo, if failed send a nack
+            if (!Actuators::getInstance().setServoAngle(servoId, angle))
+            {
+                sendNack(msg);
+                return;
+            }
+
+            break;
+        }
+        case MAVLINK_MSG_ID_WIGGLE_SERVO_TC:
+        {
+            ServosList servoId = static_cast<ServosList>(
+                mavlink_msg_wiggle_servo_tc_get_servo_id(&msg));
+
+            LOG_DEBUG(logger, "Received wiggle servo command, servoId: {}",
+                      servoId);
+
+            if (!Actuators::getInstance().wiggleServo(servoId))
+                sendNack(msg);
+
+            break;
+        }
+        case MAVLINK_MSG_ID_RESET_SERVO_TC:
+        {
+            ServosList servoId = static_cast<ServosList>(
+                mavlink_msg_reset_servo_tc_get_servo_id(&msg));
+
+            LOG_DEBUG(logger, "Received reset servo command, servoId: {}",
+                      servoId);
+
+            if (!Actuators::getInstance().setServo(servoId, 0))
+                sendNack(msg);
+
+            break;
+        }
+        case MAVLINK_MSG_ID_SET_REFERENCE_ALTITUDE_TC:
+        {
+            float altitude =
+                mavlink_msg_set_reference_altitude_tc_get_ref_altitude(&msg);
+
+            LOG_DEBUG(logger,
+                      "Received set reference altitude command, altitude: {}",
+                      altitude);
+
+            // TODO: Apply command
+            break;
+        }
+        case MAVLINK_MSG_ID_SET_REFERENCE_TEMPERATURE_TC:
+        {
+            float temperature =
+                mavlink_msg_set_reference_temperature_tc_get_ref_temp(&msg);
+
+            LOG_DEBUG(
+                logger,
+                "Received set reference temperature command, temperature: {}",
+                temperature);
+
+            // TODO: Apply command
+            break;
+        }
+        case MAVLINK_MSG_ID_SET_DEPLOYMENT_ALTITUDE_TC:
+        {
+            float altitude =
+                mavlink_msg_set_deployment_altitude_tc_get_dpl_altitude(&msg);
+
+            LOG_DEBUG(logger,
+                      "Received set deployment altitude command, altitude: {}",
+                      altitude);
+
+            // TODO: Apply command
+            break;
+        }
+        case MAVLINK_MSG_ID_SET_INITIAL_ORIENTATION_TC:
+        {
+            float yaw = mavlink_msg_set_initial_orientation_tc_get_yaw(&msg);
+            float pitch =
+                mavlink_msg_set_initial_orientation_tc_get_pitch(&msg);
+            float roll = mavlink_msg_set_initial_orientation_tc_get_roll(&msg);
+
+            LOG_DEBUG(logger,
+                      "Received set initial orientation command, yaw: {}, "
+                      "pitch: {}, roll: {}",
+                      yaw, pitch, roll);
+
+            // TODO: Apply command
+            break;
+        }
+        case MAVLINK_MSG_ID_SET_INITIAL_COORDINATES_TC:
+        {
+            float latitude =
+                mavlink_msg_set_initial_coordinates_tc_get_latitude(&msg);
+            float longitude =
+                mavlink_msg_set_initial_coordinates_tc_get_longitude(&msg);
+
+            LOG_DEBUG(logger,
+                      "Received set initial coordinates command, latitude: {}, "
+                      "longitude: {}",
+                      latitude, longitude);
+
+            // TODO: Apply command
+            break;
+        }
+        case MAVLINK_MSG_ID_RAW_EVENT_TC:
+        {
+            uint8_t topicId = mavlink_msg_raw_event_tc_get_topic_id(&msg);
+            uint8_t eventId = mavlink_msg_raw_event_tc_get_event_id(&msg);
+
+            LOG_DEBUG(logger,
+                      "Received raw event command, topicId: {}, eventId{}",
+                      topicId, eventId);
+
+            EventBroker::getInstance().post(topicId, eventId);
+            break;
+        }
+
+        default:
+        {
+            LOG_DEBUG(logger, "Received message is not of a known type");
+
+            sendNack(msg);
+            return;
+        }
+    }
+
+    // Acknowledge the message
+    sendAck(msg);
+}
+
+void Radio::handleCommand(const mavlink_message_t& msg)
+{
+    MavCommandList commandId = static_cast<MavCommandList>(
+        mavlink_msg_command_tc_get_command_id(&msg));
+
+    switch (commandId)
+    {
+        case MAV_CMD_ARM:
+            LOG_DEBUG(logger, "Received command arm");
+
+            // TODO: Apply command
+            break;
+        case MAV_CMD_DISARM:
+            LOG_DEBUG(logger, "Received command disarm");
+
+            // TODO: Apply command
+            break;
+        case MAV_CMD_FORCE_LAUNCH:
+            LOG_DEBUG(logger, "Received command force launch");
+
+            // TODO: Apply command
+            break;
+        case MAV_CMD_FORCE_LANDING:
+            LOG_DEBUG(logger, "Received command force landing");
+
+            // TODO: Apply command
+            break;
+        case MAV_CMD_FORCE_EXPULSION:
+            LOG_DEBUG(logger, "Received command force expulsion");
+
+            // TODO: Apply command
+            break;
+        case MAV_CMD_FORCE_MAIN:
+            LOG_DEBUG(logger, "Received command force main");
+
+            // TODO: Apply command
+            break;
+        case MAV_CMD_START_LOGGING:
+            LOG_DEBUG(logger, "Received command start logging");
+            Logger::getInstance().start();
+            break;
+        case MAV_CMD_CLOSE_LOG:
+            LOG_DEBUG(logger, "Received command close log");
+            Logger::getInstance().stop();
+            break;
+        case MAV_CMD_FORCE_REBOOT:
+            reboot();
+            break;
+        case MAV_CMD_TEST_MODE:
+            LOG_DEBUG(logger, "Received command test mode");
+
+            // TODO: Apply command
+            break;
+        case MAV_CMD_START_RECORDING:
+            LOG_DEBUG(logger, "Received command start recording");
+
+            // TODO: Apply command
+            break;
+        case MAV_CMD_STOP_RECORDING:
+            LOG_DEBUG(logger, "Received command stop recording");
+
+            // TODO: Apply command
+            break;
+
+        default:
+            return sendNack(msg);
+    }
+
+    // Acknowledge the message
+    sendAck(msg);
+}
+
+void Radio::sendAck(const mavlink_message_t& msg)
+{
+    mavlink_message_t ackMsg;
+    mavlink_msg_ack_tm_pack(MAV_SYSTEM_ID, MAV_COMPONENT_ID, &ackMsg, msg.msgid,
+                            msg.seq);
+    mavDriver->enqueueMsg(ackMsg);
+}
+
+void Radio::sendNack(const mavlink_message_t& msg)
+{
+    mavlink_message_t nackMsg;
+    LOG_DEBUG(logger, "Sending NACK for message {}", msg.msgid);
+    mavlink_msg_nack_tm_pack(MAV_SYSTEM_ID, MAV_COMPONENT_ID, &nackMsg,
+                             msg.msgid, msg.seq);
+    mavDriver->enqueueMsg(nackMsg);
+}
+
+bool Radio::start() { return mavDriver->start(); }
+
+bool Radio::isStarted() { return mavDriver->isStarted(); }
+
+Boardcore::MavlinkStatus Radio::getMavlinkStatus()
+{
+    return mavDriver->getStatus();
+}
+
+void Radio::logStatus()
+{
+    Logger::getInstance().log(mavDriver->getStatus());
+    // TODO: Add transceiver status logging
+}
+
+bool Radio::sendSystemTm(const SystemTMList tmId)
+{
+    bool result =
+        mavDriver->enqueueMsg(TMRepository::getInstance().packSystemTm(tmId));
+    return result;
+}
+
+bool Radio::sendSensorsTm(const SensorsTMList tmId)
+{
+    bool result =
+        mavDriver->enqueueMsg(TMRepository::getInstance().packSensorsTm(tmId));
+    return result;
+}
+
+Radio::Radio()
+{
+    transceiver = new SX1278(Buses::getInstance().spi4, sx1278::cs::getPin());
+
+    mavDriver = new MavDriver(transceiver,
+                              bind(&Radio::handleMavlinkMessage, this, _1, _2),
+                              0, MAV_OUT_BUFFER_MAX_AGE);
+
+    // Add to the scheduler the flight and statistics telemetries
+    BoardScheduler::getInstance().getScheduler().addTask(
+        [&]() { sendSystemTm(MAV_FLIGHT_ID); }, FLIGHT_TM_PERIOD,
+        FLIGHT_TM_TASK_ID);
+    BoardScheduler::getInstance().getScheduler().addTask(
+        [&]() { sendSystemTm(MAV_STATS_ID); }, STATS_TM_PERIOD,
+        STATS_TM_TASK_ID);
+}
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Radio/Radio.h b/src/boards/Parafoil/Radio/Radio.h
new file mode 100644
index 000000000..185e6c8b7
--- /dev/null
+++ b/src/boards/Parafoil/Radio/Radio.h
@@ -0,0 +1,103 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Alberto Nidasio
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <Parafoil/Configs/RadioConfig.h>
+#include <common/Mavlink.h>
+#include <radio/MavlinkDriver/MavlinkDriver.h>
+#include <radio/SX1278/SX1278.h>
+#include <scheduler/TaskScheduler.h>
+
+namespace Parafoil
+{
+
+using MavDriver = Boardcore::MavlinkDriver<RadioConfig::RADIO_PKT_LENGTH,
+                                           RadioConfig::RADIO_OUT_QUEUE_SIZE,
+                                           RadioConfig::RADIO_MAV_MSG_LENGTH>;
+
+class Radio : public Boardcore::Singleton<Radio>
+{
+    friend class Boardcore::Singleton<Radio>;
+
+public:
+    Boardcore::SX1278* transceiver;
+    MavDriver* mavDriver;
+
+    /**
+     * @brief Called by the MavlinkDriver when a message is received.
+     */
+    void handleMavlinkMessage(MavDriver* driver, const mavlink_message_t& msg);
+
+    /**
+     * @brief Called by handleMavlinkMessage to handle a command message.
+     */
+    void handleCommand(const mavlink_message_t& msg);
+
+    /**
+     * @brief Prepares and send an ack message for the given message.
+     *
+     * @param msg The message received that we need to acknowledge.
+     */
+    void sendAck(const mavlink_message_t& msg);
+
+    /**
+     * @brief Prepares and send a nack message for the given message.
+     *
+     * @param msg The message received that we need to not acknowledge.
+     */
+    void sendNack(const mavlink_message_t& msg);
+
+    /**
+     * @brief Starts the MavlinkDriver.
+     */
+    bool start();
+
+    /**
+     * @brief Tells whether the radio was started.
+     */
+    bool isStarted();
+
+    Boardcore::MavlinkStatus getMavlinkStatus();
+
+    /**
+     * @brief Saves the MavlinkDriver and transceiver status.
+     */
+    void logStatus();
+
+    /**
+     * @brief Used to send the specified system telemetry message.
+     */
+    bool sendSystemTm(const SystemTMList tmId);
+
+    /**
+     * @brief Used to send the specified sensors telemetry message.
+     */
+    bool sendSensorsTm(const SensorsTMList tmId);
+
+private:
+    Radio();
+
+    Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("radio");
+};
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Sensors/Sensors.cpp b/src/boards/Parafoil/Sensors/Sensors.cpp
new file mode 100644
index 000000000..41ee886bc
--- /dev/null
+++ b/src/boards/Parafoil/Sensors/Sensors.cpp
@@ -0,0 +1,246 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include "Sensors.h"
+
+#include <Parafoil/Buses.h>
+#include <Parafoil/Configs/SensorsConfig.h>
+#include <Parafoil/Configs/WingConfig.h>
+#include <Parafoil/Wing/WingController.h>
+#include <sensors/SensorInfo.h>
+#include <utils/AeroUtils/AeroUtils.h>
+
+#include <functional>
+
+using namespace std;
+using namespace miosix;
+using namespace Boardcore;
+using namespace Parafoil::SensorsConfig;
+using namespace Parafoil::WingConfig;
+
+namespace Parafoil
+{
+
+bool Sensors::start() { return sensorManager->start(); }
+
+bool Sensors::isStarted() { return sensorManager->areAllSensorsInitialized(); }
+
+MPU9250Data Sensors::getMpu9250LastSample()
+{
+    miosix::PauseKernelLock lock;
+    return mpu9250->getLastSample();
+}
+
+UBXGPSData Sensors::getUbxGpsLastSample()
+{
+    miosix::PauseKernelLock lock;
+    return ubxGps->getLastSample();
+}
+
+BME280Data Sensors::getBme280LastSample()
+{
+    miosix::PauseKernelLock lock;
+    return bme280->getLastSample();
+}
+
+void Sensors::calibrate()
+{
+    miosix::PauseKernelLock kLock;
+    this->needsCalibration = true;
+}
+
+std::map<string, bool> Sensors::getSensorsState()
+{
+    std::map<string, bool> sensorsState;
+
+    for (auto sensor : sensorsMap)
+        sensorsState[sensor.second.id] =
+            sensorManager->getSensorInfo(sensor.first).isInitialized;
+
+    return sensorsState;
+}
+
+Sensors::Sensors()
+{
+    // Initialize all the sensors
+    mpu9250init();
+    miosix::Thread::sleep(200);
+    ubxGpsInit();
+    miosix::Thread::sleep(200);
+    bme280init();
+    miosix::Thread::sleep(200);
+
+    // Create the sensor manager
+    sensorManager = new SensorManager(sensorsMap);
+}
+
+Sensors::~Sensors()
+{
+    delete mpu9250;
+    delete ubxGps;
+    delete bme280;
+
+    sensorManager->stop();
+    delete sensorManager;
+}
+
+void Sensors::mpu9250init()
+{
+    SPIBusConfig spiConfig{};
+    spiConfig.clockDivider = SPI::ClockDivider::DIV_64;
+    spiConfig.mode         = SPI::Mode::MODE_3;
+
+    mpu9250 =
+        new MPU9250(Buses::getInstance().spi1, sensors::mpu9250::cs::getPin(),
+                    spiConfig, IMU_SAMPLE_RATE, IMU_GYRO_SCALE, IMU_ACCEL_SCALE,
+                    SPI::ClockDivider::DIV_16);
+
+    SensorInfo info(
+        "MPU9250", IMU_SAMPLE_PERIOD,
+        [&]() { Logger::getInstance().log(mpu9250->getLastSample()); }, true);
+
+    sensorsMap.emplace(std::make_pair(mpu9250, info));
+
+    LOG_INFO(logger, "IMU MPU9250 Setup done!");
+}
+
+void Sensors::ubxGpsInit()
+{
+    ubxGps = new UBXGPSSerial(256000, GPS_SAMPLE_RATE, 2, "gps", 9600);
+
+    SensorInfo info(
+        "UbloxGPS", GPS_SAMPLE_PERIOD,
+        [&]() { Logger::getInstance().log(ubxGps->getLastSample()); }, true);
+
+    sensorsMap.emplace(std::make_pair(ubxGps, info));
+
+    LOG_INFO(logger, "Ubx GPS Setup done!");
+}
+
+void Sensors::bme280init()
+{
+    // I first create a SPI slave needed to instantiate the sensor
+    SPISlave slave(Buses::getInstance().spi1, sensors::bme280::cs::getPin(),
+                   SPIBusConfig{});
+
+    slave.config.clockDivider = SPI::ClockDivider::DIV_16;
+    slave.config.mode         = SPI::Mode::MODE_0;
+
+    auto config                      = BME280::BME280_CONFIG_ALL_ENABLED;
+    config.bits.oversamplingPressure = BME280::OVERSAMPLING_4;
+
+    // Instantiate the object
+    bme280 = new BME280(slave, config);
+
+    // Set the standby time
+    bme280->setStandbyTime(PRESS_SAMPLE_RATE);
+
+    // Bind the information with the callback method
+    SensorInfo info("BME280", PRESS_SAMPLE_PERIOD,
+                    bind(&Sensors::bme280Callback, this), true);
+    sensorsMap.emplace(std::make_pair(bme280, info));
+
+    LOG_INFO(logger, "BME280 Setup done!");
+}
+
+void Sensors::bme280Callback()
+{
+    auto data = bme280->getLastSample();
+    Logger::getInstance().log(data);
+
+    // Logic for wing procedure start and flare
+    static uint8_t count = 0;
+    static Boardcore::Stats pressureMean{};
+    static Boardcore::Stats temperatureMean{};
+
+    // If we reach the needed samples
+    if (count == WING_PRESSURE_MEAN_COUNT)
+    {
+        static bool procedureArm = false;
+        static bool flareArm     = false;
+
+        // In case of calibration needed i calibrate
+        if (needsCalibration)
+        {
+            WING_CALIBRATION_PRESSURE = pressureMean.getStats().mean;
+            WING_CALIBRATION_TEMPERATURE =
+                temperatureMean.getStats().mean + 273.15;
+
+            // Reset the mean values
+            count = 0;
+            pressureMean.reset();
+            temperatureMean.reset();
+
+            // Set calibrated status
+            needsCalibration = false;
+
+            // I don't want to calculate stuff
+            return;
+        }
+
+        // Calculate the height
+        float height = Aeroutils::relAltitude(pressureMean.getStats().mean,
+                                              WING_CALIBRATION_PRESSURE,
+                                              WING_CALIBRATION_TEMPERATURE);
+
+        // Update the radio repository
+        data.pressure    = pressureMean.getStats().mean;
+        data.temperature = temperatureMean.getStats().mean;
+
+        // Decide what the wing should do
+        if (height > WING_ALGORITHM_ARM_ALTITUDE && !procedureArm)
+            procedureArm = true;
+
+        if (height < WING_ALGORITHM_START_ALTITUDE && procedureArm)
+        {
+            // Disarm the starting command
+            procedureArm = false;
+
+            // Arm the flare command
+            flareArm = true;
+
+            // Start the algorithm
+            WingController::getInstance().start();
+        }
+
+        if (height < WING_FLARE_ALTITUDE && flareArm)
+        {
+            // Disarm the starting command
+            flareArm = false;
+
+            // Flare
+            WingController::getInstance().flare();
+        }
+
+        // Reset the mean values
+        count = 0;
+        pressureMean.reset();
+        temperatureMean.reset();
+    }
+
+    // Add the current value to the mean and increase the counting
+    pressureMean.add(data.pressure);
+    temperatureMean.add(data.temperature);
+    count++;
+}
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Control/Algorithms.h b/src/boards/Parafoil/Sensors/Sensors.h
similarity index 57%
rename from src/boards/Parafoil/Control/Algorithms.h
rename to src/boards/Parafoil/Sensors/Sensors.h
index c09fec1cc..b8816aea8 100644
--- a/src/boards/Parafoil/Control/Algorithms.h
+++ b/src/boards/Parafoil/Sensors/Sensors.h
@@ -19,53 +19,58 @@
  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
  * THE SOFTWARE.
  */
+
 #pragma once
 
-#include <Parafoil/Control/NASController.h>
-#include <diagnostic/PrintLogger.h>
-#include <scheduler/TaskScheduler.h>
-#include <sensors/MPU9250/MPU9250Data.h>
-#include <sensors/UBXGPS/UBXGPSData.h>
+#include <sensors/BME280/BME280.h>
+#include <sensors/MPU9250/MPU9250.h>
+#include <sensors/SensorManager.h>
+#include <sensors/UBXGPS/UBXGPSSerial.h>
 
 namespace Parafoil
 {
-class Algorithms
+
+class Sensors : public Boardcore::Singleton<Sensors>
 {
+    friend class Boardcore::Singleton<Sensors>;
+
 public:
-    // All the algorithms that need to be started
-    NASController* nas;
-
-    // The scheduler
-    Boardcore::TaskScheduler* scheduler;
-
-    /**
-     * @brief Construct a new Algorithms object
-     *
-     * @param scheduler The algorithms task scheduler
-     */
-    Algorithms(Boardcore::TaskScheduler* scheduler);
-
-    /**
-     * @brief Destroy the Algorithms object
-     */
-    ~Algorithms();
-
-    /**
-     * @brief Method to start the algorithms task scheduler
-     */
     bool start();
 
-    // Kernel locked getters
-    Boardcore::NASState getNASLastSample();
+    bool isStarted();
+
+    Boardcore::MPU9250Data getMpu9250LastSample();
+    Boardcore::UBXGPSData getUbxGpsLastSample();
+    Boardcore::BME280Data getBme280LastSample();
+
+    void calibrate();
+
+    std::map<string, bool> getSensorsState();
 
 private:
-    // Debug serial logger
-    Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("algorithms");
+    Sensors();
+
+    ~Sensors();
 
-    // SD logger
-    Boardcore::Logger* SDlogger = &Boardcore::Logger::getInstance();
+    void mpu9250init();
 
-    // Init functions
-    void NASInit();
+    void ubxGpsInit();
+    void ubxGpsCallback();
+
+    void bme280init();
+    void bme280Callback();
+
+    Boardcore::MPU9250* mpu9250;
+    Boardcore::UBXGPSSerial* ubxGps;
+    Boardcore::BME280* bme280;
+
+    bool needsCalibration = false;
+
+    Boardcore::SensorManager* sensorManager = nullptr;
+
+    Boardcore::SensorManager::SensorMap_t sensorsMap;
+
+    Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("sensors");
 };
-}  // namespace Parafoil
\ No newline at end of file
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/TMRepository/TMRepository.cpp b/src/boards/Parafoil/TMRepository/TMRepository.cpp
new file mode 100644
index 000000000..f78f2820d
--- /dev/null
+++ b/src/boards/Parafoil/TMRepository/TMRepository.cpp
@@ -0,0 +1,362 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#include "TMRepository.h"
+
+#include <Parafoil/BoardScheduler.h>
+#include <Parafoil/NASController/NASController.h>
+#include <Parafoil/Radio/Radio.h>
+#include <Parafoil/Sensors/Sensors.h>
+#include <diagnostic/CpuMeter/CpuMeter.h>
+#include <events/EventBroker.h>
+#include <utils/SkyQuaternion/SkyQuaternion.h>
+
+#include <Eigen/Core>
+
+using namespace Boardcore;
+using namespace Eigen;
+
+namespace Parafoil
+{
+
+mavlink_message_t TMRepository::packSystemTm(SystemTMList reqTm)
+{
+    mavlink_message_t msg;
+
+    miosix::PauseKernelLock kLock;
+
+    switch (reqTm)
+    {
+        case SystemTMList::MAV_SYS_ID:
+        {
+            mavlink_sys_tm_t tm;
+
+            tm.timestamp    = TimestampTimer::getTimestamp();
+            tm.logger       = Logger::getInstance().isStarted();
+            tm.event_broker = EventBroker::getInstance().isRunning();
+            tm.radio        = Radio::getInstance().isStarted();
+            tm.pin_observer = 0;
+            tm.sensors      = Sensors::getInstance().isStarted();
+            tm.board_scheduler =
+                BoardScheduler::getInstance().getScheduler().isRunning();
+
+            mavlink_msg_sys_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                      RadioConfig::MAV_COMPONENT_ID, &msg, &tm);
+
+            break;
+        }
+        case SystemTMList::MAV_LOGGER_ID:
+        {
+            mavlink_logger_tm_t tm;
+
+            auto stats = Logger::getInstance().getStats();
+
+            tm.timestamp          = stats.timestamp;
+            tm.log_number         = stats.logNumber;
+            tm.too_large_samples  = stats.tooLargeSamples;
+            tm.dropped_samples    = stats.droppedSamples;
+            tm.queued_samples     = stats.queuedSamples;
+            tm.buffers_filled     = stats.buffersFilled;
+            tm.buffers_written    = stats.buffersWritten;
+            tm.writes_failed      = stats.writesFailed;
+            tm.last_write_error   = stats.lastWriteError;
+            tm.average_write_time = stats.averageWriteTime;
+            tm.max_write_time     = stats.maxWriteTime;
+
+            mavlink_msg_logger_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                         RadioConfig::MAV_COMPONENT_ID, &msg,
+                                         &tm);
+            break;
+        }
+        case SystemTMList::MAV_MAVLINK_STATS:
+        {
+            mavlink_mavlink_stats_tm_t tm;
+
+            auto stats = Radio::getInstance().getMavlinkStatus();
+
+            tm.timestamp               = stats.timestamp;
+            tm.n_send_queue            = stats.nSendQueue;
+            tm.max_send_queue          = stats.maxSendQueue;
+            tm.n_send_errors           = stats.nSendErrors;
+            tm.msg_received            = stats.mavStats.msg_received;
+            tm.buffer_overrun          = stats.mavStats.buffer_overrun;
+            tm.parse_error             = stats.mavStats.parse_error;
+            tm.parse_state             = stats.mavStats.parse_state;
+            tm.packet_idx              = stats.mavStats.packet_idx;
+            tm.current_rx_seq          = stats.mavStats.current_rx_seq;
+            tm.current_tx_seq          = stats.mavStats.current_tx_seq;
+            tm.packet_rx_success_count = stats.mavStats.packet_rx_success_count;
+            tm.packet_rx_drop_count    = stats.mavStats.packet_rx_drop_count;
+
+            mavlink_msg_mavlink_stats_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                                RadioConfig::MAV_COMPONENT_ID,
+                                                &msg, &tm);
+            break;
+        }
+        case SystemTMList::MAV_NAS_ID:
+        {
+            mavlink_nas_tm_t tm;
+
+            auto state = NASController::getInstance().getNasState();
+            auto ref   = NASController::getInstance().getReferenceValues();
+
+            tm.timestamp       = state.timestamp;
+            tm.state           = 0;
+            tm.nas_n           = state.n;
+            tm.nas_e           = state.e;
+            tm.nas_d           = state.d;
+            tm.nas_vn          = state.vn;
+            tm.nas_ve          = state.ve;
+            tm.nas_vd          = state.vd;
+            tm.nas_qw          = state.qw;
+            tm.nas_qx          = state.qx;
+            tm.nas_qy          = state.qy;
+            tm.nas_qz          = state.qz;
+            tm.nas_bias_x      = state.bx;
+            tm.nas_bias_y      = state.by;
+            tm.nas_bias_z      = state.bz;
+            tm.ref_pressure    = ref.pressure;
+            tm.ref_temperature = ref.temperature;
+            tm.ref_latitude    = ref.startLatitude;
+            tm.ref_longitude   = ref.startLongitude;
+
+            mavlink_msg_nas_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                      RadioConfig::MAV_COMPONENT_ID, &msg, &tm);
+
+            break;
+        }
+        case SystemTMList::MAV_FLIGHT_ID:
+        {
+            mavlink_payload_flight_tm_t tm;
+            Sensors &sensors = Sensors::getInstance();
+
+            auto &nas = NASController::getInstance();
+
+            auto bme280Data = sensors.getBme280LastSample();
+            auto imuData    = sensors.getMpu9250LastSample();
+
+            auto nasState = NASController::getInstance().getNasState();
+
+            tm.timestamp = TimestampTimer::getTimestamp();
+
+            // State machines states
+            tm.ada_state = 0;
+            tm.fmm_state = 0;
+            tm.nas_state = 0;
+
+            // Pressures
+            tm.pressure_ada    = 0;
+            tm.pressure_digi   = bme280Data.pressure;
+            tm.pressure_static = 0;
+            tm.pressure_dpl    = 0;
+            tm.airspeed_pitot  = 0;  // TODO: Implement
+
+            // ADA estimation
+            tm.msl_altitude   = 0;
+            tm.ada_vert_speed = 0;
+            tm.ada_vert_accel = 0;
+
+            // IMU
+            tm.acc_x  = imuData.accelerationX;
+            tm.acc_y  = imuData.accelerationY;
+            tm.acc_z  = imuData.accelerationZ;
+            tm.gyro_x = imuData.angularVelocityX;
+            tm.gyro_y = imuData.angularVelocityY;
+            tm.gyro_z = imuData.angularVelocityZ;
+            tm.mag_x  = imuData.magneticFieldX;
+            tm.mag_y  = imuData.magneticFieldY;
+            tm.mag_z  = imuData.magneticFieldZ;
+
+            // GPS
+            tm.gps_fix = 0;
+            tm.gps_lat = 0;
+            tm.gps_lon = 0;
+            tm.gps_alt = 0;
+
+            // NAS
+            tm.nas_n      = nasState.n;
+            tm.nas_e      = nasState.e;
+            tm.nas_d      = nasState.d;
+            tm.nas_vn     = nasState.vn;
+            tm.nas_ve     = nasState.ve;
+            tm.nas_vd     = nasState.vd;
+            tm.nas_qx     = nasState.qx;
+            tm.nas_qy     = nasState.qy;
+            tm.nas_qz     = nasState.qz;
+            tm.nas_qw     = nasState.qw;
+            tm.nas_bias_x = nasState.bx;
+            tm.nas_bias_y = nasState.by;
+            tm.nas_bias_z = nasState.bz;
+
+            // Sensing pins statuses
+            tm.pin_nosecone = 0;
+
+            // Board status
+            tm.vbat = 0;  // = sensors.getBatteryVoltageLastSample().batVoltage;
+            tm.vsupply_5v   = 0;
+            tm.temperature  = bme280Data.temperature;
+            tm.logger_error = Logger::getInstance().getStats().lastWriteError;
+
+            mavlink_msg_payload_flight_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                                 RadioConfig::MAV_COMPONENT_ID,
+                                                 &msg, &tm);
+            break;
+        }
+        case SystemTMList::MAV_STATS_ID:
+        {
+            mavlink_rocket_stats_tm_t tm;
+
+            tm.liftoff_ts            = 0;
+            tm.liftoff_max_acc_ts    = 0;
+            tm.liftoff_max_acc       = 0;
+            tm.max_z_speed_ts        = 0;
+            tm.max_z_speed           = 0;
+            tm.max_airspeed_pitot    = 0;
+            tm.max_speed_altitude    = 0;
+            tm.apogee_ts             = 0;
+            tm.apogee_lat            = 0;
+            tm.apogee_lon            = 0;
+            tm.static_min_pressure   = 0;
+            tm.digital_min_pressure  = 0;
+            tm.ada_min_pressure      = 0;
+            tm.baro_max_altitude     = 0;
+            tm.gps_max_altitude      = 0;
+            tm.drogue_dpl_ts         = 0;
+            tm.drogue_dpl_max_acc    = 0;
+            tm.dpl_vane_max_pressure = 0;
+            tm.main_dpl_altitude_ts  = 0;
+            tm.main_dpl_altitude     = 0;
+            tm.main_dpl_zspeed       = 0;
+            tm.main_dpl_acc          = 0;
+            tm.cpu_load              = CpuMeter::getCpuStats().mean;
+
+            mavlink_msg_rocket_stats_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                               RadioConfig::MAV_COMPONENT_ID,
+                                               &msg, &tm);
+            break;
+        }
+
+        default:
+        {
+            mavlink_nack_tm_t nack;
+
+            nack.recv_msgid = 0;
+            nack.seq_ack    = 0;
+
+            LOG_DEBUG(logger, "Unknown telemetry id: {}", reqTm);
+            mavlink_msg_nack_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                       RadioConfig::MAV_COMPONENT_ID, &msg,
+                                       &nack);
+            break;
+        }
+    }
+
+    return msg;
+}
+
+mavlink_message_t TMRepository::packSensorsTm(SensorsTMList reqTm)
+{
+    mavlink_message_t msg;
+
+    switch (reqTm)
+    {
+        case SensorsTMList::MAV_GPS_ID:
+        {
+            mavlink_gps_tm_t tm;
+
+            auto gpsData = Sensors::getInstance().getUbxGpsLastSample();
+
+            tm.timestamp = TimestampTimer::getTimestamp();
+            strcpy(tm.sensor_id, "UbloxGPS");
+            tm.fix          = gpsData.fix;
+            tm.latitude     = gpsData.latitude;
+            tm.longitude    = gpsData.longitude;
+            tm.height       = gpsData.height;
+            tm.vel_north    = gpsData.velocityNorth;
+            tm.vel_east     = gpsData.velocityEast;
+            tm.vel_down     = gpsData.velocityDown;
+            tm.speed        = gpsData.speed;
+            tm.track        = gpsData.track;
+            tm.n_satellites = gpsData.satellites;
+
+            mavlink_msg_gps_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                      RadioConfig::MAV_COMPONENT_ID, &msg, &tm);
+            break;
+        }
+        case SensorsTMList::MAV_MPU9250_ID:
+        {
+            mavlink_imu_tm_t tm;
+
+            MPU9250Data imuData = Sensors::getInstance().getMpu9250LastSample();
+
+            tm.timestamp = TimestampTimer::getTimestamp();
+            strcpy(tm.sensor_id, "MPU9250");
+            tm.acc_x  = imuData.accelerationX;
+            tm.acc_y  = imuData.accelerationY;
+            tm.acc_z  = imuData.accelerationZ;
+            tm.gyro_x = imuData.angularVelocityX;
+            tm.gyro_y = imuData.angularVelocityY;
+            tm.gyro_z = imuData.angularVelocityZ;
+            tm.mag_x  = imuData.magneticFieldX;
+            tm.mag_y  = imuData.magneticFieldY;
+            tm.mag_z  = imuData.magneticFieldZ;
+
+            // Encode the message
+            mavlink_msg_imu_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                      RadioConfig::MAV_COMPONENT_ID, &msg, &tm);
+            break;
+        }
+        case SensorsTMList::MAV_BME280_ID:
+        {
+            mavlink_baro_tm_t tm;
+
+            BME280Data baro = Sensors::getInstance().getBme280LastSample();
+
+            tm.timestamp = miosix::getTick();
+            strcpy(tm.sensor_id, "BME280");
+            tm.pressure = baro.pressure;
+
+            mavlink_msg_baro_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                       RadioConfig::MAV_COMPONENT_ID, &msg,
+                                       &tm);
+            break;
+        }
+
+        default:
+        {
+            mavlink_nack_tm_t nack;
+
+            nack.recv_msgid = 0;
+            nack.seq_ack    = 0;
+
+            LOG_DEBUG(logger, "Unknown telemetry id: {}", reqTm);
+            mavlink_msg_nack_tm_encode(RadioConfig::MAV_SYSTEM_ID,
+                                       RadioConfig::MAV_COMPONENT_ID, &msg,
+                                       &nack);
+            break;
+        }
+    }
+
+    return msg;
+}
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/TMRepository/TMRepository.h b/src/boards/Parafoil/TMRepository/TMRepository.h
new file mode 100644
index 000000000..788c50d24
--- /dev/null
+++ b/src/boards/Parafoil/TMRepository/TMRepository.h
@@ -0,0 +1,70 @@
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Matteo Pignataro
+ *
+ * Permission is hereby granted, free of charge, to any person obtaining a copy
+ * of this software and associated documentation files (the "Software"), to deal
+ * in the Software without restriction, including without limitation the rights
+ * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
+ * copies of the Software, and to permit persons to whom the Software is
+ * furnished to do so, subject to the following conditions:
+ *
+ * The above copyright notice and this permission notice shall be included in
+ * all copies or substantial portions of the Software.
+ *
+ * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
+ * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
+ * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
+ * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
+ * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
+ * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
+ * THE SOFTWARE.
+ */
+
+#pragma once
+
+#include <Singleton.h>
+#include <common/Mavlink.h>
+#include <diagnostic/PrintLogger.h>
+#include <sensors/BME280/BME280Data.h>
+#include <sensors/MPU9250/MPU9250Data.h>
+
+/**
+ * @brief This class represents the collection of data that can be sent via
+ * radio communication. This refers to mavlink libraries and structures created
+ * in the correct .xml file.
+ *
+ * It is necessary that this singleton class handles the structure update
+ * (when a message pack is requested).
+ * The pack method is the core of the class. It returns a mavlink_message
+ * with the message data(specified with the id) requested.
+ */
+
+namespace Parafoil
+{
+
+class TMRepository : public Boardcore::Singleton<TMRepository>
+{
+    friend class Boardcore::Singleton<TMRepository>;
+
+public:
+    /**
+     * @brief Retrieve a system telemetry message in packed form.
+     *
+     * @param reqTm Required telemetry.
+     * @return Packed mavlink telemetry or a nack.
+     */
+    mavlink_message_t packSystemTm(SystemTMList reqTm);
+
+    /**
+     * @brief Retrieve a sensor telemetry message in packed form.
+     *
+     * @param reqTm Required telemetry.
+     * @return Packed mavlink telemetry or a nack.
+     */
+    mavlink_message_t packSensorsTm(SensorsTMList reqTm);
+
+private:
+    Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("tmrepo");
+};
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.cpp b/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.cpp
deleted file mode 100644
index 8a6caa55f..000000000
--- a/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.cpp
+++ /dev/null
@@ -1,231 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include <Parafoil/ParafoilTest.h>
-#include <Parafoil/TelemetriesTelecommands/TMRepository.h>
-#include <utils/SkyQuaternion/SkyQuaternion.h>
-
-#include <Eigen/Core>
-
-using namespace Boardcore;
-using namespace Eigen;
-
-namespace Parafoil
-{
-
-mavlink_message_t TMRepository::packSystemTM(uint8_t req_tm, uint8_t sys_id,
-                                             uint8_t comp_id)
-{
-    mavlink_message_t m;
-    mavlink_nack_tm_t nack;
-
-    miosix::PauseKernelLock kLock;
-
-    switch (req_tm)
-    {
-        case SystemTMList::MAV_LOGGER_ID:
-        {
-            tmRepository.loggerTm.timestamp = miosix::getTick();
-
-            // Get the logger stats
-            Boardcore::LoggerStats stats =
-                ParafoilTest::getInstance().SDlogger->getStats();
-
-            // First i update the loggerTm
-            tmRepository.loggerTm.log_number =
-                ParafoilTest::getInstance().SDlogger->getCurrentLogNumber();
-
-            tmRepository.loggerTm.buffers_filled    = stats.buffersFilled;
-            tmRepository.loggerTm.buffers_written   = stats.buffersWritten;
-            tmRepository.loggerTm.dropped_samples   = stats.droppedSamples;
-            tmRepository.loggerTm.max_write_time    = stats.maxWriteTime;
-            tmRepository.loggerTm.queued_samples    = stats.queuedSamples;
-            tmRepository.loggerTm.too_large_samples = stats.tooLargeSamples;
-            tmRepository.loggerTm.writes_failed     = stats.writesFailed;
-            tmRepository.loggerTm.max_write_time    = stats.maxWriteTime;
-            tmRepository.loggerTm.last_write_error  = stats.lastWriteError;
-
-            mavlink_msg_logger_tm_encode(sys_id, comp_id, &m,
-                                         &(tmRepository.loggerTm));
-            break;
-        }
-        case SystemTMList::MAV_FLIGHT_ID:
-        {
-            // I have to send the whole flight tm
-            tmRepository.flightTm.timestamp = miosix::getTick();
-
-            // Get the pressure
-            tmRepository.flightTm.pressure_digi =
-                ParafoilTest::getInstance()
-                    .sensors->getBME280LastSample()
-                    .pressure;
-
-            // Get the IMU data
-            MPU9250Data imu =
-                ParafoilTest::getInstance().sensors->getMPU9250LastSample();
-
-            tmRepository.flightTm.acc_x  = imu.accelerationX;
-            tmRepository.flightTm.acc_y  = imu.accelerationY;
-            tmRepository.flightTm.acc_z  = imu.accelerationZ;
-            tmRepository.flightTm.gyro_x = imu.angularVelocityX;
-            tmRepository.flightTm.gyro_y = imu.angularVelocityY;
-            tmRepository.flightTm.gyro_z = imu.angularVelocityZ;
-            tmRepository.flightTm.mag_x  = imu.magneticFieldX;
-            tmRepository.flightTm.mag_y  = imu.magneticFieldY;
-            tmRepository.flightTm.mag_z  = imu.magneticFieldZ;
-
-            // Get the GPS data
-            UBXGPSData gps =
-                ParafoilTest::getInstance().sensors->getGPSLastSample();
-
-            tmRepository.flightTm.gps_fix = gps.fix;
-            tmRepository.flightTm.gps_lat = gps.latitude;
-            tmRepository.flightTm.gps_lon = gps.longitude;
-            tmRepository.flightTm.gps_alt = gps.height;
-
-            // Get the NAS data
-            NASState state =
-                ParafoilTest::getInstance().algorithms->getNASLastSample();
-
-            tmRepository.flightTm.nas_n  = state.n;
-            tmRepository.flightTm.nas_e  = state.e;
-            tmRepository.flightTm.nas_d  = state.d;
-            tmRepository.flightTm.nas_vn = state.vn;
-            tmRepository.flightTm.nas_ve = state.ve;
-            tmRepository.flightTm.nas_vd = state.vd;
-
-            tmRepository.flightTm.nas_qx = state.qx;
-            tmRepository.flightTm.nas_qy = state.qy;
-            tmRepository.flightTm.nas_qz = state.qz;
-            tmRepository.flightTm.nas_qw = state.qw;
-
-            tmRepository.flightTm.nas_bias_x = state.bx;
-            tmRepository.flightTm.nas_bias_y = state.by;
-            tmRepository.flightTm.nas_bias_z = state.bz;
-
-            mavlink_msg_payload_flight_tm_encode(sys_id, comp_id, &m,
-                                                 &(tmRepository.flightTm));
-
-            break;
-        }
-        default:
-        {
-            LOG_DEBUG(logger, "Unknown telemetry id: {:d}", req_tm);
-            nack.recv_msgid = 0;
-            nack.seq_ack    = 0;
-            mavlink_msg_nack_tm_encode(sys_id, comp_id, &m, &nack);
-            break;
-        }
-    }
-    return m;
-}
-
-mavlink_message_t TMRepository::packSensorTM(uint8_t req_tm, uint8_t sys_id,
-                                             uint8_t comp_id)
-{
-    mavlink_message_t m;
-    mavlink_nack_tm_t nack;
-
-    // The kernel lock is not necessary because the sensors getters already do
-    // that
-
-    switch (req_tm)
-    {
-        case SensorsTMList::MAV_GPS_ID:
-        {
-            // Get with lock the gps data
-            UBXGPSData gps =
-                ParafoilTest::getInstance().sensors->getGPSLastSample();
-
-            // Update the repository
-            tmRepository.gpsTm.timestamp = miosix::getTick();
-            strcpy(tmRepository.gpsTm.sensor_id, "UbloxGPS\0");
-            tmRepository.gpsTm.fix          = gps.fix;
-            tmRepository.gpsTm.latitude     = gps.latitude;
-            tmRepository.gpsTm.longitude    = gps.longitude;
-            tmRepository.gpsTm.height       = gps.height;
-            tmRepository.gpsTm.vel_north    = gps.velocityNorth;
-            tmRepository.gpsTm.vel_east     = gps.velocityEast;
-            tmRepository.gpsTm.vel_down     = gps.velocityDown;
-            tmRepository.gpsTm.speed        = gps.speed;
-            tmRepository.gpsTm.track        = gps.track;
-            tmRepository.gpsTm.n_satellites = gps.satellites;
-
-            // Encode the message
-            mavlink_msg_gps_tm_encode(sys_id, comp_id, &m,
-                                      &(tmRepository.gpsTm));
-            break;
-        }
-        case SensorsTMList::MAV_MPU9250_ID:
-        {
-            // Get with lock the imu data
-            MPU9250Data imu =
-                ParafoilTest::getInstance().sensors->getMPU9250LastSample();
-
-            // Update the repository
-            tmRepository.imuTm.timestamp = miosix::getTick();
-            strcpy(tmRepository.imuTm.sensor_id, "MPU9250\0");
-            tmRepository.imuTm.acc_x  = imu.accelerationX;
-            tmRepository.imuTm.acc_y  = imu.accelerationY;
-            tmRepository.imuTm.acc_z  = imu.accelerationZ;
-            tmRepository.imuTm.gyro_x = imu.angularVelocityX;
-            tmRepository.imuTm.gyro_y = imu.angularVelocityY;
-            tmRepository.imuTm.gyro_z = imu.angularVelocityZ;
-            tmRepository.imuTm.mag_x  = imu.magneticFieldX;
-            tmRepository.imuTm.mag_y  = imu.magneticFieldY;
-            tmRepository.imuTm.mag_z  = imu.magneticFieldZ;
-
-            // Encode the message
-            mavlink_msg_imu_tm_encode(sys_id, comp_id, &m,
-                                      &(tmRepository.imuTm));
-            break;
-        }
-        case SensorsTMList::MAV_BME280_ID:
-        {
-            // Get with lock the barometer data
-            BME280Data baro =
-                ParafoilTest::getInstance().sensors->getBME280LastSample();
-
-            // Update the repository
-            tmRepository.barometerTm.timestamp = miosix::getTick();
-            strcpy(tmRepository.barometerTm.sensor_id, "BME280\0");
-            tmRepository.barometerTm.pressure = baro.pressure;
-
-            // Encode the message
-            mavlink_msg_baro_tm_encode(sys_id, comp_id, &m,
-                                       &(tmRepository.barometerTm));
-            break;
-        }
-        default:
-        {
-            // Send the nack
-            LOG_DEBUG(logger, "Unknown telemetry id: {:d}", req_tm);
-            nack.recv_msgid = 0;
-            nack.seq_ack    = 0;
-            mavlink_msg_nack_tm_encode(sys_id, comp_id, &m, &nack);
-        }
-    }
-
-    return m;
-}
-
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.h b/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.h
deleted file mode 100644
index 7dc9fa2f2..000000000
--- a/src/boards/Parafoil/TelemetriesTelecommands/TMRepository.h
+++ /dev/null
@@ -1,109 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-#pragma once
-
-#include <Parafoil/TelemetriesTelecommands/Mavlink.h>
-#include <Singleton.h>
-#include <sensors/BME280/BME280Data.h>
-#include <sensors/MPU9250/MPU9250Data.h>
-
-/**
- * @brief This class represents the collection of data that can
- * be sent via radio communication. This refers to mavlink libriaries
- * and structures created in the correct .xml file.
- *
- * It is necessary that this singleton class handles the structure update
- * (when a message pack is requested).
- * The pack method is the core of the class. It returns a mavlink_message
- * with the message data(specified with the id) requested.
- */
-
-namespace Parafoil
-{
-
-class TMRepository : public Boardcore::Singleton<TMRepository>
-{
-    friend class Boardcore::Singleton<TMRepository>;
-
-public:
-    /**
-     * @brief Retrieve a system telemetry message in packed form.
-     *
-     * @param req_tm    required telemetry
-     * @param sys_id    system id to pack it with
-     * @param comp_id   component id to pack it with
-     * @return          packed mavlink struct of that telemetry or a NACK_TM if
-     *                  the telemetry id was not found.
-     */
-    mavlink_message_t packSystemTM(uint8_t req_tm,
-                                   uint8_t sys_id  = TMTC_MAV_SYSID,
-                                   uint8_t comp_id = TMTC_MAV_COMPID);
-
-    /**
-     * @brief Retrieve a sensor telemetry message in packed form.
-     *
-     * @param req_tm    required telemetry
-     * @param sys_id    system id to pack it with
-     * @param comp_id   component id to pack it with
-     * @return          packed mavlink struct of that telemetry or a NACK_TM if
-     *                  the telemetry id was not found.
-     */
-    mavlink_message_t packSensorTM(uint8_t req_tm,
-                                   uint8_t sys_id  = TMTC_MAV_SYSID,
-                                   uint8_t comp_id = TMTC_MAV_COMPID);
-
-private:
-    /**
-     * @brief Struct containing all TMs in the form of mavlink messages.
-     */
-    struct TmRepository_t
-    {
-        // System telemetries
-        mavlink_sys_tm_t sysTm;
-        mavlink_fsm_tm_t fsmTm;
-        mavlink_pin_tm_t pinObsTm;
-        mavlink_logger_tm_t loggerTm;
-        mavlink_mavlink_stats_tm_t mavlinkStatsTm;
-        mavlink_task_stats_tm_t taskStatsTm;
-        mavlink_ada_tm_t adaTm;
-        mavlink_nas_tm_t nasTm;
-        mavlink_can_tm_t canTm;
-        mavlink_payload_flight_tm_t flightTm;
-        mavlink_payload_stats_tm_t stastTm;
-        mavlink_sensor_state_tm_t sensorsStateTm;
-
-        // Sensors telemetries
-        mavlink_gps_tm_t gpsTm;
-        mavlink_imu_tm_t imuTm;
-        mavlink_adc_tm_t adcTm;
-        mavlink_baro_tm_t barometerTm;
-        mavlink_temp_tm_t temperatureTm;
-        mavlink_attitude_tm_t attitudeTm;
-    } tmRepository;
-
-    /**
-     * @brief Logger
-     */
-    Boardcore::PrintLogger logger =
-        Boardcore::Logging::getLogger("TMRepository");
-};
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Wing/AutomaticWingAlgorithm.cpp b/src/boards/Parafoil/Wing/AutomaticWingAlgorithm.cpp
index 037069f93..fbbd9f164 100644
--- a/src/boards/Parafoil/Wing/AutomaticWingAlgorithm.cpp
+++ b/src/boards/Parafoil/Wing/AutomaticWingAlgorithm.cpp
@@ -20,9 +20,14 @@
  * THE SOFTWARE.
  */
 
-#include <Parafoil/ParafoilTest.h>
+#include <Parafoil/Actuators/Actuators.h>
+#include <Parafoil/Configs/WingConfig.h>
+#include <Parafoil/NASController/NASController.h>
+#include <Parafoil/Sensors/Sensors.h>
 #include <Parafoil/Wing/AutomaticWingAlgorithm.h>
+#include <Parafoil/Wing/WingController.h>
 #include <algorithms/NAS/NASState.h>
+#include <drivers/timer/TimestampTimer.h>
 #include <math.h>
 #include <utils/Constants.h>
 
@@ -31,59 +36,38 @@ using namespace Eigen;
 
 namespace Parafoil
 {
-AutomaticWingAlgorithm::AutomaticWingAlgorithm(float Kp, float Ki,
-                                               ServoInterface* servo1,
-                                               ServoInterface* servo2)
-    : WingAlgorithm(servo1, servo2, "")
-{
-    // TODO define umin and umax for antiwindup purposes
-    controller = new PIController(Kp, Ki, WING_UPDATE_PERIOD / 1000.0f,
-                                  -2.09439, 2.09439);
-}
 
 AutomaticWingAlgorithm::AutomaticWingAlgorithm(float Kp, float Ki)
     : WingAlgorithm("")
 {
-    controller = new PIController(Kp, Ki, WING_UPDATE_PERIOD / 1000.0f,
-                                  -2.09439, 2.09439);
+    controller = new PIController(
+        Kp, Ki, WingConfig::WING_UPDATE_PERIOD / 1000.0f, -2.09439, 2.09439);
 }
 
 AutomaticWingAlgorithm::~AutomaticWingAlgorithm() { delete (controller); }
 
 void AutomaticWingAlgorithm::step()
 {
-    // The PI calculated result
-    float result;
-
-    // Acquire the last nas state
-    NASState state = ParafoilTest::getInstance().algorithms->getNASLastSample();
-    UBXGPSData gps = ParafoilTest::getInstance().sensors->getGPSLastSample();
+    auto nas = NASController::getInstance().getNasState();
 
     // Target direction in respect to the current one
-    // TODO to be logged
-    auto targetPosition =
-        ParafoilTest::getInstance().wingController->getTargetPosition();
-    Vector2f targetDirection = targetPosition - Vector2f(state.n, state.e);
+    // TODO: To be logged
+    auto targetPosition = WingController::getInstance().getTargetPosition();
+    Vector2f targetDirection = targetPosition - Vector2f(nas.n, nas.e);
 
-    // Compute the angle of the target direciton
+    // Compute the angle of the target direction
     float targetAngle = atan2(targetDirection[1], targetDirection[0]);
 
     // Compute the angle of the current velocity
     float velocityAngle;
 
     // In case of a 0 north velocity i force the angle to 90
-    if (state.vn == 0 && state.ve == 0)
-    {
+    if (nas.vn == 0 && nas.ve == 0)
         velocityAngle = 0;
-    }
-    else if (state.vn == 0)
-    {
-        velocityAngle = (state.ve > 0 ? 1 : -1) * Constants::PI / 2;
-    }
+    else if (nas.vn == 0)
+        velocityAngle = (nas.ve > 0 ? 1 : -1) * Constants::PI / 2;
     else
-    {
-        velocityAngle = atan2(state.ve, state.vn);
-    }
+        velocityAngle = atan2(nas.ve, nas.vn);
 
     // Compute the angle difference
     float error = targetAngle - velocityAngle;
@@ -91,50 +75,42 @@ void AutomaticWingAlgorithm::step()
     // Angle difference
     if (error < -Constants::PI || Constants::PI < error)
     {
-        int moduledError = (int)fmod(error, 2 * Constants::PI);
-        if (moduledError == 0 && error > 0)
-        {
+        int errorModule = (int)fmod(error, 2 * Constants::PI);
+        if (errorModule == 0 && error > 0)
             error = 2 * Constants::PI;
-        }
     }
 
-    // Call the PI with the just calculated error. The result is in RADIANS, if
-    // positive we activate one servo, if negative the other
-    result = controller->update(error);
-
-    // Convert the result from radians back to degrees
-    result = (result / (2 * Constants::PI)) * 360;
+    // Call the PI with the just calculated error. The result is in servo
+    // percentage position [0-1]
+    float result = controller->update(error);
 
     // Actuate the result
     if (result < 0)
     {
         // Activate the servo1 and reset servo2
-        if (servo1 != NULL)
-            servo1->set(-1 * result);
-        if (servo2 != NULL)
-            servo2->set(WING_SERVO2_RESET_POSITION);
+        Actuators::getInstance().setServo(PARAFOIL_SERVO1, -result);
+        Actuators::getInstance().setServo(PARAFOIL_SERVO2, 0);
     }
     else
     {
         // Activate the servo2 and reset servo1
-        if (servo1 != NULL)
-            servo1->set(WING_SERVO1_RESET_POSITION);
-        if (servo2 != NULL)
-            servo2->set(WING_SERVO2_MAX_POSITION - result);
+        Actuators::getInstance().setServo(PARAFOIL_SERVO1, 0);
+        Actuators::getInstance().setServo(PARAFOIL_SERVO2, result);
     }
 
-    // Log the servo positions
     WingAlgorithmData data;
-    data.timestamp     = TimestampTimer::getTimestamp();
-    data.servo1Angle   = servo1 == NULL ? 0 : servo1->getCurrentPosition();
-    data.servo2Angle   = servo2 == NULL ? 0 : servo2->getCurrentPosition();
+    data.timestamp = TimestampTimer::getTimestamp();
+    data.servo1Angle =
+        Actuators::getInstance().getServoPosition(PARAFOIL_SERVO1);
+    data.servo2Angle =
+        Actuators::getInstance().getServoPosition(PARAFOIL_SERVO2);
     data.targetX       = targetDirection[0];
     data.targetY       = targetDirection[1];
     data.targetAngle   = targetAngle;
     data.velocityAngle = velocityAngle;
     data.error         = error;
     data.pidOutput     = result;
-    SDlogger->log(data);
+    Logger::getInstance().log(data);
 }
 
-}  // namespace Parafoil
\ No newline at end of file
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Wing/AutomaticWingAlgorithm.h b/src/boards/Parafoil/Wing/AutomaticWingAlgorithm.h
index a3ad01e46..0392c39af 100644
--- a/src/boards/Parafoil/Wing/AutomaticWingAlgorithm.h
+++ b/src/boards/Parafoil/Wing/AutomaticWingAlgorithm.h
@@ -19,29 +19,21 @@
  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
  * THE SOFTWARE.
  */
+
 #pragma once
 
-#include <Parafoil/Wing/WingAlgorithm.h>
 #include <algorithms/PIController.h>
 
 #include <Eigen/Core>
 
+#include "WingAlgorithm.h"
+
 namespace Parafoil
 {
+
 class AutomaticWingAlgorithm : public WingAlgorithm
 {
 public:
-    /**
-     * @brief Construct a new Automatic Wing Algorithm object
-     *
-     * @param Kp Proportional value for PI controller
-     * @param Ki Integral value for PI controller
-     * @param servo1 The first servo
-     * @param servo2 The second servo
-     */
-    AutomaticWingAlgorithm(float Kp, float Ki, ServoInterface* servo1,
-                           ServoInterface* servo2);
-
     /**
      * @brief Construct a new Automatic Wing Algorithm object
      *
@@ -66,4 +58,5 @@ protected:
      */
     void step() override;
 };
-}  // namespace Parafoil
\ No newline at end of file
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Wing/WingAlgorithm.cpp b/src/boards/Parafoil/Wing/WingAlgorithm.cpp
index 918219564..0ceab211f 100644
--- a/src/boards/Parafoil/Wing/WingAlgorithm.cpp
+++ b/src/boards/Parafoil/Wing/WingAlgorithm.cpp
@@ -20,6 +20,7 @@
  * THE SOFTWARE.
  */
 
+#include <Parafoil/Actuators/Actuators.h>
 #include <Parafoil/Wing/WingAlgorithm.h>
 #include <drivers/timer/TimestampTimer.h>
 
@@ -27,6 +28,7 @@ using namespace Boardcore;
 
 namespace Parafoil
 {
+
 std::istream& operator>>(std::istream& input, WingAlgorithmData& data)
 {
     input >> data.timestamp;
@@ -37,13 +39,6 @@ std::istream& operator>>(std::istream& input, WingAlgorithmData& data)
     return input;
 }
 
-WingAlgorithm::WingAlgorithm(ServoInterface* servo1, ServoInterface* servo2,
-                             const char* filename)
-    : parser(filename)
-{
-    setServo(servo1, servo2);
-}
-
 WingAlgorithm::WingAlgorithm(const char* filename) : parser(filename) {}
 
 bool WingAlgorithm::init()
@@ -64,19 +59,6 @@ bool WingAlgorithm::init()
     return fileValid;
 }
 
-void WingAlgorithm::setServo(ServoInterface* servo1, ServoInterface* servo2)
-{
-    if (servo1 != NULL)
-    {
-        this->servo1 = servo1;
-    }
-
-    if (servo2 != NULL)
-    {
-        this->servo2 = servo2;
-    }
-}
-
 void WingAlgorithm::addStep(WingAlgorithmData step)
 {
     // I do it if and only if the file is invalid, because
@@ -103,9 +85,6 @@ void WingAlgorithm::end()
     timeStart = 0;
 }
 
-/**
- * PROTECTED METHODS
- */
 void WingAlgorithm::step()
 {
     // Variable to remember what is the step that has to be done
@@ -114,48 +93,37 @@ void WingAlgorithm::step()
 
     if (shouldReset)
     {
-        // If the algorithm has been stopped
-        // i want to start from the beginning
+        // If the algorithm has been stopped i want to start from the beginning
         stepIndex   = 0;
         shouldReset = false;
     }
 
     if (stepIndex >= steps.size())
     {
-        LOG_INFO(logger, "Algorithm end");
         // End the procedure so it won't be executed
         end();
+
         // Set the index to 0 in case of another future execution
         stepIndex = 0;
-        // Terminate here
+
         return;
     }
 
     if (currentTimestamp - timeStart >= steps[stepIndex].timestamp)
     {
-        // I need to execute the current step (if not null servos)
-        if (servo1 != NULL)
-        {
-            servo1->set(steps[stepIndex].servo1Angle);
-        }
-        if (servo2 != NULL)
-        {
-            servo2->set(steps[stepIndex].servo2Angle);
-        }
-
-        // Log the data setting the timestamp to the absolute one
+        Actuators::getInstance().setServo(PARAFOIL_SERVO1,
+                                          steps[stepIndex].servo1Angle);
+        Actuators::getInstance().setServo(PARAFOIL_SERVO2,
+                                          steps[stepIndex].servo2Angle);
+
         WingAlgorithmData data;
         data.timestamp   = TimestampTimer::getTimestamp();
         data.servo1Angle = steps[stepIndex].servo1Angle;
         data.servo2Angle = steps[stepIndex].servo2Angle;
+        Logger::getInstance().log(data);
 
-        // After copy i can log the actual step
-        SDlogger->log(data);
-
-        // finally increment the stepIndex
         stepIndex++;
-
-        LOG_INFO(logger, "Step");
     }
 }
+
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/Wing/WingAlgorithm.h b/src/boards/Parafoil/Wing/WingAlgorithm.h
index 3e8ac90f8..4bcd97224 100644
--- a/src/boards/Parafoil/Wing/WingAlgorithm.h
+++ b/src/boards/Parafoil/Wing/WingAlgorithm.h
@@ -23,8 +23,7 @@
 #pragma once
 
 #include <Parafoil/Wing/WingAlgorithmData.h>
-#include <Parafoil/Wing/WingServo.h>
-#include <common/Algorithm.h>
+#include <algorithms/Algorithm.h>
 #include <diagnostic/PrintLogger.h>
 #include <miosix.h>
 #include <utils/CSVReader/CSVReader.h>
@@ -63,19 +62,9 @@
 namespace Parafoil
 {
 
-class WingAlgorithm : public Algorithm
+class WingAlgorithm : public Boardcore::Algorithm
 {
 public:
-    /**
-     * @brief Construct a new Wing Algorithm object
-     *
-     * @param servo1 The first servo
-     * @param servo2 The second servo
-     * @param filename The csv file where all the operations are stored
-     */
-    WingAlgorithm(ServoInterface* servo1, ServoInterface* servo2,
-                  const char* filename);
-
     /**
      * @brief Construct a new Wing Algorithm object
      *
@@ -91,13 +80,6 @@ public:
      */
     bool init() override;
 
-    /**
-     * @brief Set the Servos objects
-     * @param servo1 The first algorithm servo
-     * @param servo2 The second algorithm servo
-     */
-    void setServo(ServoInterface* servo1, ServoInterface* servo2);
-
     /**
      * @brief Adds manually the step in case of fast debug needs
      *
@@ -117,10 +99,6 @@ public:
     void end();
 
 protected:
-    // Actuators
-    ServoInterface* servo1;
-    ServoInterface* servo2;
-
     /**
      * @brief Absolute starting timestamp
      */
@@ -138,28 +116,19 @@ protected:
     Boardcore::CSVParser<WingAlgorithmData> parser;
 
     // PrintLogger
-    Boardcore::PrintLogger logger =
-        Boardcore::Logging::getLogger("WingAlgorithm");
-    /**
-     * @brief SD logger (pre started because of the ParafoilTest.h main class)
-     */
-    Boardcore::Logger* SDlogger = &Boardcore::Logger::getInstance();
+    Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("wingalgo");
 
     /**
-     * @brief Indicates whether the current file of the algorithm is readable
+     * @brief Indicates whether the current file of the algorithm is readable.
      */
     bool fileValid = false;
 
-    // This boolean is used to understand when to reset
-    // the index where the algorithm has stopped.
-    // In case of end call, we want to be able to perform
+    // This boolean is used to understand when to reset the index where the
+    // algorithm has stopped. In case of end call, we want to be able to perform
     // another time this algorithm starting from 0
     bool shouldReset = false;
 
-    /**
-     * @brief This method implements the algorithm step based on the current
-     * timestamp
-     */
     void step() override;
 };
+
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/Wing/WingAlgorithmData.h b/src/boards/Parafoil/Wing/WingAlgorithmData.h
index c95eac5e0..38f29f2c7 100644
--- a/src/boards/Parafoil/Wing/WingAlgorithmData.h
+++ b/src/boards/Parafoil/Wing/WingAlgorithmData.h
@@ -19,11 +19,14 @@
  * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
  * THE SOFTWARE.
  */
+
 #pragma once
+
 #include <sensors/SensorData.h>
 
 namespace Parafoil
 {
+
 /**
  * This class represents the algorithm data structure that needs to be logged
  * into the onboard SD card. It has the timestamp(absolute) and the servo
@@ -31,11 +34,11 @@ namespace Parafoil
  */
 struct WingAlgorithmData
 {
-    uint64_t timestamp;   // First timestamp is 0 (in microseconds)
-    float servo1Angle;    // degrees
-    float servo2Angle;    // degrees
-    float targetAngle;    // radians (automatic only)
-    float velocityAngle;  // radians
+    uint64_t timestamp;   // First timestamp is 0 [us]
+    float servo1Angle;    // [deg]
+    float servo2Angle;    // [deg]
+    float targetAngle;    // [rad] (automatic only)
+    float velocityAngle;  // [rad]
     float targetX;        // NED (only automatic algorithm)
     float targetY;        // NED (only automatic algorithm)
     float error;
@@ -54,4 +57,5 @@ struct WingAlgorithmData
            << targetY << "," << error << "," << pidOutput << "\n";
     }
 };
-}  // namespace Parafoil
\ No newline at end of file
+
+}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Wing/WingController.cpp b/src/boards/Parafoil/Wing/WingController.cpp
index 78fcb38f1..709c2a681 100644
--- a/src/boards/Parafoil/Wing/WingController.cpp
+++ b/src/boards/Parafoil/Wing/WingController.cpp
@@ -20,19 +20,20 @@
  * THE SOFTWARE.
  */
 
+#include "WingController.h"
+
+#include <Parafoil/Actuators/Actuators.h>
+#include <Parafoil/BoardScheduler.h>
 #include <Parafoil/Configs/WingConfig.h>
-#include <Parafoil/Wing/WingController.h>
 
 using namespace Boardcore;
+using namespace Parafoil::WingConfig;
 
 namespace Parafoil
 {
 
-WingController::WingController(TaskScheduler* scheduler)
+WingController::WingController()
 {
-    // Assign the task scheduler
-    this->scheduler = scheduler;
-
     // Set the current running state
     this->running = false;
 
@@ -44,53 +45,42 @@ WingController::WingController(TaskScheduler* scheduler)
     init();
 }
 
-WingController::~WingController()
-{
-    // Delete the servos
-    delete servo1;
-    delete servo2;
-}
+WingController::~WingController() {}
 
 void WingController::addAlgorithm(const char* filename)
 {
     // Create the algorithm
-    WingAlgorithm* algorithm = new WingAlgorithm(servo1, servo2, filename);
+    WingAlgorithm* algorithm = new WingAlgorithm(filename);
 
     // Add the algorithm to the vector and init it
     algorithms.push_back(algorithm);
-    // If init fails[Beacuse of inexistent file or stuff] doesn't matter
+
+    // If init fails[Because of inexistent file or stuff] doesn't matter
     // Because the algorithm is empty and so it won't do anything
     algorithms[algorithms.size() - 1]->init();
 }
 
 void WingController::addAlgorithm(WingAlgorithm* algorithm)
 {
-    // Ensure that the servos are correct
-    algorithm->setServo(servo1, servo2);
-
     // Add the algorithm to the vector
     algorithms.push_back(algorithm);
 }
 
 void WingController::selectAlgorithm(unsigned int index)
 {
-    if (index >= 0 && index < algorithms.size())
-    {
-        LOG_INFO(logger, "Algorithm {:1} selected", index);
+    if (index < algorithms.size())
         selectedAlgorithm = index;
-    }
     else
-    {
-        // I select the 0 algorithm
         selectedAlgorithm = 0;
-    }
+
+    LOG_INFO(logger, "Algorithm {:1} selected", index);
 }
 
 void WingController::start()
 {
-    // If the selected algorithm is valid --> also the
-    // algorithms array is not empty i start the whole thing
-    if (selectedAlgorithm >= 0 && selectedAlgorithm < algorithms.size())
+    // If the selected algorithm is valid --> also the algorithms array is not
+    // empty i start the whole thing
+    if (selectedAlgorithm < algorithms.size())
     {
         // Set the boolean that enables the update method to true
         running = true;
@@ -98,9 +88,6 @@ void WingController::start()
         // Begin the selected algorithm
         algorithms[selectedAlgorithm]->begin();
 
-        // In case i start also the task scheduler
-        scheduler->start();
-
         LOG_INFO(logger, "Wing algorithm started");
     }
 }
@@ -109,90 +96,49 @@ void WingController::stop()
 {
     // Set running to false so that the update method doesn't act
     running = false;
+
     // Stop the algorithm if selected
-    if (selectedAlgorithm >= 0 && selectedAlgorithm < algorithms.size())
-    {
+    if (selectedAlgorithm < algorithms.size())
         algorithms[selectedAlgorithm]->end();
-    }
 }
 
 void WingController::flare()
 {
-    // I stop any on going algorithm
     stop();
 
-    // Set the servo position to flare (pull the two ropes as skydiving people
-    // do)
-    servo1->set(WING_SERVO_MAX_DEGREES - WING_SERVO1_RESET_POSITION);
-    servo2->set(WING_SERVO_MAX_DEGREES - WING_SERVO2_RESET_POSITION);
+    Actuators::getInstance().setServo(PARAFOIL_SERVO1, 0);
+    Actuators::getInstance().setServo(PARAFOIL_SERVO2, 0);
 }
 
 void WingController::reset()
 {
-    // I stop any on going algorithm
     stop();
 
-    // Set the servo position to reset
-    servo1->set(WING_SERVO1_RESET_POSITION);
-    servo2->set(WING_SERVO2_RESET_POSITION);
+    Actuators::getInstance().setServo(PARAFOIL_SERVO1, 0);
+    Actuators::getInstance().setServo(PARAFOIL_SERVO2, 0);
 }
 
 void WingController::update()
 {
-    // Check if the algorithm is running
     if (!running)
-    {
         return;
-    }
 
     // If the selected algorithm is valid i can update it
-    if (selectedAlgorithm >= 0 && selectedAlgorithm < algorithms.size())
-    {
+    if (selectedAlgorithm < algorithms.size())
         algorithms[selectedAlgorithm]->update();
-    }
 }
 
 void WingController::init()
 {
-    // Instantiate the servos
-    servo1 = new WingServo(WING_SERVO1_TIMER, WING_SERVO1_PWM_CHANNEL,
-                           WING_SERVO1_MIN_POSITION, WING_SERVO1_MAX_POSITION,
-                           WING_SERVO1_RESET_POSITION);
-
-    servo2 = new WingServo(WING_SERVO2_TIMER, WING_SERVO2_PWM_CHANNEL,
-                           WING_SERVO2_MIN_POSITION, WING_SERVO2_MAX_POSITION,
-                           WING_SERVO2_RESET_POSITION);
-
-    // Enable servos
-    servo1->enable();
-    servo2->enable();
-
-    // Register the task
-    TaskScheduler::function_t updateFunction([=]() { update(); });
-
-    scheduler->addTask(updateFunction, WING_UPDATE_PERIOD, WING_CONTROLLER_ID);
+    BoardScheduler::getInstance().getScheduler().addTask(
+        [=]() { update(); }, WING_UPDATE_PERIOD, WING_CONTROLLER_ID);
 }
 
 void WingController::setTargetPosition(Eigen::Vector2f target)
 {
-    this->targetPosition = target;
+    targetPosition = target;
 }
 
 Eigen::Vector2f WingController::getTargetPosition() { return targetPosition; }
 
-float WingController::getServoPosition(ServosList servoId)
-{
-    switch (servoId)
-    {
-        case PARAFOIL_SERVO1:
-            return servo1->getCurrentPosition();
-        case PARAFOIL_SERVO2:
-            return servo2->getCurrentPosition();
-        default:
-            return 0;
-    }
-
-    return 0;
-}
-
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/Wing/WingController.h b/src/boards/Parafoil/Wing/WingController.h
index 41953c84b..eae475720 100644
--- a/src/boards/Parafoil/Wing/WingController.h
+++ b/src/boards/Parafoil/Wing/WingController.h
@@ -22,19 +22,18 @@
 
 #pragma once
 
-#include <Parafoil/TelemetriesTelecommands/Mavlink.h>
 #include <Parafoil/Wing/AutomaticWingAlgorithm.h>
 #include <Parafoil/Wing/WingAlgorithm.h>
+#include <common/Mavlink.h>
 #include <scheduler/TaskScheduler.h>
 
 #include <Eigen/Core>
 
 /**
- * @brief This class allows the user to select the wing algorithm
- * that has to be used during the tests. It also registers his
- * dedicated function in the task schduler in order to be
- * executed every fixed period and to update the two servos position
- * depending on the selected algorithm.
+ * @brief This class allows the user to select the wing algorithm  that has to
+ * be used during the tests. It also registers his dedicated function in the
+ * task scheduler in order to be executed every fixed period and to update the
+ * two servos position depending on the selected algorithm.
  *
  * Use case example:
  * controller = new WingController(scheduler);
@@ -52,15 +51,12 @@
 
 namespace Parafoil
 {
-class WingController
+
+class WingController : public Boardcore::Singleton<WingController>
 {
-private:
-    /**
-     * @brief Servo actuators
-     */
-    ServoInterface* servo1;
-    ServoInterface* servo2;
+    friend Boardcore::Singleton<WingController>;
 
+private:
     /**
      * @brief Target position
      */
@@ -74,17 +70,11 @@ private:
     /**
      * @brief PrintLogger
      */
-    Boardcore::PrintLogger logger =
-        Boardcore::Logging::getLogger("ParafoilTest");
-
-    /**
-     * @brief The common task scheduler
-     */
-    Boardcore::TaskScheduler* scheduler;
+    Boardcore::PrintLogger logger = Boardcore::Logging::getLogger("wingctrl");
 
     /**
      * @brief This attribute is modified by the mavlink radio section.
-     * The user using the Ground Station can select the pre-enumered algorithm
+     * The user using the Ground Station can select the pre-enumerated algorithm
      * to execute
      */
     unsigned int selectedAlgorithm;
@@ -101,12 +91,7 @@ private:
     void init();
 
 public:
-    /**
-     * @brief Construct a new Wing Controller object
-     *
-     * @param scheduler The main used task scheduler
-     */
-    WingController(Boardcore::TaskScheduler* scheduler);
+    WingController();
 
     /**
      * @brief Destroy the Wing Controller object.
@@ -176,4 +161,5 @@ public:
 
     float getServoPosition(ServosList servoId);
 };
+
 }  // namespace Parafoil
diff --git a/src/boards/Parafoil/Wing/WingServo.cpp b/src/boards/Parafoil/Wing/WingServo.cpp
deleted file mode 100644
index e628c5457..000000000
--- a/src/boards/Parafoil/Wing/WingServo.cpp
+++ /dev/null
@@ -1,71 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include <Parafoil/Wing/WingServo.h>
-
-using namespace Boardcore;
-
-namespace Parafoil
-{
-
-WingServo::WingServo(TIM_TypeDef* timer, TimerUtils::Channel pwmChannel,
-                     float minPosition, float maxPosition)
-    : WingServo(timer, pwmChannel, minPosition, maxPosition, minPosition)
-{
-}
-
-WingServo::WingServo(TIM_TypeDef* timer, TimerUtils::Channel pwmChannel,
-                     float minPosition, float maxPosition, float resetPosition)
-    : ServoInterface(minPosition, maxPosition, resetPosition)
-{
-    servo = new Servo(timer, pwmChannel, WING_SERVO_MIN_PULSE,
-                      WING_SERVO_MAX_PULSE, WING_SERVO_FREQUENCY);
-}
-
-WingServo::~WingServo() {}
-
-void WingServo::enable()
-{
-    servo->enable();
-    // Set the servo position to reset
-    setPosition(RESET_POS);
-}
-
-void WingServo::disable() { servo->disable(); }
-
-void WingServo::selfTest()
-{
-    setPosition(MIN_POS);
-    miosix::Thread::sleep(1000);
-    setPosition(RESET_POS);
-    miosix::Thread::sleep(1000);
-    setPosition(MAX_POS);
-}
-
-void WingServo::setPosition(float angle)
-{
-    servo->setPosition(angle / WING_SERVO_MAX_DEGREES);
-    this->currentPosition = angle;
-}
-
-float WingServo::preprocessPosition(float angle) { return angle; }
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/Wing/WingServo.h b/src/boards/Parafoil/Wing/WingServo.h
deleted file mode 100644
index 6dcfab74e..000000000
--- a/src/boards/Parafoil/Wing/WingServo.h
+++ /dev/null
@@ -1,92 +0,0 @@
-/* Copyright (c) 2022 Skyward Experimental Rocketry
- * Author: Matteo Pignataro
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <Parafoil/Configs/WingConfig.h>
-#include <actuators/Servo/Servo.h>
-#include <common/ServoInterface.h>
-
-namespace Parafoil
-{
-
-class WingServo : public ServoInterface
-{
-public:
-    /**
-     * @brief Construct a new Wing Servo object
-     * It will use the min position as reset
-     *
-     * @param timer The servo timer that needs to be used
-     * @param pwmChannel The servo pwm port used
-     * @param minPosition The min allowed servo position(degrees)
-     * @param maxPosition The max allowed servo position(degrees)
-     */
-    WingServo(TIM_TypeDef* timer, Boardcore::TimerUtils::Channel pwmChannel,
-              float minPosition, float maxPosition);
-
-    /**
-     * @brief Construct a new Wing Servo object
-     *
-     * @param timer The servo timer that needs to be used
-     * @param pwmChannel The servo pwm port used
-     * @param minPosition The min allowed servo position(degrees)
-     * @param maxPosition The max allowed servo position(degrees)
-     * @param resetPosition The position where the servo is when it
-     * resets(degrees)
-     */
-    WingServo(TIM_TypeDef* timer, Boardcore::TimerUtils::Channel pwmChannel,
-              float minPosition, float maxPosition, float resetPosition);
-
-    /**
-     * @brief Destroy the Wing Servo object
-     */
-    ~WingServo();
-
-    void enable() override;
-
-    void disable() override;
-
-    /**
-     * @brief Execute a self test with the servo
-     */
-    void selfTest() override;
-
-private:
-    Boardcore::Servo* servo;
-
-protected:
-    /**
-     * @brief Set the servo position
-     * @param angle Servo position(degrees)
-     */
-    void setPosition(float angle) override;
-
-    /**
-     * @brief Method to convert the angle passed by the user to an
-     * useful angle for the servo interface
-     * @param angle The angle(degrees)
-     * @return float The converted angle
-     */
-    float preprocessPosition(float angle) override;
-};
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/mocksensors/MockGPS.h b/src/boards/Parafoil/mocksensors/MockGPS.h
deleted file mode 100644
index cc49cd9d7..000000000
--- a/src/boards/Parafoil/mocksensors/MockGPS.h
+++ /dev/null
@@ -1,101 +0,0 @@
-/* Copyright (c) 2019 Skyward Experimental Rocketry
- * Author: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <TimestampTimer.h>
-#include <mocksensors/MockSensorsData.h>
-#include <mocksensors/lynx_flight_data/lynx_gps_data.h>
-#include <sensors/Sensor.h>
-
-namespace DeathStackBoard
-{
-
-class MockGPS : public Sensor<MockGPSData>
-{
-public:
-    MockGPS() {}
-
-    bool init() override { return true; }
-
-    bool selfTest() override { return true; }
-
-    MockGPSData sampleImpl() override
-    {
-        // if (inside_lha)
-        // {
-        //     lat = lat_inside;
-        //     lon = lon_inside;
-        // }
-        // else
-        // {
-        //     lat = lat_outside;
-        //     lon = lon_outside;
-        // }
-
-        MockGPSData data;
-
-        data.gps_timestamp = TimestampTimer::getTimestamp();
-        data.fix           = true;
-
-        if (before_liftoff)
-        {
-            data.latitude       = GPS_DATA_LAT[0];
-            data.longitude      = GPS_DATA_LON[0];
-            data.velocity_north = GPS_DATA_VNORD[0];
-            data.velocity_east  = GPS_DATA_VEAST[0];
-            data.velocity_down  = GPS_DATA_VDOWN[0];
-            data.num_satellites = GPS_DATA_NSATS[0];
-            data.fix            = true;
-        }
-        else if (i < GPS_DATA_SIZE)
-        {
-            data.latitude       = GPS_DATA_LAT[i];
-            data.longitude      = GPS_DATA_LON[i];
-            data.velocity_north = GPS_DATA_VNORD[i];
-            data.velocity_east  = GPS_DATA_VEAST[i];
-            data.velocity_down  = GPS_DATA_VDOWN[i];
-            data.num_satellites = GPS_DATA_NSATS[i];
-            data.fix            = true;
-            i++;
-        }
-
-        return data;
-    }
-
-    void signalLiftoff() { before_liftoff = false; }
-
-private:
-    // Set of coordinates inside the Launch Hazard Area
-    // const double lat_inside = 41.807487124105;
-    // const double lon_inside = 14.0551665469291;
-
-    // Set of coordinates outside the Launch Hazard Area
-    // const double lat_outside = 41.840794;
-    // const double lon_outside = 14.003920;
-
-    volatile bool before_liftoff = true;
-    bool inside_lha              = true;
-
-    unsigned int i = 0;
-};
-}  // namespace DeathStackBoard
diff --git a/src/boards/Parafoil/mocksensors/MockIMU.h b/src/boards/Parafoil/mocksensors/MockIMU.h
deleted file mode 100644
index 8405b14d7..000000000
--- a/src/boards/Parafoil/mocksensors/MockIMU.h
+++ /dev/null
@@ -1,80 +0,0 @@
-/* Copyright (c) 2020 Skyward Experimental Rocketry
- * Authors: Luca Conterio, Marco Cella
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <TimestampTimer.h>
-#include <mocksensors/MockSensorsData.h>
-#include <mocksensors/lynx_flight_data/lynx_imu_data.h>
-#include <sensors/Sensor.h>
-
-namespace DeathStackBoard
-{
-
-class MockIMU : public Sensor<MockIMUData>
-{
-public:
-    MockIMU() {}
-
-    bool init() override { return true; }
-
-    bool selfTest() override { return true; }
-
-    MockIMUData sampleImpl() override
-    {
-        if (before_liftoff)
-        {
-            index = 0;
-        }
-
-        MockIMUData data;
-        uint64_t t = TimestampTimer::getTimestamp();
-
-        data.accel_timestamp = t;
-        data.accel_x         = ACCEL_DATA[index][0];
-        data.accel_y         = ACCEL_DATA[index][1];
-        data.accel_z         = ACCEL_DATA[index][2];
-
-        data.gyro_timestamp = t;
-        data.gyro_x         = GYRO_DATA[index][0];
-        data.gyro_y         = GYRO_DATA[index][1];
-        data.gyro_z         = GYRO_DATA[index][2];
-
-        data.mag_timestamp = t;
-        data.mag_x         = MAG_DATA[index][0];
-        data.mag_y         = MAG_DATA[index][1];
-        data.mag_z         = MAG_DATA[index][2];
-
-        // when finished, go back to the beginning
-        index = (index + 1) % IMU_DATA_SIZE;
-
-        return data;
-    }
-
-    void signalLiftoff() { before_liftoff = false; }
-
-private:
-    unsigned int index           = 0;
-    volatile bool before_liftoff = true;
-};
-
-}  // namespace DeathStackBoard
diff --git a/src/boards/Parafoil/mocksensors/MockPressureSensor.h b/src/boards/Parafoil/mocksensors/MockPressureSensor.h
deleted file mode 100644
index 53fbbc12b..000000000
--- a/src/boards/Parafoil/mocksensors/MockPressureSensor.h
+++ /dev/null
@@ -1,109 +0,0 @@
-/* Copyright (c) 2019 Skyward Experimental Rocketry
- * Author: Luca Mozzarelli
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-//#include <mocksensors/lynx_flight_data/lynx_press_data.h>
-#include <Parafoil/mocksensors/lynx_flight_data/lynx_pressure_static_data.h>
-#include <drivers/timer/TimestampTimer.h>
-#include <sensors/Sensor.h>
-
-#include <random>
-
-#include "MockSensorsData.h"
-
-namespace Parafoil
-{
-
-class MockPressureSensor : public Boardcore::Sensor<MockPressureData>
-{
-public:
-    MockPressureSensor(bool with_noise_ = false) : with_noise(with_noise_) {}
-
-    bool init() override { return true; }
-
-    bool selfTest() override { return true; }
-
-    MockPressureData sampleImpl() override
-    {
-        MockPressureData data;
-
-        data.pressureTimestamp = Boardcore::TimestampTimer::getTimestamp();
-
-        if (before_liftoff)
-        {
-            data.pressure = PRESSURE_STATIC_DATA[0];
-        }
-        else
-        {
-            if (i < PRESSURE_STATIC_DATA_SIZE)
-            {
-                data.pressure = PRESSURE_STATIC_DATA[i++];
-            }
-            else
-            {
-                data.pressure =
-                    PRESSURE_STATIC_DATA[PRESSURE_STATIC_DATA_SIZE - 1];
-                // Reset
-                i = 0;
-            }
-        }
-
-        if (with_noise)
-        {
-            data.pressure = addNoise(data.pressure);
-        }
-
-        data.pressure = movingAverage(data.pressure);
-
-        return data;
-    }
-
-    void signalLiftoff() { before_liftoff = false; }
-
-private:
-    bool with_noise;
-    volatile bool before_liftoff = true;
-    volatile unsigned int i      = 0;  // Last index
-    std::default_random_engine generator{1234567};
-    std::normal_distribution<float> distribution{0.0f, 5.0f};
-
-    // moving average
-    const float moving_avg_coeff = 0.95;
-    float accumulator            = 0.0;
-
-    float addNoise(float sample)
-    {
-        return quantization(sample + distribution(generator));
-    }
-
-    float quantization(float sample) { return round(sample / 30.0) * 30.0; }
-
-    float movingAverage(float new_value)
-    {
-        accumulator = (moving_avg_coeff * new_value) +
-                      (1.0 - moving_avg_coeff) * accumulator;
-        return accumulator;
-    }
-};
-
-}  // namespace Parafoil
diff --git a/src/boards/Parafoil/mocksensors/MockSensors.h b/src/boards/Parafoil/mocksensors/MockSensors.h
deleted file mode 100644
index 3b0b5ca5c..000000000
--- a/src/boards/Parafoil/mocksensors/MockSensors.h
+++ /dev/null
@@ -1,29 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include "MockGPS.h"
-#include "MockIMU.h"
-#include "MockPressureSensor.h"
-#include "MockSpeedSensor.h"
-#include "utils/testutils/TestSensor.h"
\ No newline at end of file
diff --git a/src/boards/Parafoil/mocksensors/MockSensorsData.h b/src/boards/Parafoil/mocksensors/MockSensorsData.h
deleted file mode 100644
index de12014dc..000000000
--- a/src/boards/Parafoil/mocksensors/MockSensorsData.h
+++ /dev/null
@@ -1,90 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <sensors/SensorData.h>
-
-struct MockIMUData : public Boardcore::AccelerometerData,
-                     public Boardcore::GyroscopeData,
-                     public Boardcore::MagnetometerData
-{
-    static std::string header()
-    {
-        return "accel_timestamp,accel_x,accel_y,accel_z,gyro_timestamp,gyro_x,"
-               "gyro_y,"
-               "gyro_z,mag_timestamp,mag_x,mag_y,mag_z\n";
-    }
-
-    void print(std::ostream& os) const
-    {
-        os << accelerationTimestamp << "," << accelerationX << ","
-           << accelerationY << "," << accelerationZ << ","
-           << angularVelocityTimestamp << "," << angularVelocityX << ","
-           << angularVelocityY << "," << angularVelocityZ << ","
-           << magneticFieldTimestamp << "," << magneticFieldX << ","
-           << magneticFieldY << "," << magneticFieldZ << "\n";
-    }
-};
-
-struct MockPressureData : public Boardcore::PressureData
-{
-    static std::string header()
-    {
-        return "press_timestamp,press,temp_timestamp,temp\n";
-    }
-
-    void print(std::ostream& os) const
-    {
-        os << pressureTimestamp << "," << pressure << "\n";
-    }
-};
-
-struct MockGPSData : public Boardcore::GPSData
-{
-    static std::string header()
-    {
-        return "gps_timestamp,latitude,longitude,height,velocity_north,"
-               "velocity_east,velocity_down,speed,track,num_satellites,fix\n";
-    }
-
-    void print(std::ostream& os) const
-    {
-        os << gpsTimestamp << "," << latitude << "," << longitude << ","
-           << height << "," << velocityNorth << "," << velocityEast << ","
-           << velocityDown << "," << speed << "," << track << ","
-           << (int)satellites << "," << (int)fix << "\n";
-    }
-};
-
-struct MockSpeedData
-{
-    uint64_t timestamp;
-    float speed;
-
-    static std::string header() { return "timestamp,speed\n"; }
-
-    void print(std::ostream& os) const
-    {
-        os << timestamp << "," << speed << "\n";
-    }
-};
diff --git a/src/boards/Parafoil/mocksensors/MockSpeedSensor.h b/src/boards/Parafoil/mocksensors/MockSpeedSensor.h
deleted file mode 100644
index 1b1642c27..000000000
--- a/src/boards/Parafoil/mocksensors/MockSpeedSensor.h
+++ /dev/null
@@ -1,76 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <Common.h>
-#include <mocksensors/MockSensorsData.h>
-#include <mocksensors/lynx_flight_data/lynx_airspeed_data.h>
-#include <sensors/Sensor.h>
-
-#include <random>
-
-namespace DeathStackBoard
-{
-
-class MockSpeedSensor : public Sensor<MockSpeedData>
-{
-public:
-    MockSpeedSensor() {}
-
-    bool init() override { return true; }
-
-    bool selfTest() override { return true; }
-
-    MockSpeedData sampleImpl() override
-    {
-        MockSpeedData data;
-
-        data.timestamp = TimestampTimer::getTimestamp();
-
-        if (before_liftoff)
-        {
-            data.speed = AIRSPEED_DATA[0];
-        }
-        else
-        {
-            if (i < AIRSPEED_DATA_SIZE)
-            {
-                data.speed = AIRSPEED_DATA[i++];
-            }
-            else
-            {
-                data.speed = AIRSPEED_DATA[AIRSPEED_DATA_SIZE - 1];
-            }
-        }
-
-        return data;
-    }
-
-    void signalLiftoff() { before_liftoff = false; }
-
-private:
-    volatile bool before_liftoff = true;
-    volatile unsigned int i      = 0;  // Last index
-};
-
-}  // namespace DeathStackBoard
diff --git a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_airspeed_data.cpp b/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_airspeed_data.cpp
deleted file mode 100644
index bd3dbd2cf..000000000
--- a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_airspeed_data.cpp
+++ /dev/null
@@ -1,923 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include "lynx_airspeed_data.h"
-
-const float AIRSPEED_DATA[AIRSPEED_DATA_SIZE] = {
-    12.4113951, 10.6396132, 17.169529,  22.8292465, 10.5444088, 8.39081669,
-    10.641614,  11.4718409, 20.4783287, 15.3504314, 15.3513031, 9.63413239,
-    25.3731174, 18.9253101, 16.0033855, 24.1376781, 28.4115391, 27.6845875,
-    29.4730015, 33.6768837, 34.5762138, 35.450737,  36.8664055, 36.8693237,
-    38.7607841, 41.314991,  41.3147278, 42.0521317, 45.778492,  46.6648064,
-    47.7517242, 49.6425095, 52.0558586, 52.4533348, 53.8047791, 55.6794052,
-    58.0183525, 60.6116638, 60.7854004, 63.1039772, 65.9648132, 66.4317398,
-    68.2648849, 70.625473,  71.7813721, 73.9020615, 75.5481796, 77.4300003,
-    78.3614883, 80.6872864, 82.9510956, 82.7034836, 86.2424927, 86.9628677,
-    88.2577972, 90.9050903, 92.1436462, 94.1384506, 95.7668915, 97.7961044,
-    99.5847855, 102.038879, 103.549995, 105.355217, 107.584,    109.401268,
-    112.003922, 112.947815, 114.310066, 116.204742, 117.900772, 119.379234,
-    121.453636, 123.484711, 124.659866, 126.166412, 127.724335, 129.257675,
-    130.638611, 132.462296, 133.884125, 135.494843, 137.123718, 138.941895,
-    140.886703, 143.3172,   143.985199, 146.436874, 147.651245, 149.980957,
-    151.795288, 152.972382, 155.550827, 157.63028,  158.979904, 159.744888,
-    162.516342, 163.158035, 164.464325, 165.421356, 167.523666, 169.456955,
-    170.805832, 172.415237, 173.797318, 175.7146,   177.344955, 179.430923,
-    181.203964, 182.604797, 184.202942, 183.232407, 183.828201, 185.775909,
-    187.161652, 188.274979, 190.970871, 193.048584, 193.552383, 193.903107,
-    195.170502, 196.671463, 197.220306, 197.083771, 197.749985, 198.354935,
-    199.889923, 200.472031, 201.510834, 201.720306, 201.343964, 201.127594,
-    201.470779, 200.658096, 200.537796, 200.431641, 199.389252, 199.213486,
-    198.424728, 197.32753,  196.845001, 195.506439, 194.997894, 194.371918,
-    193.090515, 193.750916, 192.536942, 192.263809, 191.898621, 191.349625,
-    191.828659, 191.363953, 190.446213, 189.351685, 185.858109, 180.658096,
-    180.828461, 183.347458, 184.327713, 186.507248, 187.238586, 187.274399,
-    188.080185, 187.780655, 186.073151, 186.473251, 184.401474, 185.514282,
-    184.814407, 182.69313,  182.772842, 182.772842, 181.386536, 180.426163,
-    179.513199, 179.017822, 179.074036, 179.045639, 178.686157, 177.242355,
-    177.189133, 176.377136, 176.152817, 175.485916, 174.898453, 174.489395,
-    173.92334,  173.084961, 172.043137, 171.424362, 171.075867, 170.613815,
-    169.925919, 169.062241, 168.137009, 167.604156, 167.320312, 166.214432,
-    166.065033, 166.495438, 165.243683, 164.243286, 163.642975, 163.649567,
-    162.826721, 163.247635, 162.502182, 160.487228, 160.60936,  160.999207,
-    159.284119, 158.065231, 157.567429, 156.423874, 157.117569, 154.945602,
-    156.644455, 156.413177, 155.87352,  155.647827, 154.769485, 153.900177,
-    153.991287, 152.611343, 152.811279, 151.95636,  151.686584, 151.216324,
-    150.376831, 150.142502, 149.453705, 148.636536, 148.431534, 147.900177,
-    147.052231, 146.009003, 145.9505,   145.679123, 144.611954, 144.45787,
-    143.784164, 143.393646, 143.088669, 142.234741, 141.963608, 141.214371,
-    141.056747, 140.908966, 140.156128, 140.33905,  139.678894, 138.870056,
-    138.330856, 137.469437, 135.973679, 135.708847, 135.49617,  134.939362,
-    134.409241, 133.690781, 133.235306, 133.319,    132.43364,  132.332947,
-    131.808243, 132.145615, 131.843628, 131.656967, 131.189651, 130.84111,
-    130.822113, 129.194061, 129.159836, 128.43576,  127.813522, 127.921944,
-    126.603584, 125.869659, 126.404015, 125.184059, 124.586815, 124.220787,
-    124.580544, 124.249268, 124.175308, 123.479156, 123.30941,  122.77816,
-    122.195129, 121.41465,  121.199074, 120.922768, 120.377502, 120.308357,
-    119.179604, 119.280205, 119.204651, 118.655434, 117.689667, 117.722618,
-    117.010521, 116.232468, 116.834404, 116.555901, 115.722458, 115.18029,
-    115.082939, 114.965645, 115.294937, 114.62886,  113.85054,  113.45314,
-    113.286819, 112.595406, 112.576797, 111.637688, 111.34462,  110.939369,
-    110.725937, 111.067787, 111.307861, 110.192368, 109.503044, 109.619461,
-    109.293739, 108.835175, 108.321236, 107.688713, 108.302734, 107.286201,
-    107.089714, 106.759506, 106.905746, 106.503944, 105.741417, 106.211449,
-    104.930573, 104.959724, 104.948799, 104.656197, 104.231476, 104.327293,
-    104.25589,  103.044258, 103.076309, 103.095726, 103.103935, 103.013115,
-    102.692505, 102.904404, 102.244812, 102.244812, 100.50853,  101.400246,
-    99.6098175, 99.6516418, 99.0769882, 99.6706009, 98.7544479, 98.1889343,
-    98.0998154, 97.5229416, 97.294548,  97.5436935, 96.7283325, 96.6032104,
-    96.0145493, 95.925087,  95.3586502, 96.0646896, 95.3726273, 94.9047775,
-    95.2724152, 94.6777878, 93.9669113, 93.8663254, 93.5023575, 92.8998337,
-    92.1656876, 92.1644287, 92.0681839, 91.6967316, 90.8415756, 90.6017685,
-    90.6057816, 90.6103745, 89.8713226, 90.7580795, 89.7719803, 90.0259781,
-    89.1295776, 89.1429672, 89.0196991, 88.9238129, 88.4012299, 88.1494522,
-    87.8901901, 87.9061508, 87.256691,  86.4787445, 86.7329102, 86.0919266,
-    86.1069946, 85.7037277, 84.5901794, 85.6158752, 84.9309998, 82.9900208,
-    82.935997,  82.1810913, 81.3405228, 81.0612259, 82.0060654, 82.1019135,
-    81.2657013, 80.8491669, 80.4293671, 80.7200241, 80.585083,  80.5918961,
-    79.8911362, 79.6070709, 79.7559662, 78.9017639, 78.7602005, 78.9147797,
-    78.6235962, 78.0473709, 77.4674454, 77.0251999, 77.3284149, 76.8851242,
-    76.1434631, 75.9982681, 76.1545715, 76.0106964, 75.5613708, 74.8006821,
-    74.9684753, 74.8190384, 74.9822693, 75.1356201, 74.8413315, 75.1525192,
-    73.9239197, 74.0867538, 73.1514816, 73.3152008, 72.3738251, 72.0599976,
-    70.9409103, 70.9441223, 70.2937088, 70.140213,  69.9797897, 70.3167725,
-    69.9882202, 68.8350296, 69.0057449, 68.8466949, 69.1870804, 68.5203094,
-    68.0226212, 68.1939926, 68.3654556, 68.2077789, 67.8697815, 68.0446091,
-    67.0231018, 66.8602066, 66.6925735, 65.9965057, 65.8304214, 65.8362885,
-    65.8388062, 65.8448029, 65.6725159, 64.6115875, 64.6147308, 64.4388885,
-    64.0865479, 63.7265358, 63.5475883, 63.1892509, 63.0096741, 63.7465324,
-    62.4627075, 62.8401031, 62.6645813, 62.2936783, 62.1134071, 62.3037453,
-    61.9358864, 61.1863976, 61.5671234, 61.3853912, 60.0524178, 60.0564346,
-    60.0612564, 59.2879105, 59.2919846, 58.899395,  58.7092056, 58.9122047,
-    58.321167,  57.9245033, 57.5246315, 57.729763,  57.5287971, 57.5352554,
-    57.5404243, 57.7434425, 56.5259209, 56.3256836, 56.3274956, 55.5005493,
-    54.8687096, 54.8751602, 55.092392,  55.0932121, 55.0972252, 55.1003227,
-    54.8914223, 54.89645,   54.6863785, 55.1166954, 53.6196175, 53.4029846,
-    51.8619728, 53.6315536, 52.7581978, 52.5371323, 52.3209801, 52.323204,
-    52.3257484, 51.8822556, 50.7485352, 50.0599213, 50.5264931, 49.3616409,
-    49.3656807, 49.3667259, 49.3687859, 49.3724022, 49.3762398, 49.3780861,
-    48.6644897, 47.9443398, 47.9471207, 47.9490433, 47.7080727, 47.9534836,
-    47.9575996, 47.958744,  47.7178268, 46.2292938, 46.2304153, 46.4842529,
-    46.234417,  44.9570503, 46.4934654, 45.47789,   44.9655609, 45.2264938,
-    44.7079926, 44.7103996, 44.7117538, 44.4523392, 43.1193924, 43.1209602,
-    43.1238022, 42.854023,  42.8559265, 42.8587952, 42.85952,   42.8622475,
-    41.475563,  41.7597542, 41.4811821, 40.9140892, 41.2012596, 41.202652,
-    41.2042427, 41.2053795, 41.4914932, 40.349575,  40.6394196, 39.4713898,
-    39.4743118, 39.1792641, 39.4780922, 39.4780922, 39.4808846, 39.1840248,
-    39.185955,  39.4847832, 39.4861526, 38.8903236, 39.4900551, 38.8932724,
-    39.4927559, 37.6717682, 37.0458107, 37.6758652, 37.3641129, 37.6788673,
-    37.0512886, 37.3682556, 37.369503,  37.3701096, 37.3719177, 37.3730927,
-    37.6870918, 37.6876945, 37.3767242, 35.4465446, 35.4460869, 35.4472466,
-    35.449543,  35.4499092, 35.4511642, 35.4511642, 35.4538002, 35.4547119,
-    35.1230011, 33.410881,  33.0581741, 34.4510002, 33.0604782, 31.9786453,
-    31.2377892, 30.8595219, 30.8598766, 31.2406349, 31.2420692, 31.2429924,
-    31.2429924, 30.8647938, 30.8668213, 30.8664036, 31.6195831, 31.2468319,
-    30.869627,  31.2483406, 31.2496529, 30.4884949, 30.8720722, 31.2515697,
-    31.6262512, 31.2538109, 31.6281986, 31.6281986, 29.3145161, 28.5018139,
-    24.5097885, 24.9864769, 24.9864426, 24.987608,  24.5116386, 24.9877625,
-    24.9884148, 25.4550762, 24.9890804, 24.9899445, 25.4569378, 24.5155354,
-    24.031086,  24.5171452, 24.9924126, 24.9930611, 21.4468918, 22.5186787,
-    21.9900837, 20.8932552, 21.99086,   21.991396,  21.9915123, 21.9920998,
-    21.9926891, 21.9928856, 21.9945145, 21.9945145, 20.8961391, 21.9940243,
-    21.4522953, 21.994606,  21.4526997, 21.9957924, 21.9958515, 21.996254,
-    21.9964314, 21.9965725, 21.9964924, 21.9976387, 20.3273621, 21.4550629,
-    19.7407608, 21.4558983, 21.9986305, 21.9989548, 21.9993973, 21.9991398,
-    19.7421799, 21.4567852, 20.3296833, 20.3300762, 22.0001965, 18.5116444,
-    22.0004635, 17.8649158, 18.5126705, 17.8653278, 21.4595833, 18.512888,
-    20.9040699, 19.1385517, 17.8656101, 18.5133038, 21.4594917, 22.5309448,
-    22.5318375, 22.5320187, 22.0026321, 22.0030384, 22.0026226, 22.5323658,
-    22.003109,  21.4602718, 22.0032024, 17.1941872, 18.513855,  17.86726,
-    17.8674145, 17.8668137, 18.5143547, 17.8674564, 17.8672352, 18.5146198,
-    18.5145397, 17.8666153, 18.5147762, 18.5147762, 19.1403484, 18.5144711,
-    18.5147095, 18.5133171, 18.5145321, 18.514267,  18.5146809, 18.514204,
-    19.140276,  17.8670464, 19.1403503, 20.9043922, 19.745657,  19.1379051,
-    12.4201765, 13.3371429, 9.14465141, 14.1921349, 3.60264635, 6.04226494,
-    13.3364954, 17.1931267, 19.139143,  6.04244566, 18.5128231, 17.8655987,
-    18.5122795, 17.8650379, 17.8648739, 18.5121994, 18.5116119, 17.8652287,
-    19.7448235, 6.04315424, 13.3384638, 16.4980888, 9.14543152, 17.1910973,
-    22.0007267, 25.4744186, 22.0027752, 23.0486393, 25.0114841, 22.5339508,
-    18.5152931, 27.6943932, 30.5291271, 22.5358543, 20.9087124, 7.59722328,
-    22.0097103, 12.4254007, 20.3355427, 35.5281181, 12.3314304, 10.3577375,
-    5.84748268, 15.6973457, 11.3356037, 12.4266768, 3.2577486,  7.5973978,
-    3.25779343, 3.25704408, 7.74968767, 14.1891499, 13.2464952, 9.01299667,
-    6.03971958, 6.0393858,  13.3299341, 18.5029831, 17.8552227, 21.9898586,
-    21.9898586, 18.502203,  17.8566074, 18.5038853, 18.5051804, 7.74701643,
-    6.04055595, 7.74729586, 6.04036283, 3.25602245, 7.59292507, 14.1051168,
-    6.04049158, 9.14046478, 12.3218737, 9.1409235,  14.1859617, 6.03975201,
-    5.84166813, 9.01044941, 6.03848886, 10.2303801, 7.74395752, 3.59899211,
-    3.25361276, 3.59889698, 3.59870267, 6.03561115, 10.3407993, 7.74237823,
-    13.3237381, 13.3240919, 17.8494205, 18.4972916, 18.4962921, 19.1214581,
-    17.8483868, 18.49576,   17.8477268, 18.4927731, 18.492672,  18.4916954,
-    17.8443089, 12.406496,  12.4056816, 3.59816217, 6.03494692, 3.59752965,
-    6.03406143, 5.83609486, 10.22295,   11.3140211, 11.3134918, 10.2218494,
-    10.2215061, 10.2211504, 12.3060255, 11.3137445, 10.2221661, 11.3136711,
-    11.3136711, 11.3124952, 15.664196,  14.8965168, 14.0859232, 10.2211866,
-    11.3135366, 10.2217808, 9.00197983, 10.2213392, 6.03308296, 3.59690285,
-    7.7373147,  3.59669352, 7.73725796, 6.03254986, 3.59651208, 12.3028679,
-    10.2183495, 8.99698067, 10.216466,  11.3068304, 11.3062677, 5.8319993,
-    7.73274469, 6.02868652, 3.59436488, 3.59407854, 3.59391236, 6.02781248,
-    6.02781248, 7.73060513, 6.02756834, 7.73031759, 7.72989035, 6.02676058,
-    3.59323215, 6.02651882, 3.59302473, 6.02615547, 7.72881031, 3.24800467,
-    6.02536201, 3.59233379, 6.02535677, 7.72803164, 3.59216714, 8.98922825,
-    3.24734902, 10.2073698, 11.2969427, 11.2966814, 11.2965622, 8.98867702,
-    11.2960491, 10.2066708, 10.2069464, 11.2960768, 11.2956123, 10.2055216,
-    11.2948475, 10.2069149, 11.2959919, 11.2962055, 10.2063618, 11.2964983,
-    12.2879896, 17.0724678, 17.0715714, 16.3699131, 17.0712872, 15.6387024,
-    16.3675041, 10.20292,   10.2030973, 11.2921638, 11.2914381, 11.2906418,
-    10.2012043, 10.2003527, 8.98231316, 10.1990118, 5.82227564, 6.01907253,
-    6.01874828, 6.01868629, 3.58817148, 12.2762976, 3.58810663, 3.58776307,
-    6.01753235, 7.71756935, 6.01720285, 7.71708059, 6.01679659, 7.5632906,
-    8.97652531, 5.81914234, 5.81880713, 7.71594667, 3.5868032,  3.58661366,
-    5.81885719, 11.2806158, 12.271019,  10.1920471, 11.2795677, 10.1915274,
-    10.1918221, 10.1917429, 10.1912527, 11.2786007, 11.2786112, 11.2781916,
-    10.1905231, 10.1902819, 11.2775879, 11.2776461, 15.6158009, 11.2757177,
-    14.0409632, 11.2755575, 11.274991,  14.8487339, 15.6146145, 11.2755175,
-    17.0420246, 17.0419502, 17.0410709, 14.0389328, 13.1812143, 11.2738237,
-    10.1854382, 7.7101841,  6.01100254, 6.01100254, 7.70991182, 11.3741245,
-    6.01128531, 6.01112461, 6.01021528, 3.58349705, 7.70864153, 6.01033497,
-    10.183567,  11.2703085, 16.3360367, 17.0351124, 21.2924366, 20.170599,
-    20.170599,  17.7087135, 16.3377495, 10.1839733, 6.01016378, 12.354497,
-    13.263361,  14.1137018, 13.2632685, 17.0976734, 13.2626057, 12.3517237,
-    12.3511477, 7.70557833, 7.70467758, 7.70467758, 6.00756264, 6.007164,
-    6.00702906, 6.00666142, 11.365983,  12.3460808, 13.2555418, 14.1044979,
-    13.2529917, 13.2529707, 13.2517376, 3.57969761, 6.00419092, 6.00360107,
-    6.00360107, 3.5793159,  10.1701603, 11.2555685, 10.169241,  10.1685524,
-    10.1681852, 5.8049345,  6.00042915, 3.23430943, 3.57742977, 5.99990034,
-    5.99987411, 5.99963045, 7.69487047, 7.69487047, 5.99846077, 3.57622719,
-    5.9984169,  3.57625532, 7.69332075, 3.57635856, 5.9985199,  3.57627439,
-    5.80163622, 3.57631397, 7.54045773, 3.2331686,  8.94923306, 11.2472944,
-    8.94926929, 5.99862003, 5.99791861, 10.2751884, 9.07659531, 15.5735836,
-    5.99738121, 3.57544804, 11.3474636, 5.79976702, 8.946311,   3.57490706,
-    5.99591637, 7.6905179,  12.324584,  3.57464027, 3.57431889, 5.99452639,
-    3.57412672, 5.99432373, 5.99418545, 5.99430752, 3.5738368,  7.68710852,
-    3.57327032, 5.99312401, 5.99244642, 5.99194384, 5.99204922, 3.57221198,
-    3.57221198, 5.9910593,  5.99095249, 7.68387556, 5.99070454, 3.57172537,
-    3.57166409, 5.99046659, 3.57143831, 7.68247938, 3.57120061, 5.98979473,
-    5.9890089,  7.68116999, 5.98880625, 5.98880625, 7.68037462, 5.98834944,
-    7.68022776, 5.98784971, 7.52708721, 5.79197502, 10.1455574, 11.2285032,
-    10.1458092, 5.79199791, 13.128891,  7.52783871, 13.1292086, 3.2278235,
-    3.2278235,  3.22768569, 3.5701232,  3.57018566, 9.06131268, 3.56986642,
-    5.98688555, 5.98638582, 7.52399063, 5.98484755, 5.98485136, 5.98437738,
-    3.56741905, 5.98319244, 10.1362906, 11.2182264, 3.56646395, 8.92491913,
-    5.98152447, 7.67152357, 7.67128038, 3.56601739, 11.2156086, 3.56605697,
-    5.98091507, 11.2148094, 7.5176158,  3.22347832, 3.56539583, 5.97957325,
-    3.2231431,  5.97923613, 5.97887087, 8.92055225, 5.97849798, 3.56453681,
-    3.56443191, 3.56433344, 5.97805643, 7.66717768, 7.51434851, 7.66710997,
-    5.97793961, 5.97740984, 7.66646338, 3.22194648, 11.2070274, 5.97679329,
-    3.56318951, 5.97603703, 5.97590065, 7.6642375,  3.56273842, 5.97523069,
-    5.97500849, 7.66360664, 7.66348839, 3.56244898, 5.97504091, 5.97509336,
-    5.97509336, 5.97487879, 5.97498083, 3.56233811, 11.304224,  14.0306425,
-    14.0295267, 13.1844702, 10.2325621, 5.97272062, 7.66025352, 5.97268009,
-    5.97211075, 7.5076704,  10.1188536, 11.1989279, 3.56036615, 5.97102213,
-    7.65805006, 7.65733051, 5.96992445, 5.9700017,  3.55930924, 7.65694571,
-    7.65652943, 9.03396606, 10.1145563, 8.9068737,  10.2287149, 9.03457832,
-    7.50459671, 12.2718077, 5.97014618, 10.2276001, 11.2961884, 11.1935053,
-    3.21725106, 5.96846628, 11.1922293, 16.2208328, 3.55774903, 5.77160883,
-    10.1094856, 10.1095581, 5.96686077, 7.50045633, 5.96654606, 3.21563625,
-    3.5566566,  9.0260725,  5.96454144, 7.65039444, 5.96486378, 5.96432686,
-    7.64937544, 5.96365499, 3.21465659, 5.96285439, 3.55512285, 7.64714098,
-    3.55482578, 5.96200752, 3.5544672,  3.55451393, 3.55422473, 5.96149969,
-    5.96121264, 5.96128702, 3.55409288, 5.9612956,  5.96124363, 5.9613657,
-    5.96145439, 3.55421925, 5.96093798, 3.21309805, 5.96044922, 5.96043587,
-    3.55358911, 10.098197,  13.916523,  18.1972065, 8.89144993, 5.95890617,
-    7.64157057, 7.48945284, 5.76255131, 5.95762777, 3.21122432, 5.95686388,
-    5.95686388, 7.63983297, 3.55138516, 7.63987255, 7.63961267, 3.55131745,
-    3.21058846, 9.01285362, 3.55105591, 10.0911579, 14.706398,  10.0909786,
-    10.0910883, 11.1683483, 10.0907621, 10.0907621, 8.88502979, 11.167366,
-    12.1476259, 11.1651192, 7.4845438,  8.88363934, 5.75845623, 3.54942799,
-    3.54939342, 5.95278311, 5.95216179, 5.95157242, 5.95135164, 7.63264704,
-    5.95098734, 7.63193941, 5.95037413, 7.63199186, 5.75587749, 3.54757261,
-    10.0811577, 3.54731202, 7.63029957, 5.94852304, 5.94873667, 5.94861269,
-    5.94800091, 5.94818068, 5.94799852, 5.94799852, 5.94842768, 3.54655766,
-    3.5470531,  3.54731011, 11.2570257, 15.5217209, 20.5828362, 18.2268982,
-    18.2256298, 18.2252045, 13.1271458, 18.2200317, 17.5805988, 14.7572603,
-    3.54469323, 5.94502163, 5.94509554, 3.54447913, 7.62516308, 7.62472439,
-    7.62417555, 5.94443512, 5.94343376, 5.94335413, 5.9430685,  3.54321885,
-    5.94245577, 5.94235849, 7.62124968, 5.94210148, 5.94195652, 5.94189501,
-    5.9417305,  8.99121666, 7.62052822, 13.0257034, 5.74648094, 7.61990452,
-    7.6197629,  5.94117498, 3.54200101, 5.94098902, 5.94080925, 7.61954832,
-    13.1123629, 5.9404583,  5.94045448, 7.46690226, 7.61790228, 7.61802912,
-    8.98751736, 3.54084778, 7.6173501,  5.93858528, 5.93837786, 7.61608219,
-    5.93749857, 7.61466932, 5.93706417, 5.93706417, 5.93653202, 7.61411667,
-    7.61357117, 7.61343384, 5.9360323,  5.93591213, 5.93569469, 7.61276579,
-    10.0564842, 10.0561552, 10.0561571, 10.0554066, 11.1291246, 11.1294632,
-    10.0560875, 11.1300077, 10.0553951, 10.0548286, 8.85348892, 10.0534792,
-    7.45834875, 5.93319559, 5.93233061, 7.60854006, 5.93191099, 5.93193197,
-    13.0926151, 13.9312391, 14.7227669, 13.9307919, 13.9292288, 7.60701561,
-    17.5350285, 11.2236567, 10.1626549, 19.3261051, 14.6478043, 21.0142803,
-    16.1234341, 11.2231293, 10.0492678, 3.5363307,  13.849905,  11.1222973,
-    3.19719362, 14.7214508, 14.7197962, 19.3757839, 13.9270439, 3.5349977,
-    13.9246883, 18.1633053, 18.775528,  17.5262432, 17.5264339, 17.5262012,
-    18.1605053, 13.8413582, 5.92726326, 19.3104534, 15.3916883, 5.92809486,
-    17.4635448, 7.45011139, 10.0427885, 18.715147,  13.0832834, 3.5340395,
-    5.92668915, 10.153801,  18.1573048, 8.84122849, 19.8845654, 5.92488718,
-    3.53252649, 3.53227448, 15.4549074, 7.59775972, 3.19308734, 5.9231801,
-    8.83705902, 5.92234707, 10.035224,  13.9095736, 7.59579182, 3.53058672,
-    5.92130327, 5.92097378, 8.95991611, 8.95991611, 7.59323835, 5.92002964,
-    7.59272957, 5.91936255, 5.91917467, 5.9190588,  3.52901626, 5.91884756,
-    5.91863251, 5.91841841, 5.91790533, 5.91784573, 3.52822089, 7.58936405,
-    7.58936405, 5.91709089, 8.82846451, 5.72304678, 7.58827114, 5.91637754,
-    7.58782434, 5.91643667, 7.58741617, 7.58728504, 5.91542864, 5.91536808,
-    5.91477728, 5.91507101, 5.91467667, 5.91467667, 7.5867424,  8.82519531,
-    5.91450262, 5.91396236, 5.91371632, 5.72051144, 5.91476154, 18.7332764,
-    19.3259335, 17.4860172, 8.94877434, 13.8869486, 13.0504255, 11.1875944,
-    7.58307171, 7.5822835,  7.58143282, 5.91134596, 11.1856537, 17.4782276,
-    18.1110134, 3.18628049, 7.58162689, 15.3520947, 3.52491188, 3.18669963,
-    5.91144943, 3.52519703, 14.6744404, 18.1133919, 13.0453939, 10.1236525,
-    7.57933998, 3.18526816, 7.5782671,  7.577981,   3.52247834, 5.90714931,
-    5.90715027, 7.57603884, 3.52158785, 5.90661478, 7.57527542, 7.57472801,
-    7.57472801, 7.57452106, 5.90573359, 8.81113243, 5.90509462, 5.90493393,
-    7.5733242,  7.57331848, 5.90438271, 3.52005005, 7.57231808, 5.90374947,
-    8.80777359, 7.57106209, 7.57073402, 5.90271568, 5.90264273, 7.57040215,
-    5.90211487, 5.70867062, 7.56980038, 5.90182209, 5.90195942, 5.70824623,
-    5.90112543, 5.901227,   9.99766445, 8.80345154, 5.70712042, 7.56760883,
-    5.90027857, 5.70721531, 9.996418,   11.0628948, 8.80273819, 8.80233288,
-    8.80211735, 7.56650972, 5.89913464, 5.89922285, 7.56639433, 5.89928055,
-    7.56584692, 14.6415634, 13.8529606, 13.8529606, 13.8518286, 13.8510284,
-    13.8508673, 14.6368952, 7.56291294, 5.8966918,  5.89646769, 5.89606333,
-    5.89575672, 7.56211329, 5.89588976, 5.89584208, 5.89574051, 5.89574051,
-    8.79655838, 7.41026831, 3.51455522, 7.56061602, 7.56006813, 8.79475403,
-    5.8941164,  3.17706466, 8.79417038, 7.55984545, 13.8435545, 14.6309185,
-    18.0602055, 21.46311,   13.8410463, 14.6279182, 5.89305735, 7.55800104,
-    21.4567432, 14.6249208, 18.6629696, 18.0538921, 7.55694532, 13.7587976,
-    8.79062653, 11.1503181, 19.198225,  18.6029606, 21.4041195, 15.3740301,
-    14.5507851, 5.69944525, 3.17618728, 16.0819206, 8.91504288, 12.1085167,
-    3.51208878, 5.69738436, 7.55418444, 12.1065035, 7.55293274, 7.55257845,
-    5.88781118, 5.69517422, 5.88728333, 9.9748106,  7.55189562, 7.55066681,
-    5.88728809, 5.88698292, 5.88703537, 5.88623238, 7.548944,   7.54850149,
-    7.54843664, 7.54820967, 5.69214964, 8.77977943, 8.77888489, 3.17152977,
-    3.50804186, 3.50766969, 3.50745177, 7.5450263,  5.88237381, 7.54472256,
-    3.50729895, 7.54506397, 5.88232136, 7.54403973, 5.88174534, 7.54376936,
-    5.8811903,  7.54256535, 5.8807888,  5.8807888,  5.88153028, 17.3269634,
-    12.0900116, 9.96597195, 7.54411936, 5.88186884, 3.50686049, 13.7364082,
-    8.77676105, 5.68996096, 15.2737284, 15.2755785, 21.8864517, 18.6330624,
-    20.295948,  8.775877,   12.8940296, 14.5240755, 15.3424206, 11.1286554,
-    5.88024759, 20.8816242, 15.9809971, 14.5172968, 9.96080685, 14.515296,
-    7.54014874, 22.3719063, 14.5166759, 11.02388,   9.96124458, 7.38803196,
-    11.9899931, 7.53835678, 18.0053711, 7.53725672, 3.16737843, 8.89224243,
-    8.89128685, 7.5351553,  7.53442574, 5.87405491, 5.87395048, 7.53308868,
-    5.87336445, 5.87308741, 7.53240252, 3.5012641,  7.53184843, 7.53170776,
-    9.94887161, 3.5008297,  7.53099155, 5.8717103,  7.38044024, 9.94781113,
-    7.38039112, 9.94709587, 8.75895786, 11.0081139, 11.0077763, 11.0073862,
-    8.7583437,  9.94490814, 8.75810146, 11.0063667, 9.94497681, 8.75695705,
-    8.7569828,  9.94467449, 13.7046757, 9.94400597, 9.94365883, 11.0043039,
-    9.94299889, 9.94214058, 9.94256878, 8.75529194, 3.16271257, 7.52530813,
-    7.52471828, 8.87760067, 7.52464008, 8.87749767, 5.86629963, 5.86602926,
-    5.86596203, 5.86562824, 7.52262306, 7.52262306, 5.86535025, 5.86464834,
-    5.86472988, 7.52198124, 7.52195549, 5.86500931, 13.6937132, 5.86376715,
-    7.5212779,  5.86410475, 14.5562744, 14.5558281, 20.286005,  12.9420042,
-    12.9420042, 12.0523376, 17.9615993, 3.16006231, 13.7703552, 7.51991224,
-    8.87221432, 5.8630209,  10.9947348, 14.5522537, 16.0044823, 17.8985424,
-    15.2225933, 11.9602118, 5.67070436, 8.87197971, 3.16022062, 17.3327236,
-    10.9925241, 7.51751947, 10.9919729, 10.0436144, 16.6122379, 19.0968742,
-    16.679575,  5.86168528, 9.93158054, 17.2660236, 13.6850471, 3.1589725,
-    15.9292192, 12.8482265, 15.9275255, 14.5443907, 12.0454245, 12.043993,
-    16.6088505, 12.8444777, 13.6808891, 5.85871172, 10.9858913, 7.36373615,
-    5.85734892, 7.5122447,  18.5502243, 13.7548561, 8.73679829, 7.50943947,
-    7.36028481, 5.8540802,  5.85411739, 10.028636,  5.8535862,  5.85346127,
-    5.85250616, 5.85248756, 9.916399,   8.73152637, 9.91540909, 11.9372301,
-    9.91480827, 3.15411234, 9.91410351, 10.971962,  7.35516357, 7.50458527,
-    12.8273458, 10.9705267, 3.48810863, 7.50343084, 7.50357103, 3.15338063,
-    12.9113903, 10.0218544, 10.9687567, 9.91088104, 8.85136986, 7.50158691,
-    5.84887314, 8.85038567, 5.84821701, 7.50086641, 13.7356548, 12.0208664,
-    13.7344933, 13.7342796, 14.5146351, 13.7327528, 13.7327929, 5.84692144,
-    3.48604202, 3.15172839, 5.84637213, 3.48564816, 5.65416288, 12.8166904,
-    3.48526049, 5.8453927,  3.48515534, 3.15076637, 3.15066004, 7.49680471,
-    7.49658298, 7.49641609, 7.4963727,  10.013236,  9.90289497, 3.15047836,
-    5.6531353,  3.48437834, 15.1750832, 7.49591303, 13.6464128, 12.8123856,
-    15.9518337, 3.14978647, 7.3448987,  3.14948559, 8.71751499, 13.6418591,
-    10.9552145, 15.1683817, 15.1688318, 7.34346867, 9.89787674, 5.84149551,
-    12.8922119, 7.34139299, 9.89566994, 5.8394556,  7.33998203, 9.89331341,
-    15.1611853, 13.6333036, 8.71154499, 3.14724207, 9.89174652, 11.9093056,
-    8.71002197, 3.14657927, 19.017168,  11.9070473, 9.8891592,  8.70848274,
-    9.88809776, 9.8880415,  9.88718987, 9.88680744, 9.88742828, 8.70623684,
-    8.70623684, 10.9411583, 9.88601685, 8.70497227, 8.70520401, 9.88480377,
-    9.88524437, 10.9409876, 9.88557434, 8.70570374, 8.70604229, 9.88658524,
-    13.6247263, 15.1495647, 14.4064274, 15.1492958, 15.1462002, 14.402627,
-    15.8539314, 14.402194,  8.70189762, 9.88022804, 7.47924376, 5.83120632,
-    8.82364464, 14.4729824, 8.69941711, 8.82439804, 7.47932005, 3.14320707,
-    7.4791069,  16.5240345, 7.47758198, 3.47609878, 14.4699306, 14.3936262,
-    5.63830233, 9.87573242, 8.69695187, 3.14167929, 10.9295301, 5.82779312,
-    8.69486237, 8.81847572, 3.47427964, 8.81823635, 5.82679272, 3.14077401,
-    5.82619143, 5.82637501, 3.47374916, 7.47240067, 7.47214031, 7.47163057,
-    5.82537222, 7.47158813, 5.82511091, 7.47028446, 5.82436466, 13.6800699,
-    8.81438065, 3.47277617, 5.82415915, 5.82390451, 5.63260746, 8.81227589,
-    9.86588478, 9.86631489, 10.9185028, 10.9183207, 9.86495876, 14.3762379,
-    8.68683243, 12.7633791, 7.3175931,  8.68562126, 7.31758928, 7.4660821,
-    8.68542099, 13.5916128, 9.86256695, 9.86188889, 5.82047939, 8.68507957,
-    7.46541977, 7.46502686, 5.81988525, 8.80524349, 9.85774803, 8.68084335,
-    9.85773849, 8.68115616, 10.9101753, 9.85814953, 8.68036366, 10.9089804,
-    9.85655594, 9.85621262, 8.67896843, 9.85491276, 8.67817783, 8.67759514,
-    7.31015348, 8.67685699, 8.6767292,  8.6767292,  8.67611599, 7.3095603,
-    8.67613602, 9.85182953, 9.85193729, 8.67585945, 9.85147858, 8.67547417,
-    5.62384844, 8.67473984, 11.8603725, 14.35604,   10.9013405, 8.67401886,
-    7.30781794, 3.4657104,  3.46579385, 8.67320251, 5.62253523, 5.62217522,
-    9.84775925, 8.67211056, 3.46522188, 7.45505095, 13.650631,  13.6504803,
-    11.9472103, 7.45400667, 8.79409027, 7.45340538, 13.6466932, 8.79329967,
-    7.4521656,  7.45243359, 7.45174742, 7.45118809, 3.46361041, 5.80932331,
-    8.79106331, 5.80902815, 7.45007992, 7.44989204, 8.78967667, 7.44889832,
-    7.44889832, 7.44834805, 7.4484601,  8.78767967, 13.6386652, 14.4131374,
-    7.29913425, 7.44768524, 13.6389961, 8.66486454, 15.0812426, 9.83869839,
-    15.0812044, 8.6646452,  20.5739174, 18.3368721, 15.0789013, 3.46231365,
-    10.8874598, 5.80624533, 10.8859959, 10.9845505, 5.80489826, 8.65997314,
-    8.78267765, 9.83258247, 9.8324728,  12.7214499, 8.65780067, 12.7210712,
-    7.29358625, 3.12734723, 9.82996082, 8.65587044, 8.65583801, 11.8338413,
-    9.82882977, 3.12701583, 5.80110788, 7.29240561, 7.43994665, 5.80024099,
-    7.43808556, 7.43798971, 5.79900932, 9.82524872, 9.82458591, 10.8727179,
-    9.82462692, 8.65087032, 7.43639278, 5.79781055, 5.79779339, 5.7975812,
-    7.43564558, 7.43540907, 8.77233982, 5.79677963, 7.4341135,  5.79638863,
-    8.7716198,  5.79592085, 7.28544378, 5.79576778, 8.77002716, 3.45542502,
-    5.79511881, 5.79520941, 7.43236446, 7.43200254, 5.79479361, 9.92728043,
-    7.28416014, 8.64587307, 7.43206024, 9.81776905, 5.79380512, 3.45449662,
-    3.4540453,  5.79264307, 7.4290123,  7.4288578,  7.42904425, 5.79170322,
-    5.79113483, 13.5217352, 7.42803335, 3.45296407, 7.42888308, 13.6047716,
-    8.76586437, 15.110465,  20.03512,   9.8121748,  5.79180527, 13.5237265,
-    7.27980566, 3.45322418, 13.5222874, 12.6950302, 9.92028236, 17.6815872,
-    8.76396084, 7.27882767, 22.0851669, 5.60044765, 11.9009361, 8.7619009,
-    15.0342369, 11.8088474, 9.8081007,  7.42443228, 16.4051266, 16.4060574,
-    10.8552933, 9.80659771, 7.27552366, 5.59900427, 10.8532782, 5.59800625,
-    7.42302227, 15.796587,  13.5907383, 11.8937111, 9.91114998, 7.41996193,
-    3.11819744, 5.78472853, 5.78457594, 7.41931486, 7.41880751, 5.59418917,
-    7.41782093, 3.11745501, 8.62905502, 5.78347492, 5.78319597, 5.78286695,
-    3.11710668, 5.78272486, 3.44764471, 8.75021839, 5.78220654, 8.7492218,
-    8.75000477, 5.7819829,  5.59249353, 3.44743705, 13.5007935, 10.8415785,
-    3.44717216, 5.78177118, 21.5569477, 18.309206,  7.41312885, 5.59105015,
-    9.90161419, 14.344491,  11.879159,  9.90094376, 7.41229677, 5.77897692,
-    3.44529057, 10.835639,  7.4111681,  11.7871685, 5.58878803, 10.833147,
-    3.44471908, 5.77715158, 7.40965986, 10.8336191, 5.77683592, 3.11366892,
-    11.8745394, 10.9304428, 11.873518,  5.77614021, 3.11326933, 7.40793514,
-    17.69627,   8.61650372, 7.40613174, 7.40622807, 3.44250846, 7.40566587,
-    7.40540695, 7.4053669,  5.77315617, 8.73617458, 5.77283239, 5.77267218,
-    3.44156098, 7.40304852, 5.77173042, 7.40273476, 5.77173615, 7.40210485,
-    5.77075672, 3.44077015, 8.60992527, 8.60986996, 8.60950375, 9.77627182,
-    8.60941505, 9.77604675, 9.77639008, 5.76942825, 7.39938593, 5.76904154,
-    7.39928579, 5.76846838, 5.76821804, 3.43903422, 7.39803648, 7.39770508,
-    5.76790428, 8.72783279, 5.76705694, 8.72697926, 5.76699162, 8.60496044,
-    5.57771158, 8.60423279, 3.10805154, 3.4378283,  7.39480686, 5.76571417,
-    5.76509857, 7.39430475, 7.24683619, 7.39415264, 7.39404964, 3.43715072,
-    5.76473475, 7.39358902, 17.0452709, 11.8486586, 14.3069363, 15.7345409,
-    13.5376711, 12.7208967, 15.7323389, 12.7198877, 16.3974838, 10.9045601,
-    3.10662079, 10.9062347, 5.76319361, 20.9866962, 18.1966095, 7.3908267,
-    5.7620306,  11.8450851, 5.76132202, 8.59600353, 7.38931561, 13.5305614,
-    3.43460512, 14.2986135, 8.71657467, 7.38711691, 7.38703823, 7.38661289,
-    5.75870371, 5.75860214, 12.7098904, 13.5243816, 13.5236397, 13.5237389,
-    7.38523149, 15.7200203, 18.2381783, 14.218421,  17.0264339, 10.8962994,
-    5.75756788, 12.7081823, 5.75714159, 7.23649216, 11.8327971, 3.10269642,
-    5.75574493, 5.56741476, 5.75545979, 9.75146198, 5.75511742, 7.38097477,
-    5.75450039, 8.70804882, 9.85850811, 3.1017673,  7.38024855, 7.37978458,
-    10.8878956, 8.70732117, 13.5131989, 8.70693398, 11.8262529, 7.37872934,
-    7.37872934, 5.75190592, 7.37753677, 5.7514081,  8.70358944, 5.75125217,
-    7.3763485,  5.75083733, 7.37556267, 8.70227242, 5.75040436, 8.57962799,
-    5.74988985, 7.37502003, 3.09944963, 3.42831373, 5.74961567, 7.37464857,
-    8.57805634, 5.56080246, 13.4250593, 8.69937897, 3.42752814, 8.57653999,
-    7.3726306,  5.5597806,  3.42672896, 3.0978322,  5.74655008, 8.69602871,
-    5.74643707, 5.74623203, 5.74569893, 5.55750895, 10.774189,  7.36925697,
-    8.57281017, 10.7745285, 7.36829853, 7.22166538, 5.74507713, 5.74542284,
-    8.69338703, 7.36738777, 7.36733103, 7.36733103, 7.36636686, 5.74319935,
-    7.36565113, 7.36544943, 7.36552715, 5.74228716, 5.74254274, 12.6742077,
-    8.68988228, 5.74237394, 5.74235773, 7.36591196, 3.42408347, 9.73090267,
-    14.9130735, 12.5920601, 10.7685404, 9.72865582, 3.09493136, 7.364048,
-    7.36252928, 7.36227798, 5.73950481, 7.36153841, 8.6858778,  5.73961067,
-    7.36086559, 5.73898411, 7.35992146, 3.42130971, 7.21275187, 7.35890388,
-    5.73750591, 7.35829687, 3.42033553, 7.35786152, 7.35763025, 5.73669243,
-    8.55848408, 9.7185154,  9.71834183, 8.55777645, 11.6998901, 15.5888481,
-    18.6850491, 18.1078682, 14.1605101, 14.1606989, 8.5559845,  9.71669674,
-    9.71689415, 9.71627617, 11.6987944, 14.8916569, 14.1609287, 14.8913336,
-    18.1069279, 15.588521,  18.1044998, 19.7838402, 18.6823082, 18.1044254,
-    15.5849552, 15.5845051, 14.8863811, 15.583209,  15.5828428, 15.5816641,
-    8.55233002, 8.55243015, 9.71134281, 9.71016407, 10.7459354, 8.54990101,
-    3.4165833,  8.54955006, 8.67101288, 7.34855843, 8.67008781, 7.20189142,
-    9.70734882, 5.54145098, 7.20091009, 5.54057217, 5.72843313, 3.08786201,
-    10.7406721, 8.54628468, 8.6685791,  3.4153161,  5.72809029, 10.7401762,
-    8.54476261, 7.34533024, 7.34466743, 5.72627544, 9.7016716,  14.1385632,
-    14.8678169, 18.6559753, 19.2146511, 14.8707542, 9.70253181, 12.6384172,
-    18.7110023, 24.1363297, 29.9945183, 28.5494843, 24.5701256, 22.7867966,
-    20.3358383, 16.9297905, 8.66628265, 3.41471505, 15.5681391, 3.08670807,
-    9.70020962, 21.7850838, 8.66056442, 7.34023619, 5.53433371, 8.53704834,
-    8.53615284, 5.72105408, 9.69300747, 7.33737898, 7.33769798, 7.3374176,
-    5.72054672, 7.19057465, 5.72041559, 8.65637779, 7.33691359, 8.65639496,
-    5.72024679, 7.33557701, 7.33642292, 8.65599632, 7.33532858, 7.33423567,
-    5.71784258, 7.33382082, 3.40946746, 7.33426523, 8.53205967, 3.08222651,
-    8.53118134, 5.71757603, 7.33500862, 9.68956375, 5.71717072, 8.52994537,
-    5.71711111, 5.52946949, 5.71709204, 8.52985287, 3.40861797, 7.33205462,
-    3.08130717, 5.52933645, 7.33204174, 3.08144379, 7.33185005, 5.71637297,
-    8.65053272, 8.5290184,  5.71633625, 5.71606779, 5.52886724, 3.40799928,
-    8.52852249, 5.71598864, 5.71596527, 5.71591711, 5.71599197, 5.71591282,
-    5.71579123, 7.33102179, 5.71558762, 8.64934444, 9.68376827, 7.3306036,
-    5.71549988, 5.52823782, 5.52809668, 5.71524429, 7.33029747, 5.52787828,
-    7.33027077, 5.71500874, 8.6485815,  7.32993603, 3.08043671, 3.0804255,
-    3.40727091, 7.32977962, 5.52748489, 7.32977104, 3.40712094, 7.32964754,
-    7.32955313, 5.71469593, 5.71446753, 7.32917643, 7.32915306, 7.32907629,
-    7.32907009, 7.32907867, 7.32907867, 7.32907867, 9.68145275, 9.68138981,
-    8.52562809, 8.52546883, 5.5268321,  5.71388054, 8.52541637, 10.7142067,
-    8.52504253, 7.32844257, 3.40654755, 7.32812405, 8.64602661, 7.32803392,
-    8.52463436, 8.52429867, 3.07958961, 5.71311378, 7.32758713, 3.40624785,
-    7.18165255, 5.525877,   7.32721233, 8.52375984, 5.5257287,  7.18110085,
-    8.64455318, 7.32691574, 9.67916393, 8.64510822, 8.52336407, 3.07922649,
-    3.40596676, 8.52309704, 5.52523184, 3.40578103, 7.1805253,  3.07907796,
-    8.52287579, 3.40578437, 7.32650995, 8.52276802, 5.5250659,  7.18003178,
-    7.32606411, 9.67736626, 7.32594252, 7.32561922, 5.52457809, 5.71172333,
-    7.32587147, 7.32558393, 5.71154308, 3.07864118, 3.40527081, 7.32534647,
-    3.40520215, 3.07847238, 8.52123356, 5.7112093,  7.32506227, 3.40512896,
-    3.40513992, 7.17894268, 8.52100563, 10.7090998, 7.17876673, 5.71078348,
-    7.32468939, 7.32455254, 5.52389622, 9.67565823, 8.52025509, 3.40475035,
-    5.71057653, 7.17803335, 5.52343035, 9.67469978, 8.51950264, 5.52306175,
-    5.71000004, 7.32362556, 3.40439606, 5.71015453, 8.51970959, 9.67461109,
-    8.51972294, 5.71001959, 8.51946449, 8.6409235,  5.52275801, 3.07758164,
-    3.07757521, 5.70954037, 9.67390442, 8.51858997, 5.70954752, 7.17677784,
-    5.70932627, 8.63984489, 8.51840019, 7.1767087,  8.5179615,  3.40394759,
-    3.07742095, 5.52203035, 5.7087965,  10.7046194, 7.17612791, 7.17605352,
-    3.40371656, 7.17600727, 3.07709122, 3.40358305, 3.40352035, 9.67196369,
-    3.07705402, 8.51684856, 8.51724625, 9.67196083, 9.67133617, 7.17545891,
-    9.6715517,  7.17527914, 7.17525196, 5.52117157, 7.17518711, 8.51605606,
-    8.51620865, 7.3206954,  7.17480898, 9.67052841, 9.67057133, 7.17472363,
-    8.51604271, 9.67036438, 5.70748329, 7.32044363, 7.32005501, 5.70732069,
-    7.32006073, 3.40279031, 5.70718479, 3.076262,   3.4026823,  7.31974554,
-    5.70699739, 5.70705795, 5.70703506, 7.31975698, 7.31929588, 7.31947756,
-    5.51968241, 5.70662832, 5.70674706, 7.17318487, 3.07591915, 5.70630646,
-    7.31899405, 7.31910419, 9.66847801, 5.5192728,  5.70630121, 8.63535118,
-    5.70634031, 7.31846333, 3.07567096, 5.70600796, 7.31816769, 8.6349926,
-    8.63483906, 8.63470936, 7.31814766, 3.40185189, 5.51878786, 5.70571232,
-    8.51295757, 9.66702271, 9.6670332,  9.6670332,  7.31749058, 5.51852226,
-    8.51237774, 5.70518208, 5.5183301,  5.70519352, 5.51832533, 8.6332531,
-    7.31706333, 7.31706762, 10.6971483, 7.17108583, 5.51784039, 7.31666231,
-    5.70462227, 7.31663609, 5.70451498, 8.63243198, 5.70440722, 8.6324091,
-    7.31635857, 7.31641865, 7.31618404, 5.70417404, 8.63213634, 5.70418453,
-    7.31605053, 5.7040391,  5.70409012, 5.70409012, 5.70384455, 5.70381212,
-    7.31574726, 7.31546926, 8.63131046, 7.31515789, 7.31518745, 5.7035346,
-    7.31520176, 7.31520605, 5.703475,   5.70328999, 8.63070011, 7.31489944,
-    8.50935555, 9.66327572, 5.70302248, 5.51628494, 8.6303587,  8.63008785,
-    5.70297337, 5.70287991, 3.40010905, 9.66212463, 8.50860977, 7.16836596,
-    3.40002346, 5.70242023, 3.3999629,  3.07381845, 5.51570892, 5.70239353,
-    7.16796017, 5.51555109, 7.31377888, 9.66144466, 3.3997581,  3.39975095,
-    5.70206738, 5.51543951, 9.66102123, 8.50770569, 10.6921635, 8.50756454,
-    8.50756454, 9.66057873, 5.70181751, 8.6281929,  5.70176363, 8.50720215,
-    9.66036797, 3.39944601, 9.65995979, 8.50679016, 7.3127265,  7.16693878,
-    7.31255579, 7.31233501, 5.70138693, 7.31251287, 8.6274128,  7.31218863,
-    8.62734795, 8.62716675, 3.39904451, 7.31181049, 7.31180286, 7.31180239,
-    7.16593838, 5.7007699,  7.31158733, 5.70069933, 5.7006197,  5.70048332,
-    8.50522995, 7.16572523, 8.50513268, 5.70038033, 5.70032215, 7.3112731,
-    5.51367331, 3.39864826, 7.31117296, 3.39856672, 3.07254386, 3.39864731,
-    8.50465298, 8.50448132, 7.16486073, 7.16486073, 7.31053543, 7.31048918,
-    9.65709972, 7.31036806, 3.39822006, 3.39830613, 3.39821124, 3.07220984,
-    9.65679741, 5.51281738, 5.69955158, 5.69948959, 9.65639114, 8.50368118,
-    7.31002235, 7.16426897, 7.30977631, 3.07203293, 7.30964804, 7.16408777,
-    7.30961466, 7.30953741, 3.39781094, 7.30960417, 7.30995417, 9.65701008,
-    9.65630341, 7.16406584, 3.07193494, 8.50309563, 9.65539646, 8.50268841,
-    3.397614,   8.50216103, 3.07162356, 7.16316128, 7.16308022, 8.62321949,
-    7.30839729, 7.30847454, 7.30862045, 5.69812489, 7.30848789, 8.62301159,
-    7.30840778, 7.30819464, 8.6227808,  7.30822515, 7.30798149, 5.69785929,
-    7.30798006, 7.30792618, 5.69767094, 5.69770193, 5.69770908, 7.30768824,
-    3.39708877, 5.69759083, 7.30755043, 5.69751787, 3.39701033, 7.30748796,
-    5.69744968, 7.30727673, 7.30733776, 3.39682651, 5.69733477, 5.51059341,
-    7.16152716, 3.39675665, 8.50031376, 8.50032902, 3.07087898, 7.16122484,
-    7.16122484, 8.49990082, 9.65222645, 5.51036692, 5.51029444, 5.69687891,
-    8.49975586, 3.39652658, 5.51016045, 8.49973202, 9.65185261, 3.07058573,
-    9.65155411, 3.07050586, 8.62021255, 7.30603552, 9.75903702, 7.30602264,
-    8.49890137, 3.07032108, 5.50946045, 3.0703721,  7.30583477, 7.30546331,
-    5.69586182, 7.30540466, 5.69594431, 7.30530691, 8.61933327, 8.61940956,
-    7.30535555, 7.30503321, 7.30502748, 7.30484152, 5.6955471,  7.30485249,
-    7.15925598, 5.50877047, 7.30447531, 5.69532871, 3.06985712, 7.30446148,
-    3.06976914, 7.30452633, 5.50860548, 7.15887356, 8.61838341, 5.50849247,
-    7.3042264,  8.49676228, 7.30423403, 8.49683285, 7.1584506,  7.30379486,
-    5.69461346, 7.30385017, 5.6946125,  3.39526534, 7.30366373, 7.15801001,
-    5.69443321, 7.15796804, 10.6775417, 9.64779377, 7.30318737, 3.39503241,
-    3.394979,   7.30307388, 5.50757885, 3.06921887, 5.6940217,  9.64715672,
-    5.5073576,  3.069067,   5.50735235, 7.15724516, 5.50726223, 3.39470124,
-    7.30247498, 8.6161356,  8.61596775, 5.69364119, 7.30220318, 7.30215263,
-    8.61557388, 7.30215931, 7.30215693, 7.30219841, 8.61549187, 7.3020587,
-    5.69323587, 7.15638161, 5.50663424, 7.30178165, 7.15616465, 9.64559937,
-    7.15617275, 7.30167341, 8.49353218, 9.64520741, 8.49363041, 7.15576696,
-    7.30117083, 8.61443138, 7.30110645, 9.64477921, 7.30099154, 5.69239426,
-    7.15529537, 8.49279308, 7.15523863, 9.64424324, 3.06821012, 7.15509367,
-    8.49269676, 8.49250412, 5.50564957, 7.30046129, 3.39364696, 7.15474939,
-    9.64367104, 3.06810641, 3.39359593, 8.49229908, 8.49224377, 5.50551939,
-    3.0680449,  5.69187927, 3.39356494, 7.29989719, 7.15443802, 7.29992199,
-    8.49157715, 5.50493097, 5.50493956, 5.69133043, 3.06765103, 5.50474787,
-    8.61234474, 7.29929876, 7.15377283, 10.6713409, 8.49097538, 3.39300895,
-    5.6907382,  3.06748652, 5.50434637, 5.69077873, 8.49069977, 3.06737947,
-    7.29867887, 5.6907239,  7.29882622, 5.69087553, 7.29930353, 7.29955053,
-    7.29959393, 5.69124317, 8.61256218, 8.61248875, 7.2994051,  7.29961538,
-    3.39311075, 8.49127769, 5.69112015, 3.39315033, 5.6908989,  5.69088316,
-    8.4907074,  7.2983427,  5.50406122, 8.48969841, 5.69001102, 7.29756498,
-    9.74756527, 5.50329542, 7.2972908,  9.63954735, 3.39206457, 9.63961124,
-    8.48875809, 3.0667243,  5.68925571, 7.29689837, 5.68906593, 3.39190674,
-    7.29663801, 5.68902969, 7.29654026, 9.74601555, 7.29637432, 7.29644966,
-    5.68871307, 3.06641293, 8.60858154, 8.60858154, 5.68865776, 7.29608059,
-    7.29613972, 7.29603624, 7.1505909,  3.06619406, 7.15053701, 7.15042162,
-    9.74508572, 7.29583311, 3.06610012, 7.15001535, 7.15003824, 5.68807459,
-    5.68807459, 7.29522753, 7.29528952, 5.68791914, 8.60737705, 5.68771458,
-    3.39116788, 3.06584191, 5.68765688, 3.39102769, 7.29487276, 7.29466963,
-    7.29454947, 8.48577595, 7.29454947, 8.60665989, 3.39088583, 8.48541641,
-    7.2944417,  7.29427719, 3.3907299,  5.50086117, 3.06556249, 7.2940402,
-    7.29382801, 7.29395199, 5.68695021, 7.29373932, 7.29382277, 5.68681002,
-    7.29381704, 8.48447418, 8.48460388, 9.63481712, 8.60543442, 7.29327774,
-    7.2933588,  7.29342127, 7.29314089, 9.74167919, 8.60512829, 8.60495377,
-    5.6861105,  7.29293919, 7.29285383, 10.6621866, 7.29273987, 5.6858573,
-    8.48346901, 3.39004064, 8.4832983,  8.48323631, 8.48339748, 7.14698744,
-    3.06470037, 5.49937773, 9.63312244, 8.6038456,  5.68542719, 7.29191971,
-    7.29191971, 7.29199934, 7.29192877, 7.2917366,  7.29163313, 5.68533516,
-    7.29171515, 7.29139137, 7.29155874, 5.68494654, 7.29152393, 7.29132175,
-    7.29125643, 7.2911973,  9.73917007, 7.29119444, 7.29114914, 7.29100657,
-    7.29097176, 7.29089594, 5.68463945, 7.14560175, 9.63114834, 3.06403875,
-    7.14528179, 3.38911533, 9.63068485, 8.48089695, 5.68425226, 7.14506865,
-    3.06389594, 3.38896346, 5.6839056,  8.48051262, 7.28993893, 7.14467764,
-    3.06370878, 8.48044777, 9.62982559, 5.4974966,  3.06358171, 7.14427233,
-    5.68353081, 3.06349874, 3.06354856, 8.60077763, 3.06346822, 5.68327951,
-    7.28935671, 7.2889657,  7.28914356, 9.6288805,  5.68310118, 8.60004807,
-    7.28889227, 7.28888083, 5.49684715, 7.2888236,  5.68279886, 7.288764,
-    7.288764,   7.28836346, 8.5992918,  7.28818893, 3.06300473, 7.2883172,
-    7.28810644, 5.68244076, 7.14273357, 7.14278316, 8.59887981, 7.1426034,
-    5.68219185, 5.68204498, 8.59857178, 8.59857178, 7.14231586, 5.49584293,
-    7.28761148, 8.59833431, 8.59820366, 8.59802341, 7.287323,   7.28722334,
-    5.68155766, 3.06249881, 3.06248307, 3.06247115, 7.2869854,  7.14160061,
-    3.38734245, 9.6256609,  5.49511671, 7.28685045, 8.59715271, 7.28645372,
-    7.2864151,  7.28642416, 7.28635311, 7.28627062, 5.68088293, 5.68082094,
-    7.28616285, 7.28599882, 8.59646702, 5.68064594, 8.59639835, 5.68060207,
-    7.28564262, 8.59624386, 7.28575993, 7.28575134, 7.28571844, 8.59575939,
-    5.68035793, 8.59611225, 5.68023634, 5.68023205, 5.68004704, 7.28523064,
-    7.28523064, 5.68001842, 7.28505278, 8.59520054, 8.59512138, 8.59511948,
-    7.28481102, 8.59529781, 7.28446913, 5.67973566, 5.679667,   7.2845211,
-    5.6795516,  7.28445101, 8.5946703,  7.28438759, 7.28429794, 7.28420591,
-    7.28411484, 7.28388739, 7.28407192, 5.67902899, 8.59405804, 7.28396082,
-    7.28371763, 7.28365469, 7.2834816,  7.2836628,  8.59364796, 7.28342772,
-    7.28342772, 7.28329754, 7.28345871, 8.59350967, 8.59315014, 7.28313684,
-    7.28307009, 5.67845678, 8.59296608, 7.28301525, 7.2828064,  7.2828393,
-    8.59268475, 7.28266621, 7.28255367, 7.28255367, 7.28249264, 8.59241104,
-    8.59213543, 5.67778254, 7.28205585, 5.67780209, 7.28226757, 5.67775249,
-    8.59200668, 7.28182983, 7.28211021, 9.72676086, 5.67750311, 8.59162521,
-    7.28180647, 7.2817049,  7.28175116, 8.59154224, 8.59133816, 8.59134007,
-    7.28136969, 7.28141689, 5.6770339,  7.28114414, 7.28130388, 7.28135824,
-    8.59064388, 5.67697334, 7.2809701,  8.59063911, 8.59063339, 8.59053802,
-    7.28089809, 5.67668581, 7.28072929, 8.59018421, 7.28073072, 5.67657709,
-    7.28063488, 7.28065014, 8.59002399, 7.280406,   7.28045797, 8.58985615,
-    7.28030729, 8.58961201, 8.58974934, 8.58972836, 7.27991867, 7.27991295,
-    5.67601109, 7.27988863, 5.67583466, 7.2799058,  7.27987814, 7.27959394,
-    7.27970791, 5.67566109, 8.5891304,  7.27969217, 7.27952147, 7.27936649,
-    7.27922583, 7.27919674, 7.27942848, 7.27934074, 5.67551661, 5.67540455,
-    7.27901697, 7.27914906, 7.27887917, 7.27889633, 5.67508745, 7.27886629,
-    7.27886629, 7.27862692, 8.58780956, 7.27848768, 8.58749866, 5.67458725,
-    5.67473555, 7.27821875, 8.58719921, 7.27792549, 7.27775717, 8.58693981,
-    5.67426872, 7.27794695, 8.58686256, 7.27777052, 8.58660412, 7.27760696,
-    5.67413521, 7.27753687, 7.27736712, 8.58640003, 7.27751112, 7.27741766,
-    7.27722788, 7.27712297, 5.67393017, 8.58610249, 7.2771821,  8.58593178,
-    7.27698135, 5.67377758, 7.27689743, 7.27684689, 7.27676678, 7.27680969,
-    8.58567142, 7.27694035, 8.58540249, 7.27674294, 7.27645636, 7.27640009,
-    7.27643728, 5.67313528, 8.5851078,  7.27628326, 7.27626657, 7.276021,
-    8.58483601, 7.2760067,  7.27603245, 5.67285919, 5.67286682, 7.27565193,
-    5.67275143, 7.27571201, 7.27539825, 7.27550745, 7.27558184, 7.27527952,
-    7.27527952, 7.2752552,  7.27512074, 7.27513313, 8.58379459, 7.27526569,
-    5.67221642, 7.2751112,  7.2747674,  7.27479362, 7.27464962, 7.27463245,
-    7.27450418, 7.27443409, 7.27422714, 7.27422714, 5.67163658, 7.27430725,
-    7.27431154, 7.27412367, 5.67159796, 5.67140436, 5.67157555, 8.58245087,
-    8.58234882, 5.671381,   5.67125845, 8.58214378, 8.58221149, 8.58221149,
-    8.58221149, 7.27353621, 7.27372932, 8.5820713,  7.27352142, 5.6711092,
-    7.27355719, 5.67094803, 7.27350092, 7.27336311, 8.58151245, 7.27336454,
-    5.67081642, 8.58142471, 8.58169079, 8.58169079, 7.27328873, 5.6707325,
-    5.67067337, 8.58174229, 5.67085218, 7.27309227, 5.6706109,  7.27269793,
-    7.27271032, 8.5809164,  7.27247858, 7.27243996, 7.27226782, 7.27210712,
-    7.27210712, 5.66986513, 7.27210903, 8.58000278, 7.271873,   5.66982937,
-    7.27184725, 8.57978725, 7.27154636, 8.57953548, 8.5796833,  8.57945347,
-    7.27140713, 7.27150345, 7.27127695, 8.5792017,  5.6693716,  8.57924366,
-    5.66915131, 7.27121258, 7.27109051, 8.57895756, 7.27115345, 5.66901112,
-    7.27089357, 5.66904831, 7.27086782, 7.27083111, 8.57875443, 7.27106428,
-    8.57894993, 5.66977692, 7.27214909, 5.66988945, 8.57999039, 7.27181768,
-    7.27128601, 8.57917976, 7.27082872, 7.27078581, 8.57881451, 8.57858276,
-    7.27065468, 8.57843113, 7.27071047, 7.27071047, 5.66879702, 7.27090549,
-    7.27118158, 8.57941723, 7.27182341, 7.27181053, 7.27163839, 5.66948271,
-    8.57809925, 8.5777216,  9.71102142, 5.66807318, 7.26970196, 5.66787386,
-    8.57713985, 5.66773224, 7.26935768, 7.269279,   7.26934481, 7.26915216,
-    8.57688904, 8.57677841, 8.57642937, 7.26909494, 7.26906061, 7.26902151,
-    7.26898718, 8.57672405, 8.5763073,  7.26882458, 5.66729212, 5.66724777,
-    7.26880407, 7.2685833,  5.66726017, 5.66730022, 5.66737795, 7.26958942,
-    9.71054077, 7.26969814, 7.26925039, 7.2689085,  7.26868725, 7.26872158,
-    8.57618618, 7.26831388, 7.26827765, 7.26794481, 7.26799202, 5.66669798,
-    7.26793242, 7.26780081, 7.26803017, 8.57499313, 8.57492256, 7.26753139,
-    7.26748371, 5.66635418, 5.66633749, 8.5748148,  5.66604805, 7.2672286,
-    7.26729107, 8.5743351,  7.26704168, 7.26694441, 7.26696014, 7.26676178,
-    7.26698589, 7.26688194, 7.26682186, 5.66572285, 7.26662922, 9.70642567,
-    8.57377815, 5.66557884, 7.26650429, 7.26663828, 8.57352352, 8.57339859,
-    7.26642323, 8.57377243, 5.66539001, 7.26633692, 7.26619768, 8.57332134,
-    5.66534138, 7.26617241, 7.26618004, 7.26618004, 5.66522455, 7.2659688,
-    7.2658,     7.26574278, 8.57271767, 8.57287216, 9.70515251, 8.57245636,
-    8.57258224, 7.2656002,  8.57234669, 5.66476393, 5.66470146, 7.2655592,
-    7.2655592,  7.26534557, 7.26533127, 7.26530886, 7.2653203,  7.26540327,
-    7.26537752, 8.57209492, 8.57210922, 8.5718956,  8.57183266, 8.57183075,
-    7.26497793, 7.26499271, 8.57200241, 7.26517582, 7.26489639, 5.66424179,
-    7.2648325,  7.26492786, 8.57171154, 7.26472521, 8.57144547, 8.57144737,
-    7.26471519, 7.26462793, 7.26469374, 7.26451159, 9.703578,   5.6639204,
-    5.6639204,  7.26432228, 8.57083797, 7.26400566, 8.57071114, 9.70302963,
-    7.26415396, 7.26401424, 7.2640028,  8.57073021, 7.26399469, 7.26404142,
-    5.66350365, 7.26395273, 7.26390314, 7.26390314, 7.26386452, 7.26404285,
-    7.26393414, 7.26357412, 8.57027245, 8.57013988, 8.5700655,  8.56978798,
-    7.26318026, 7.2632432,  7.26329851, 7.26309013, 8.56989765, 7.26324272,
-    5.66297197, 5.66299725, 7.26351786, 8.57035255, 8.57072067, 8.57069397,
-    7.26424217, 7.26418638, 7.26388836, 7.2640667,  7.2640934,  7.2638855,
-    8.57019329, 5.6632967,  7.26353216, 7.26353216, 7.26312351, 5.66272831,
-    9.70134068, 7.2625246,  8.5691061,  7.26247787, 8.56894398, 7.26263428,
-    7.26249743, 7.26251698, 7.26243591, 7.26244164, 7.26230097, 7.26245451,
-    8.56879234, 7.26233006, 5.66236639, 7.26285219, 7.26315546, 7.26316977,
-    7.26304722, 8.56974411, 8.56950855, 7.26286602, 8.56934738, 7.26285267,
-    7.26222086, 9.70018578, 7.2619586,  8.56820774, 7.26159763, 7.26171827,
-    8.56776714, 8.56768799, 8.56782532, 8.56767941, 7.26149035, 5.66135073,
-    7.2610445,  5.66129827, 7.26097822, 7.26100349, 8.5669651,  7.26106882,
-    7.26106882, 5.66111708, 7.26081324, 8.56680489, 8.566782,   7.26056385,
-    5.66096687, 7.2607851,  7.26062346, 8.56641197, 7.26057196, 5.66081905,
-    7.26049137, 5.66070509, 8.5663147,  7.260355,   5.66067266, 7.26030159,
-    5.66066694, 8.56612587, 7.26016903, 5.66065979, 7.26020193, 7.26015854,
-    5.66048193, 7.2601285,  5.66040564, 7.26003408, 7.25977516, 7.25979948,
-    7.25979948, 7.25990009, 8.56573582, 8.56567383, 8.56564713, 8.56548023,
-    8.56536484, 7.25976038, 7.25939655, 8.56517696, 7.25946617, 7.2592926,
-    7.25933552, 7.25912762, 7.259233,   7.259233,   7.25921249, 8.56482887,
-    8.56491661, 8.5647707,  7.25928497, 7.25927353, 5.65945339, 7.25881672,
-    8.56448746, 7.25888014, 7.25897217, 7.25861311, 7.25880337, 7.25864649,
-    8.56429958, 8.56421947, 7.25852537, 5.65925407, 7.25833559, 8.56394577,
-    7.25835085, 5.65912724, 7.25824785, 8.56373119, 8.56378078, 7.25805569,
-    5.65889263, 8.56371403, 8.56366253, 8.56366253, 8.56360912, 8.56336212,
-    7.25795984, 7.25789499, 8.56327152, 7.25789213, 7.25780392, 7.25759506,
-    7.2575593,  8.56294441, 7.25779676, 7.25740194, 7.25758219, 8.56288433,
-    9.69409275, 7.25730848, 7.257442,   7.25724125, 5.6581893,  7.25718641,
-    7.25729465, 7.25708008, 8.56261635, 8.56247234, 8.56270409, 7.25689936,
-    7.25696611, 7.25700331, 7.25690079, 7.25690079, 8.56233883, 7.2568922,
-    7.25666666, 7.25684166, 8.56217766, 7.25662184, 5.65772009, 8.56178665,
-    7.25678968, 8.5621624,  7.25704145, 8.56277084, 8.56281567, 7.25745487,
-    7.25745487, 7.25763321, 7.25728941, 5.65848398, 7.2572279,  7.25712967,
-    7.25696802, 7.25671434, 5.65746641, 7.2564435,  8.56168652, 7.25604296,
-    7.25612974, 7.25607109, 8.56153679, 7.25630569, 8.56204414, 7.25693989,
-    8.56223011, 8.56249237, 8.56227398, 8.56167507, 7.25631618, 5.65710688,
-    7.25574017, 8.56087303, 8.56084633, 7.25568295, 8.56063843, 8.56056213,
-    7.25547934, 5.65683031, 7.25538158, 7.25533724, 8.56033134, 5.65690374,
-    5.65655518, 7.25524092, 5.65650988, 8.56029987, 7.25498247, 8.55978966,
-    7.25478649, 7.25467443, 9.69068527, 8.55987453, 7.25487518, 7.25471067,
-    7.2545743,  5.6562438,  8.55962849, 5.65616846, 7.25484991, 7.25441074,
-    7.25461817, 7.25455427, 8.55932999, 8.55924225, 9.69005775, 7.25433588,
-    7.25433588, 8.55896854, 7.25437307, 7.25407887, 7.25405073, 7.25412846,
-    7.25422907, 7.25415277, 7.25408459, 8.5588932,  5.65568542, 8.55883312,
-    5.65561199, 8.55877876, 7.25379658, 7.25379658, 8.55869579, 7.2537303,
-    7.25386381, 7.25361061, 5.65548229, 7.2535677,  5.65561199, 7.25340509,
-    7.25353432, 7.25369596, 7.25324774, 8.55786228, 7.25330639, 7.2533021,
-    8.55799294, 7.25335455, 7.25319529, 8.55805206, 8.55793667, 8.5575819,
-    5.65506649, 8.55790138, 5.65501547, 7.25293398, 7.2528553,  8.5573616,
-    8.55728531, 9.68801403, 8.5574913,  7.25287628, 7.25277567, 7.25278425,
-    7.25278997, 7.25253439, 8.55725384, 7.25249672, 8.55700302, 7.25253105,
-    8.55709553, 8.5569582,  7.25251722, 8.55688763, 8.5569849,  8.55723763,
-    8.55723763, 7.25223207, 8.55659676, 8.55668068, 5.65439987, 7.25216007,
-    7.25211763, 7.25200033, 7.25216198, 7.25210667, 7.25187397, 7.25212336,
-    7.25184345, 7.25200224, 7.25176382, 8.55617809, 7.25167179, 7.25205994,
-    8.55602264, 7.25169182, 8.55579948, 7.25172567, 7.25170994, 5.65390444,
-    8.55595493, 7.25141478, 8.55583096, 8.55572987, 8.55553055, 9.68609142,
-    7.25145721, 7.25135231, 7.25115252, 5.65349722, 8.55524635, 8.55536175,
-    7.25137615, 7.25113249, 8.55534649, 8.55531979, 7.25079775, 7.25078535,
-    8.5548172,  8.5549469,  8.55503178, 7.2507925,  7.25085068, 9.68505383,
-    7.25059462, 7.25072145, 8.55459213, 8.55461311, 8.55462551, 7.25028563,
-    8.55433846, 7.25050592, 7.25021172, 5.65288115, 7.25018215, 8.55431271,
-    8.55431271, 8.55459404, 8.55426311, 8.55444622, 8.55416203, 8.55414963,
-    7.25023746, 7.25019789, 7.25023174, 9.68446255, 8.55406952, 8.55403042,
-    8.5539856,  8.55387115, 8.55405903, 5.65262175, 5.65249205, 7.24991274,
-    7.24984884, 7.24983072, 8.55391216, 7.24978399, 7.24971724, 8.55356598,
-    7.24967194, 7.24956989, 8.55361843, 8.55347538, 7.24954319, 7.24937868,
-    9.68331528, 7.24953318, 5.65228748, 5.652246,   8.55346203, 8.55348969,
-    7.24943733, 7.24951839, 9.68309498, 8.55303669, 7.24932718, 8.55316162,
-    8.55313492, 8.55292797, 5.6518712,  7.24900436, 7.24881744, 8.552742,
-    7.24881029, 8.55268097, 7.24863386, 8.55238819, 8.55251598, 8.55226612,
-    8.55213356, 7.2486558,  7.24858665, 7.24843979, 8.5519743,  7.2485404,
-    8.55237484, 5.6512804,  9.68210697, 5.65125036, 5.65126991, 7.24832678,
-    7.24830437, 8.55171585, 8.55191326, 7.24792719, 5.65123224, 5.65116167,
-    5.65111923, 7.10352278, 8.55168629, 7.24795628, 7.24798918, 5.65098667,
-    7.24778652, 5.65081835, 7.24775505, 8.55150986, 8.55104733, 7.24750519,
-    7.24751616, 7.24740601, 5.65071297, 7.2471199,  8.55104923, 7.24718094,
-    7.24718094, 5.65045595, 5.65034771, 7.24705362, 8.55052853, 8.55055237,
-    9.68021393, 7.24703074, 7.24700546, 7.2468791,  8.55047607, 8.55031967,
-    8.55006409, 7.24671173, 8.55018425, 5.65006161, 7.24654198, 7.24667978,
-    8.55024052, 8.55002308, 8.54984283, 7.2463932,  8.549963,   7.24624062,
-    5.64966202, 8.54976463, 7.2464385,  7.24616528, 5.64968157, 7.24625301,
-    7.24625301, 5.64964485, 7.24600124, 7.24617243, 7.24603462, 7.24565554,
-    7.24591446, 8.54931736, 7.24572277, 7.24607801, 7.24639654, 7.24686337,
-    5.64997101, 5.46363926, 7.25156784, 3.37094092, 3.3684454,  8.42868042,
-    9.57192612, 8.42880917, 8.42844296, 8.42857552, 9.57120419, 8.42841721,
-    7.24512768, 7.24531698, 7.24521542, 7.24513388, 8.54863071, 7.24524355,
-    7.24524355, 7.2449584,  7.24519587, 8.54811764, 9.67825794, 8.54873371,
-    7.10020876, 8.4287529,  8.42825603, 8.42836761, 7.10093164, 9.57135582,
-    9.57128143, 9.57122707, 9.5712347,  8.428545,   8.42840672, 8.42864037,
-    9.57113743, 8.42865944, 7.10092306, 7.1008482,  9.57125187, 8.42864418,
-    8.42878723, 8.42864037, 9.57126236, 9.57108593, 8.42838001, 8.42839146,
-    9.57105923, 9.5710125,  9.57113552, 9.57125187, 7.10095406, 7.1009655,
-    8.42864895, 8.4284811,  8.42847538, 8.42857075, 8.4283371,  8.42842674,
-    8.42862797, 8.42862415, 9.57119846, 8.42851353, 8.42839527, 8.42869663,
-    8.42868996, 7.10073709, 7.10088396, 9.57122993, 9.57119274, 7.1010108,
-    8.42820644, 7.10094309, 8.428442,   8.42838955, 7.10102987, 8.42846394,
-    7.10093975, 8.42840576, 8.42843342, 8.42841434, 7.10092974, 8.42848778,
-    9.57113075, 8.42837715, 7.10103798, 8.42836857, 7.10095501, 8.4285183,
-    9.57118511, 8.42850304, 8.42868614, 7.10112667, 7.10101271, 8.4285059,
-    8.42863846, 7.10092402, 8.42842674, 8.42856693, 9.57147312, 8.42837334,
-    8.42853928, 9.57138634, 8.42846012, 8.42863846, 8.42846298, 8.42854691,
-    7.10100889, 8.42851162, 8.42870522, 7.10092068, 8.42854214, 7.1009593,
-    8.4288168,  7.10105085, 9.57123661, 7.24546003, 7.24555874, 5.64907312,
-    7.24532652, 8.54855824, 8.54862595, 7.24536324, 8.54894733, 8.54878044,
-    9.67820072, 7.24535894, 9.67810154, 8.54867935, 7.24545479, 8.548522,
-    7.24543715, 9.67821407, 7.24544954, 8.54859447, 7.24540424, 9.67797375,
-    8.54864597, 9.67788601, 7.24540663, 8.54864693, 7.24544239, 7.24534893,
-    7.24559736, 7.24541664, 8.54880142, 8.54874325, 9.67810822, 8.5487833,
-    7.24539614, 7.24536085, 8.54876518, 7.24548101, 8.54850388, 8.5486517,
-    7.24551249, 8.5488081,  8.54863453, 7.2455368,  8.54872322, 8.54858303,
-    9.6779995,  8.54874039, 7.24553061, 8.54874229, 7.24536753, 8.5488472,
-    8.5488472,  7.24538708, 5.6490202,  9.67805672, 5.64908886, 8.54893017,
-    7.24557877, 7.24542999, 8.54860115, 8.54863644, 7.2454915,  7.24547625,
-    8.54874134, 7.24553537, 7.24555111, 8.54884815, 9.67792988, 7.24539948,
-    7.2455492,  7.24530125, 7.24537611, 7.24520969, 7.24547386, 8.5486784,
-    7.24558544, 8.54885006, 7.24545813, 7.24534845, 7.24542189, 8.54862404,
-    9.67794895, 8.54870033, 7.24543905, 9.678298,   7.24546051, 8.54885578,
-    7.24557638, 8.54884434, 7.24532843, 9.67792511, 8.54874706, 5.64910603,
-    8.54879284, 7.24535847, 9.67820644, 8.54885197, 9.67829227, 7.24568176,
-    8.54878044, 8.54878426, 9.67803574, 8.54872894, 7.24547672, 8.54866505,
-    8.5488224,  8.54887772, 7.24542904, 7.24542189, 7.24536514, 7.24555969,
-    8.54885864, 8.54864979, 9.67793369, 8.54869938, 8.54872608, 7.24535036,
-    7.24536753, 7.24552155, 7.24548578, 5.64906788, 7.24538946, 7.24533701,
-    7.24556303, 7.24538946, 8.54896259, 7.24564791, 8.54893398, 8.5488739,
-    7.24552155, 9.67792606, 7.24553394, 7.24541426, 7.24551487, 8.54875183,
-    7.24564695, 8.54863834, 9.67806911, 8.54866695, 3.04500675, 7.10104704,
-    9.5712862,  8.42847538, 7.1011796,  8.4287672,  7.10095692, 7.10102034,
-    8.42850971, 9.57134724, 8.42857933, 8.42859364, 8.4284935,  8.4283762,
-    7.10103607, 7.10089874, 8.42836475, 5.46396208, 3.36807752, 8.42859268,
-    7.10104084, 7.100914,   3.04496884, 8.42867851, 8.4285984,  3.04501152,
-    5.64914608, 7.10101652, 8.42857456, 8.42857361, 8.42860985, 8.42871094,
-    9.57142353, 8.42868614, 7.2454505,  8.4284029,  7.10101032, 3.36808872,
-    3.04504347, 8.42857265, 7.10102367, 8.42846966, 5.64913654, 8.42867661,
-    5.46405458, 5.4641037,  7.10097075, 7.10097075, 9.57109261, 5.64907026,
-    9.57126427, 7.10087252, 5.64899302, 5.46416044, 8.42867565, 7.10102081,
-    3.0449779,  3.04504228, 8.42847252, 7.10094595, 8.4284668,  8.42854977,
-    8.42854977, 8.42850494, 7.2454505,  8.42854977, 7.1010952,  9.57125759,
-    9.5714159,  3.36807466, 5.46410608, 7.10106945, 7.10103035, 7.10110712,
-    3.36813903, 7.10105944, 7.10098886, 8.42852306, 8.4284153,  8.42852592,
-    8.42850113, 3.0450294,  8.42829037, 8.4286375,  7.24541759, 7.1008606,
-    8.42870426, 8.42858601, 3.36807442, 8.54880619, 8.42840481, 7.10107565,
-    8.42862511, 7.10099316, 8.42841148, 5.6489954,  9.57114029, 5.46398115,
-    7.24545479, 3.36805773, 8.42847729, 7.10098934, 5.46399784, 3.36807752,
-    5.46398401, 7.10101175, 7.10096073, 8.42848873, 8.42824173, 7.24545765,
-    5.46405935, 5.64890766, 3.3680203,  8.5487566,  9.57122612, 7.10083675,
-    5.64896965, 5.46405077, 8.42843437, 8.54873371, 7.24538803, 7.10098839,
-    3.04499364, 8.4284668,  5.6490097,  8.42846203, 8.42853737, 3.04499555,
-    8.42841721, 8.54864311, 7.10086012, 7.10118818, 5.64909124, 8.42842484,
-    7.10094309, 3.36813259, 7.24543285, 8.428545,   7.24546289, 7.245327,
-    7.24537659, 8.5482502,  8.54854012, 7.24545431, 7.24539614, 9.67787552,
-    9.6777153,  8.5486412,  7.24538374, 7.24531031, 8.54841423, 8.54879951,
-    9.67814732, 8.54858971, 8.54860973, 8.5487566,  8.54844952, 7.24545097,
-    9.67816162, 7.24541998, 8.54874897, 8.54876995, 8.5487833,  9.67811584,
-    8.54877567, 7.24530172, 8.54862404, 8.54862404, 7.24525642, 7.24555159,
-    7.24561071, 8.54864693, 8.54877472, 8.5489006,  7.24542665, 9.67788696,
-    9.6779623,  8.54860687, 7.24537039, 8.54876709, 8.54876328, 7.2455492,
-    7.2455492,  7.24531937, 7.24541426, 8.54865742, 9.67789841, 8.54874897,
-    8.54868698, 8.54879856, 8.54867077, 9.67799473, 7.24543953, 7.24538422,
-    8.54859543, 8.54849625, 7.24532604, 7.24532604, 8.54859734, 8.54887295,
-    8.5487175,  8.54844284, 8.54866409, 8.54863548, 8.54869366, 9.67795372,
-    7.24526262, 8.5487442,  7.24523973, 7.24526501, 8.54886913, 10.6894016,
-    8.54865932, 7.24516201, 8.54880714, 7.24530602, 8.54856491, 7.24531555,
-    8.54861736, 7.24542475, 8.54858685, 8.54860497, 8.54874706, 8.5486145,
-    8.54876232, 8.54862118, 7.24545193, 8.5487318,  7.24531507, 7.24539566,
-    8.5487566,  7.24530697, 9.6778307,  8.54864216, 8.5487957,  9.67823124,
-    8.54878998, 9.67807007, 7.24551582, 7.24530745, 8.54856682, 8.54863167,
-    9.67795753, 8.54868317, 8.54869652, 8.54869175, 7.24533987, 9.6779089,
-    9.67794037, 8.54869556, 8.54859161, 7.24542713, 8.54850006, 7.24544525,
-    7.2452364,  8.54864407, 7.24532986, 8.54858685, 8.54850101, 8.54864216,
-    8.54854488, 9.67793751, 9.67785645, 8.54859447, 7.24539995, 7.24516296,
-    8.54874802, 7.24538231, 7.10097742, 5.64900589, 8.54846287, 9.67804337,
-    9.67804337, 9.67807293, 3.04497218, 7.10076523, 8.42840195, 9.67793846,
-    8.42849731, 7.10094786, 5.6490345,  5.64898491, 8.42831802, 7.24532843,
-    7.24534321, 7.10093927, 8.54858303, 8.42842102, 8.4285326,  3.04494166,
-    7.24514961, 5.46398306, 5.46397352, 3.36808443, 8.42861557, 7.10091591,
-    3.36799455, 3.36801362, 5.64899302, 7.24537277, 5.64897776, 8.54866791,
-    9.67799759, 8.54859638, 8.42818928, 5.46391582, 9.67796993, 8.54866982,
-    7.2453022,  3.36811757, 8.54859352, 8.54864693, 5.46399832, 8.42839432,
-    7.10096121, 8.54865074, 7.24533892, 8.54859734, 8.54843903, 5.46399736,
-    5.64901304, 8.54851532, 7.10091066, 8.42855453, 8.54862022, 8.54861546,
-    9.67809486, 8.54871464, 3.36806703, 3.04499364, 5.6490078,  8.54854012,
-    7.2452898,  8.42834663, 9.67762852, 7.24548531, 3.36801696, 8.54853439,
-    7.24530888, 8.54851246, 7.10093832, 7.10067272, 8.54868984, 8.54847813,
-    3.04493189, 8.5484705,  7.24545097, 3.04500961, 5.46406269, 3.36800504,
-    7.10094357, 8.54851151, 8.54866886, 10.5927849, 7.24540377, 7.10075283,
-    7.24534369, 8.54843235, 9.67783642, 7.24517918, 8.54879951, 8.548522,
-    8.548522,   9.67778301, 8.54860115, 7.10093164, 8.42852306, 5.64902306,
-    3.04495406, 7.24548578, 3.04489493, 3.04494214, 7.24534893, 8.54843903,
-    5.46406937, 3.36802626, 9.67804337, 7.24543238, 5.64898205, 8.54842758,
-    3.04494452, 3.04497337, 7.24522591, 8.54879475, 7.2453618,  8.42841053,
-    9.57095623, 7.10093355, 5.46401739, 8.42823792, 8.54849911, 8.54875183,
-    5.64911509, 7.24519968, 3.36812043, 7.24549627, 3.04498339, 7.10086727,
-    8.42856026, 8.42859173, 3.04481268, 7.24532175, 3.36802101, 8.42823792,
-    8.54860115, 3.36796093, 9.67775059, 9.67775059, 9.67768764, 8.54860115,
-    9.67777348, 8.54845715, 8.54848385, 7.24536133, 8.54850864, 8.54850769,
-    9.67781639, 7.24537849, 7.24520159, 8.54855919, 8.54855537, 7.24519587,
-    8.54842854, 9.677948,   9.67787457, 8.5485487,  8.54859638, 8.54852486,
-    8.54869843, 8.54856968, 7.24519157, 10.6890306, 8.54838657, 7.24541616,
-    8.54855347, 9.67801189, 8.54869461, 8.54869461, 7.24515867, 8.5485239,
-    8.54871655, 8.54845047, 8.54845428, 7.24527645, 8.54839706, 7.24514294,
-    7.24548101, 8.54843044, 8.54857635, 8.54848385, 8.54835129, 8.5487299,
-    8.5487299,  8.54850483, 8.54849625, 8.54861069, 7.24535179, 8.5484066,
-    8.54865646, 7.24535894, 7.24524355, 10.6893644, 8.54849148, 8.54852676,
-    7.24538612, 7.24532795, 9.67798424, 8.54865551, 10.6891737, 7.2452693,
-    8.54872513, 8.54863167, 9.67783546, 8.548522,   8.5486517,  8.54854679,
-    8.54851913, 8.54853058, 7.24531841, 8.54833317, 9.67802525, 9.67797279,
-    8.54864502, 8.54887867, 8.54854679, 7.24550486, 8.54846764, 9.67776108,
-    5.64895296, 10.6895771, 9.67808437, 7.24518299, 9.67793846, 8.5486908,
-    9.67781734, 8.54827976, 9.67785645, 8.54854298, 7.2452569,  8.54874706,
-    9.67804909, 3.04495716, 7.24530792, 3.04493141, 8.54869556, 7.24528456,
-    3.36803365, 9.67791367, 8.54862022, 8.54866791, 7.24512434, 9.67784405,
-    8.54853153, 7.10101318, 7.24540567, 8.54863548, 9.67797852, 8.54854393,
-    8.42855549, 8.54858875, 9.6777401,  9.67780876, 8.54880238, 7.24542999,
-    9.67799664, 9.67793846, 9.67816734, 9.67816734, 5.64909172, 9.67804813,
-    9.67784214, 8.54853344, 8.54864025, 5.6489892,  8.54871655, 7.24519587,
-    8.54860115, 8.54881001, 7.24530077, 7.24541664, 9.67792988, 5.46404219,
-    8.54865074, 8.54857445, 8.54853439, 8.54873848, 8.54854107, 8.54854488,
-    8.54865932, 7.24547338, 7.24516535, 8.54849148, 8.54853058, 9.67776966,
-    8.5487051,  9.67784119, 8.54872322, 7.24544525, 9.67783737, 8.54861641,
-    8.5487442,  8.54861069, 9.6781168,  7.24540949, 7.24533892, 3.04493976,
-    8.54883671, 9.67795563, 9.67778397, 8.54867268, 9.6780014,  8.54862785,
-    9.67795277, 8.54854679, 8.54880428, 8.54883575, 7.24538469, 9.67802906,
-    8.54888344, 9.67798042, 8.54868507, 5.46399879, 10.6895142, 8.54852676,
-    8.54869843, 8.54868317, 8.54869843, 3.04499841, 3.36809969, 7.24543095,
-    9.67807961, 9.67805576, 9.67798233, 8.54868221, 8.54860497, 8.54870701,
-    8.54848385, 8.5486412,  9.67798615, 8.54881287, 9.67815304, 7.24539518,
-    5.64905691, 9.67804432, 3.3681438,  9.67823029, 8.54854393, 8.54850578,
-    7.24552011, 9.67810535, 8.54876232, 9.67815113, 8.54876328, 9.67800903,
-    8.54845333, 8.54876232, 9.67807293, 9.67807293, 7.24555397, 9.67800236,
-    8.54891872, 8.54874134, 9.67811108, 8.5487175,  9.6781702,  8.54857922,
-    9.67806149, 9.67820644, 9.67806911, 5.46411324, 8.54864311, 3.36811256,
-    8.548769,   8.54872608, 7.24541473, 9.67819977, 8.54888153, 7.24551058,
-    7.2453866,  8.54862022, 3.04508567, 3.36803555, 5.64911175, 5.64906168,
-    7.24531889, 8.54879284, 7.24552441, 8.54881668, 9.67796135, 9.67796993,
-    9.67819977, 8.54873562, 5.46410894, 8.42869854, 7.10112619, 5.46413422,
-    5.46404457, 7.10100889, 7.10103083, 7.10087013, 8.42854595, 5.46431112,
-    7.1013093,  8.42872524, 8.42856789, 8.42877579, 8.4286108,  7.10108471,
-    7.10111713, 8.42870522, 7.10117722, 7.10108423, 7.10116291, 5.46417046,
-    5.46410227, 8.42852306, 7.10091877, 7.10091877, 8.42876053, 7.1011095,
-    8.42865086, 8.42845726, 7.10110044, 8.42866516, 5.46416044, 7.10095024,
-    5.46399307, 5.46412134, 7.10102654, 8.42853832, 7.10112858, 8.42865181,
-    8.42865181, 7.10094023, 7.10088062, 8.42878056, 7.10099649, 7.1011157,
-    7.10101175, 5.46409607, 7.10099077, 7.10110712, 7.1011138,  7.10096455,
-    8.4284668,  7.10101175, 5.46410799, 7.10104561, 8.42859745, 5.46416044,
-    7.10087252, 5.46405506, 8.42874813, 7.10093355, 5.4641819,  5.4641881,
-    5.46416664, 7.10129452, 7.10114193, 7.1008954,  8.42853546, 5.4641099,
-    5.4641099,  7.10110474, 7.1011548,  8.42870617, 5.46414089, 7.10110712,
-    8.42862034, 5.4642539,  7.10094786, 7.10091734, 7.10112095, 7.10101986,
-    8.54879189, 8.54861546, 9.67801952, 8.54868698, 8.54884529, 8.54895592,
-    8.54869461, 9.67792988, 9.67812061, 9.67813778, 8.54891109, 11.6121511,
-    8.54892159, 7.24555683, 7.24559784, 8.54881954, 9.67842865, 8.54896736,
-    7.24565172, 8.54852104, 8.54890347, 8.54875278, 9.67812347, 10.6893873,
-    9.67832088, 8.5486536};
diff --git a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_gps_data.cpp b/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_gps_data.cpp
deleted file mode 100644
index 693cea75a..000000000
--- a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_gps_data.cpp
+++ /dev/null
@@ -1,10979 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Authors: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include "lynx_gps_data.h"
-
-const float GPS_DATA_LAT[GPS_DATA_SIZE] = {
-    41.808651,  41.808651,  41.808651,  41.808651,  41.808651,  41.808651,
-    41.808651,  41.808651,  41.808651,  41.808651,  41.808651,  41.8086472,
-    41.8086472, 41.8086472, 41.8086433, 41.8086395, 41.8086395, 41.8086357,
-    41.8086357, 41.8086319, 41.8086319, 41.8086281, 41.8086243, 41.8086205,
-    41.8086166, 41.8086128, 41.8086128, 41.808609,  41.8086014, 41.8085976,
-    41.8085938, 41.8085938, 41.8085861, 41.8085823, 41.8085747, 41.8085747,
-    41.8085747, 41.8085594, 41.8085518, 41.8085518, 41.8085442, 41.8085365,
-    41.8085327, 41.8085251, 41.8085175, 41.8085136, 41.808506,  41.8084984,
-    41.8084908, 41.8084831, 41.8084755, 41.8084679, 41.8084602, 41.8084526,
-    41.808445,  41.8084335, 41.8084297, 41.8084221, 41.8084145, 41.808403,
-    41.8083954, 41.8083878, 41.8083725, 41.8083649, 41.8083534, 41.808342,
-    41.8083344, 41.8083191, 41.8083038, 41.8082924, 41.8082771, 41.8082619,
-    41.8082466, 41.8082314, 41.8082161, 41.808197,  41.8081818, 41.8081665,
-    41.8081512, 41.808136,  41.8081207, 41.8081093, 41.8080978, 41.8080788,
-    41.8080673, 41.8080521, 41.8080368, 41.8080254, 41.8080101, 41.8079987,
-    41.8079834, 41.807972,  41.8079567, 41.8079453, 41.8079338, 41.8079224,
-    41.8079071, 41.8078957, 41.8078804, 41.807869,  41.8078575, 41.8078461,
-    41.8078346, 41.8078232, 41.8078156, 41.8078041, 41.8078003, 41.8077888,
-    41.8077774, 41.8077698, 41.8077583, 41.8077507, 41.8077393, 41.8077316,
-    41.8077202, 41.8077126, 41.8077011, 41.8076935, 41.807682,  41.8076744,
-    41.807663,  41.8076591, 41.8076477, 41.8076401, 41.8076286, 41.807621,
-    41.8076134, 41.8076019, 41.8075981, 41.8075867, 41.807579,  41.8075714,
-    41.80756,   41.8075523, 41.8075409, 41.8075371, 41.8075256, 41.807518,
-    41.8075104, 41.8074989, 41.8074913, 41.8074837, 41.807476,  41.8074646,
-    41.8074608, 41.8074493, 41.8074417, 41.8074341, 41.8074226, 41.807415,
-    41.8074036, 41.8073959, 41.8073883, 41.8073807, 41.8073692, 41.8073616,
-    41.807354,  41.8073425, 41.8073349, 41.8073273, 41.8073196, 41.8073082,
-    41.8073006, 41.8072929, 41.8072815, 41.8072739, 41.8072662, 41.8072586,
-    41.8072472, 41.8072395, 41.8072319, 41.8072243, 41.8072128, 41.8072052,
-    41.8071976, 41.8071899, 41.8071823, 41.8071747, 41.8071632, 41.8071594,
-    41.807148,  41.8071442, 41.8071327, 41.8071251, 41.8071213, 41.8071098,
-    41.8071022, 41.8070946, 41.8070869, 41.8070831, 41.8070717, 41.8070641,
-    41.8070602, 41.8070526, 41.807045,  41.8070374, 41.8070297, 41.8070221,
-    41.8070145, 41.8070068, 41.8069992, 41.8069916, 41.8069839, 41.8069763,
-    41.8069687, 41.8069611, 41.8069534, 41.8069458, 41.8069382, 41.8069267,
-    41.8069229, 41.8069115, 41.8069038, 41.8068962, 41.8068886, 41.806881,
-    41.8068733, 41.8068657, 41.8068542, 41.8068466, 41.806839,  41.8068314,
-    41.8068237, 41.8068161, 41.8068085, 41.8068008, 41.8067932, 41.8067856,
-    41.806778,  41.8067665, 41.8067627, 41.8067513, 41.8067474, 41.806736,
-    41.8067284, 41.8067245, 41.8067131, 41.8067055, 41.8066978, 41.8066902,
-    41.8066864, 41.806675,  41.8066673, 41.8066635, 41.8066559, 41.8066483,
-    41.8066406, 41.806633,  41.8066254, 41.8066216, 41.8066139, 41.8066063,
-    41.8066025, 41.8065948, 41.8065872, 41.8065834, 41.8065758, 41.8065681,
-    41.8065643, 41.8065567, 41.8065491, 41.8065453, 41.8065376, 41.80653,
-    41.8065262, 41.8065186, 41.8065109, 41.8065071, 41.8064995, 41.8064919,
-    41.8064842, 41.8064766, 41.806469,  41.8064651, 41.8064575, 41.8064499,
-    41.8064461, 41.8064384, 41.806427,  41.8064232, 41.8064156, 41.8064079,
-    41.8064003, 41.8063927, 41.8063889, 41.8063774, 41.8063698, 41.806366,
-    41.8063545, 41.8063469, 41.8063393, 41.8063316, 41.8063278, 41.8063164,
-    41.8063087, 41.8063049, 41.8062935, 41.8062897, 41.806282,  41.8062744,
-    41.8062668, 41.8062592, 41.8062515, 41.8062439, 41.8062363, 41.8062286,
-    41.8062248, 41.8062134, 41.8062096, 41.8062019, 41.8061943, 41.8061867,
-    41.806179,  41.8061714, 41.8061676, 41.80616,   41.8061485, 41.8061447,
-    41.8061371, 41.8061295, 41.8061218, 41.8061142, 41.8061104, 41.8061028,
-    41.8060951, 41.8060913, 41.8060799, 41.8060722, 41.8060684, 41.8060608,
-    41.8060532, 41.8060493, 41.8060417, 41.8060341, 41.8060303, 41.8060188,
-    41.8060112, 41.8060074, 41.8059998, 41.8059921, 41.8059883, 41.8059807,
-    41.8059731, 41.8059692, 41.8059616, 41.805954,  41.8059502, 41.8059425,
-    41.8059349, 41.8059311, 41.8059235, 41.8059158, 41.805912,  41.8059044,
-    41.8058968, 41.8058929, 41.8058853, 41.8058777, 41.8058739, 41.8058624,
-    41.8058548, 41.805851,  41.8058434, 41.8058357, 41.8058319, 41.8058243,
-    41.8058167, 41.8058128, 41.8058014, 41.8057938, 41.8057899, 41.8057823,
-    41.8057747, 41.8057709, 41.8057594, 41.8057518, 41.805748,  41.8057404,
-    41.8057327, 41.8057289, 41.8057175, 41.8057137, 41.805706,  41.8056984,
-    41.8056908, 41.8056831, 41.8056755, 41.8056717, 41.8056641, 41.8056564,
-    41.8056488, 41.8056412, 41.8056335, 41.8056297, 41.8056221, 41.8056145,
-    41.8056068, 41.8055992, 41.8055954, 41.8055878, 41.8055763, 41.8055725,
-    41.8055649, 41.8055573, 41.8055496, 41.805542,  41.8055344, 41.8055305,
-    41.8055229, 41.8055153, 41.8055077, 41.8055,    41.8054962, 41.8054886,
-    41.8054771, 41.8054733, 41.8054657, 41.8054581, 41.8054543, 41.8054466,
-    41.8054352, 41.8054314, 41.8054237, 41.8054161, 41.8054123, 41.8054008,
-    41.805397,  41.8053894, 41.8053818, 41.8053741, 41.8053665, 41.8053589,
-    41.8053551, 41.8053474, 41.8053398, 41.805336,  41.8053246, 41.8053169,
-    41.8053131, 41.8053055, 41.8052979, 41.8052902, 41.8052826, 41.805275,
-    41.8052711, 41.8052635, 41.8052559, 41.8052483, 41.8052406, 41.8052368,
-    41.8052292, 41.8052216, 41.8052139, 41.8052063, 41.8051987, 41.8051949,
-    41.8051872, 41.8051796, 41.8051758, 41.8051682, 41.8051605, 41.8051567,
-    41.8051491, 41.8051414, 41.8051376, 41.80513,   41.8051224, 41.8051186,
-    41.8051109, 41.8051033, 41.8050957, 41.805088,  41.8050804, 41.8050766,
-    41.8050652, 41.8050575, 41.8050499, 41.8050423, 41.8050385, 41.8050308,
-    41.8050232, 41.8050194, 41.8050117, 41.8050041, 41.8050003, 41.8049927,
-    41.804985,  41.8049774, 41.8049736, 41.8049698, 41.8049622, 41.8049583,
-    41.8049545, 41.8049507, 41.8049431, 41.8049393, 41.8049355, 41.8049278,
-    41.804924,  41.8049202, 41.8049164, 41.8049126, 41.8049049, 41.8049011,
-    41.8048973, 41.8048935, 41.8048897, 41.8048859, 41.804882,  41.8048782,
-    41.8048744, 41.8048706, 41.8048668, 41.8048592, 41.8048592, 41.8048553,
-    41.8048515, 41.8048477, 41.8048439, 41.8048401, 41.8048401, 41.8048363,
-    41.8048325, 41.8048286, 41.8048248, 41.804821,  41.804821,  41.8048172,
-    41.8048134, 41.8048096, 41.8048058, 41.8048058, 41.8048019, 41.8047981,
-    41.8047981, 41.8047943, 41.8047905, 41.8047905, 41.8047867, 41.8047829,
-    41.8047791, 41.8047791, 41.8047791, 41.8047752, 41.8047714, 41.8047714,
-    41.8047676, 41.8047638, 41.80476,   41.80476,   41.80476,   41.8047562,
-    41.8047562, 41.8047523, 41.8047485, 41.8047485, 41.8047447, 41.8047447,
-    41.8047409, 41.8047409, 41.8047409, 41.8047371, 41.8047333, 41.8047333,
-    41.8047295, 41.8047295, 41.8047256, 41.8047256, 41.8047218, 41.8047218,
-    41.8047218, 41.804718,  41.804718,  41.8047142, 41.8047142, 41.8047104,
-    41.8047104, 41.8047066, 41.8047066, 41.8047028, 41.8047028, 41.8046989,
-    41.8046989, 41.8046989, 41.8046989, 41.8046951, 41.8046951, 41.8046913,
-    41.8046913, 41.8046875, 41.8046875, 41.8046875, 41.8046837, 41.8046837,
-    41.8046799, 41.8046799, 41.8046799, 41.8046799, 41.8046799, 41.8046761,
-    41.8046761, 41.8046761, 41.8046722, 41.8046722, 41.8046722, 41.8046684,
-    41.8046684, 41.8046646, 41.8046646, 41.8046646, 41.8046646, 41.8046608,
-    41.8046608, 41.8046608, 41.8046608, 41.8046608, 41.804657,  41.804657,
-    41.804657,  41.8046532, 41.8046532, 41.8046494, 41.8046494, 41.8046494,
-    41.8046455, 41.8046455, 41.8046455, 41.8046417, 41.8046417, 41.8046417,
-    41.8046417, 41.8046417, 41.8046379, 41.8046379, 41.8046379, 41.8046341,
-    41.8046341, 41.8046341, 41.8046303, 41.8046303, 41.8046265, 41.8046265,
-    41.8046265, 41.8046227, 41.8046227, 41.8046227, 41.8046227, 41.8046227,
-    41.8046188, 41.8046188, 41.8046188, 41.804615,  41.804615,  41.804615,
-    41.8046112, 41.8046112, 41.8046112, 41.8046074, 41.8046074, 41.8046074,
-    41.8046074, 41.8046036, 41.8046036, 41.8046036, 41.8045998, 41.8045998,
-    41.8045998, 41.8045998, 41.8045998, 41.8045998, 41.8045998, 41.8045959,
-    41.8045959, 41.8045959, 41.8045959, 41.8045921, 41.8045921, 41.8045921,
-    41.8045921, 41.8045921, 41.8045883, 41.8045883, 41.8045883, 41.8045883,
-    41.8045883, 41.8045883, 41.8045883, 41.8045845, 41.8045845, 41.8045845,
-    41.8045845, 41.8045845, 41.8045845, 41.8045845, 41.8045845, 41.8045807,
-    41.8045807, 41.8045807, 41.8045807, 41.8045807, 41.8045807, 41.8045807,
-    41.8045807, 41.8045807, 41.8045807, 41.8045807, 41.8045807, 41.8045807,
-    41.8045807, 41.8045807, 41.8045807, 41.8045807, 41.8045807, 41.8045807,
-    41.8045807, 41.8045807, 41.8045807, 41.8045807, 41.8045807, 41.8045769,
-    41.8045769, 41.8045769, 41.8045769, 41.8045769, 41.8045769, 41.8045769,
-    41.8045769, 41.8045769, 41.8045769, 41.8045769, 41.8045769, 41.8045769,
-    41.8045769, 41.8045769, 41.8045731, 41.8045731, 41.8045731, 41.8045731,
-    41.8045731, 41.8045731, 41.8045692, 41.8045692, 41.8045692, 41.8045692,
-    41.8045692, 41.8045692, 41.8045692, 41.8045692, 41.8045692, 41.8045654,
-    41.8045654, 41.8045654, 41.8045654, 41.8045654, 41.8045616, 41.8045616,
-    41.8045616, 41.8045616, 41.8045616, 41.8045616, 41.8045616, 41.8045616,
-    41.8045616, 41.8045616, 41.8045616, 41.8045616, 41.8045616, 41.8045616,
-    41.8045578, 41.8045578, 41.8045578, 41.8045578, 41.804554,  41.804554,
-    41.804554,  41.804554,  41.804554,  41.804554,  41.804554,  41.8045502,
-    41.8045502, 41.8045502, 41.8045502, 41.8045464, 41.8045464, 41.8045464,
-    41.8045464, 41.8045425, 41.8045425, 41.8045425, 41.8045425, 41.8045425,
-    41.8045425, 41.8045425, 41.8045425, 41.8045425, 41.8045425, 41.8045425,
-    41.8045387, 41.8045387, 41.8045387, 41.8045387, 41.8045387, 41.8045349,
-    41.8045349, 41.8045349, 41.8045311, 41.8045311, 41.8045311, 41.8045311,
-    41.8045311, 41.8045273, 41.8045273, 41.8045273, 41.8045273, 41.8045235,
-    41.8045235, 41.8045235, 41.8045235, 41.8045235, 41.8045235, 41.8045197,
-    41.8045197, 41.8045197, 41.8045197, 41.8045158, 41.8045158, 41.8045158,
-    41.8045158, 41.8045158, 41.804512,  41.804512,  41.804512,  41.804512,
-    41.8045082, 41.8045082, 41.8045082, 41.8045082, 41.8045082, 41.8045082,
-    41.8045044, 41.8045044, 41.8045044, 41.8045006, 41.8045006, 41.8045006,
-    41.8045006, 41.8045006, 41.8045006, 41.8045006, 41.8044968, 41.8044968,
-    41.8044968, 41.8044968, 41.804493,  41.804493,  41.804493,  41.804493,
-    41.804493,  41.804493,  41.804493,  41.8044891, 41.8044891, 41.8044891,
-    41.8044891, 41.8044891, 41.8044891, 41.8044853, 41.8044853, 41.8044815,
-    41.8044815, 41.8044815, 41.8044815, 41.8044815, 41.8044815, 41.8044815,
-    41.8044815, 41.8044815, 41.8044815, 41.8044777, 41.8044777, 41.8044777,
-    41.8044777, 41.8044777, 41.8044739, 41.8044739, 41.8044739, 41.8044739,
-    41.8044739, 41.8044701, 41.8044701, 41.8044701, 41.8044701, 41.8044662,
-    41.8044662, 41.8044662, 41.8044662, 41.8044624, 41.8044624, 41.8044624,
-    41.8044624, 41.8044624, 41.8044624, 41.8044624, 41.8044624, 41.8044624,
-    41.8044624, 41.8044624, 41.8044624, 41.8044624, 41.8044624, 41.8044624,
-    41.8044624, 41.8044586, 41.8044586, 41.8044586, 41.8044586, 41.8044586,
-    41.8044586, 41.8044586, 41.8044586, 41.8044586, 41.8044586, 41.8044548,
-    41.8044548, 41.8044548, 41.8044548, 41.8044548, 41.8044548, 41.8044548,
-    41.804451,  41.804451,  41.804451,  41.804451,  41.8044472, 41.8044472,
-    41.8044472, 41.8044472, 41.8044434, 41.8044434, 41.8044434, 41.8044434,
-    41.8044434, 41.8044434, 41.8044434, 41.8044434, 41.8044395, 41.8044395,
-    41.8044395, 41.8044395, 41.8044395, 41.8044357, 41.8044357, 41.8044357,
-    41.8044357, 41.8044319, 41.8044319, 41.8044319, 41.8044319, 41.8044281,
-    41.8044281, 41.8044281, 41.8044281, 41.8044243, 41.8044243, 41.8044243,
-    41.8044243, 41.8044243, 41.8044243, 41.8044243, 41.8044243, 41.8044243,
-    41.8044243, 41.8044205, 41.8044205, 41.8044205, 41.8044167, 41.8044167,
-    41.8044167, 41.8044167, 41.8044128, 41.8044128, 41.8044128, 41.8044128,
-    41.804409,  41.804409,  41.804409,  41.804409,  41.8044052, 41.8044052,
-    41.8044052, 41.8044052, 41.8044052, 41.8044052, 41.8044014, 41.8044014,
-    41.8044014, 41.8044014, 41.8044014, 41.8044014, 41.8044014, 41.8044014,
-    41.8044014, 41.8044014, 41.8044014, 41.8044014, 41.8044014, 41.8044014,
-    41.8044014, 41.8044014, 41.8044014, 41.8044014, 41.8044014, 41.8044014,
-    41.8044014, 41.8044014, 41.8044014, 41.8043976, 41.8043976, 41.8043976,
-    41.8043976, 41.8043976, 41.8043976, 41.8043976, 41.8043976, 41.8043976,
-    41.8043938, 41.8043938, 41.8043938, 41.8043938, 41.8043938, 41.8043938,
-    41.80439,   41.80439,   41.80439,   41.80439,   41.80439,   41.8043861,
-    41.8043861, 41.8043861, 41.8043861, 41.8043861, 41.8043861, 41.8043861,
-    41.8043823, 41.8043823, 41.8043823, 41.8043823, 41.8043823, 41.8043823,
-    41.8043823, 41.8043823, 41.8043823, 41.8043823, 41.8043823, 41.8043823,
-    41.8043823, 41.8043823, 41.8043823, 41.8043823, 41.8043823, 41.8043823,
-    41.8043823, 41.8043823, 41.8043823, 41.8043785, 41.8043785, 41.8043785,
-    41.8043785, 41.8043785, 41.8043785, 41.8043785, 41.8043785, 41.8043747,
-    41.8043747, 41.8043747, 41.8043747, 41.8043747, 41.8043747, 41.8043747,
-    41.8043709, 41.8043709, 41.8043709, 41.8043709, 41.8043709, 41.8043709,
-    41.8043709, 41.8043671, 41.8043671, 41.8043671, 41.8043671, 41.8043671,
-    41.8043671, 41.8043671, 41.8043633, 41.8043633, 41.8043633, 41.8043633,
-    41.8043633, 41.8043633, 41.8043633, 41.8043633, 41.8043633, 41.8043633,
-    41.8043633, 41.8043633, 41.8043594, 41.8043594, 41.8043594, 41.8043594,
-    41.8043594, 41.8043594, 41.8043594, 41.8043594, 41.8043556, 41.8043556,
-    41.8043556, 41.8043556, 41.8043556, 41.8043556, 41.8043556, 41.8043556,
-    41.8043518, 41.8043518, 41.8043518, 41.8043518, 41.8043518, 41.8043518,
-    41.8043518, 41.804348,  41.804348,  41.804348,  41.804348,  41.804348,
-    41.804348,  41.804348,  41.804348,  41.804348,  41.804348,  41.804348,
-    41.804348,  41.804348,  41.804348,  41.804348,  41.8043442, 41.8043442,
-    41.8043442, 41.8043442, 41.8043442, 41.8043442, 41.8043442, 41.8043442,
-    41.8043442, 41.8043442, 41.8043442, 41.8043442, 41.8043442, 41.8043442,
-    41.8043442, 41.8043442, 41.8043442, 41.8043404, 41.8043404, 41.8043404,
-    41.8043404, 41.8043404, 41.8043404, 41.8043404, 41.8043365, 41.8043365,
-    41.8043365, 41.8043365, 41.8043365, 41.8043365, 41.8043365, 41.8043327,
-    41.8043327, 41.8043327, 41.8043327, 41.8043327, 41.8043327, 41.8043327,
-    41.8043327, 41.8043289, 41.8043289, 41.8043289, 41.8043289, 41.8043289,
-    41.8043289, 41.8043289, 41.8043289, 41.8043289, 41.8043289, 41.8043289,
-    41.8043251, 41.8043251, 41.8043251, 41.8043251, 41.8043251, 41.8043251,
-    41.8043251, 41.8043251, 41.8043251, 41.8043251, 41.8043213, 41.8043213,
-    41.8043213, 41.8043175, 41.8043175, 41.8043175, 41.8043175, 41.8043137,
-    41.8043137, 41.8043137, 41.8043137, 41.8043137, 41.8043137, 41.8043137,
-    41.8043137, 41.8043137, 41.8043137, 41.8043137, 41.8043137, 41.8043137,
-    41.8043137, 41.8043137, 41.8043137, 41.8043137, 41.8043137, 41.8043098,
-    41.8043098, 41.8043098, 41.8043098, 41.8043098, 41.8043098, 41.8043098,
-    41.8043098, 41.804306,  41.804306,  41.804306,  41.804306,  41.804306,
-    41.804306,  41.804306,  41.804306,  41.804306,  41.804306,  41.804306,
-    41.804306,  41.804306,  41.804306,  41.804306,  41.804306,  41.804306,
-    41.8043022, 41.8043022, 41.8043022, 41.8043022, 41.8043022, 41.8043022,
-    41.8043022, 41.8043022, 41.8043022, 41.8043022, 41.8043022, 41.8043022,
-    41.8042984, 41.8042984, 41.8042984, 41.8042984, 41.8042984, 41.8042984,
-    41.8042984, 41.8042984, 41.8042946, 41.8042946, 41.8042946, 41.8042946,
-    41.8042946, 41.8042946, 41.8042946, 41.8042946, 41.8042946, 41.8042946,
-    41.8042946, 41.8042946, 41.8042946, 41.8042946, 41.8042946, 41.8042946,
-    41.8042946, 41.8042946, 41.8042946, 41.8042946, 41.8042946, 41.8042946,
-    41.8042946, 41.8042946, 41.8042946, 41.8042946, 41.8042946, 41.8042946,
-    41.8042908, 41.8042908, 41.8042908, 41.8042908, 41.8042908, 41.8042908,
-    41.804287,  41.804287,  41.804287,  41.804287,  41.804287,  41.8042831,
-    41.8042831, 41.8042831, 41.8042831, 41.8042831, 41.8042831, 41.8042831,
-    41.8042831, 41.8042793, 41.8042793, 41.8042793, 41.8042793, 41.8042793,
-    41.8042755, 41.8042755, 41.8042755, 41.8042755, 41.8042717, 41.8042717,
-    41.8042717, 41.8042717, 41.8042717, 41.8042679, 41.8042679, 41.8042679,
-    41.8042679, 41.8042641, 41.8042641, 41.8042641, 41.8042641, 41.8042641,
-    41.8042641, 41.8042641, 41.8042641, 41.8042603, 41.8042603, 41.8042603,
-    41.8042603, 41.8042564, 41.8042564, 41.8042564, 41.8042526, 41.8042526,
-    41.8042526, 41.8042526, 41.8042488, 41.8042488, 41.8042488, 41.8042488,
-    41.804245,  41.804245,  41.804245,  41.804245,  41.804245,  41.804245,
-    41.804245,  41.804245,  41.8042412, 41.8042412, 41.8042412, 41.8042412,
-    41.8042412, 41.8042374, 41.8042374, 41.8042374, 41.8042374, 41.8042374,
-    41.8042374, 41.8042336, 41.8042336, 41.8042336, 41.8042336, 41.8042297,
-    41.8042297, 41.8042297, 41.8042259, 41.8042259, 41.8042259, 41.8042221,
-    41.8042221, 41.8042221, 41.8042221, 41.8042221, 41.8042221, 41.8042221,
-    41.8042221, 41.8042183, 41.8042183, 41.8042183, 41.8042183, 41.8042183,
-    41.8042183, 41.8042183, 41.8042145, 41.8042145, 41.8042145, 41.8042145,
-    41.8042145, 41.8042107, 41.8042107, 41.8042107, 41.8042068, 41.8042068,
-    41.8042068, 41.8042068, 41.804203,  41.804203,  41.804203,  41.804203,
-    41.804203,  41.804203,  41.804203,  41.8041992, 41.8041992, 41.8041992,
-    41.8041954, 41.8041954, 41.8041954, 41.8041954, 41.8041916, 41.8041916,
-    41.8041916, 41.8041916, 41.8041916, 41.8041878, 41.8041878, 41.8041878,
-    41.8041878, 41.8041878, 41.804184,  41.804184,  41.804184,  41.804184,
-    41.804184,  41.804184,  41.804184,  41.8041801, 41.8041801, 41.8041801,
-    41.8041801, 41.8041763, 41.8041763, 41.8041763, 41.8041763, 41.8041725,
-    41.8041725, 41.8041725, 41.8041687, 41.8041687, 41.8041687, 41.8041649,
-    41.8041649, 41.8041649, 41.8041649, 41.8041649, 41.8041649, 41.8041649,
-    41.8041611, 41.8041611, 41.8041611, 41.8041611, 41.8041611, 41.8041573,
-    41.8041573, 41.8041573, 41.8041534, 41.8041534, 41.8041534, 41.8041534,
-    41.8041496, 41.8041496, 41.8041496, 41.8041496, 41.8041496, 41.8041496,
-    41.8041458, 41.8041458, 41.8041458, 41.8041458, 41.8041458, 41.8041458,
-    41.8041458, 41.8041458, 41.804142,  41.804142,  41.804142,  41.8041382,
-    41.8041382, 41.8041382, 41.8041344, 41.8041344, 41.8041344, 41.8041344,
-    41.8041306, 41.8041306, 41.8041306, 41.8041306, 41.8041267, 41.8041267,
-    41.8041267, 41.8041267, 41.8041229, 41.8041229, 41.8041229, 41.8041229,
-    41.8041229, 41.8041229, 41.8041229, 41.8041191, 41.8041191, 41.8041191,
-    41.8041153, 41.8041153, 41.8041153, 41.8041153, 41.8041115, 41.8041115,
-    41.8041115, 41.8041077, 41.8041077, 41.8041039, 41.8041039, 41.8041039,
-    41.8041039, 41.8041039, 41.8041,    41.8041,    41.8041,    41.8040962,
-    41.8040962, 41.8040962, 41.8040962, 41.8040962, 41.8040924, 41.8040924,
-    41.8040924, 41.8040924, 41.8040886, 41.8040886, 41.8040886, 41.8040848,
-    41.8040848, 41.8040848, 41.8040848, 41.8040848, 41.8040848, 41.804081,
-    41.804081,  41.804081,  41.8040771, 41.8040771, 41.8040733, 41.8040733,
-    41.8040733, 41.8040695, 41.8040695, 41.8040657, 41.8040657, 41.8040657,
-    41.8040657, 41.8040619, 41.8040619, 41.8040581, 41.8040581, 41.8040543,
-    41.8040543, 41.8040504, 41.8040504, 41.8040504, 41.8040466, 41.8040466,
-    41.8040466, 41.8040466, 41.8040428, 41.8040428, 41.804039,  41.804039,
-    41.8040352, 41.8040352, 41.8040314, 41.8040314, 41.8040276, 41.8040237,
-    41.8040237, 41.8040237, 41.8040237, 41.8040199, 41.8040199, 41.8040161,
-    41.8040161, 41.8040123, 41.8040123, 41.8040085, 41.8040047, 41.8040047,
-    41.8040047, 41.8040047, 41.8040009, 41.8040009, 41.803997,  41.8039932,
-    41.8039932, 41.8039894, 41.8039894, 41.8039856, 41.8039856, 41.8039856,
-    41.8039856, 41.8039818, 41.8039818, 41.803978,  41.803978,  41.8039742,
-    41.8039742, 41.8039703, 41.8039703, 41.8039665, 41.8039665, 41.8039665,
-    41.8039665, 41.8039627, 41.8039627, 41.8039589, 41.8039589, 41.8039551,
-    41.8039551, 41.8039513, 41.8039513, 41.8039474, 41.8039474, 41.8039474,
-    41.8039474, 41.8039436, 41.8039436, 41.8039398, 41.8039398, 41.803936,
-    41.803936,  41.8039322, 41.8039322, 41.8039284, 41.8039284, 41.8039246,
-    41.8039246, 41.8039246, 41.8039246, 41.8039207, 41.8039207, 41.8039169,
-    41.8039169, 41.8039131, 41.8039131, 41.8039093, 41.8039093, 41.8039055,
-    41.8039055, 41.8039055, 41.8039055, 41.8039017, 41.8039017, 41.8038979,
-    41.8038979, 41.803894,  41.8038902, 41.8038902, 41.8038864, 41.8038864,
-    41.8038864, 41.8038864, 41.8038826, 41.8038826, 41.8038826, 41.8038788,
-    41.8038788, 41.803875,  41.803875,  41.8038712, 41.8038712, 41.8038673,
-    41.8038673, 41.8038673, 41.8038673, 41.8038635, 41.8038597, 41.8038597,
-    41.8038597, 41.8038559, 41.8038521, 41.8038521, 41.8038521, 41.8038483,
-    41.8038483, 41.8038483, 41.8038483, 41.8038445, 41.8038445, 41.8038445,
-    41.8038406, 41.8038406, 41.8038368, 41.8038368, 41.803833,  41.803833,
-    41.8038292, 41.8038292, 41.8038254, 41.8038254, 41.8038254, 41.8038254,
-    41.8038216, 41.8038216, 41.8038216, 41.8038177, 41.8038177, 41.8038139,
-    41.8038139, 41.8038101, 41.8038101, 41.8038063, 41.8038063, 41.8038063,
-    41.8038063, 41.8038025, 41.8038025, 41.8038025, 41.8037987, 41.8037987,
-    41.8037949, 41.803791,  41.803791,  41.8037872, 41.8037872, 41.8037872,
-    41.8037872, 41.8037834, 41.8037834, 41.8037796, 41.8037758, 41.8037758,
-    41.803772,  41.803772,  41.8037682, 41.8037682, 41.8037682, 41.8037643,
-    41.8037643, 41.8037605, 41.8037567, 41.8037567, 41.8037529, 41.8037491,
-    41.8037491, 41.8037491, 41.8037453, 41.8037453, 41.8037415, 41.8037376,
-    41.8037376, 41.8037338, 41.80373,   41.80373,   41.8037262, 41.8037262,
-    41.8037262, 41.8037224, 41.8037224, 41.8037186, 41.8037148, 41.8037109,
-    41.8037109, 41.8037071, 41.8037071, 41.8037071, 41.8037033, 41.8036995,
-    41.8036995, 41.8036957, 41.8036919, 41.803688,  41.803688,  41.803688,
-    41.8036842, 41.8036842, 41.8036804, 41.8036766, 41.8036766, 41.8036728,
-    41.803669,  41.803669,  41.803669,  41.8036652, 41.8036652, 41.8036613,
-    41.8036575, 41.8036575, 41.8036537, 41.8036499, 41.8036499, 41.8036499,
-    41.8036499, 41.8036461, 41.8036423, 41.8036423, 41.8036385, 41.8036346,
-    41.8036346, 41.8036308, 41.8036308, 41.8036308, 41.8036308, 41.803627,
-    41.8036232, 41.8036232, 41.8036194, 41.8036194, 41.8036156, 41.8036156,
-    41.8036118, 41.8036118, 41.8036079, 41.8036079, 41.8036079, 41.8036079,
-    41.8036079, 41.8036041, 41.8036041, 41.8036003, 41.8036003, 41.8035965,
-    41.8035965, 41.8035965, 41.8035927, 41.8035927, 41.8035889, 41.8035889,
-    41.8035889, 41.8035889, 41.8035889, 41.8035889, 41.8035851, 41.8035851,
-    41.8035851, 41.8035812, 41.8035812, 41.8035812, 41.8035774, 41.8035774,
-    41.8035774, 41.8035736, 41.8035736, 41.8035736, 41.8035698, 41.8035698,
-    41.8035698, 41.8035698, 41.8035698, 41.8035698, 41.8035698, 41.803566,
-    41.803566,  41.803566,  41.803566,  41.8035622, 41.8035622, 41.8035622,
-    41.8035622, 41.8035622, 41.8035583, 41.8035583, 41.8035583, 41.8035583,
-    41.8035545, 41.8035545, 41.8035545, 41.8035507, 41.8035507, 41.8035507,
-    41.8035469, 41.8035469, 41.8035469, 41.8035469, 41.8035469, 41.8035469,
-    41.8035469, 41.8035469, 41.8035431, 41.8035431, 41.8035431, 41.8035431,
-    41.8035393, 41.8035393, 41.8035393, 41.8035355, 41.8035355, 41.8035355,
-    41.8035316, 41.8035316, 41.8035316, 41.8035278, 41.8035278, 41.8035278,
-    41.8035278, 41.8035278, 41.8035278, 41.8035278, 41.803524,  41.803524,
-    41.803524,  41.8035202, 41.8035202, 41.8035202, 41.8035164, 41.8035164,
-    41.8035164, 41.8035164, 41.8035126, 41.8035126, 41.8035126, 41.8035088,
-    41.8035088, 41.8035088, 41.8035088, 41.8035088, 41.8035088, 41.8035088,
-    41.8035049, 41.8035049, 41.8035049, 41.8035011, 41.8035011, 41.8035011,
-    41.8035011, 41.8035011, 41.8034973, 41.8034935, 41.8034935, 41.8034935,
-    41.8034897, 41.8034897, 41.8034897, 41.8034897, 41.8034897, 41.8034897,
-    41.8034859, 41.8034859, 41.8034859, 41.8034821, 41.8034821, 41.8034821,
-    41.8034782, 41.8034782, 41.8034744, 41.8034744, 41.8034744, 41.8034706,
-    41.8034706, 41.8034706, 41.8034706, 41.8034706, 41.8034668, 41.8034668,
-    41.8034668, 41.803463,  41.803463,  41.803463,  41.8034592, 41.8034592,
-    41.8034592, 41.8034554, 41.8034554, 41.8034515, 41.8034515, 41.8034515,
-    41.8034477, 41.8034477, 41.8034477, 41.8034477, 41.8034477, 41.8034477,
-    41.8034439, 41.8034439, 41.8034439, 41.8034401, 41.8034401, 41.8034401,
-    41.8034401, 41.8034363, 41.8034363, 41.8034363, 41.8034363, 41.8034325,
-    41.8034325, 41.8034325, 41.8034286, 41.8034286, 41.8034286, 41.8034286,
-    41.8034286, 41.8034286, 41.8034286, 41.8034286, 41.8034248, 41.8034248,
-    41.8034248, 41.8034248, 41.803421,  41.803421,  41.803421,  41.803421,
-    41.8034172, 41.8034172, 41.8034172, 41.8034172, 41.8034172, 41.8034134,
-    41.8034134, 41.8034134, 41.8034134, 41.8034096, 41.8034096, 41.8034096,
-    41.8034096, 41.8034096, 41.8034096, 41.8034096, 41.8034096, 41.8034096,
-    41.8034058, 41.8034058, 41.8034058, 41.8034058, 41.8034058, 41.8034019,
-    41.8034019, 41.8034019, 41.8034019, 41.8033981, 41.8033981, 41.8033981,
-    41.8033981, 41.8033943, 41.8033943, 41.8033943, 41.8033943, 41.8033905,
-    41.8033905, 41.8033905, 41.8033905, 41.8033905, 41.8033905, 41.8033905,
-    41.8033905, 41.8033867, 41.8033867, 41.8033867, 41.8033829, 41.8033829,
-    41.8033829, 41.8033829, 41.8033791, 41.8033791, 41.8033791, 41.8033791,
-    41.8033752, 41.8033752, 41.8033752, 41.8033714, 41.8033714, 41.8033714,
-    41.8033714, 41.8033714, 41.8033714, 41.8033714, 41.8033714, 41.8033676,
-    41.8033676, 41.8033676, 41.8033676, 41.8033638, 41.8033638, 41.8033638,
-    41.8033638, 41.80336,   41.80336,   41.80336,   41.8033562, 41.8033562,
-    41.8033562, 41.8033562, 41.8033524, 41.8033524, 41.8033524, 41.8033485,
-    41.8033485, 41.8033485, 41.8033485, 41.8033485, 41.8033485, 41.8033485,
-    41.8033447, 41.8033447, 41.8033447, 41.8033409, 41.8033409, 41.8033409,
-    41.8033409, 41.8033371, 41.8033371, 41.8033371, 41.8033371, 41.8033333,
-    41.8033333, 41.8033333, 41.8033295, 41.8033295, 41.8033295, 41.8033295,
-    41.8033295, 41.8033295, 41.8033295, 41.8033257, 41.8033257, 41.8033257,
-    41.8033257, 41.8033218, 41.8033218, 41.8033218, 41.8033218, 41.803318,
-    41.803318,  41.803318,  41.8033142, 41.8033142, 41.8033142, 41.8033142,
-    41.8033104, 41.8033104, 41.8033104, 41.8033104, 41.8033104, 41.8033104,
-    41.8033104, 41.8033104, 41.8033066, 41.8033066, 41.8033066, 41.8033028,
-    41.8033028, 41.8033028, 41.8033028, 41.803299,  41.803299,  41.803299,
-    41.8032951, 41.8032951, 41.8032951, 41.8032913, 41.8032913, 41.8032913,
-    41.8032913, 41.8032913, 41.8032913, 41.8032913, 41.8032875, 41.8032875,
-    41.8032837, 41.8032837, 41.8032837, 41.8032837, 41.8032799, 41.8032799,
-    41.8032761, 41.8032761, 41.8032761, 41.8032722, 41.8032722, 41.8032722,
-    41.8032722, 41.8032722, 41.8032684, 41.8032684, 41.8032646, 41.8032646,
-    41.8032646, 41.8032608, 41.8032608, 41.803257,  41.803257,  41.8032532,
-    41.8032532, 41.8032532, 41.8032494, 41.8032494, 41.8032494, 41.8032494,
-    41.8032455, 41.8032455, 41.8032417, 41.8032417, 41.8032379, 41.8032379,
-    41.8032379, 41.8032341, 41.8032341, 41.8032303, 41.8032303, 41.8032303,
-    41.8032303, 41.8032303, 41.8032265, 41.8032265, 41.8032227, 41.8032227,
-    41.8032188, 41.8032188, 41.8032188, 41.803215,  41.803215,  41.803215,
-    41.8032112, 41.8032112, 41.8032112, 41.8032112, 41.8032112, 41.8032112,
-    41.8032112, 41.8032074, 41.8032074, 41.8032074, 41.8032074, 41.8032074,
-    41.8032074, 41.8032036, 41.8032036, 41.8032036, 41.8032036, 41.8032036,
-    41.8032036, 41.8032036, 41.8032036, 41.8031998, 41.8031998, 41.8031998,
-    41.8031998, 41.8031998, 41.8031998, 41.8031998, 41.8031998, 41.8031998,
-    41.8031998, 41.8031998, 41.8031998, 41.803196,  41.803196,  41.803196,
-    41.803196,  41.803196,  41.803196,  41.803196,  41.803196,  41.8031921,
-    41.8031921, 41.8031921, 41.8031921, 41.8031921, 41.8031921, 41.8031921,
-    41.8031921, 41.8031921, 41.8031921, 41.8031921, 41.8031921, 41.8031921,
-    41.8031883, 41.8031883, 41.8031883, 41.8031883, 41.8031883, 41.8031883,
-    41.8031883, 41.8031845, 41.8031845, 41.8031845, 41.8031845, 41.8031845,
-    41.8031807, 41.8031807, 41.8031807, 41.8031769, 41.8031769, 41.8031769,
-    41.8031769, 41.8031731, 41.8031731, 41.8031731, 41.8031731, 41.8031731,
-    41.8031731, 41.8031731, 41.8031731, 41.8031731, 41.8031731, 41.8031731,
-    41.8031693, 41.8031693, 41.8031693, 41.8031693, 41.8031693, 41.8031654,
-    41.8031654, 41.8031654, 41.8031616, 41.8031616, 41.8031616, 41.8031616,
-    41.8031578, 41.8031578, 41.8031578, 41.8031578, 41.8031578, 41.803154,
-    41.803154,  41.803154,  41.803154,  41.8031502, 41.8031502, 41.8031502,
-    41.8031502, 41.8031502, 41.8031502, 41.8031502, 41.8031502, 41.8031464,
-    41.8031464, 41.8031464, 41.8031464, 41.8031425, 41.8031425, 41.8031425,
-    41.8031425, 41.8031425, 41.8031387, 41.8031387, 41.8031387, 41.8031387,
-    41.8031349, 41.8031349, 41.8031349, 41.8031349, 41.8031349, 41.8031311,
-    41.8031311, 41.8031311, 41.8031311, 41.8031311, 41.8031311, 41.8031273,
-    41.8031273, 41.8031273, 41.8031235, 41.8031235, 41.8031235, 41.8031197,
-    41.8031197, 41.8031158, 41.8031158, 41.8031158, 41.803112,  41.803112,
-    41.803112,  41.803112,  41.8031082, 41.8031082, 41.8031082, 41.8031044,
-    41.8031044, 41.8031044, 41.8031006, 41.8031006, 41.8030968, 41.8030968,
-    41.803093,  41.803093,  41.803093,  41.803093,  41.8030891, 41.8030891,
-    41.8030853, 41.8030853, 41.8030815, 41.8030815, 41.8030777, 41.8030777,
-    41.8030739, 41.8030739, 41.8030739, 41.8030739, 41.8030739, 41.8030701,
-    41.8030701, 41.8030663, 41.8030663, 41.8030663, 41.8030624, 41.8030624,
-    41.8030586, 41.8030586, 41.8030548, 41.8030548, 41.803051,  41.803051,
-    41.803051,  41.803051,  41.803051,  41.8030472, 41.8030472, 41.8030472,
-    41.8030434, 41.8030434, 41.8030434, 41.8030396, 41.8030396, 41.8030357,
-    41.8030357, 41.8030357, 41.8030319, 41.8030319, 41.8030319, 41.8030319,
-    41.8030319, 41.8030281, 41.8030281, 41.8030281, 41.8030243, 41.8030243,
-    41.8030243, 41.8030205, 41.8030205, 41.8030205, 41.8030167, 41.8030167,
-    41.8030167, 41.8030128, 41.8030128, 41.8030128, 41.8030128, 41.8030128,
-    41.803009,  41.803009,  41.8030052, 41.8030052, 41.8030052, 41.8030014,
-    41.8030014, 41.8030014, 41.8029976, 41.8029976, 41.8029938, 41.8029938,
-    41.8029938, 41.8029938, 41.80299,   41.80299,   41.80299,   41.8029861,
-    41.8029861, 41.8029861, 41.8029823, 41.8029823, 41.8029823, 41.8029785,
-    41.8029785, 41.8029785, 41.8029747, 41.8029747, 41.8029747, 41.8029747,
-    41.8029747, 41.8029747, 41.8029709, 41.8029709, 41.8029709, 41.8029671,
-    41.8029671, 41.8029671, 41.8029671, 41.8029633, 41.8029633, 41.8029633,
-    41.8029594, 41.8029594, 41.8029594, 41.8029594, 41.8029556, 41.8029556,
-    41.8029556, 41.8029556, 41.8029518, 41.8029518, 41.8029518, 41.8029518,
-    41.8029518, 41.8029518, 41.8029518, 41.802948,  41.802948,  41.802948,
-    41.8029442, 41.8029442, 41.8029442, 41.8029404, 41.8029404, 41.8029404,
-    41.8029404, 41.8029366, 41.8029366, 41.8029366, 41.8029327, 41.8029327,
-    41.8029327, 41.8029327, 41.8029327, 41.8029327, 41.8029327, 41.8029289,
-    41.8029289, 41.8029289, 41.8029251, 41.8029251, 41.8029251, 41.8029213,
-    41.8029213, 41.8029213, 41.8029175, 41.8029175, 41.8029175, 41.8029137,
-    41.8029137, 41.8029137, 41.8029137, 41.8029137, 41.8029099, 41.8029099,
-    41.8029099, 41.802906,  41.802906,  41.802906,  41.8029022, 41.8029022,
-    41.8029022, 41.8028984, 41.8028984, 41.8028984, 41.8028984, 41.8028946,
-    41.8028946, 41.8028946, 41.8028946, 41.8028946, 41.8028946, 41.8028946,
-    41.8028946, 41.8028908, 41.8028908, 41.8028908, 41.8028908, 41.802887,
-    41.802887,  41.802887,  41.8028831, 41.8028831, 41.8028831, 41.8028831,
-    41.8028831, 41.8028831, 41.8028831, 41.8028793, 41.8028793, 41.8028793,
-    41.8028793, 41.8028793, 41.8028755, 41.8028755, 41.8028717, 41.8028717,
-    41.8028717, 41.8028717, 41.8028717, 41.8028717, 41.8028717, 41.8028717,
-    41.8028717, 41.8028717, 41.8028679, 41.8028679, 41.8028679, 41.8028679,
-    41.8028679, 41.8028679, 41.8028641, 41.8028641, 41.8028641, 41.8028641,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028641, 41.8028641, 41.8028641, 41.8028641,
-    41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641,
-    41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641,
-    41.8028641, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641,
-    41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641,
-    41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641,
-    41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641,
-    41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641, 41.8028641,
-    41.8028641, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028603, 41.8028603, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603,
-    41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028603, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564,
-    41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028564, 41.8028526,
-    41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526, 41.8028526,
-    41.8028526, 41.8028526,
-};
-
-const float GPS_DATA_LON[3230] = {
-    14.0542908, 14.0542908, 14.0542908, 14.0542908, 14.0542898, 14.0542898,
-    14.0542879, 14.0542879, 14.0542879, 14.054286,  14.054286,  14.054285,
-    14.054285,  14.0542831, 14.0542812, 14.0542812, 14.0542803, 14.0542784,
-    14.0542765, 14.0542755, 14.0542736, 14.0542717, 14.0542707, 14.0542688,
-    14.0542669, 14.0542641, 14.0542622, 14.0542593, 14.0542564, 14.0542545,
-    14.0542526, 14.0542517, 14.0542498, 14.0542479, 14.0542459, 14.0542459,
-    14.0542459, 14.0542402, 14.0542364, 14.0542336, 14.0542307, 14.0542307,
-    14.0542269, 14.0542269, 14.0542269, 14.0542269, 14.0542269, 14.0542259,
-    14.054224,  14.054224,  14.0542221, 14.0542212, 14.0542212, 14.0542192,
-    14.0542173, 14.0542164, 14.0542145, 14.0542145, 14.0542145, 14.0542145,
-    14.0542145, 14.0542145, 14.0542145, 14.0542145, 14.0542145, 14.0542126,
-    14.0542126, 14.0542116, 14.0542116, 14.0542097, 14.0542078, 14.0542078,
-    14.0542068, 14.0542049, 14.054203,  14.054203,  14.0542002, 14.0542002,
-    14.0541983, 14.0541964, 14.0541964, 14.0541935, 14.0541916, 14.0541906,
-    14.0541887, 14.0541868, 14.0541859, 14.0541859, 14.054184,  14.0541821,
-    14.0541821, 14.0541811, 14.0541811, 14.0541821, 14.0541811, 14.054184,
-    14.0541859, 14.0541868, 14.0541887, 14.0541906, 14.0541916, 14.0541935,
-    14.0541964, 14.0542011, 14.0542049, 14.0542097, 14.0542164, 14.0542212,
-    14.054224,  14.0542288, 14.0542336, 14.0542364, 14.0542412, 14.0542459,
-    14.0542517, 14.0542564, 14.0542612, 14.054266,  14.0542707, 14.0542755,
-    14.0542784, 14.0542831, 14.0542879, 14.0542927, 14.0542974, 14.0543022,
-    14.054307,  14.0543118, 14.0543165, 14.0543213, 14.0543261, 14.0543299,
-    14.0543346, 14.0543394, 14.0543442, 14.0543489, 14.0543537, 14.0543585,
-    14.0543633, 14.054368,  14.0543728, 14.0543776, 14.0543823, 14.0543871,
-    14.0543919, 14.0543966, 14.0544004, 14.0544052, 14.05441,   14.0544147,
-    14.0544195, 14.0544224, 14.0544271, 14.0544319, 14.0544348, 14.0544395,
-    14.0544453, 14.05445,   14.0544548, 14.0544596, 14.0544624, 14.0544672,
-    14.054472,  14.0544767, 14.0544815, 14.0544863, 14.0544891, 14.0544949,
-    14.0544996, 14.0545044, 14.0545092, 14.0545139, 14.0545187, 14.0545235,
-    14.0545282, 14.054533,  14.0545378, 14.0545406, 14.0545454, 14.0545502,
-    14.0545549, 14.0545597, 14.0545645, 14.0545712, 14.0545759, 14.0545807,
-    14.0545855, 14.0545921, 14.0545988, 14.0546036, 14.0546093, 14.0546141,
-    14.0546207, 14.0546255, 14.0546322, 14.054637,  14.0546436, 14.0546484,
-    14.0546541, 14.0546589, 14.0546656, 14.0546703, 14.0546751, 14.0546818,
-    14.0546865, 14.0546913, 14.0546961, 14.0547009, 14.0547056, 14.0547104,
-    14.0547152, 14.0547199, 14.0547247, 14.0547295, 14.0547333, 14.054739,
-    14.0547428, 14.0547476, 14.0547523, 14.0547571, 14.0547619, 14.0547667,
-    14.0547714, 14.0547762, 14.054781,  14.0547857, 14.0547905, 14.0547953,
-    14.0548,    14.0548048, 14.0548096, 14.0548143, 14.0548191, 14.0548239,
-    14.0548286, 14.0548325, 14.0548372, 14.054842,  14.0548468, 14.0548515,
-    14.0548563, 14.0548611, 14.0548639, 14.0548687, 14.0548735, 14.0548782,
-    14.054883,  14.0548878, 14.0548925, 14.0548964, 14.0549011, 14.0549059,
-    14.0549107, 14.0549154, 14.0549202, 14.0549269, 14.0549316, 14.0549374,
-    14.0549421, 14.0549488, 14.0549536, 14.0549603, 14.054965,  14.0549698,
-    14.0549765, 14.0549812, 14.054987,  14.0549917, 14.0549965, 14.0550032,
-    14.0550079, 14.0550127, 14.0550175, 14.0550241, 14.0550289, 14.0550337,
-    14.0550385, 14.0550432, 14.0550499, 14.0550547, 14.0550594, 14.0550642,
-    14.055069,  14.0550756, 14.0550804, 14.0550852, 14.055088,  14.0550928,
-    14.0550976, 14.0551023, 14.0551071, 14.0551119, 14.0551167, 14.0551214,
-    14.0551262, 14.05513,   14.0551348, 14.0551395, 14.0551443, 14.0551491,
-    14.0551538, 14.0551567, 14.0551615, 14.0551662, 14.055171,  14.0551758,
-    14.0551805, 14.0551853, 14.0551891, 14.0551939, 14.0551987, 14.0552034,
-    14.0552082, 14.0552111, 14.0552158, 14.0552206, 14.0552254, 14.0552301,
-    14.055234,  14.0552387, 14.0552435, 14.0552483, 14.0552511, 14.0552559,
-    14.0552607, 14.0552654, 14.0552702, 14.055274,  14.0552788, 14.0552835,
-    14.0552883, 14.0552931, 14.0552979, 14.0553026, 14.0553055, 14.0553102,
-    14.055315,  14.0553198, 14.0553246, 14.0553284, 14.0553331, 14.0553379,
-    14.0553427, 14.0553474, 14.0553522, 14.055357,  14.0553637, 14.0553684,
-    14.0553732, 14.0553789, 14.0553837, 14.0553885, 14.0553932, 14.0553999,
-    14.0554047, 14.0554094, 14.0554161, 14.0554209, 14.0554256, 14.0554304,
-    14.0554371, 14.0554419, 14.0554466, 14.0554514, 14.0554562, 14.0554609,
-    14.0554676, 14.0554724, 14.0554771, 14.0554819, 14.0554867, 14.0554914,
-    14.0554972, 14.0555019, 14.0555077, 14.0555124, 14.0555172, 14.055522,
-    14.0555267, 14.0555315, 14.0555363, 14.055542,  14.0555468, 14.0555515,
-    14.0555573, 14.055562,  14.0555668, 14.0555716, 14.0555763, 14.0555811,
-    14.0555859, 14.0555906, 14.0555954, 14.0556002, 14.0556049, 14.0556097,
-    14.0556145, 14.0556192, 14.055624,  14.0556288, 14.0556335, 14.0556383,
-    14.0556431, 14.0556479, 14.0556517, 14.0556564, 14.0556612, 14.055666,
-    14.0556707, 14.0556755, 14.0556803, 14.0556831, 14.0556879, 14.0556927,
-    14.0556974, 14.0557022, 14.055706,  14.0557108, 14.0557156, 14.0557184,
-    14.0557232, 14.055728,  14.0557327, 14.0557356, 14.0557404, 14.0557451,
-    14.0557508, 14.0557537, 14.0557585, 14.0557632, 14.0557661, 14.0557709,
-    14.0557756, 14.0557804, 14.0557842, 14.055789,  14.0557938, 14.0557985,
-    14.0558014, 14.0558062, 14.0558109, 14.0558147, 14.0558195, 14.0558243,
-    14.055829,  14.0558319, 14.0558367, 14.0558414, 14.0558462, 14.05585,
-    14.0558548, 14.0558596, 14.0558643, 14.0558691, 14.055872,  14.0558767,
-    14.0558815, 14.0558844, 14.0558891, 14.0558949, 14.0558996, 14.0559044,
-    14.0559092, 14.0559139, 14.0559187, 14.0559235, 14.0559282, 14.055933,
-    14.0559378, 14.0559444, 14.0559492, 14.055954,  14.0559587, 14.0559635,
-    14.0559683, 14.0559711, 14.0559759, 14.0559807, 14.0559835, 14.0559893,
-    14.055994,  14.0559969, 14.0560017, 14.0560045, 14.0560093, 14.0560131,
-    14.056016,  14.0560207, 14.0560255, 14.0560284, 14.0560331, 14.0560389,
-    14.0560436, 14.0560484, 14.0560532, 14.0560579, 14.0560627, 14.0560675,
-    14.0560722, 14.056077,  14.0560818, 14.0560865, 14.0560932, 14.056098,
-    14.0561028, 14.0561085, 14.0561132, 14.0561199, 14.0561247, 14.0561314,
-    14.056138,  14.0561428, 14.0561476, 14.0561533, 14.05616,   14.0561647,
-    14.0561714, 14.0561762, 14.0561829, 14.0561886, 14.0561934, 14.0562,
-    14.0562067, 14.0562124, 14.0562172, 14.0562239, 14.0562305, 14.0562353,
-    14.056242,  14.0562477, 14.0562525, 14.0562592, 14.0562658, 14.0562706,
-    14.0562773, 14.056283,  14.0562878, 14.0562944, 14.0563011, 14.0563068,
-    14.0563116, 14.0563183, 14.056325,  14.0563316, 14.0563374, 14.0563421,
-    14.0563488, 14.0563555, 14.0563602, 14.056366,  14.0563726, 14.0563774,
-    14.0563841, 14.0563908, 14.0563965, 14.0564013, 14.0564079, 14.0564146,
-    14.0564203, 14.056427,  14.0564318, 14.0564384, 14.0564451, 14.0564508,
-    14.0564556, 14.0564623, 14.056469,  14.0564737, 14.0564804, 14.0564861,
-    14.0564928, 14.0564976, 14.0565042, 14.05651,   14.0565147, 14.0565214,
-    14.0565281, 14.0565348, 14.0565395, 14.0565453, 14.0565519, 14.0565586,
-    14.0565634, 14.0565701, 14.0565758, 14.0565825, 14.0565872, 14.0565939,
-    14.0565996, 14.0566063, 14.0566111, 14.0566177, 14.0566244, 14.0566292,
-    14.0566349, 14.0566397, 14.0566463, 14.056653,  14.0566578, 14.0566645,
-    14.0566692, 14.056675,  14.0566797, 14.0566864, 14.0566912, 14.0566978,
-    14.0567026, 14.0567083, 14.0567141, 14.0567198, 14.0567245, 14.0567293,
-    14.056736,  14.0567408, 14.0567455, 14.0567522, 14.056757,  14.0567636,
-    14.0567684, 14.0567741, 14.0567789, 14.0567837, 14.0567904, 14.0567951,
-    14.0567999, 14.0568066, 14.0568113, 14.056818,  14.0568228, 14.0568285,
-    14.0568333, 14.056838,  14.0568447, 14.0568495, 14.0568562, 14.0568609,
-    14.0568676, 14.0568724, 14.0568771, 14.0568829, 14.0568876, 14.0568924,
-    14.0568972, 14.0569019, 14.0569077, 14.0569134, 14.0569181, 14.0569229,
-    14.0569277, 14.0569324, 14.0569372, 14.056942,  14.0569468, 14.0569525,
-    14.0569572, 14.056963,  14.0569677, 14.0569725, 14.0569773, 14.056982,
-    14.0569887, 14.0569935, 14.0569983, 14.057003,  14.0570078, 14.0570126,
-    14.0570173, 14.0570221, 14.0570269, 14.0570316, 14.0570364, 14.0570431,
-    14.0570478, 14.0570526, 14.0570593, 14.0570641, 14.0570688, 14.0570736,
-    14.0570784, 14.057085,  14.0570898, 14.0570946, 14.0570993, 14.0571041,
-    14.0571108, 14.0571156, 14.0571203, 14.0571251, 14.0571308, 14.0571356,
-    14.0571423, 14.057147,  14.0571518, 14.0571585, 14.0571632, 14.0571699,
-    14.0571747, 14.0571804, 14.0571852, 14.0571899, 14.0571957, 14.0572014,
-    14.0572062, 14.0572109, 14.0572157, 14.0572224, 14.0572271, 14.0572319,
-    14.0572386, 14.0572433, 14.0572481, 14.0572529, 14.0572596, 14.0572643,
-    14.0572691, 14.0572739, 14.0572796, 14.0572844, 14.0572891, 14.0572958,
-    14.0573006, 14.0573053, 14.057312,  14.0573168, 14.0573215, 14.0573263,
-    14.0573311, 14.0573359, 14.0573425, 14.0573473, 14.0573521, 14.0573568,
-    14.0573635, 14.0573683, 14.057373,  14.0573778, 14.0573826, 14.0573893,
-    14.057394,  14.0573988, 14.0574045, 14.0574093, 14.0574141, 14.0574188,
-    14.0574236, 14.0574284, 14.0574331, 14.0574389, 14.0574436, 14.0574484,
-    14.0574532, 14.0574579, 14.0574627, 14.0574656, 14.0574703, 14.0574751,
-    14.0574818, 14.0574865, 14.0574913, 14.057498,  14.0575027, 14.0575075,
-    14.0575123, 14.0575171, 14.0575218, 14.0575266, 14.0575333, 14.057538,
-    14.0575428, 14.0575476, 14.0575523, 14.0575571, 14.0575619, 14.0575647,
-    14.0575695, 14.0575724, 14.0575771, 14.0575829, 14.0575876, 14.0575924,
-    14.0575972, 14.0576019, 14.0576067, 14.0576096, 14.0576143, 14.0576191,
-    14.0576239, 14.0576286, 14.0576334, 14.0576382, 14.0576429, 14.0576477,
-    14.0576515, 14.0576563, 14.0576611, 14.0576658, 14.0576706, 14.0576754,
-    14.0576801, 14.0576849, 14.0576897, 14.0576944, 14.0576992, 14.0577021,
-    14.0577068, 14.0577116, 14.0577164, 14.0577211, 14.057725,  14.0577297,
-    14.0577345, 14.0577374, 14.0577421, 14.0577469, 14.0577507, 14.0577555,
-    14.0577602, 14.0577631, 14.0577679, 14.0577707, 14.0577765, 14.0577812,
-    14.057786,  14.0577888, 14.0577936, 14.0577984, 14.0578032, 14.057806,
-    14.0578108, 14.0578156, 14.0578213, 14.0578241, 14.0578289, 14.0578318,
-    14.0578365, 14.0578413, 14.0578461, 14.0578499, 14.0578547, 14.0578594,
-    14.0578623, 14.0578671, 14.0578718, 14.0578766, 14.0578804, 14.0578852,
-    14.0578899, 14.0578947, 14.0578976, 14.0579023, 14.0579071, 14.0579119,
-    14.0579166, 14.0579205, 14.0579252, 14.05793,   14.0579348, 14.0579395,
-    14.0579424, 14.0579472, 14.0579519, 14.0579548, 14.0579596, 14.0579634,
-    14.0579681, 14.0579729, 14.0579758, 14.0579805, 14.0579844, 14.0579891,
-    14.0579939, 14.0579967, 14.0580015, 14.0580063, 14.0580091, 14.058013,
-    14.0580177, 14.0580206, 14.0580254, 14.0580292, 14.058032,  14.0580368,
-    14.0580416, 14.0580444, 14.0580492, 14.058053,  14.0580559, 14.0580606,
-    14.0580645, 14.0580673, 14.0580721, 14.0580769, 14.0580797, 14.0580845,
-    14.0580883, 14.0580931, 14.0580959, 14.0581007, 14.0581036, 14.0581083,
-    14.0581121, 14.0581169, 14.0581198, 14.0581236, 14.0581284, 14.0581312,
-    14.0581341, 14.0581379, 14.0581408, 14.0581455, 14.0581484, 14.0581532,
-    14.058157,  14.0581598, 14.0581646, 14.0581684, 14.0581713, 14.058176,
-    14.0581789, 14.0581837, 14.0581875, 14.0581903, 14.0581951, 14.058198,
-    14.0582018, 14.0582047, 14.0582085, 14.0582113, 14.0582142, 14.058218,
-    14.0582209, 14.0582237, 14.0582285, 14.0582323, 14.0582371, 14.0582399,
-    14.0582428, 14.0582476, 14.0582514, 14.0582542, 14.058259,  14.0582628,
-    14.0582657, 14.0582705, 14.0582733, 14.0582781, 14.0582819, 14.0582848,
-    14.0582895, 14.0582924, 14.0582962, 14.058301,  14.0583038, 14.0583076,
-    14.0583124, 14.0583153, 14.0583181, 14.058322,  14.0583248, 14.0583277,
-    14.0583315, 14.0583363, 14.0583391, 14.058342,  14.0583458, 14.0583487,
-    14.0583525, 14.0583553, 14.0583582, 14.058362,  14.0583668, 14.0583696,
-    14.0583725, 14.0583763, 14.0583792, 14.0583839, 14.0583868, 14.0583906,
-    14.0583935, 14.0583963, 14.0584002, 14.058403,  14.0584078, 14.0584116,
-    14.0584145, 14.0584173, 14.0584192, 14.0584221, 14.0584259, 14.0584288,
-    14.0584316, 14.0584364, 14.0584402, 14.0584431, 14.0584459, 14.0584497,
-    14.0584526, 14.0584564, 14.0584593, 14.0584621, 14.058466,  14.0584688,
-    14.0584717, 14.0584755, 14.0584784, 14.0584812, 14.058485,  14.0584879,
-    14.0584908, 14.0584946, 14.0584974, 14.0585012, 14.0585041, 14.058507,
-    14.0585108, 14.0585136, 14.0585165, 14.0585203, 14.0585232, 14.0585279,
-    14.0585308, 14.0585346, 14.0585375, 14.0585423, 14.0585461, 14.0585489,
-    14.0585537, 14.0585566, 14.0585604, 14.0585632, 14.0585661, 14.0585709,
-    14.0585747, 14.0585775, 14.0585804, 14.0585823, 14.0585852, 14.058589,
-    14.0585918, 14.0585957, 14.0585985, 14.0586014, 14.0586061, 14.05861,
-    14.0586128, 14.0586157, 14.0586195, 14.0586224, 14.0586252, 14.058629,
-    14.058629,  14.058629,  14.0586395, 14.0586433, 14.0586462, 14.05865,
-    14.0586529, 14.0586557, 14.0586596, 14.0586624, 14.0586672, 14.05867,
-    14.0586739, 14.0586767, 14.0586796, 14.0586843, 14.0586882, 14.058691,
-    14.0586958, 14.0586996, 14.0587025, 14.0587053, 14.0587091, 14.058712,
-    14.0587149, 14.0587187, 14.0587215, 14.0587244, 14.0587282, 14.0587311,
-    14.0587339, 14.0587378, 14.0587406, 14.0587444, 14.0587473, 14.0587502,
-    14.058754,  14.0587568, 14.0587568, 14.0587568, 14.0587683, 14.0587711,
-    14.058774,  14.0587788, 14.0587826, 14.0587854, 14.0587902, 14.058794,
-    14.0587969, 14.0587997, 14.0588036, 14.0588064, 14.0588093, 14.0588131,
-    14.058816,  14.0588188, 14.0588226, 14.0588255, 14.0588284, 14.0588322,
-    14.058835,  14.0588388, 14.0588398, 14.0588436, 14.0588465, 14.0588493,
-    14.0588531, 14.058856,  14.0588589, 14.0588627, 14.0588636, 14.0588675,
-    14.0588703, 14.0588732, 14.058877,  14.0588779, 14.0588818, 14.0588846,
-    14.0588884, 14.0588913, 14.0588942, 14.0588961, 14.0588989, 14.0589027,
-    14.0589056, 14.0589085, 14.0589123, 14.0589151, 14.058917,  14.0589199,
-    14.0589228, 14.0589266, 14.0589294, 14.0589333, 14.0589361, 14.058939,
-    14.0589428, 14.0589457, 14.0589504, 14.0589533, 14.0589571, 14.05896,
-    14.0589628, 14.0589666, 14.0589714, 14.0589743, 14.0589771, 14.0589828,
-    14.0589857, 14.0589886, 14.0589924, 14.0589972, 14.059,     14.0590029,
-    14.0590076, 14.0590115, 14.0590143, 14.0590172, 14.059021,  14.0590239,
-    14.0590277, 14.0590305, 14.0590334, 14.0590372, 14.0590401, 14.0590448,
-    14.0590477, 14.0590515, 14.0590563, 14.0590591, 14.059062,  14.0590668,
-    14.0590706, 14.0590754, 14.0590782, 14.059082,  14.0590868, 14.0590897,
-    14.0590925, 14.0590973, 14.0590992, 14.0591021, 14.0591059, 14.0591087,
-    14.0591116, 14.0591164, 14.0591202, 14.059123,  14.0591269, 14.0591297,
-    14.0591326, 14.0591373, 14.0591412, 14.059144,  14.0591488, 14.0591516,
-    14.0591555, 14.0591602, 14.0591631, 14.0591679, 14.0591717, 14.0591764,
-    14.0591793, 14.0591822, 14.0591869, 14.0591908, 14.0591936, 14.0591965,
-    14.0592003, 14.0592051, 14.0592079, 14.0592108, 14.0592146, 14.0592194,
-    14.0592222, 14.059226,  14.0592289, 14.0592337, 14.0592365, 14.0592403,
-    14.0592451, 14.059248,  14.0592508, 14.0592556, 14.0592594, 14.0592642,
-    14.059267,  14.0592709, 14.0592737, 14.0592785, 14.0592813, 14.0592852,
-    14.0592899, 14.0592928, 14.0592957, 14.0593004, 14.0593042, 14.0593071,
-    14.0593119, 14.0593147, 14.0593204, 14.0593233, 14.0593233, 14.0593233,
-    14.0593348, 14.0593376, 14.0593405, 14.0593452, 14.0593491, 14.0593519,
-    14.0593567, 14.0593596, 14.0593634, 14.0593681, 14.0593729, 14.0593758,
-    14.0593805, 14.0593843, 14.0593891, 14.059392,  14.0593967, 14.0593996,
-    14.0594044, 14.0594082, 14.059411,  14.0594149, 14.0594177, 14.0594225,
-    14.0594254, 14.0594292, 14.059432,  14.0594349, 14.0594387, 14.0594416,
-    14.0594444, 14.0594492, 14.059453,  14.0594559, 14.0594587, 14.0594645,
-    14.0594673, 14.0594702, 14.0594749, 14.0594788, 14.0594835, 14.0594864,
-    14.0594893, 14.059494,  14.0594978, 14.0595007, 14.0595036, 14.0595083,
-    14.0595121, 14.059515,  14.0595188, 14.0595217, 14.0595245, 14.0595284,
-    14.0595331, 14.059536,  14.0595388, 14.0595436, 14.0595474, 14.0595503,
-    14.0595531, 14.059557,  14.0595598, 14.0595636, 14.0595665, 14.0595694,
-    14.0595732, 14.059576,  14.0595789, 14.0595827, 14.0595875, 14.0595884,
-    14.0595922, 14.0595951, 14.059598,  14.0596018, 14.0596066, 14.0596094,
-    14.0596132, 14.0596161, 14.0596189, 14.0596228, 14.0596256, 14.0596285,
-    14.0596304, 14.0596333, 14.0596371, 14.0596399, 14.0596428, 14.0596466,
-    14.0596495, 14.0596523, 14.0596581, 14.0596609, 14.0596638, 14.0596676,
-    14.0596724, 14.0596752, 14.0596781, 14.0596819, 14.0596848, 14.0596876,
-    14.0596914, 14.0596943, 14.0596972, 14.059701,  14.0597057, 14.0597086,
-    14.0597124, 14.0597153, 14.05972,   14.0597229, 14.0597267, 14.0597315,
-    14.0597343, 14.0597391, 14.059742,  14.0597467, 14.0597506, 14.0597534,
-    14.0597582, 14.059762,  14.0597668, 14.0597696, 14.0597744, 14.0597792,
-    14.059782,  14.0597858, 14.0597906, 14.0597954, 14.0597982, 14.059803,
-    14.0598068, 14.0598116, 14.0598164, 14.0598192, 14.059824,  14.0598269,
-    14.0598316, 14.0598364, 14.0598402, 14.0598431, 14.0598478, 14.0598516,
-    14.0598545, 14.0598593, 14.0598621, 14.059866,  14.0598707, 14.0598736,
-    14.0598783, 14.0598812, 14.059886,  14.0598898, 14.0598946, 14.0598974,
-    14.0599012, 14.0599041, 14.059907,  14.0599117, 14.0599155, 14.0599184,
-    14.0599232, 14.059926,  14.0599298, 14.0599327, 14.0599356, 14.0599394,
-    14.0599442, 14.059947,  14.0599508, 14.0599556, 14.0599585, 14.0599613,
-    14.0599661, 14.0599699, 14.0599728, 14.0599775, 14.0599804, 14.0599842,
-    14.0599871, 14.0599899, 14.0599937, 14.0599966, 14.0600004, 14.0600033,
-    14.060008,  14.06001,   14.0600147, 14.0600176, 14.0600204, 14.0600243,
-    14.0600271, 14.0600319, 14.0600348, 14.0600386, 14.0600433, 14.0600462,
-    14.06005,   14.0600548, 14.0600576, 14.0600605, 14.0600643, 14.0600672,
-    14.0600719, 14.0600748, 14.0600786, 14.0600815, 14.0600843, 14.0600901,
-    14.0600929, 14.0600958, 14.0600996, 14.0601025, 14.0601053, 14.0601091,
-    14.060112,  14.0601149, 14.0601187, 14.0601215, 14.0601263, 14.0601311,
-    14.0601339, 14.0601397, 14.0601425, 14.0601473, 14.0601501, 14.0601549,
-    14.0601587, 14.0601635, 14.0601664, 14.0601711, 14.060174,  14.0601788,
-    14.0601826, 14.0601854, 14.0601892, 14.0601921, 14.0601969, 14.0601997,
-    14.0602036, 14.0602064, 14.0602093, 14.060214,  14.0602179, 14.0602207,
-    14.0602236, 14.0602274, 14.0602322, 14.060235,  14.0602398, 14.0602436,
-    14.0602484, 14.0602531, 14.060256,  14.0602608, 14.0602636, 14.0602684,
-    14.0602732, 14.060277,  14.0602818, 14.0602846, 14.0602884, 14.0602932,
-    14.0602961, 14.0602989, 14.0603037, 14.0603075, 14.0603123, 14.060317,
-    14.0603199, 14.0603247, 14.0603294, 14.0603342, 14.060338,  14.0603428,
-    14.0603476, 14.0603523, 14.0603571, 14.0603619, 14.0603647, 14.0603695,
-    14.0603743, 14.060379,  14.0603838, 14.0603886, 14.0603933, 14.0603981,
-    14.0604029, 14.0604067, 14.0604115, 14.0604143, 14.0604191, 14.0604219,
-    14.0604258, 14.0604305, 14.0604334, 14.0604382, 14.060442,  14.0604448,
-    14.0604467, 14.0604496, 14.0604544, 14.0604563, 14.0604591, 14.060462,
-    14.0604639, 14.0604668, 14.0604687, 14.0604715, 14.0604734, 14.0604773,
-    14.0604801, 14.060482,  14.0604849, 14.0604877, 14.0604916, 14.0604944,
-    14.0604973, 14.0605011, 14.060504,  14.0605068, 14.0605106, 14.0605135,
-    14.0605183, 14.0605211, 14.0605249, 14.0605297, 14.0605326, 14.0605373,
-    14.0605412, 14.0605459, 14.0605507, 14.0605536, 14.0605583, 14.0605631,
-    14.0605659, 14.0605717, 14.0605764, 14.0605812, 14.060586,  14.0605907,
-    14.0605936, 14.0605984, 14.0606031, 14.0606079, 14.0606127, 14.0606155,
-    14.0606213, 14.060626,  14.0606289, 14.0606337, 14.0606365, 14.0606403,
-    14.0606451, 14.0606499, 14.0606527, 14.0606575, 14.0606604, 14.0606651,
-    14.0606689, 14.0606718, 14.0606766, 14.0606804, 14.0606833, 14.0606861,
-    14.0606899, 14.0606928, 14.0606956, 14.0606995, 14.0607023, 14.0607071,
-    14.06071,   14.0607119, 14.0607157, 14.0607185, 14.0607214, 14.0607233,
-    14.0607262, 14.06073,   14.0607328, 14.0607347, 14.0607376, 14.0607405,
-    14.0607424, 14.0607452, 14.0607491, 14.06075,   14.0607538, 14.0607548,
-    14.0607586, 14.0607595, 14.0607634, 14.0607653, 14.0607662, 14.06077,
-    14.060771,  14.0607729, 14.0607758, 14.0607777, 14.0607805, 14.0607824,
-    14.0607853, 14.0607872, 14.0607901, 14.0607939, 14.0607948, 14.0607986,
-    14.0607996, 14.0608034, 14.0608044, 14.0608082, 14.0608091, 14.060813,
-    14.0608149, 14.0608177, 14.0608196, 14.0608225, 14.0608253, 14.0608273,
-    14.0608301, 14.060832,  14.0608349, 14.0608387, 14.0608397, 14.0608435,
-    14.0608463, 14.0608482, 14.0608511, 14.060853,  14.0608559, 14.0608587,
-    14.0608606, 14.0608644, 14.0608654, 14.0608692, 14.0608702, 14.060874,
-    14.0608749, 14.0608788, 14.0608816, 14.0608835, 14.0608864, 14.0608883,
-    14.0608912, 14.0608931, 14.0608959, 14.0608978, 14.0609007, 14.0609026,
-    14.0609055, 14.0609074, 14.0609102, 14.0609121, 14.060915,  14.0609169,
-    14.0609188, 14.0609198, 14.0609236, 14.0609245, 14.0609283, 14.0609293,
-    14.0609331, 14.0609341, 14.060936,  14.0609388, 14.0609407, 14.0609426,
-    14.0609455, 14.0609474, 14.0609484, 14.0609522, 14.0609531, 14.060955,
-    14.0609589, 14.0609598, 14.0609636, 14.0609646, 14.0609684, 14.0609694,
-    14.0609732, 14.0609741, 14.0609779, 14.0609789, 14.0609827, 14.0609837,
-    14.0609875, 14.0609903, 14.0609922, 14.0609951, 14.060998,  14.0610018,
-    14.0610046, 14.0610085, 14.0610113, 14.0610142, 14.061018,  14.0610209,
-    14.0610237, 14.0610275, 14.0610304, 14.0610332, 14.0610371, 14.0610418,
-    14.0610447, 14.0610476, 14.0610533, 14.0610561, 14.061059,  14.0610638,
-    14.0610676, 14.0610723, 14.0610752, 14.0610781, 14.0610828, 14.0610867,
-    14.0610914, 14.0610943, 14.0610991, 14.0611029, 14.0611076, 14.0611105,
-    14.0611134, 14.0611181, 14.0611219, 14.0611267, 14.0611296, 14.0611343,
-    14.0611391, 14.061142,  14.0611458, 14.0611506, 14.0611534, 14.0611582,
-    14.061162,  14.0611668, 14.0611696, 14.0611725, 14.0611773, 14.0611811,
-    14.0611839, 14.0611868, 14.0611916, 14.0611954, 14.0612001, 14.061203,
-    14.0612068, 14.0612116, 14.0612144, 14.0612192, 14.0612221, 14.0612268,
-    14.0612307, 14.0612354, 14.0612383, 14.0612411, 14.0612469, 14.0612497,
-    14.0612545, 14.0612574, 14.0612621, 14.0612659, 14.0612707, 14.0612755,
-    14.0612783, 14.0612831, 14.061286,  14.061286,  14.061286,  14.0612993,
-    14.0613022, 14.061306,  14.0613108, 14.0613136, 14.0613184, 14.0613213,
-    14.0613251, 14.0613298, 14.0613327, 14.0613375, 14.0613403, 14.0613441,
-    14.0613489, 14.0613518, 14.0613556, 14.0613604, 14.0613632, 14.0613661,
-    14.0613699, 14.0613728, 14.0613775, 14.0613804, 14.0613842, 14.0613871,
-    14.0613909, 14.0613956, 14.0613985, 14.0614014, 14.0614052, 14.061408,
-    14.0614109, 14.0614147, 14.0614176, 14.0614204, 14.0614243, 14.0614271,
-    14.06143,   14.0614338, 14.0614367, 14.0614405, 14.0614433, 14.0614462,
-    14.0614481, 14.061451,  14.0614548, 14.0614576, 14.0614605, 14.0614624,
-    14.0614653, 14.0614691, 14.0614719, 14.0614738, 14.0614767, 14.0614796,
-    14.0614815, 14.0614843, 14.0614882, 14.0614901, 14.0614929, 14.0614958,
-    14.0614977, 14.0615005, 14.0615044, 14.0615053, 14.0615091, 14.061512,
-    14.0615149, 14.0615168, 14.0615196, 14.0615215, 14.0615244, 14.0615282,
-    14.0615292, 14.061533,  14.0615358, 14.0615377, 14.0615406, 14.0615444,
-    14.0615454, 14.0615492, 14.0615501, 14.061554,  14.0615549, 14.0615587,
-    14.0615597, 14.0615635, 14.0615644, 14.0615683, 14.0615711, 14.061573,
-    14.0615759, 14.0615778, 14.0615807, 14.0615845, 14.0615854, 14.0615892,
-    14.0615902, 14.061594,  14.0615969, 14.0615988, 14.0616016, 14.0616035,
-    14.0616035, 14.0616035, 14.0616112, 14.061614,  14.0616179, 14.0616188,
-    14.0616226, 14.0616255, 14.0616274, 14.0616302, 14.0616341, 14.061635,
-    14.0616388, 14.0616417, 14.0616446, 14.0616465, 14.0616493, 14.0616531,
-    14.0616531, 14.0616531, 14.0616608, 14.0616627, 14.0616655, 14.0616674,
-    14.0616703, 14.0616732, 14.0616751, 14.0616779, 14.0616798, 14.0616837,
-    14.0616865, 14.0616884, 14.0616913, 14.0616941, 14.0616961, 14.0616989,
-    14.0617008, 14.0617037, 14.0617075, 14.0617085, 14.0617123, 14.0617151,
-    14.061717,  14.0617199, 14.0617228, 14.0617247, 14.0617275, 14.0617294,
-    14.0617332, 14.0617361, 14.061738,  14.0617409, 14.0617437, 14.0617456,
-    14.0617485, 14.0617523, 14.0617533, 14.0617571, 14.0617599, 14.0617619,
-    14.0617647, 14.0617666, 14.0617695, 14.0617714, 14.0617743, 14.0617762,
-    14.061779,  14.0617809, 14.0617838, 14.0617857, 14.0617886, 14.0617924,
-    14.0617933, 14.0617952, 14.0617981, 14.0618019, 14.0618029, 14.0618048,
-    14.0618076, 14.0618095, 14.0618124, 14.0618143, 14.0618172, 14.0618191,
-    14.0618219, 14.0618238, 14.0618258, 14.0618286, 14.0618305, 14.0618334,
-    14.0618353, 14.0618372, 14.0618401, 14.061842,  14.0618429, 14.0618467,
-    14.0618477, 14.0618496, 14.0618525, 14.0618544, 14.0618572, 14.0618591,
-    14.061861,  14.061862,  14.0618658, 14.0618668, 14.0618687, 14.0618715,
-    14.0618734, 14.0618753, 14.0618782, 14.0618801, 14.061882,  14.0618849,
-    14.0618868, 14.0618877, 14.0618916, 14.0618925, 14.0618944, 14.0618963,
-    14.0618992, 14.0619011, 14.061904,  14.0619059, 14.0619087, 14.0619106,
-    14.0619135, 14.0619154, 14.0619183, 14.0619202, 14.061923,  14.0619268,
-    14.0619278, 14.0619316, 14.0619345, 14.0619364, 14.0619392, 14.0619421,
-    14.061944,  14.0619469, 14.0619507, 14.0619516, 14.0619555, 14.0619583,
-    14.0619612, 14.0619631, 14.0619659, 14.0619698, 14.0619726, 14.0619745,
-    14.0619774, 14.0619812, 14.0619841, 14.061986,  14.0619888, 14.0619917,
-    14.0619955, 14.0619965, 14.0620003, 14.0620031, 14.062006,  14.0620098,
-    14.0620108, 14.0620146, 14.0620174, 14.0620193, 14.0620222, 14.062026,
-    14.0620289, 14.0620317, 14.0620356, 14.0620365, 14.0620403, 14.0620432,
-    14.0620461, 14.062048,  14.0620508, 14.0620546, 14.0620556, 14.0620594,
-    14.0620623, 14.0620651, 14.062067,  14.0620708, 14.0620718, 14.0620756,
-    14.0620766, 14.0620804, 14.0620813, 14.0620852, 14.0620861, 14.0620899,
-    14.0620909, 14.0620947, 14.0620956, 14.0620995, 14.0621004, 14.0621023,
-    14.0621052, 14.0621071, 14.0621099, 14.0621119, 14.0621138, 14.0621166,
-    14.0621185, 14.0621204, 14.0621233, 14.0621252, 14.0621262, 14.0621281,
-    14.0621309, 14.0621328, 14.0621347, 14.0621357, 14.0621395, 14.0621405,
-    14.0621424, 14.0621443, 14.0621452, 14.062149,  14.06215,   14.0621519,
-    14.0621538, 14.0621567, 14.0621586, 14.0621595, 14.0621614, 14.0621634,
-    14.0621662, 14.0621681, 14.06217,   14.062171,  14.0621729, 14.0621758,
-    14.0621777, 14.0621796, 14.0621805, 14.0621843, 14.0621853, 14.0621872,
-    14.0621891, 14.062192,  14.0621939, 14.0621948, 14.0621967, 14.0621986,
-    14.0622015, 14.0622034, 14.0622044, 14.0622063, 14.0622091, 14.062211,
-    14.0622129, 14.0622149, 14.0622177, 14.0622196, 14.0622206, 14.0622244,
-    14.0622253, 14.0622272, 14.0622292, 14.062232,  14.0622339, 14.0622349,
-    14.0622368, 14.0622396, 14.0622416, 14.0622435, 14.0622463, 14.0622482,
-    14.0622492, 14.0622511, 14.062254,  14.0622559, 14.0622578, 14.0622606,
-    14.0622625, 14.0622654, 14.0622673, 14.0622692, 14.0622721, 14.062274,
-    14.0622749, 14.0622787, 14.0622797, 14.0622835, 14.0622845, 14.0622883,
-    14.0622892, 14.0622911, 14.062294,  14.0622959, 14.0622988, 14.0623007,
-    14.0623035, 14.0623055, 14.0623093, 14.0623121, 14.062314,  14.0623169,
-    14.0623188, 14.0623217, 14.0623245, 14.0623264, 14.0623293, 14.0623331,
-    14.062336,  14.0623379, 14.0623407, 14.0623436, 14.0623474, 14.0623484,
-    14.0623522, 14.062355,  14.0623569, 14.0623598, 14.0623636, 14.0623646,
-    14.0623684, 14.0623713, 14.0623741, 14.062376,  14.0623789, 14.0623827,
-    14.0623856, 14.0623884, 14.0623903, 14.0623932, 14.062397,  14.062398,
-    14.0624018, 14.0624046, 14.0624065, 14.0624094, 14.0624132, 14.0624161,
-    14.0624189, 14.0624228, 14.0624256, 14.0624275, 14.0624304, 14.0624332,
-    14.0624371, 14.062438,  14.0624418, 14.0624447, 14.0624475, 14.0624514,
-    14.0624542, 14.062458,  14.0624609, 14.0624628, 14.0624657, 14.0624685,
-    14.0624723, 14.0624752, 14.0624752, 14.0624752, 14.0624828, 14.0624866,
-    14.0624895, 14.0624914, 14.0624943, 14.0624971, 14.062499,  14.0625029,
-    14.0625057, 14.0625086, 14.0625105, 14.0625134, 14.0625172, 14.0625181,
-    14.0625219, 14.0625229, 14.0625267, 14.0625277, 14.0625315, 14.0625324,
-    14.0625362, 14.0625372, 14.0625391, 14.062542,  14.0625439, 14.0625467,
-    14.0625486, 14.0625505, 14.0625534, 14.0625553, 14.0625572, 14.0625601,
-    14.062562,  14.0625648, 14.0625668, 14.0625696, 14.0625715, 14.0625725,
-    14.0625763, 14.0625772, 14.0625792, 14.062582,  14.0625839, 14.0625858,
-    14.0625868, 14.0625906, 14.0625916, 14.0625935, 14.0625954, 14.0625982,
-    14.0626001, 14.062602,  14.0626049, 14.0626068, 14.0626078, 14.0626116,
-    14.0626125, 14.0626144, 14.0626173, 14.0626192, 14.0626211, 14.062624,
-    14.0626259, 14.0626268, 14.0626307, 14.0626316, 14.0626335, 14.0626364,
-    14.0626383, 14.0626402, 14.0626411, 14.062645,  14.0626469, 14.0626478,
-    14.0626497, 14.0626526, 14.0626545, 14.0626564, 14.0626593, 14.0626612,
-    14.0626621, 14.0626659, 14.0626669, 14.0626707, 14.0626717, 14.0626736,
-    14.0626764, 14.0626783, 14.0626812, 14.0626831, 14.062686,  14.0626898,
-    14.0626907, 14.0626945, 14.0626974, 14.0626993, 14.0627022, 14.062706,
-    14.0627069, 14.0627108, 14.0627136, 14.0627155, 14.0627184, 14.0627213,
-    14.0627232, 14.062726,  14.0627298, 14.0627327, 14.0627356, 14.0627394,
-    14.0627422, 14.062746,  14.062747,  14.0627508, 14.0627537, 14.0627565,
-    14.0627604, 14.0627632, 14.0627661, 14.0627699, 14.0627728, 14.0627756,
-    14.0627794, 14.0627823, 14.0627851, 14.062789,  14.0627918, 14.0627956,
-    14.0628004, 14.0628033, 14.0628061, 14.0628099, 14.0628128, 14.0628157,
-    14.0628195, 14.0628223, 14.0628252, 14.062829,  14.0628319, 14.0628347,
-    14.0628386, 14.0628414, 14.0628452, 14.0628481, 14.062851,  14.0628548,
-    14.0628595, 14.0628624, 14.0628653, 14.0628691, 14.0628719, 14.0628748,
-    14.0628786, 14.0628815, 14.0628862, 14.0628901, 14.0628929, 14.0628958,
-    14.0628996, 14.0629025, 14.0629053, 14.0629091, 14.0629139, 14.0629168,
-    14.0629196, 14.0629234, 14.0629263, 14.0629311, 14.0629349, 14.0629377,
-    14.0629425, 14.0629454, 14.0629501, 14.0629539, 14.0629587, 14.0629616,
-    14.0629663, 14.0629692, 14.062974,  14.0629787, 14.0629826, 14.0629873,
-    14.0629921, 14.062995,  14.0629997, 14.0630035, 14.0630083, 14.0630131,
-    14.0630178, 14.0630207, 14.0630255, 14.0630302, 14.063035,  14.0630398,
-    14.0630436, 14.0630484, 14.0630531, 14.0630579, 14.0630608, 14.0630655,
-    14.0630703, 14.0630751, 14.0630779, 14.0630836, 14.0630884, 14.0630932,
-    14.063098,  14.0631027, 14.0631075, 14.0631104, 14.0631151, 14.0631199,
-    14.0631227, 14.0631285, 14.0631332, 14.0631361, 14.0631409, 14.0631456,
-    14.0631485, 14.0631533, 14.063158,  14.0631628, 14.0631666, 14.0631714,
-    14.0631762, 14.0631809, 14.0631838, 14.0631886, 14.0631933, 14.0631971,
-    14.0632019, 14.0632067, 14.0632095, 14.0632143, 14.0632191, 14.0632219,
-    14.0632277, 14.0632305, 14.0632353, 14.0632401, 14.0632429, 14.0632477,
-    14.0632515, 14.0632563, 14.063261,  14.0632639, 14.0632687, 14.0632725,
-    14.0632772, 14.0632801, 14.063283,  14.0632877, 14.0632925, 14.0632963,
-    14.0632992, 14.0633039, 14.0633068, 14.0633116, 14.0633154, 14.0633202,
-    14.063323,  14.0633278, 14.0633316, 14.0633345, 14.0633373, 14.0633411,
-    14.063344,  14.0633469, 14.0633507, 14.0633535, 14.0633564, 14.0633602,
-    14.0633631, 14.0633659, 14.0633698, 14.0633726, 14.0633745, 14.0633774,
-    14.0633812, 14.0633821, 14.063386,  14.0633888, 14.0633907, 14.0633936,
-    14.0633955, 14.0633984, 14.0634003, 14.0634031, 14.063405,  14.0634079,
-    14.0634098, 14.0634108, 14.0634146, 14.0634155, 14.0634174, 14.0634212,
-    14.0634222, 14.063426,  14.063427,  14.0634289, 14.0634317, 14.0634336,
-    14.0634356, 14.0634384, 14.0634403, 14.0634413, 14.0634432, 14.063446,
-    14.063448,  14.0634499, 14.0634527, 14.0634556, 14.0634575, 14.0634594,
-    14.0634623, 14.0634642, 14.0634661, 14.063467,  14.0634708, 14.0634718,
-    14.0634737, 14.0634756, 14.0634785, 14.0634804, 14.0634813, 14.0634851,
-    14.0634861, 14.063488,  14.0634899, 14.0634909, 14.0634928, 14.0634947,
-    14.0634956, 14.0634975, 14.0634995, 14.0635004, 14.0635004, 14.0635004,
-    14.0635023, 14.0635023, 14.0635023, 14.0635023, 14.0635042, 14.0635042,
-    14.0635042, 14.0635042, 14.0635042, 14.0635042, 14.0635042, 14.0635042,
-    14.0635042, 14.0635042, 14.0635042, 14.0635042, 14.0635042, 14.0635052,
-    14.0635052, 14.0635052, 14.0635052, 14.0635052, 14.0635052, 14.0635052,
-    14.0635052, 14.0635052, 14.0635052, 14.0635052, 14.0635052, 14.0635071,
-    14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.0635071,
-    14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.0635071,
-    14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.0635071,
-    14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.0635071,
-    14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.0635071,
-    14.0635071, 14.0635071, 14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.0635071, 14.063509,
-    14.063509,  14.063509,  14.0635071, 14.0635071, 14.0635071, 14.0635071,
-    14.0635071, 14.0635071, 14.0635071, 14.063509,  14.063509,  14.063509,
-    14.063509,  14.0635071, 14.0635071, 14.0635071, 14.0635071, 14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.0635071, 14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.063509,
-    14.063509,  14.063509,  14.063509,  14.063509,  14.063509,  14.0635099,
-    14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099,
-    14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099,
-    14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099,
-    14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099,
-    14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099,
-    14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099,
-    14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099,
-    14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099, 14.0635099,
-    14.0635099, 14.0635118, 14.0635118, 14.0635118, 14.0635118, 14.0635118,
-    14.0635118, 14.0635118, 14.0635118, 14.0635138, 14.0635138, 14.0635138,
-    14.0635138, 14.0635138, 14.0635138, 14.0635138, 14.0635138, 14.0635138,
-    14.0635138, 14.0635138, 14.0635138, 14.0635138, 14.0635138, 14.0635138,
-    14.0635138, 14.0635138, 14.0635138, 14.0635138, 14.0635138, 14.0635138,
-    14.0635138, 14.0635138, 14.0635157, 14.0635157, 14.0635157, 14.0635157,
-    14.0635157, 14.0635157, 14.0635157, 14.0635157, 14.0635166, 14.0635166,
-    14.0635166, 14.0635166, 14.0635166, 14.0635166, 14.0635166, 14.0635166,
-    14.0635166, 14.0635166, 14.0635166, 14.0635166, 14.0635166, 14.0635166,
-    14.0635166, 14.0635166, 14.0635166, 14.0635166, 14.0635166, 14.0635166,
-    14.0635185, 14.0635185, 14.0635185, 14.0635185, 14.0635185, 14.0635185,
-    14.0635185, 14.0635185, 14.0635185, 14.0635185, 14.0635185, 14.0635185,
-    14.0635185, 14.0635185, 14.0635185, 14.0635185, 14.0635185, 14.0635185,
-    14.0635185, 14.0635185, 14.0635185, 14.0635185, 14.0635185, 14.0635185,
-    14.0635185, 14.0635185, 14.0635185, 14.0635185, 14.0635185, 14.0635185,
-    14.0635185, 14.0635185, 14.0635204, 14.0635204, 14.0635204, 14.0635204,
-    14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204,
-    14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204,
-    14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204,
-    14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204,
-    14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204,
-    14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204,
-    14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204,
-    14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204,
-    14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635204, 14.0635214,
-    14.0635214, 14.0635214, 14.0635214, 14.0635214, 14.0635214, 14.0635214,
-    14.0635214, 14.0635214, 14.0635204, 14.0635204, 14.0635204, 14.0635204,
-    14.0635204, 14.0635204, 14.0635204, 14.0635214, 14.0635214, 14.0635214,
-    14.0635214, 14.0635214, 14.0635214, 14.0635214, 14.0635214, 14.0635214,
-    14.0635214, 14.0635214, 14.0635214, 14.0635214, 14.0635214, 14.0635214,
-    14.0635214, 14.0635214, 14.0635214, 14.0635214, 14.0635214, 14.0635214,
-    14.0635214, 14.0635214, 14.0635214, 14.0635214, 14.0635233, 14.0635233,
-    14.0635233, 14.0635233, 14.0635233, 14.0635233, 14.0635233, 14.0635233,
-    14.0635233, 14.0635233, 14.0635233, 14.0635233, 14.0635233, 14.0635233,
-    14.0635233, 14.0635252, 14.0635252, 14.0635252, 14.0635252, 14.0635252,
-    14.0635252, 14.0635252, 14.0635252, 14.0635252, 14.0635252, 14.0635252,
-    14.0635262, 14.0635262, 14.0635262, 14.0635262, 14.0635262, 14.0635262,
-    14.0635262, 14.0635262, 14.0635262, 14.0635262, 14.0635281, 14.0635281,
-    14.0635281, 14.0635281, 14.0635281, 14.0635281, 14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.0635309, 14.0635309, 14.0635309, 14.0635309,
-    14.0635309, 14.0635309, 14.0635309, 14.0635309, 14.0635309, 14.0635309,
-    14.0635309, 14.0635309, 14.0635309, 14.0635309, 14.0635309, 14.0635309,
-    14.0635309, 14.0635309, 14.0635309, 14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.0635309,
-    14.0635309, 14.0635309, 14.0635309, 14.0635309, 14.0635309, 14.0635309,
-    14.0635309, 14.0635309, 14.0635309, 14.0635309, 14.0635309, 14.0635309,
-    14.0635309, 14.0635309, 14.0635309, 14.0635309, 14.0635309, 14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.06353,   14.06353,   14.06353,   14.06353,   14.06353,
-    14.06353,   14.0635281, 14.0635281, 14.0635281, 14.0635281, 14.0635281,
-    14.0635281, 14.0635281, 14.0635281, 14.0635281, 14.0635281, 14.0635281,
-    14.0635281, 14.0635281,
-};
-
-const float GPS_DATA_VNORD[3230] = {
-    0.351999998,
-    0.148000002,
-    0.416000009,
-    0.93900001,
-    0.730000019,
-    1.02699995,
-    0.666000009,
-    -0.231000006,
-    -1.16999996,
-    -2.30699992,
-    -3.20600009,
-    -3.00200009,
-    -3.70700002,
-    -4.22700024,
-    -4.67199993,
-    -5.57399988,
-    -5.45200014,
-    -5.48999977,
-    -5.64799976,
-    -6.33300018,
-    -6.73199987,
-    -7.62200022,
-    -8.29199982,
-    -8.40400028,
-    -9.70100021,
-    -10.507,
-    -11.7489996,
-    -12.0839996,
-    -12.5909996,
-    -12.6820002,
-    -11.7309999,
-    -11.9650002,
-    -12.0939999,
-    -13.6719999,
-    -15.0109997,
-    -15.0109997,
-    -15.0109997,
-    -14.8500004,
-    -15.4840002,
-    -15.2959995,
-    -17.5100002,
-    -16.7810001,
-    -16.1110001,
-    -19.118,
-    -19.1270008,
-    -19.5230007,
-    -20.0550003,
-    -20.7089996,
-    -20.9389992,
-    -21.2119999,
-    -21.5429993,
-    -22.3339996,
-    -22.5639992,
-    -23.4220009,
-    -23.0650005,
-    -23.2950001,
-    -22.4379997,
-    -21.3029995,
-    -24.0820007,
-    -25.4619999,
-    -25.5200005,
-    -25.8449993,
-    -26.3719997,
-    -26.8829994,
-    -27.6389999,
-    -28.3600006,
-    -29.3729992,
-    -31.7099991,
-    -33.6010017,
-    -34.3619995,
-    -35.3660011,
-    -33.8919983,
-    -36.1969986,
-    -39.1339989,
-    -40.9700012,
-    -41.4020004,
-    -41.3540001,
-    -41.2709999,
-    -41.3740005,
-    -41.144001,
-    -41.1500015,
-    -41.6889992,
-    -41.4199982,
-    -40.4099998,
-    -41.5540009,
-    -43.0079994,
-    -42.7929993,
-    -41.257,
-    -41.098999,
-    -40.2929993,
-    -39.7179985,
-    -39.9920006,
-    -38.5600014,
-    -38.9049988,
-    -38.8969994,
-    -37.618,
-    -38.0940018,
-    -37.6609993,
-    -37.4220009,
-    -36.7929993,
-    -36.1969986,
-    -35.8510017,
-    -35.1310005,
-    -34.4799995,
-    -33.6529999,
-    -32.3510017,
-    -30.5639992,
-    -29.6720009,
-    -29.0009995,
-    -28.4799995,
-    -28.0240002,
-    -28.1830006,
-    -27.5569992,
-    -26.9740009,
-    -27.2469997,
-    -26.9790001,
-    -26.5960007,
-    -26.3360004,
-    -26.1350002,
-    -26.2299995,
-    -26.0359993,
-    -25.4969997,
-    -25.5699997,
-    -25.3560009,
-    -25.2299995,
-    -25.2409992,
-    -25.1720009,
-    -25.2049999,
-    -25.0540009,
-    -25.2329998,
-    -25.1000004,
-    -25.2369995,
-    -25.4580002,
-    -25.4519997,
-    -25.3460007,
-    -25.3729992,
-    -25.2730007,
-    -25.2269993,
-    -25.2450008,
-    -25.7280006,
-    -25.3500004,
-    -25.2579994,
-    -25.1259995,
-    -24.9729996,
-    -24.7450008,
-    -24.2549992,
-    -24.3139992,
-    -24.4720001,
-    -24.7630005,
-    -24.5160007,
-    -24.2290001,
-    -24.1709995,
-    -23.573,
-    -24.1159992,
-    -24.1599998,
-    -24.2220001,
-    -23.9729996,
-    -23.7670002,
-    -23.7339993,
-    -23.5450001,
-    -23.4020004,
-    -23.4820004,
-    -23.9060001,
-    -23.6959991,
-    -23.7159996,
-    -23.6879997,
-    -23.698,
-    -23.6170006,
-    -23.3279991,
-    -23.2590008,
-    -23.0960007,
-    -22.8899994,
-    -22.868,
-    -22.698,
-    -23.0669994,
-    -22.9610004,
-    -23.1200008,
-    -22.9799995,
-    -22.9039993,
-    -23.118,
-    -23.2870007,
-    -23.1669998,
-    -23.2210007,
-    -23.4470005,
-    -23.1030006,
-    -22.9179993,
-    -22.9309998,
-    -22.8889999,
-    -22.9470005,
-    -22.7229996,
-    -22.8719997,
-    -22.8859997,
-    -22.9960003,
-    -23.2439995,
-    -23.0319996,
-    -23.1350002,
-    -23.0809994,
-    -23.2019997,
-    -23.0149994,
-    -22.9899998,
-    -22.9400005,
-    -22.7810001,
-    -22.5709991,
-    -22.6569996,
-    -23.0300007,
-    -22.7900009,
-    -22.5699997,
-    -22.3059998,
-    -22.2070007,
-    -22.1119995,
-    -22.2619991,
-    -22.2819996,
-    -22.2880001,
-    -22.0349998,
-    -21.9650002,
-    -21.9190006,
-    -22.0090008,
-    -22.1159992,
-    -22.3589993,
-    -22.1410007,
-    -21.9680004,
-    -22.2049999,
-    -22.0580006,
-    -21.9549999,
-    -21.9389992,
-    -21.8789997,
-    -21.7840004,
-    -21.8889999,
-    -21.4790001,
-    -21.6650009,
-    -21.5709991,
-    -21.4220009,
-    -21.3269997,
-    -21.2010002,
-    -21.4230003,
-    -21.2520008,
-    -21.4060001,
-    -21.2970009,
-    -21.2940006,
-    -21.375,
-    -21.4589996,
-    -21.4519997,
-    -21.4009991,
-    -21.4379997,
-    -21.4209995,
-    -21.3799992,
-    -21.3729992,
-    -21.2940006,
-    -21.4430008,
-    -21.3619995,
-    -21.2819996,
-    -21.5370007,
-    -21.2299995,
-    -21.0820007,
-    -20.8589993,
-    -21.0330009,
-    -21.2339993,
-    -21.1410007,
-    -21.1280003,
-    -21.0680008,
-    -20.9790001,
-    -21.2600002,
-    -21.2670002,
-    -20.9710007,
-    -21.2140007,
-    -21.1949997,
-    -21.0030003,
-    -21.3069992,
-    -21.184,
-    -21.1210003,
-    -20.9309998,
-    -20.8880005,
-    -21.1060009,
-    -21.0559998,
-    -21.3029995,
-    -21.4179993,
-    -21.2929993,
-    -21.1860008,
-    -21.1889992,
-    -21.1450005,
-    -21.1509991,
-    -21.2420006,
-    -21.3169994,
-    -21.4319992,
-    -21.2150002,
-    -21.2159996,
-    -20.8719997,
-    -21.1119995,
-    -21.6289997,
-    -21.5219994,
-    -21.573,
-    -20.9780006,
-    -20.7649994,
-    -20.6940002,
-    -20.7259998,
-    -20.7959995,
-    -20.868,
-    -20.7369995,
-    -20.5990009,
-    -20.6779995,
-    -20.7310009,
-    -20.816,
-    -20.9659996,
-    -21.132,
-    -20.9500008,
-    -20.9780006,
-    -20.8390007,
-    -20.9290009,
-    -20.8519993,
-    -20.8889999,
-    -20.8939991,
-    -20.8929996,
-    -20.7099991,
-    -20.8299999,
-    -20.8129997,
-    -20.8139992,
-    -20.5610008,
-    -20.6949997,
-    -20.5349998,
-    -20.8190002,
-    -20.5249996,
-    -20.4820004,
-    -20.5699997,
-    -20.5949993,
-    -20.4190006,
-    -20.4799995,
-    -20.4009991,
-    -20.3479996,
-    -20.559,
-    -20.4780006,
-    -20.4029999,
-    -20.3419991,
-    -20.4629993,
-    -20.3850002,
-    -20.5760002,
-    -20.316,
-    -20.1700001,
-    -20.3239994,
-    -20.3640003,
-    -20.4349995,
-    -20.1930008,
-    -20.3519993,
-    -20.3670006,
-    -20.4759998,
-    -20.4039993,
-    -20.6310005,
-    -20.4279995,
-    -20.3789997,
-    -20.3509998,
-    -20.4309998,
-    -20.4699993,
-    -20.5370007,
-    -20.3630009,
-    -20.4459991,
-    -20.507,
-    -20.6900005,
-    -20.4400005,
-    -20.2070007,
-    -20.3549995,
-    -20.2600002,
-    -20.5130005,
-    -20.3490009,
-    -20.3759995,
-    -20.3169994,
-    -20.2709999,
-    -20.1580009,
-    -20.2469997,
-    -20.1420002,
-    -20.302,
-    -20.4699993,
-    -20.2600002,
-    -20.1700001,
-    -20.2409992,
-    -20.0830002,
-    -20.1480007,
-    -20.3770008,
-    -20.3740005,
-    -20.1299992,
-    -19.7929993,
-    -20.0939999,
-    -20.2779999,
-    -20.5209999,
-    -20.4220009,
-    -20.3419991,
-    -20.4109993,
-    -20.3330002,
-    -20.1940002,
-    -20.1499996,
-    -20.0249996,
-    -20.2099991,
-    -20.1070004,
-    -20.1299992,
-    -20.1380005,
-    -20.0410004,
-    -19.948,
-    -20.0879993,
-    -20.0830002,
-    -20.0680008,
-    -20.1660004,
-    -20.0200005,
-    -20.1159992,
-    -20.2269993,
-    -20.0769997,
-    -19.9810009,
-    -19.9920006,
-    -20.059,
-    -20.1070004,
-    -19.9570007,
-    -19.9360008,
-    -19.9510002,
-    -20.0639992,
-    -20.0179996,
-    -20.1380005,
-    -19.8710003,
-    -19.9090004,
-    -19.9139996,
-    -19.882,
-    -19.9680004,
-    -19.8059998,
-    -19.8950005,
-    -20.007,
-    -19.941,
-    -19.9099998,
-    -19.9309998,
-    -19.9319992,
-    -19.7140007,
-    -19.9029999,
-    -19.9650002,
-    -19.9099998,
-    -19.8010006,
-    -19.8110008,
-    -19.8120003,
-    -19.7870007,
-    -19.6229992,
-    -19.8460007,
-    -19.8519993,
-    -19.8920002,
-    -20.0389996,
-    -19.9050007,
-    -19.8460007,
-    -19.8099995,
-    -19.8010006,
-    -19.7490005,
-    -19.7649994,
-    -20.0219994,
-    -19.8180008,
-    -19.7240009,
-    -19.7719994,
-    -19.7140007,
-    -19.6849995,
-    -19.7110004,
-    -19.4389992,
-    -19.6459999,
-    -20.0009995,
-    -19.2240009,
-    -18.6280003,
-    -18.6560001,
-    -18.7019997,
-    -18.6900005,
-    -18.0919991,
-    -18.1560001,
-    -18.0170002,
-    -17.5529995,
-    -16.9150009,
-    -16.9220009,
-    -17.5130005,
-    -18.9169998,
-    -20.3040009,
-    -20.3190002,
-    -20.5559998,
-    -20.0020008,
-    -20.0419998,
-    -20.6380005,
-    -20.6620007,
-    -20.6849995,
-    -20.7929993,
-    -20.9510002,
-    -20.3850002,
-    -20.0149994,
-    -19.9239998,
-    -18.8530006,
-    -18.6340008,
-    -18.3409996,
-    -18.2999992,
-    -18.3600006,
-    -18.0639992,
-    -17.0419998,
-    -15.9940004,
-    -15.9429998,
-    -15.6289997,
-    -15.4130001,
-    -14.8760004,
-    -14.4429998,
-    -14.5909996,
-    -14.8319998,
-    -14.7950001,
-    -14.7030001,
-    -14.6009998,
-    -14.4219999,
-    -14.2419996,
-    -14.1120005,
-    -14.0439997,
-    -13.9259996,
-    -13.5539999,
-    -13.5620003,
-    -13.0410004,
-    -12.5220003,
-    -12.5500002,
-    -12.2370005,
-    -12.1560001,
-    -12.2399998,
-    -11.9639997,
-    -11.9200001,
-    -11.4849997,
-    -11.3450003,
-    -11.3719997,
-    -11.6110001,
-    -11.2530003,
-    -11.3500004,
-    -10.8879995,
-    -10.7019997,
-    -10.4469995,
-    -10.25,
-    -9.94099998,
-    -9.55500031,
-    -9.4659996,
-    -9.34799957,
-    -9.29399967,
-    -9.1960001,
-    -9.32499981,
-    -8.93000031,
-    -9.10599995,
-    -8.95199966,
-    -8.64099979,
-    -8.58699989,
-    -8.50399971,
-    -8.52299976,
-    -8.42800045,
-    -8.24300003,
-    -8.16800022,
-    -7.92299986,
-    -7.59800005,
-    -7.54099989,
-    -7.75699997,
-    -7.53299999,
-    -7.27400017,
-    -7.17199993,
-    -6.99900007,
-    -6.86800003,
-    -6.76000023,
-    -6.85900021,
-    -6.71099997,
-    -6.8579998,
-    -6.38899994,
-    -6.2420001,
-    -6.28499985,
-    -6.30999994,
-    -6.14499998,
-    -6.28499985,
-    -6.29199982,
-    -6.18200016,
-    -6.09000015,
-    -6.06400013,
-    -6.09000015,
-    -5.74399996,
-    -5.64099979,
-    -5.67600012,
-    -5.67000008,
-    -5.78200006,
-    -5.68100023,
-    -5.48600006,
-    -5.31500006,
-    -5.41699982,
-    -5.28800011,
-    -5.31099987,
-    -5.39599991,
-    -5.28599977,
-    -5.07499981,
-    -5.03399992,
-    -5.07600021,
-    -4.77400017,
-    -4.68400002,
-    -5.15799999,
-    -4.54799986,
-    -4.48199987,
-    -4.51200008,
-    -4.62799978,
-    -4.48799992,
-    -4.38399982,
-    -4.31400013,
-    -4.15999985,
-    -4.2249999,
-    -4.21999979,
-    -4.14499998,
-    -3.99600005,
-    -3.83299994,
-    -3.90799999,
-    -3.86800003,
-    -3.77999997,
-    -3.6559999,
-    -3.648,
-    -3.5250001,
-    -3.64299989,
-    -3.71499991,
-    -3.38899994,
-    -3.53800011,
-    -3.36400008,
-    -3.26600003,
-    -3.02399993,
-    -3.24399996,
-    -3.08999991,
-    -3.50500011,
-    -3.204,
-    -3.14299989,
-    -3.17700005,
-    -3.00200009,
-    -2.99000001,
-    -3.20900011,
-    -3.43799996,
-    -3.62899995,
-    -3.88499999,
-    -3.82800007,
-    -3.3829999,
-    -3.3440001,
-    -3.28900003,
-    -3.18700004,
-    -3.33999991,
-    -3.52099991,
-    -3.71700001,
-    -3.83699989,
-    -3.63199997,
-    -3.68499994,
-    -3.79200006,
-    -3.60700011,
-    -3.40300012,
-    -3.352,
-    -3.41400003,
-    -3.5710001,
-    -3.66100001,
-    -3.62700009,
-    -3.70300007,
-    -3.76699996,
-    -3.65499997,
-    -3.78900003,
-    -3.71600008,
-    -4.00299978,
-    -3.83500004,
-    -3.59200001,
-    -3.50600004,
-    -3.17499995,
-    -3.07999992,
-    -2.91499996,
-    -2.9519999,
-    -2.96499991,
-    -2.9230001,
-    -2.72600007,
-    -2.62100005,
-    -2.96600008,
-    -2.80500007,
-    -2.93099999,
-    -2.8039999,
-    -3.01900005,
-    -3.1500001,
-    -3.14499998,
-    -2.98399997,
-    -3.1559999,
-    -3.08400011,
-    -3.05800009,
-    -2.88400006,
-    -2.85899997,
-    -2.7579999,
-    -2.80500007,
-    -2.49499989,
-    -2.454,
-    -2.25099993,
-    -2.23200011,
-    -2.38400006,
-    -2.2980001,
-    -2.27600002,
-    -2.31900001,
-    -2.13700008,
-    -1.90199995,
-    -1.89499998,
-    -1.93599999,
-    -1.67900002,
-    -1.75300002,
-    -1.71000004,
-    -1.66999996,
-    -1.60800004,
-    -1.47000003,
-    -1.43299997,
-    -1.579,
-    -1.574,
-    -1.46599996,
-    -1.41900003,
-    -1.54799998,
-    -1.72399998,
-    -1.66199994,
-    -1.52400005,
-    -1.41199994,
-    -1.24199998,
-    -1.07799995,
-    -1.00699997,
-    -0.885999978,
-    -0.926999986,
-    -0.853999972,
-    -0.871999979,
-    -1.05799997,
-    -1,
-    -0.978999972,
-    -1.10599995,
-    -0.930000007,
-    -1.03199995,
-    -1.22899997,
-    -1.17900002,
-    -1.03600001,
-    -1.03400004,
-    -1.12,
-    -1.15199995,
-    -1.01699996,
-    -0.940999985,
-    -0.838,
-    -0.708999991,
-    -0.55400002,
-    -0.546000004,
-    -0.574000001,
-    -0.514999986,
-    -0.666000009,
-    -0.810000002,
-    -0.902999997,
-    -1.40600002,
-    -1.20500004,
-    -1.27999997,
-    -1.49699998,
-    -1.55299997,
-    -1.62300003,
-    -1.50300002,
-    -1.51600003,
-    -1.375,
-    -1.76600003,
-    -1.73300004,
-    -1.54100001,
-    -1.40900004,
-    -1.74300003,
-    -1.63399994,
-    -1.20700002,
-    -0.879999995,
-    -0.836000025,
-    -1.28999996,
-    -1.824,
-    -2.0940001,
-    -2.10500002,
-    -1.66799998,
-    -1.60899997,
-    -1.23199999,
-    -0.885999978,
-    -0.470999986,
-    -0.880999982,
-    -1.02600002,
-    -1.329,
-    -1.21000004,
-    -1.35300004,
-    -1.25800002,
-    -1.77100003,
-    -1.83800006,
-    -1.67400002,
-    -1.84099996,
-    -1.76100004,
-    -1.75899994,
-    -1.83299994,
-    -2.03299999,
-    -1.99399996,
-    -2.44400001,
-    -2.125,
-    -1.63699996,
-    -1.26800001,
-    -0.870000005,
-    -0.855000019,
-    -1.12899995,
-    -1.22899997,
-    -1.53400004,
-    -1.98699999,
-    -2.40899992,
-    -1.93200004,
-    -1.79999995,
-    -1.93200004,
-    -1.69200003,
-    -1.81599998,
-    -1.39900005,
-    -1.38600004,
-    -1.329,
-    -1.39999998,
-    -1.30299997,
-    -1.26800001,
-    -1.102,
-    -1.34000003,
-    -1.38499999,
-    -1.48500001,
-    -1.546,
-    -1.71800005,
-    -1.91299999,
-    -1.88499999,
-    -2.0539999,
-    -1.93799996,
-    -2.31299996,
-    -2.25999999,
-    -2.18600011,
-    -2.37599993,
-    -2.22600007,
-    -2.0250001,
-    -1.73199999,
-    -1.51699996,
-    -1.72599995,
-    -1.80599999,
-    -1.99399996,
-    -2.15499997,
-    -2.31699991,
-    -2.51200008,
-    -2.54299998,
-    -2.50099993,
-    -2.65899992,
-    -2.62100005,
-    -2.81699991,
-    -2.51900005,
-    -2.39700007,
-    -2.31800008,
-    -2.03500009,
-    -1.829,
-    -1.95500004,
-    -1.56500006,
-    -1.62199998,
-    -1.96300006,
-    -1.91799998,
-    -2.14499998,
-    -2.13700008,
-    -1.34599996,
-    -1.03299999,
-    -1.17400002,
-    -1.73099995,
-    -2.11899996,
-    -2.6789999,
-    -2.78800011,
-    -2.45099998,
-    -2.59599996,
-    -2.64599991,
-    -2.46799994,
-    -2.60100007,
-    -2.5940001,
-    -2.50600004,
-    -2.16700006,
-    -2.24600005,
-    -2.10500002,
-    -2.06599998,
-    -2.07999992,
-    -1.97300005,
-    -1.64400005,
-    -1.43599999,
-    -1.255,
-    -1.40999997,
-    -1.16600001,
-    -1.13999999,
-    -0.888999999,
-    -1.24300003,
-    -0.916000009,
-    -1.37399995,
-    -1.50899994,
-    -2.11500001,
-    -2.33800006,
-    -2.69799995,
-    -3.27099991,
-    -2.37400007,
-    -1.21800005,
-    -1.64300001,
-    -1.64900005,
-    -1.63,
-    -1.37,
-    -1.28699994,
-    -1.50199997,
-    -2.16799998,
-    -2.35700011,
-    -1.86000001,
-    -1.38,
-    -1.10099995,
-    -1.102,
-    -1.324,
-    -1.43700004,
-    -1.25999999,
-    -1.08299994,
-    -1.56299996,
-    -2.04699993,
-    -1.676,
-    -1.99399996,
-    -1.89400005,
-    -1.60000002,
-    -1.81400001,
-    -1.954,
-    -1.94000006,
-    -1.85000002,
-    -1.57200003,
-    -1.44099998,
-    -1.24399996,
-    -1.17200005,
-    -1.36000001,
-    -1.11300004,
-    -0.981000006,
-    -1.11500001,
-    -1.05400002,
-    -0.953000009,
-    -0.962000012,
-    -1.04700005,
-    -0.759000003,
-    -0.568000019,
-    -0.657000005,
-    -0.91900003,
-    -0.856999993,
-    -0.976000011,
-    -1.06599998,
-    -0.699000001,
-    -0.565999985,
-    -0.796000004,
-    -0.883000016,
-    -0.66900003,
-    -0.833000004,
-    -0.755999982,
-    -0.785000026,
-    -0.82099998,
-    -0.897000015,
-    -1.03400004,
-    -1.801,
-    -2.07399988,
-    -2.25900006,
-    -2.39299989,
-    -1.77999997,
-    -1.60800004,
-    -1.72099996,
-    -2.11400008,
-    -2.29900002,
-    -2.4690001,
-    -2.5150001,
-    -1.97599995,
-    -1.96899998,
-    -1.75300002,
-    -2.0710001,
-    -2.02699995,
-    -1.71000004,
-    -2.34100008,
-    -2.02099991,
-    -2.03900003,
-    -1.91499996,
-    -1.38100004,
-    -1.68700004,
-    -1.59099996,
-    -1.68900001,
-    -2.13000011,
-    -2.17400002,
-    -2.32599998,
-    -2.60899997,
-    -3.01799989,
-    -2.72300005,
-    -2.33400011,
-    -1.972,
-    -2.273,
-    -2.17499995,
-    -2.41400003,
-    -2.39899993,
-    -2.14700007,
-    -1.69099998,
-    -1.70099998,
-    -1.39699996,
-    -1.87199998,
-    -2.17499995,
-    -2.13400006,
-    -2.72799993,
-    -2.60100007,
-    -3.35700011,
-    -2.59800005,
-    -2.43099999,
-    -1.87199998,
-    -2.16199994,
-    -2.76999998,
-    -2.98900008,
-    -2.4460001,
-    -2.53999996,
-    -2.54500008,
-    -2.773,
-    -2.64599991,
-    -2.29900002,
-    -1.94200003,
-    -1.96899998,
-    -1.45099998,
-    -1.29299998,
-    -1.39400005,
-    -1.02499998,
-    -1.26600003,
-    -0.953000009,
-    -1.25300002,
-    -1.579,
-    -1.51699996,
-    -1.08899999,
-    -0.86500001,
-    -0.878000021,
-    -0.725000024,
-    -0.513000011,
-    -0.620999992,
-    -1.046,
-    -1.421,
-    -1.51400006,
-    -1.41900003,
-    -0.943000019,
-    -0.363999993,
-    -0.00300000003,
-    -0.180999994,
-    -0.115999997,
-    -0.147,
-    -0.294,
-    -0.57099998,
-    -1.00800002,
-    -1.04700005,
-    -0.962000012,
-    -0.963999987,
-    -1.08500004,
-    -0.81099999,
-    -1.08599997,
-    -1.10300004,
-    -1.01300001,
-    -0.827000022,
-    -1.26499999,
-    -1.27999997,
-    -1.06200004,
-    -1.48099995,
-    -1.71300006,
-    -1.53400004,
-    -1.68799996,
-    -1.93200004,
-    -2.01900005,
-    -1.96899998,
-    -1.898,
-    -1.69599998,
-    -1.41100001,
-    -1.14100003,
-    -0.879000008,
-    -1.00199997,
-    -1.43900001,
-    -1.37300003,
-    -1.53900003,
-    -1.49800003,
-    -1.08899999,
-    -1.02999997,
-    -1.03199995,
-    -0.970000029,
-    -0.970000029,
-    -0.970000029,
-    -1.16700006,
-    -1.06599998,
-    -0.839999974,
-    -0.409000009,
-    -0.55400002,
-    -0.625,
-    -0.708000004,
-    -0.875,
-    -0.822000027,
-    -0.662999988,
-    -1.02100003,
-    -1.01400006,
-    -0.730000019,
-    -0.964999974,
-    -1.19099998,
-    -1.10699999,
-    -1.34800005,
-    -1.05999994,
-    -1.04900002,
-    -1.25,
-    -1.33700001,
-    -1.26699996,
-    -1.21899998,
-    -1.31400001,
-    -1.30499995,
-    -1.44099998,
-    -1.45299995,
-    -1.59399998,
-    -1.46500003,
-    -1.24300003,
-    -0.952000022,
-    -0.906000018,
-    -0.745000005,
-    -1.03199995,
-    -1.20700002,
-    -1.59300005,
-    -1.59300005,
-    -1.59300005,
-    -1.10300004,
-    -1.14999998,
-    -1.449,
-    -1.55200005,
-    -1.70799994,
-    -1.60000002,
-    -1.824,
-    -1.65600002,
-    -1.61199999,
-    -1.57200003,
-    -1.48699999,
-    -1.60800004,
-    -1.41100001,
-    -1.44400001,
-    -1.29700005,
-    -1.27600002,
-    -1.13499999,
-    -0.875,
-    -0.866999984,
-    -0.927999973,
-    -1.35000002,
-    -1.36600006,
-    -1.34500003,
-    -1.24800003,
-    -1.14999998,
-    -0.827000022,
-    -0.666000009,
-    -0.875,
-    -1.00300002,
-    -1.43599999,
-    -1.40699995,
-    -1.51600003,
-    -1.37100005,
-    -1.54700005,
-    -1.66299999,
-    -1.69599998,
-    -1.352,
-    -1.148,
-    -0.961000025,
-    -1.079,
-    -1.028,
-    -0.938000023,
-    -0.765999973,
-    -0.827000022,
-    -0.538999975,
-    -0.588,
-    -0.488000005,
-    -0.158999994,
-    -0.31099999,
-    -0.0700000003,
-    -0.075000003,
-    -0.328999996,
-    -0.291999996,
-    -0.477999985,
-    -1.44200003,
-    -1.329,
-    -1.301,
-    -1.05999994,
-    -1.14100003,
-    -1.26300001,
-    -1.33299994,
-    -1.06599998,
-    -0.948000014,
-    -1.24100006,
-    -1.03699994,
-    -0.893000007,
-    -0.878000021,
-    -0.796000004,
-    -0.908999979,
-    -0.992999971,
-    -0.725000024,
-    -1.17700005,
-    -1.49800003,
-    -1.28400004,
-    -1.46500003,
-    -1.72399998,
-    -1.78799999,
-    -1.29999995,
-    -1.85000002,
-    -2.25999999,
-    -1.49600005,
-    -1.21899998,
-    -0.921000004,
-    -0.904999971,
-    -0.458000004,
-    -0.625,
-    -0.721000016,
-    -1.11699998,
-    -1.37899995,
-    -1.19700003,
-    -1.30900002,
-    -1.24000001,
-    -0.966000021,
-    -1.04499996,
-    -0.861000001,
-    -0.573000014,
-    -0.462000012,
-    -0.442999989,
-    -0.338999987,
-    -0.282999992,
-    -0.398999989,
-    0.0930000022,
-    -0.925999999,
-    -1.75600004,
-    -1.73000002,
-    -1.63999999,
-    -1.75100005,
-    -1.83099997,
-    -1.48300004,
-    -1.5,
-    -1.56500006,
-    -1.61500001,
-    -1.93099999,
-    -1.898,
-    -2.05299997,
-    -2.36299992,
-    -2.38400006,
-    -2.4849999,
-    -2.56100011,
-    -2.61100006,
-    -2.17199993,
-    -1.85699999,
-    -1.26900005,
-    -0.833999991,
-    -1.02600002,
-    -0.528999984,
-    -0.651000023,
-    -0.75999999,
-    -0.463999987,
-    -0.398999989,
-    -0.296999991,
-    0.0700000003,
-    -0.0160000008,
-    0.389999986,
-    0.838,
-    0.0379999988,
-    -0.632000029,
-    -0.531000018,
-    -0.925999999,
-    -1.21300006,
-    -1.38300002,
-    -1.097,
-    -0.552999973,
-    -0.681999981,
-    -0.916000009,
-    -0.558000028,
-    -0.527999997,
-    -0.455000013,
-    -0.449999988,
-    -0.806999981,
-    -0.846000016,
-    -0.681999981,
-    -0.469000012,
-    -0.532999992,
-    -0.579999983,
-    -0.535000026,
-    -0.670000017,
-    -0.358999997,
-    -0.226999998,
-    -0.268000007,
-    -0.499000013,
-    -0.481000006,
-    -0.481000006,
-    -0.481000006,
-    -0.970000029,
-    -1.04299998,
-    -0.850000024,
-    -1.02199996,
-    -1.15999997,
-    -1.31200004,
-    -1.62800002,
-    -1.66100001,
-    -1.70700002,
-    -1.68099999,
-    -1.5,
-    -1.72399998,
-    -1.505,
-    -1.22500002,
-    -1.14999998,
-    -0.802999973,
-    -0.824999988,
-    -0.796000004,
-    -0.870999992,
-    -0.828000009,
-    -0.693000019,
-    -0.663999975,
-    -0.598999977,
-    -0.565999985,
-    -0.363999993,
-    -0.108999997,
-    0.0149999997,
-    -0.256999999,
-    -0.252999991,
-    0.107000001,
-    0.224999994,
-    0.344999999,
-    0.842999995,
-    0.885999978,
-    0.488999993,
-    -0.111000001,
-    -0.633000016,
-    -0.726999998,
-    -0.896000028,
-    -0.726000011,
-    -0.77700001,
-    -0.572000027,
-    -0.469000012,
-    -0.372000009,
-    -0.693000019,
-    -0.686999977,
-    -0.699999988,
-    -0.981999993,
-    -1.296,
-    -1.37699997,
-    -1.47800004,
-    -1.50199997,
-    -1.63699996,
-    -1.852,
-    -2.0150001,
-    -2.07399988,
-    -1.44099998,
-    -1.16700006,
-    -1.37399995,
-    -2.09899998,
-    -2.06399989,
-    -2.27399993,
-    -2.43400002,
-    -2.47799993,
-    -1.95200002,
-    -2.12599993,
-    -2.34899998,
-    -1.96300006,
-    -1.71000004,
-    -1.83599997,
-    -1.80200005,
-    -1.62,
-    -1.95299995,
-    -2.04900002,
-    -2.34200001,
-    -2.04200006,
-    -1.90499997,
-    -1.31099999,
-    -1.46099997,
-    -1.37399995,
-    -1.51600003,
-    -1.75100005,
-    -2.09299994,
-    -2.47300005,
-    -2.3900001,
-    -2.38400006,
-    -2.30699992,
-    -2.31999993,
-    -2.14700007,
-    -2.08999991,
-    -2.05299997,
-    -2.04999995,
-    -2.18799996,
-    -2.48300004,
-    -2.43600011,
-    -2.40499997,
-    -2.47900009,
-    -2.50699997,
-    -2.55800009,
-    -2.6500001,
-    -2.57200003,
-    -2.13000011,
-    -1.99600005,
-    -1.91400003,
-    -2.25099993,
-    -2.17199993,
-    -2.24499989,
-    -2.18700004,
-    -2.29999995,
-    -2.1730001,
-    -2.11899996,
-    -2.18300009,
-    -2.08599997,
-    -2.24799991,
-    -2.2650001,
-    -2.13199997,
-    -2.12199998,
-    -2.12299991,
-    -1.80900002,
-    -1.79299998,
-    -1.78199995,
-    -1.86000001,
-    -1.73899996,
-    -1.66499996,
-    -1.28199995,
-    -1.44000006,
-    -1.18400002,
-    -1.74000001,
-    -2.21000004,
-    -2.35599995,
-    -2.63100004,
-    -2.70799994,
-    -2.97099996,
-    -3.3210001,
-    -3.35400009,
-    -3.47799993,
-    -3.16300011,
-    -2.898,
-    -2.4849999,
-    -2.37700009,
-    -2.1500001,
-    -1.75899994,
-    -2.05999994,
-    -2.03699994,
-    -2.02200007,
-    -1.57299995,
-    -1.22500002,
-    -1.08700001,
-    -1.07700002,
-    -1.49800003,
-    -1.56799996,
-    -1.72800004,
-    -1.64699996,
-    -1.89600003,
-    -1.96700001,
-    -2.17700005,
-    -1.90600002,
-    -2.22000003,
-    -2.3829999,
-    -2.81699991,
-    -2.88000011,
-    -2.56399989,
-    -2.28699994,
-    -2.09200001,
-    -2.00300002,
-    -2.10299993,
-    -2.08200002,
-    -2.25500011,
-    -2.78699994,
-    -3.19300008,
-    -3.01999998,
-    -2.62800002,
-    -2.99099994,
-    -2.36800003,
-    -2.55599999,
-    -2.35500002,
-    -2.2190001,
-    -1.99100006,
-    -2.19499993,
-    -2.11400008,
-    -1.70899999,
-    -1.89100003,
-    -2.20499992,
-    -2.17600012,
-    -2.05100012,
-    -1.90799999,
-    -1.43299997,
-    -1.32700002,
-    -1.28499997,
-    -1.38300002,
-    -2.07399988,
-    -2.62299991,
-    -2.85599995,
-    -2.89599991,
-    -2.98099995,
-    -2.6730001,
-    -2.50699997,
-    -2.39199996,
-    -2.28699994,
-    -2.19099998,
-    -2.11500001,
-    -2.43199992,
-    -2.296,
-    -2.296,
-    -2.22600007,
-    -2.2019999,
-    -2.60500002,
-    -3.22799993,
-    -2.79399991,
-    -2.84200001,
-    -2.91499996,
-    -2.93199992,
-    -2.98900008,
-    -3.11899996,
-    -2.58500004,
-    -2.25999999,
-    -1.63499999,
-    -0.76700002,
-    -2.42400002,
-    -3.00699997,
-    -3.24300003,
-    -2.9230001,
-    -2.59299994,
-    -2.36599994,
-    -2.33400011,
-    -2.33999991,
-    -2.50300002,
-    -2.49799991,
-    -2.64499998,
-    -2,
-    -1.64699996,
-    -1.33899999,
-    -1.13800001,
-    -1.03199995,
-    -0.779999971,
-    -1.08299994,
-    -2.07399988,
-    -2.49300003,
-    -2.40899992,
-    -2.65899992,
-    -2.7349999,
-    -2.64899993,
-    -2.7420001,
-    -2.85299993,
-    -2.3900001,
-    -2.78999996,
-    -2.53699994,
-    -2.48200011,
-    -2.34500003,
-    -2.30299997,
-    -2.23799992,
-    -2.3670001,
-    -2.22199988,
-    -2.32599998,
-    -2.55299997,
-    -2.42600012,
-    -2.52800012,
-    -2.39199996,
-    -2.3269999,
-    -2.28699994,
-    -2.03600001,
-    -1.97800004,
-    -1.63199997,
-    -1.75600004,
-    -2.29500008,
-    -2.8900001,
-    -3.42499995,
-    -3.43099999,
-    -3.21499991,
-    -2.79699993,
-    -2.69400001,
-    -2.42000008,
-    -2.28999996,
-    -2.4059999,
-    -2.33200002,
-    -2.78200006,
-    -3.12400007,
-    -2.98699999,
-    -3.23900008,
-    -3.58400011,
-    -3.74900007,
-    -3.96499991,
-    -4.01399994,
-    -3.90400004,
-    -3.55100012,
-    -3.37700009,
-    -2.42199993,
-    -2.23600006,
-    -2.16499996,
-    -2.49499989,
-    -2.37299991,
-    -2.11299992,
-    -1.73000002,
-    -1.778,
-    -2.2019999,
-    -2.7650001,
-    -2.90400004,
-    -3.0150001,
-    -2.76300001,
-    -3.05800009,
-    -2.98399997,
-    -3.92499995,
-    -4.10599995,
-    -3.14199996,
-    -2.8269999,
-    -2.76999998,
-    -2.85899997,
-    -3.56399989,
-    -4.20200014,
-    -3.86800003,
-    -3.51900005,
-    -3.14199996,
-    -3.1329999,
-    -3.579,
-    -3.84899998,
-    -3.95499992,
-    -4.15899992,
-    -4.32999992,
-    -4.38399982,
-    -4.23500013,
-    -4.43599987,
-    -4.48600006,
-    -4.37799978,
-    -4.35500002,
-    -4.34000015,
-    -4.62599993,
-    -4.33900023,
-    -4.13600016,
-    -4.47100019,
-    -4.35599995,
-    -4.47200012,
-    -4.62099981,
-    -4.69399977,
-    -4.44999981,
-    -4.49499989,
-    -4.55100012,
-    -4.48999977,
-    -4.48199987,
-    -4.35099983,
-    -4.53299999,
-    -4.57499981,
-    -4.82800007,
-    -4.84200001,
-    -4.72300005,
-    -4.69799995,
-    -4.73000002,
-    -5.05200005,
-    -5.28599977,
-    -5.27799988,
-    -5.14900017,
-    -4.74399996,
-    -5.24300003,
-    -5.62300014,
-    -5.48500013,
-    -5.25899982,
-    -5,
-    -4.58599997,
-    -4.53599977,
-    -4.73999977,
-    -5,
-    -5.20900011,
-    -4.47399998,
-    -4.57499981,
-    -4.53999996,
-    -4.83500004,
-    -4.69000006,
-    -4.8210001,
-    -4.27400017,
-    -4.48999977,
-    -4.08599997,
-    -4.19199991,
-    -4.50199986,
-    -4.22399998,
-    -4.26300001,
-    -4.28999996,
-    -4.44500017,
-    -4.50899982,
-    -4.30999994,
-    -4.39599991,
-    -4.11399984,
-    -4.26499987,
-    -4.01399994,
-    -3.96799994,
-    -4.20800018,
-    -4.28800011,
-    -3.95700002,
-    -4.05299997,
-    -4.13000011,
-    -4.22900009,
-    -4.44299984,
-    -4.55999994,
-    -4.53299999,
-    -4.704,
-    -4.67600012,
-    -4.44999981,
-    -4.34100008,
-    -4.46700001,
-    -4.5250001,
-    -4.57299995,
-    -4.32600021,
-    -3.87100005,
-    -3.87800002,
-    -3.84800005,
-    -3.97300005,
-    -4.30100012,
-    -4.3039999,
-    -4.13399982,
-    -4.20800018,
-    -4.05000019,
-    -4.46000004,
-    -4.51900005,
-    -4.88800001,
-    -4.796,
-    -4.92399979,
-    -4.73699999,
-    -4.49399996,
-    -4.63000011,
-    -4.37200022,
-    -4.40500021,
-    -4.70900011,
-    -4.53800011,
-    -4.50699997,
-    -4.50299978,
-    -4.57200003,
-    -4.61199999,
-    -4.5539999,
-    -4.25400019,
-    -4.42199993,
-    -4.04300022,
-    -4.03800011,
-    -3.92499995,
-    -4.32999992,
-    -4.42999983,
-    -4.57299995,
-    -4.42199993,
-    -4.47800016,
-    -4.64599991,
-    -4.51900005,
-    -4.57299995,
-    -4.56400013,
-    -4.40700006,
-    -4.55600023,
-    -4.25699997,
-    -4.41900015,
-    -4.68400002,
-    -4.71000004,
-    -4.46700001,
-    -4.49399996,
-    -3.9849999,
-    -4.1880002,
-    -4.14300013,
-    -4.08500004,
-    -3.99699998,
-    -3.72099996,
-    -2.85800004,
-    -3.39599991,
-    -3.43199992,
-    -3.72199988,
-    -3.76399994,
-    -3.92199993,
-    -4.64499998,
-    -4.98000002,
-    -4.77099991,
-    -4.579,
-    -4.49900007,
-    -4.09499979,
-    -3.85400009,
-    -4.05600023,
-    -3.84299994,
-    -3.81699991,
-    -3.94499993,
-    -3.88599992,
-    -4.18100023,
-    -4.329,
-    -4.34000015,
-    -4.33699989,
-    -4.42399979,
-    -4.43100023,
-    -4.23999977,
-    -4.28599977,
-    -4.12200022,
-    -3.96499991,
-    -4.04699993,
-    -4.15199995,
-    -4.3579998,
-    -4.13600016,
-    -4.54699993,
-    -4.704,
-    -4.64499998,
-    -4.63700008,
-    -4.60200024,
-    -4.76300001,
-    -4.90100002,
-    -5.00600004,
-    -5.10300016,
-    -5.12900019,
-    -5.13199997,
-    -5.14599991,
-    -5.16800022,
-    -5.34200001,
-    -5.46299982,
-    -5.37099981,
-    -5.42799997,
-    -5.59499979,
-    -5.58099985,
-    -5.71999979,
-    -5.95699978,
-    -6.07299995,
-    -6,
-    -5.89400005,
-    -5.85699987,
-    -5.95699978,
-    -5.90299988,
-    -5.86100006,
-    -6.04899979,
-    -6.03000021,
-    -6.04099989,
-    -6.09499979,
-    -5.98600006,
-    -5.85400009,
-    -5.97800016,
-    -6.04899979,
-    -6.23400021,
-    -5.92600012,
-    -5.66499996,
-    -6.06699991,
-    -6.26900005,
-    -6.20699978,
-    -6.34000015,
-    -5.94099998,
-    -6.16699982,
-    -6.5710001,
-    -6.45599985,
-    -6.53999996,
-    -6.48699999,
-    -6.671,
-    -6.79400015,
-    -6.85099983,
-    -6.73199987,
-    -6.3499999,
-    -5.81799984,
-    -5.38600016,
-    -5.29899979,
-    -5.4000001,
-    -5.72599983,
-    -5.93200016,
-    -6.03999996,
-    -6.26100016,
-    -6.27799988,
-    -6.06400013,
-    -5.77199984,
-    -5.69899988,
-    -5.40700006,
-    -5.46600008,
-    -5.48799992,
-    -5.41400003,
-    -5.57499981,
-    -5.46700001,
-    -5.4289999,
-    -5.70499992,
-    -5.57999992,
-    -5.63500023,
-    -5.55700016,
-    -5.72700024,
-    -5.44899988,
-    -5.05900002,
-    -5.13700008,
-    -5.13700008,
-    -5.13700008,
-    -4.91400003,
-    -4.84600019,
-    -4.69999981,
-    -4.57800007,
-    -4.66800022,
-    -4.63700008,
-    -4.62300014,
-    -4.59899998,
-    -4.50199986,
-    -4.38100004,
-    -4.375,
-    -4.20300007,
-    -4.05499983,
-    -4.03000021,
-    -3.99399996,
-    -3.852,
-    -3.66400003,
-    -3.72000003,
-    -3.53600001,
-    -3.33200002,
-    -3.39299989,
-    -3.39499998,
-    -3.43199992,
-    -3.23099995,
-    -2.99600005,
-    -3.14899993,
-    -2.90100002,
-    -2.94300008,
-    -2.91199994,
-    -3.26999998,
-    -3.23399997,
-    -3.375,
-    -3.01600003,
-    -3.03500009,
-    -2.7809999,
-    -2.6960001,
-    -2.70099998,
-    -2.65700006,
-    -2.90499997,
-    -2.84899998,
-    -3.00600004,
-    -2.9519999,
-    -2.94000006,
-    -2.53900003,
-    -2.47199988,
-    -2.6329999,
-    -2.46600008,
-    -2.3829999,
-    -2.34200001,
-    -2.19700003,
-    -2.07500005,
-    -1.92299998,
-    -1.89100003,
-    -1.96500003,
-    -2.1400001,
-    -2.20000005,
-    -1.98399997,
-    -2.0999999,
-    -2.15100002,
-    -2.17600012,
-    -2.66300011,
-    -2.89299989,
-    -2.7190001,
-    -2.56800008,
-    -2.28699994,
-    -2.73000002,
-    -2.4289999,
-    -2.2349999,
-    -2.42000008,
-    -2.50699997,
-    -2.03800011,
-    -2.21600008,
-    -2.32999992,
-    -2.5309999,
-    -2.50699997,
-    -2.58999991,
-    -2.46099997,
-    -2.36899996,
-    -2.11800003,
-    -2.33899999,
-    -2.41400003,
-    -2.72399998,
-    -2.75600004,
-    -2.73200011,
-    -2.671,
-    -2.51099992,
-    -2.63899994,
-    -2.71000004,
-    -2.7809999,
-    -2.65799999,
-    -3.05900002,
-    -2.53399992,
-    -2.53999996,
-    -2.68700004,
-    -2.61599994,
-    -2.65199995,
-    -2.81500006,
-    -2.5539999,
-    -2.69899988,
-    -2.48399997,
-    -2.55100012,
-    -2.6559999,
-    -2.579,
-    -2.579,
-    -2.579,
-    -2.50900006,
-    -2.4289999,
-    -2.34800005,
-    -2.36299992,
-    -2.46099997,
-    -2.60899997,
-    -2.56500006,
-    -2.57500005,
-    -2.8210001,
-    -2.92400002,
-    -3.06100011,
-    -2.92499995,
-    -2.89299989,
-    -2.92000008,
-    -2.71000004,
-    -2.75399995,
-    -2.75399995,
-    -2.75399995,
-    -2.87199998,
-    -2.82299995,
-    -2.42000008,
-    -2.91599989,
-    -2.95000005,
-    -2.85899997,
-    -3.00300002,
-    -3.04900002,
-    -2.77900004,
-    -2.96799994,
-    -3.25900006,
-    -3.19300008,
-    -3.079,
-    -3.01900005,
-    -3.20600009,
-    -3.37100005,
-    -3.33400011,
-    -3.51999998,
-    -3.39199996,
-    -3.48300004,
-    -3.48000002,
-    -3.40400004,
-    -3.28999996,
-    -3.21399999,
-    -3.23000002,
-    -3.1329999,
-    -3.39299989,
-    -3.37299991,
-    -3.26600003,
-    -3.13499999,
-    -3.34200001,
-    -3.20600009,
-    -3.11599994,
-    -3.02900004,
-    -3.00900006,
-    -2.83999991,
-    -3.20600009,
-    -3.27800012,
-    -3.36999989,
-    -3.171,
-    -2.86199999,
-    -3,
-    -3.14599991,
-    -2.50099993,
-    -3.45600009,
-    -2.84299994,
-    -2.78699994,
-    -2.61800003,
-    -2.76600003,
-    -2.85599995,
-    -2.80900002,
-    -2.57999992,
-    -2.625,
-    -2.44199991,
-    -2.62800002,
-    -2.44899988,
-    -2.27200007,
-    -2.3269999,
-    -2.58699989,
-    -2.34800005,
-    -2.50600004,
-    -2.41700006,
-    -2.21700001,
-    -2.07500005,
-    -2.20900011,
-    -2.16199994,
-    -2.16799998,
-    -2.41100001,
-    -2.65899992,
-    -2.523,
-    -2.56399989,
-    -2.38599992,
-    -2.35400009,
-    -2.25399995,
-    -1.824,
-    -1.995,
-    -1.89100003,
-    -2.08699989,
-    -1.898,
-    -1.79299998,
-    -2.20099998,
-    -2.00399995,
-    -1.88,
-    -2.01200008,
-    -2.03699994,
-    -2.16300011,
-    -2.48900008,
-    -2.04399991,
-    -2.05200005,
-    -1.96700001,
-    -2.12700009,
-    -1.91799998,
-    -2.03699994,
-    -2.03699994,
-    -1.72500002,
-    -2.04500008,
-    -1.88399994,
-    -2.00900006,
-    -2.11899996,
-    -2.148,
-    -2.14599991,
-    -2.11400008,
-    -2.40700006,
-    -2.01600003,
-    -2.13100004,
-    -2.05200005,
-    -2.17700005,
-    -2.2420001,
-    -2.18899989,
-    -2.05599999,
-    -2.06699991,
-    -2.43700004,
-    -2.39299989,
-    -2.43799996,
-    -2.28900003,
-    -2.36800003,
-    -2.31100011,
-    -2.43899989,
-    -2.41300011,
-    -2.47799993,
-    -2.36999989,
-    -2.46199989,
-    -2.55100012,
-    -2.49600005,
-    -2.39400005,
-    -2.62100005,
-    -2.52600002,
-    -2.46700001,
-    -2.5480001,
-    -2.6960001,
-    -2.6099999,
-    -2.72900009,
-    -2.46399999,
-    -2.421,
-    -2.44400001,
-    -2.52200007,
-    -2.46300006,
-    -2.37899995,
-    -2.33299994,
-    -2.31100011,
-    -2.69199991,
-    -2.1329999,
-    -1.93599999,
-    -1.60099995,
-    -2.07500005,
-    -2.22399998,
-    -2.21600008,
-    -2.47300005,
-    -2.82500005,
-    -2.77399993,
-    -2.76699996,
-    -2.72300005,
-    -2.58899999,
-    -2.58299994,
-    -2.61400008,
-    -2.60800004,
-    -2.87899995,
-    -2.58299994,
-    -2.97399998,
-    -2.78600001,
-    -2.54900002,
-    -2.59699988,
-    -2.68600011,
-    -2.75399995,
-    -2.83500004,
-    -2.87400007,
-    -2.76099992,
-    -2.6500001,
-    -2.55800009,
-    -2.73000002,
-    -2.773,
-    -2.42199993,
-    -2.43499994,
-    -2.5250001,
-    -2.33699989,
-    -2.39400005,
-    -2.47099996,
-    -2.52099991,
-    -2.54999995,
-    -2.52900004,
-    -2.71799994,
-    -2.68099999,
-    -2.47399998,
-    -2.48600006,
-    -2.40199995,
-    -2.66599989,
-    -2.53399992,
-    -2.32599998,
-    -2.32299995,
-    -2.33100009,
-    -2.4690001,
-    -2.40799999,
-    -2.57999992,
-    -2.67799997,
-    -2.63899994,
-    -2.42600012,
-    -2.22900009,
-    -2.37400007,
-    -2.44799995,
-    -2.43499994,
-    -2.41000009,
-    -2.23900008,
-    -2.40199995,
-    -2.46600008,
-    -2.40400004,
-    -2.546,
-    -2.56500006,
-    -2.62599993,
-    -2.54500008,
-    -2.50200009,
-    -2.55599999,
-    -2.53800011,
-    -2.477,
-    -2.60400009,
-    -2.64199996,
-    -2.68199992,
-    -2.71700001,
-    -2.55299997,
-    -2.5,
-    -2.67199993,
-    -2.63599992,
-    -2.7750001,
-    -2.5999999,
-    -2.56800008,
-    -2.84100008,
-    -2.76200008,
-    -2.80800009,
-    -2.8499999,
-    -2.8829999,
-    -3.11599994,
-    -3.10599995,
-    -2.98000002,
-    -3.18799996,
-    -3.1960001,
-    -3.10700011,
-    -3.05100012,
-    -3.18600011,
-    -3.28800011,
-    -3.23300004,
-    -3.25900006,
-    -3.20099998,
-    -3.45799994,
-    -3.36599994,
-    -3.59599996,
-    -3.46799994,
-    -3.50099993,
-    -3.6730001,
-    -3.60400009,
-    -3.65100002,
-    -3.82500005,
-    -3.7249999,
-    -3.57299995,
-    -3.63800001,
-    -3.66799998,
-    -3.57800007,
-    -3.51600003,
-    -3.6329999,
-    -3.64700007,
-    -3.21000004,
-    -3.8499999,
-    -4.03499985,
-    -4.1960001,
-    -4.28399992,
-    -4,
-    -4.11199999,
-    -4.15999985,
-    -4.22100019,
-    -4.00099993,
-    -3.96099997,
-    -3.98699999,
-    -3.78299999,
-    -3.80599999,
-    -3.61199999,
-    -3.73200011,
-    -3.47199988,
-    -3.47099996,
-    -3.63800001,
-    -3.20000005,
-    -3.61599994,
-    -3.46700001,
-    -3.33299994,
-    -2.9519999,
-    -3.02200007,
-    -3.03399992,
-    -2.80900002,
-    -2.97600007,
-    -2.72600007,
-    -2.48799992,
-    -2.40799999,
-    -2.35700011,
-    -2.49000001,
-    -2.08800006,
-    -2.30999994,
-    -2.08500004,
-    -2.22199988,
-    -2.03600001,
-    -1.54200006,
-    -1.57700002,
-    -1.35699999,
-    -1.32700002,
-    -1.19700003,
-    -1.37600005,
-    -1.07000005,
-    -0.995999992,
-    -1.15799999,
-    -1.05700004,
-    -0.851000011,
-    -0.899999976,
-    -1.08599997,
-    -0.758000016,
-    -0.479999989,
-    -0.425000012,
-    -0.51700002,
-    -0.0309999995,
-    -0.356000006,
-    -0.252000004,
-    -0.772000015,
-    -0.574999988,
-    -1.07099998,
-    -1.48199999,
-    -1.14999998,
-    -1.38399994,
-    -1.49000001,
-    -1.09000003,
-    -1,
-    -0.902999997,
-    -0.871999979,
-    -0.97299999,
-    -0.612999976,
-    -0.189999998,
-    -0.419,
-    -0.851000011,
-    -1.19400001,
-    -1.56299996,
-    -1.61399996,
-    -1.72099996,
-    -1.72099996,
-    -1.72099996,
-    -2.06999993,
-    -1.79799998,
-    -1.47399998,
-    -1.22300005,
-    -1.14699996,
-    -1.01100004,
-    -1.13900006,
-    -1.37,
-    -1.41499996,
-    -1.45700002,
-    -1.38800001,
-    -1.23699999,
-    -1.40199995,
-    -2.17799997,
-    -2.54299998,
-    -2.93799996,
-    -3.06100011,
-    -2.97300005,
-    -2.52900004,
-    -2.1329999,
-    -2.18499994,
-    -1.972,
-    -2.32399988,
-    -2.33800006,
-    -2.05900002,
-    -1.94599998,
-    -1.83399999,
-    -1.55900002,
-    -1.13499999,
-    -1.33500004,
-    -1.20799994,
-    -1.63399994,
-    -1.66400003,
-    -1.69400001,
-    -1.66100001,
-    -1.71099997,
-    -1.43499994,
-    -1.90999997,
-    -1.98500001,
-    -2.27200007,
-    -2.25600004,
-    -2.27200007,
-    -2.21700001,
-    -2.28500009,
-    -2.43300009,
-    -2.22199988,
-    -1.96599996,
-    -1.96000004,
-    -2.00600004,
-    -1.87899995,
-    -2.22300005,
-    -1.84599996,
-    -1.93200004,
-    -2.19199991,
-    -1.926,
-    -2.24900007,
-    -2.15899992,
-    -2.11599994,
-    -1.82599998,
-    -1.898,
-    -1.95299995,
-    -2.08100009,
-    -1.97599995,
-    -1.83599997,
-    -1.95000005,
-    -1.90199995,
-    -2.10700011,
-    -2.08299994,
-    -2.00999999,
-    -2.11500001,
-    -2.10400009,
-    -1.94599998,
-    -1.89400005,
-    -1.70200002,
-    -1.41299999,
-    -1.51999998,
-    -1.35000002,
-    -1.58500004,
-    -1.40199995,
-    -1.80900002,
-    -1.93400002,
-    -2.29399991,
-    -2.41300011,
-    -2.25699997,
-    -2.33500004,
-    -2.2420001,
-    -2.46199989,
-    -2.46799994,
-    -2.64700007,
-    -2.45099998,
-    -2.39100003,
-    -2.37100005,
-    -2.648,
-    -3.18600011,
-    -3.01600003,
-    -3.27800012,
-    -3.25399995,
-    -3.41300011,
-    -3.52699995,
-    -3.86599994,
-    -3.96099997,
-    -3.58200002,
-    -3.37100005,
-    -3.171,
-    -3.11599994,
-    -2.61299992,
-    -2.83299994,
-    -3.3670001,
-    -3.48200011,
-    -3.56599998,
-    -3.8599999,
-    -3.60100007,
-    -3.56800008,
-    -3.74799991,
-    -4.1170001,
-    -3.81900001,
-    -4.18400002,
-    -4.62699986,
-    -4.079,
-    -4.25600004,
-    -3.47900009,
-    -4.10900021,
-    -4.21400023,
-    -3.70900011,
-    -3.44799995,
-    -3.579,
-    -3.78200006,
-    -3.83299994,
-    -3.83299994,
-    -3.62400007,
-    -3.227,
-    -3.24099994,
-    -3.46099997,
-    -3.3829999,
-    -3.99099994,
-    -3.85299993,
-    -3.6960001,
-    -3.25500011,
-    -3.32800007,
-    -3.57500005,
-    -3.40100002,
-    -3.39199996,
-    -3.3900001,
-    -3.38700008,
-    -3.58200002,
-    -3.18199992,
-    -3.02999997,
-    -2.99799991,
-    -2.8900001,
-    -2.79999995,
-    -2.85100007,
-    -2.92799997,
-    -3.02099991,
-    -2.92700005,
-    -2.93899989,
-    -2.99300003,
-    -3.18000007,
-    -2.82399988,
-    -3.04900002,
-    -3.102,
-    -2.8269999,
-    -2.796,
-    -2.96000004,
-    -3.0539999,
-    -3.13199997,
-    -2.78800011,
-    -2.60100007,
-    -2.6170001,
-    -2.70700002,
-    -2.96300006,
-    -2.8900001,
-    -3.1500001,
-    -3.02699995,
-    -3.42000008,
-    -3.64700007,
-    -3.65799999,
-    -3.26600003,
-    -3.03200006,
-    -2.43199992,
-    -2.69400001,
-    -2.60400009,
-    -2.90799999,
-    -3.0539999,
-    -3.23200011,
-    -3.26099992,
-    -2.89299989,
-    -3.12400007,
-    -3.40400004,
-    -3.62400007,
-    -3.69099998,
-    -3.375,
-    -2.83899999,
-    -2.9749999,
-    -3.102,
-    -3.08400011,
-    -2.84800005,
-    -2.93499994,
-    -2.95900011,
-    -2.98699999,
-    -3.28500009,
-    -3.36800003,
-    -3.54399991,
-    -3.25099993,
-    -3.04699993,
-    -3.36100006,
-    -2.93700004,
-    -3.09800005,
-    -3.19300008,
-    -3.31100011,
-    -3.25300002,
-    -3.0079999,
-    -3.01300001,
-    -2.74000001,
-    -2.80599999,
-    -2.38199997,
-    -2.6400001,
-    -2.70000005,
-    -2.64899993,
-    -2.25099993,
-    -1.80999994,
-    -2.4059999,
-    -2.60500002,
-    -2.60899997,
-    -2.58599997,
-    -2.23600006,
-    -2.15300012,
-    -2.08200002,
-    -2.2980001,
-    -2.47199988,
-    -2.704,
-    -2.47099996,
-    -2.16799998,
-    -1.87199998,
-    -2.125,
-    -2.45300007,
-    -2.41100001,
-    -2.61199999,
-    -2.773,
-    -2.55299997,
-    -2.45499992,
-    -2.20799994,
-    -2.1730001,
-    -2.454,
-    -2.72600007,
-    -2.64100003,
-    -2.3210001,
-    -2.25,
-    -2.2190001,
-    -2.20900011,
-    -2.51300001,
-    -2.48600006,
-    -2.58699989,
-    -2.54500008,
-    -2.74300003,
-    -2.74699998,
-    -2.67400002,
-    -2.8829999,
-    -2.92799997,
-    -3.01099992,
-    -3.04200006,
-    -3.03500009,
-    -2.92400002,
-    -3.02200007,
-    -3.00600004,
-    -3.023,
-    -2.9230001,
-    -3.24300003,
-    -3.06999993,
-    -3.02200007,
-    -3.02399993,
-    -2.84100008,
-    -2.89899993,
-    -2.72199988,
-    -3,
-    -2.66300011,
-    -2.67199993,
-    -2.7420001,
-    -2.78399992,
-    -2.80999994,
-    -2.75,
-    -2.57299995,
-    -2.30100012,
-    -2.37100005,
-    -2.49699998,
-    -2.36100006,
-    -2.34200001,
-    -2.34299994,
-    -2.4059999,
-    -2.22600007,
-    -1.84599996,
-    -1.66999996,
-    -1.66600001,
-    -1.82099998,
-    -2.08299994,
-    -2.31800008,
-    -2.25600004,
-    -1.64900005,
-    -2.12400007,
-    -1.88600004,
-    -1.65799999,
-    -1.25300002,
-    -1.35399997,
-    -1.46599996,
-    -1.245,
-    -1.51199996,
-    -1.35800004,
-    -1.454,
-    -1.10000002,
-    -0.824000001,
-    -0.657999992,
-    -1.18799996,
-    -1.45500004,
-    -1.93700004,
-    -2.5,
-    -1.65799999,
-    -1.40100002,
-    -1.61800003,
-    -1.90699995,
-    -2.20700002,
-    -1.48500001,
-    -1.403,
-    -1.153,
-    -1.32299995,
-    -1.17299998,
-    -1.33200002,
-    -1.41199994,
-    -1.80900002,
-    -1.676,
-    -1.58099997,
-    -1.472,
-    -1.58399999,
-    -1.91799998,
-    -2.00699997,
-    -1.699,
-    -1.59399998,
-    -1.66600001,
-    -1.55999994,
-    -1.52999997,
-    -1.64499998,
-    -1.77999997,
-    -1.64900005,
-    -1.52400005,
-    -1.26999998,
-    -1.26699996,
-    -1.30799997,
-    -0.55400002,
-    -0.196999997,
-    -0.388999999,
-    -1.051,
-    -0.898999989,
-    -0.349000007,
-    -0.0439999998,
-    0.194999993,
-    0.0729999989,
-    0.268999994,
-    0.287999988,
-    0.419999987,
-    -0.244000003,
-    -0.499000013,
-    -0.291999996,
-    -0.279000014,
-    0.270000011,
-    0.0869999975,
-    0.107000001,
-    0.0350000001,
-    -0.126000002,
-    -0.275000006,
-    0.167999998,
-    -0.0719999969,
-    -0.061999999,
-    -0.175999999,
-    -0.215000004,
-    -0.0610000007,
-    -0.213,
-    -0.0579999983,
-    -0.448000014,
-    -0.795000017,
-    -0.308999985,
-    -0.194999993,
-    -0.217999995,
-    0.122000001,
-    -0.0219999999,
-    -0.264999986,
-    -0.127000004,
-    -0.213,
-    -0.948000014,
-    -0.532999992,
-    -0.532999992,
-    -0.532999992,
-    0.075000003,
-    -0.0430000015,
-    -0.0209999997,
-    -0.0649999976,
-    0.238000005,
-    0.195999995,
-    0.125,
-    0.243000001,
-    0.231000006,
-    0.0240000002,
-    0.188999996,
-    0.521000028,
-    0.202999994,
-    0.150999993,
-    -0.0410000011,
-    0.150000006,
-    0.231999993,
-    0.116999999,
-    0.0579999983,
-    -0.0359999985,
-    0.0560000017,
-    0.119999997,
-    0.141000003,
-    0.112999998,
-    0.180000007,
-    0.0890000015,
-    0.152999997,
-    -0.0209999997,
-    0,
-    0,
-    0.00200000009,
-    -0.0170000009,
-    -0.270000011,
-    -0.238000005,
-    -0.0520000011,
-    -0.0209999997,
-    0.0960000008,
-    -0.0489999987,
-    -0.103,
-    -0.31099999,
-    -0.202999994,
-    -0.0949999988,
-    -0.211999997,
-    -0.0599999987,
-    0,
-    0.00600000005,
-    0.129999995,
-    0.107000001,
-    -0.0379999988,
-    -0.169,
-    -0.289000005,
-    -0.171000004,
-    -0.159999996,
-    -0.231000006,
-    0.0890000015,
-    0.158000007,
-    -0.101000004,
-    -0.333000004,
-    -0.221000001,
-    0.0170000009,
-    0.133000001,
-    -0.0879999995,
-    0.00999999978,
-    0.0240000002,
-    -0.00999999978,
-    -0.0829999968,
-    0.107000001,
-    0.147,
-    0.160999998,
-    0.140000001,
-    0.133000001,
-    0.112000003,
-    0.160999998,
-    0.166999996,
-    0,
-    0.31099999,
-    0.193000004,
-    0.129999995,
-    0.128999993,
-    0.194999993,
-    0.107000001,
-    -0.0979999974,
-    -0.136999995,
-    -0.0189999994,
-    0.0439999998,
-    0.147,
-    0.252999991,
-    0.108000003,
-    0.0450000018,
-    0.175999999,
-    0.143999994,
-    0.189999998,
-    0.152999997,
-    0.389999986,
-    0.118000001,
-    -0.0240000002,
-    0.0219999999,
-    0.0140000004,
-    0.0590000004,
-    0.252999991,
-    0.151999995,
-    0.0579999983,
-    -0.233999997,
-    -0.112999998,
-    -0.0439999998,
-    0.0799999982,
-    0.179000005,
-    0.229000002,
-    0.159999996,
-    0.187999994,
-    0.296000004,
-    0.531000018,
-    0.328000009,
-    0.395999998,
-    0.272000015,
-    0.35800001,
-    0.179000005,
-    0.277999997,
-    0.171000004,
-    0.308999985,
-    0.330000013,
-    0.248999998,
-    0.317999989,
-    0.224000007,
-    0.0579999983,
-    0.26699999,
-    0.150999993,
-    0.0430000015,
-    0.130999997,
-    0.130999997,
-    0.0370000005,
-    0.0160000008,
-    0.109999999,
-    0.143000007,
-    0.224999994,
-    0.0649999976,
-    -0.150999993,
-    -0.0179999992,
-    0.0469999984,
-    0.0450000018,
-    -0.0430000015,
-    -0.155000001,
-    -0.361999989,
-    -0.472000003,
-    -0.126000002,
-    -0.129999995,
-    -0.159999996,
-    0.103,
-    0.100000001,
-    0.250999987,
-    -0.0579999983,
-    0.192000002,
-    0.118000001,
-    0.246999994,
-    0.0680000037,
-    0.153999999,
-    0.218999997,
-    0.248999998,
-    0.112000003,
-    0.0659999996,
-    -0.149000004,
-    -0.150000006,
-    -0.221000001,
-    0.0900000036,
-    0.0680000037,
-    0.199000001,
-    0.163000003,
-    0.275999993,
-    0.166999996,
-    0.0140000004,
-    0.0890000015,
-    -0.0320000015,
-    -0.344999999,
-    -0.214000002,
-    0.0419999994,
-    -0.0810000002,
-    -0.268999994,
-    -0.120999999,
-    -0.246999994,
-    -0.201000005,
-    -0.354000002,
-    -0.36500001,
-    -0.196999997,
-    0.00400000019,
-    0.122000001,
-    0.0480000004,
-    -0.125,
-    -0.127000004,
-    -0.421999991,
-    -0.25999999,
-    -0.277999997,
-    -0.128999993,
-    -0.0949999988,
-    -0.0209999997,
-    0.0890000015,
-    0.0160000008,
-    -0.192000002,
-    -0.152999997,
-    -0.400000006,
-    -0.414000005,
-    -0.101000004,
-    -0.0439999998,
-    -0.236000001,
-    -0.188999996,
-    -0.254999995,
-    0.0820000023,
-    0.0949999988,
-    -0.0329999998,
-    0.0560000017,
-    -0.00300000003,
-    -0.0450000018,
-    -0.00499999989,
-    0.104000002,
-    0.0240000002,
-    -0.184,
-    -0.209000006,
-    -0.330000013,
-    0.0390000008,
-    -0.243000001,
-    -0.165999994,
-    -0.156000003,
-    -0.0469999984,
-    -0.114,
-    -0.0520000011,
-    0.169,
-    -0.0689999983,
-    -0.316000015,
-    -0.275000006,
-    -0.492000014,
-    -0.238999993,
-    -0.160999998,
-    0.0359999985,
-    -0.104000002,
-    -0.114,
-    -0.0839999989,
-    -0.156000003,
-    -0.308999985,
-    -0.529999971,
-    -0.533999979,
-    -0.245000005,
-    -0.105999999,
-    -0.386000007,
-    0.100000001,
-    -0.108000003,
-    0.0379999988,
-    -0.115999997,
-    -0.193000004,
-    -0.166999996,
-    -0.00300000003,
-    -0.247999996,
-    -0.231999993,
-    -0.294,
-    -0.226999998,
-    -0.145999998,
-    -0.0759999976,
-    -0.118000001,
-    -0.268999994,
-    -0.0430000015,
-    -0.0890000015,
-    -0.0869999975,
-    -0.118000001,
-    -0.287999988,
-    -0.31400001,
-    -0.25999999,
-    -0.370000005,
-    -0.331999987,
-    -0.241999999,
-    -0.0680000037,
-    -0.225999996,
-    -0.360000014,
-    -0.270000011,
-    -0.35800001,
-    -0.225999996,
-    -0.0439999998,
-    -0.0340000018,
-    0.0949999988,
-    0.245000005,
-    -0.0680000037,
-    0.182999998,
-    -0.108999997,
-    0.237000003,
-    0.252999991,
-    -0.155000001,
-    -0.310000002,
-    0.00400000019,
-    0.140000001,
-    0.0560000017,
-    0.0560000017,
-    0.0560000017,
-    0.0410000011,
-    0.103,
-    -0.0799999982,
-    -0.266000003,
-    -0.245000005,
-    -0.0829999968,
-    0.136000007,
-    0.123000003,
-    -0.180000007,
-    -0.277999997,
-    -0.239999995,
-    -0.411000013,
-    -0.469000012,
-    -0.433999985,
-    -0.42899999,
-    -0.330000013,
-    -0.153999999,
-    -0.141000003,
-    -0.0480000004,
-    -0.0680000037,
-    -0.0850000009,
-    -0.187999994,
-    -0.398000002,
-    -0.31099999,
-    -0.0149999997,
-    -0.0659999996,
-    -0.0170000009,
-    0.057,
-    -0.104000002,
-    -0.0289999992,
-    0.123999998,
-    0.144999996,
-    0.0930000022,
-    0.0480000004,
-    -0.0729999989,
-    0.150000006,
-    0.294,
-    0.323000014,
-    -0.00400000019,
-    -0.165000007,
-    -0.211999997,
-    -0.218999997,
-    -0.0140000004,
-    0.118000001,
-    0.0379999988,
-    0.26699999,
-    0.133000001,
-    -0.122000001,
-    -0.0680000037,
-    -0.162,
-    -0.209000006,
-    -0.162,
-    -0.0469999984,
-    -0.181999996,
-    -0.264999986,
-    -0.177000001,
-    -0.0130000003,
-    0.131999999,
-    -0.143000007,
-    0,
-    0.0280000009,
-    0.101999998,
-    0.118000001,
-    -0.0410000011,
-    -0.0850000009,
-    -0.0850000009,
-    -0.0850000009,
-    -0.256999999,
-    -0.236000001,
-    -0.0790000036,
-    -0.225999996,
-    0.270999998,
-    0.174999997,
-    -0.0399999991,
-    -0.0390000008,
-    0.0350000001,
-    0.050999999,
-    -0.120999999,
-    -0.107000001,
-    -0.101000004,
-    -0.210999995,
-    -0.301999986,
-    -0.35800001,
-    -0.108999997,
-    0.218999997,
-    0.0649999976,
-    -0.0879999995,
-    0.0590000004,
-    0.0209999997,
-    0.172999993,
-    0.075000003,
-    -0.180000007,
-    -0.111000001,
-    -0.0399999991,
-    0.157000005,
-    0.0920000002,
-    -0.00700000022,
-    -0.152999997,
-    -0.0529999994,
-    0.0680000037,
-    0.127000004,
-    -0.0769999996,
-    -0.142000005,
-    -0.0890000015,
-    -0.0209999997,
-    -0.0280000009,
-    0.063000001,
-    -0.174999997,
-    0.112999998,
-    0.175999999,
-    -0.0560000017,
-    -0.101000004,
-    0.0500000007,
-    0.0680000037,
-    -0.136000007,
-    -0.142000005,
-    -0.0260000005,
-    -0.133000001,
-    -0.208000004,
-    -0.0450000018,
-    -0.158999994,
-    -0.144999996,
-    -0.129999995,
-    -0.0149999997,
-    0.0260000005,
-    -0.188999996,
-    -0.155000001,
-    -0.122000001,
-    -0.0299999993,
-    -0.185000002,
-    -0.157000005,
-    -0.208000004,
-    -0.0120000001,
-    0.00899999961,
-    -0.219999999,
-    -0.344999999,
-    -0.0689999983,
-    -0.25,
-    -0.300000012,
-    -0.0320000015,
-    -0.129999995,
-    0.0160000008,
-    -0.00999999978,
-    -0.109999999,
-    -0.0240000002,
-    -0.137999997,
-    0.130999997,
-    0.193000004,
-    -0.0359999985,
-    -0.180000007,
-    -0.128000006,
-    -0.145999998,
-    -0.243000001,
-    -0.111000001,
-    -0.425999999,
-    -0.0260000005,
-    -0.312999994,
-    -0.36500001,
-    0.0759999976,
-    0.0340000018,
-    -0.120999999,
-    -0.57099998,
-    -0.477999985,
-    -0.328000009,
-    -0.400000006,
-    -0.344999999,
-    -0.103,
-    -0.123000003,
-    -0.351000011,
-    0.00999999978,
-    -0.712000012,
-    -0.509000003,
-    -0.504999995,
-    -0.245000005,
-    -0.228,
-    -0.407999992,
-    -0.238999993,
-    -0.105999999,
-    -0.0900000036,
-    -0.34799999,
-    -0.223000005,
-    -0.50999999,
-    -0.181999996,
-    0.064000003,
-    0.0590000004,
-    0.0860000029,
-    -0.0109999999,
-    0.206,
-    0.180999994,
-    0.163000003,
-    0.0280000009,
-    -0.321999997,
-    -0.455000013,
-    -0.259000003,
-    -0.289000005,
-    -0.123000003,
-    0.104999997,
-    0.0489999987,
-    0.239999995,
-    0.103,
-    0.226999998,
-    0.463,
-    0.708999991,
-    0.776000023,
-    0.829999983,
-    0.384000003,
-    0.118000001,
-    0.063000001,
-    0.187000006,
-    0.0260000005,
-    0.252000004,
-    0.266000003,
-    0.273000002,
-    0.246000007,
-    0.361999989,
-    0.472000003,
-    0.30399999,
-    0.263000011,
-    0.108999997,
-    -0.187999994,
-    -0.167999998,
-    -0.202000007,
-    -0.0970000029,
-    -0.0890000015,
-    0.257999986,
-    0.326999992,
-    0.116999999,
-    0.167999998,
-    0.133000001,
-    0.101999998,
-    0.216999993,
-    0.0250000004,
-    0.0879999995,
-    0.0219999999,
-    -0.0680000037,
-    -0.195999995,
-    0.00100000005,
-    -0.118000001,
-    -0.129999995,
-    -0.228,
-    -0.363000005,
-    -0.163000003,
-    -0.294,
-    -0.261999995,
-    0.023,
-    0.00600000005,
-    -0.137999997,
-    -0.155000001,
-    0.100000001,
-    -0.00100000005,
-    0.0120000001,
-    0.0250000004,
-    -0.241999999,
-    -0.0340000018,
-    0.0489999987,
-    0.194999993,
-    0.00300000003,
-    -0.266000003,
-    -0.196999997,
-    -0.172999993,
-    -0.252000004,
-    -0.261999995,
-    -0.27700001,
-    -0.231000006,
-    -0.298999995,
-    -0.150000006,
-    -0.00600000005,
-    -0.314999998,
-};
-
-const float GPS_DATA_VEAST[3230] = {
-    0.0599999987,
-    0.103,
-    0.0989999995,
-    -0.907000005,
-    -1.31700003,
-    -0.967000008,
-    -1.58099997,
-    -1.57500005,
-    -2.06100011,
-    -1.86800003,
-    -1.53499997,
-    -1.39100003,
-    -1.949,
-    -2.35299993,
-    -2.43400002,
-    -2.92499995,
-    -2.41700006,
-    -2.3269999,
-    -2.8210001,
-    -3.24699998,
-    -3.76600003,
-    -3.74699998,
-    -3.44499993,
-    -3.31800008,
-    -4.28599977,
-    -4.9920001,
-    -5.14499998,
-    -5.60900021,
-    -5.046,
-    -4.61399984,
-    -4.21600008,
-    -3.16300011,
-    -3.07500005,
-    -3.22600007,
-    -3.67000008,
-    -3.67000008,
-    -3.67000008,
-    -4.19000006,
-    -5.76399994,
-    -6.76300001,
-    -6.78499985,
-    -3.34299994,
-    -3.93000007,
-    -1.653,
-    -0.119000003,
-    -0.601000011,
-    -0.912999988,
-    -0.382999986,
-    -3.61199999,
-    -1.93700004,
-    -1.62899995,
-    -2.08400011,
-    -1.52900004,
-    -2.00099993,
-    -2.87299991,
-    -3.3499999,
-    -3.03600001,
-    -2.54999995,
-    -0.925999999,
-    0.202000007,
-    0.0419999994,
-    -0.0170000009,
-    -0.0610000007,
-    -0.555000007,
-    -0.97299999,
-    -0.83099997,
-    -1.11300004,
-    -1.72899997,
-    -1.74800003,
-    -1.79400003,
-    -2.56599998,
-    -1.01900005,
-    -1.48699999,
-    -1.85899997,
-    -1.85699999,
-    -1.17400002,
-    -3.18000007,
-    -2.75300002,
-    -1.79400003,
-    -2.76099992,
-    -2.96700001,
-    -4.46799994,
-    -5.09399986,
-    -3.80599999,
-    -4.92399979,
-    -4.75099993,
-    -4.41200018,
-    -2.65199995,
-    -3.34699988,
-    -3.2980001,
-    -3.03999996,
-    -5.10500002,
-    -2.45900011,
-    -0.879999995,
-    -1.88600004,
-    0.971000016,
-    2.34899998,
-    2.55999994,
-    2.85500002,
-    2.69099998,
-    2.898,
-    3.14400005,
-    3.16199994,
-    5.17600012,
-    6.19299984,
-    6.74100018,
-    7.49800014,
-    7.59800005,
-    7.7750001,
-    7.90199995,
-    8.09300041,
-    8.08699989,
-    8.61299992,
-    8.84500027,
-    9.15799999,
-    9.39999962,
-    9.15799999,
-    9.07400036,
-    9.16600037,
-    9.10000038,
-    8.97999954,
-    8.7489996,
-    9.125,
-    9.25300026,
-    9.18599987,
-    9.49300003,
-    9.43200016,
-    9.29699993,
-    9.33699989,
-    9.36499977,
-    9.21399975,
-    8.97399998,
-    9.09799957,
-    9.01399994,
-    9.19200039,
-    9,
-    9.16699982,
-    9.09799957,
-    9.11400032,
-    9.46100044,
-    9.31900024,
-    9.18799973,
-    9.15600014,
-    9.22799969,
-    8.72000027,
-    8.69999981,
-    8.80799961,
-    8.96899986,
-    8.85000038,
-    8.70899963,
-    8.74699974,
-    8.66300011,
-    8.32900047,
-    8.36100006,
-    8.34799957,
-    8.52799988,
-    8.43400002,
-    8.51900005,
-    8.47000027,
-    8.49199963,
-    8.40499973,
-    8.27999973,
-    8.23600006,
-    8.41499996,
-    8.50399971,
-    8.34200001,
-    8.36499977,
-    8.5010004,
-    8.83100033,
-    8.92300034,
-    8.95699978,
-    8.87699986,
-    8.57800007,
-    8.63899994,
-    8.84300041,
-    8.81299973,
-    8.54500008,
-    8.35400009,
-    8.49199963,
-    8.7159996,
-    8.78999996,
-    8.65200043,
-    8.68799973,
-    8.77999973,
-    8.66499996,
-    8.53600025,
-    8.77099991,
-    8.89500046,
-    8.82499981,
-    8.76399994,
-    8.84300041,
-    8.93599987,
-    8.97599983,
-    8.87199974,
-    8.6590004,
-    8.7670002,
-    8.76299953,
-    8.79599953,
-    8.59000015,
-    8.73799992,
-    8.72399998,
-    8.49600029,
-    8.47500038,
-    8.46399975,
-    8.67000008,
-    8.45699978,
-    8.44099998,
-    8.40699959,
-    8.5170002,
-    8.40699959,
-    8.26599979,
-    8.23600006,
-    8.3380003,
-    8.56299973,
-    8.32699966,
-    8.58399963,
-    8.56200027,
-    8.24300003,
-    8.28899956,
-    8.18799973,
-    8.22399998,
-    8.45600033,
-    8.30000019,
-    8.43599987,
-    8.40100002,
-    8.45100021,
-    8.30200005,
-    8.52299976,
-    8.41499996,
-    8.50199986,
-    8.44799995,
-    8.5340004,
-    8.60599995,
-    8.69799995,
-    8.74300003,
-    8.57499981,
-    8.42399979,
-    8.61200047,
-    8.69799995,
-    8.63099957,
-    8.59599972,
-    8.64900017,
-    8.6079998,
-    8.64299965,
-    8.58899975,
-    8.40400028,
-    8.60999966,
-    8.36499977,
-    8.4659996,
-    8.5010004,
-    8.36100006,
-    8.42099953,
-    8.5710001,
-    8.72799969,
-    8.76599979,
-    8.64500046,
-    8.77200031,
-    8.93999958,
-    8.97399998,
-    9.01599979,
-    8.81599998,
-    8.76500034,
-    8.84899998,
-    8.81299973,
-    8.84899998,
-    8.74699974,
-    8.62300014,
-    8.72500038,
-    8.55200005,
-    8.62699986,
-    8.48900032,
-    8.60499954,
-    8.60200024,
-    8.60200024,
-    8.62300014,
-    8.39000034,
-    8.4090004,
-    8.51299953,
-    8.61999989,
-    8.6239996,
-    8.6260004,
-    8.52999973,
-    8.72000027,
-    8.7130003,
-    8.65600014,
-    8.5539999,
-    8.42599964,
-    8.66800022,
-    8.90200043,
-    8.91600037,
-    8.85999966,
-    8.47900009,
-    8.57199955,
-    8.52999973,
-    8.49800014,
-    8.32600021,
-    8.54199982,
-    8.31099987,
-    8.22099972,
-    8.33899975,
-    8.37699986,
-    8.5710001,
-    8.4659996,
-    8.67599964,
-    8.34599972,
-    8.35400009,
-    8.50500011,
-    8.52700043,
-    8.35200024,
-    8.43999958,
-    8.45499992,
-    8.51500034,
-    8.52600002,
-    8.4460001,
-    8.2869997,
-    8.61400032,
-    8.77799988,
-    8.76299953,
-    8.72099972,
-    8.70899963,
-    8.67399979,
-    8.41100025,
-    8.74800014,
-    8.72399998,
-    8.74499989,
-    8.84200001,
-    8.78499985,
-    8.81799984,
-    8.87699986,
-    8.95899963,
-    8.57800007,
-    8.5909996,
-    8.69099998,
-    8.81299973,
-    8.92800045,
-    8.65200043,
-    8.69200039,
-    8.76299953,
-    8.73900032,
-    8.79399967,
-    8.70100021,
-    8.62100029,
-    8.79699993,
-    8.77099991,
-    8.75199986,
-    8.77400017,
-    8.6079998,
-    8.63300037,
-    8.63199997,
-    8.66600037,
-    8.66899967,
-    8.72200012,
-    8.57600021,
-    8.75199986,
-    8.82499981,
-    8.81900024,
-    8.78600025,
-    8.60599995,
-    8.62800026,
-    8.5909996,
-    8.75300026,
-    8.70300007,
-    8.72500038,
-    8.76500034,
-    8.76599979,
-    8.67199993,
-    8.74400043,
-    8.73400021,
-    8.75899982,
-    8.72299957,
-    8.8579998,
-    8.73400021,
-    8.68999958,
-    8.67300034,
-    8.87199974,
-    8.77499962,
-    8.86800003,
-    8.65699959,
-    8.80000019,
-    8.78600025,
-    8.76399994,
-    8.85000038,
-    8.79399967,
-    8.70899963,
-    8.76399994,
-    8.72900009,
-    8.70499992,
-    8.84599972,
-    8.86100006,
-    8.76299953,
-    8.82800007,
-    8.75399971,
-    8.83899975,
-    8.54199982,
-    8.75899982,
-    8.80799961,
-    8.69900036,
-    8.73099995,
-    8.66800022,
-    8.64599991,
-    8.78100014,
-    8.75199986,
-    8.77099991,
-    8.75399971,
-    8.67800045,
-    8.71899986,
-    8.73400021,
-    8.82299995,
-    8.80700016,
-    8.56999969,
-    8.52700043,
-    8.74199963,
-    8.79100037,
-    8.75300026,
-    8.6079998,
-    8.69099998,
-    8.69699955,
-    8.6960001,
-    8.77999973,
-    8.65799999,
-    8.67199993,
-    8.5909996,
-    8.68200016,
-    8.67199993,
-    8.75599957,
-    8.66499996,
-    8.8210001,
-    8.63599968,
-    8.61499977,
-    8.78899956,
-    8.70400047,
-    8.74400043,
-    8.7159996,
-    8.6619997,
-    8.69799995,
-    8.60299969,
-    8.59000015,
-    8.78899956,
-    8.68000031,
-    8.60599995,
-    8.70899963,
-    8.71399975,
-    8.67500019,
-    8.80900002,
-    8.74400043,
-    8.57400036,
-    8.76799965,
-    8.81900024,
-    8.65200043,
-    8.63000011,
-    8.92599964,
-    8.77600002,
-    8.72799969,
-    8.66100025,
-    8.57900047,
-    8.28999996,
-    8.30000019,
-    8.35099983,
-    8.37199974,
-    8.46500015,
-    8.59300041,
-    9.06200027,
-    9.24100018,
-    9.19900036,
-    9.51299953,
-    9.5,
-    9.94499969,
-    10.4890003,
-    10.177,
-    10.1599998,
-    10.0089998,
-    9.8210001,
-    9.375,
-    9.12100029,
-    9.24199963,
-    9.11900043,
-    8.72900009,
-    8.53899956,
-    8.27499962,
-    7.93900013,
-    7.8670001,
-    7.66200018,
-    8.09899998,
-    7.63999987,
-    7.60300016,
-    7.68200016,
-    7.9829998,
-    8.27900028,
-    8.51599979,
-    8.94400024,
-    9.28800011,
-    9.26399994,
-    9.32900047,
-    9.41499996,
-    9.13399982,
-    9.0170002,
-    8.92700005,
-    9.1590004,
-    9.18400002,
-    9.51599979,
-    10.0640001,
-    10.026,
-    10.2329998,
-    10.2950001,
-    10.3710003,
-    10.2200003,
-    10.4680004,
-    10.4239998,
-    10.5579996,
-    10.7779999,
-    10.9770002,
-    10.882,
-    10.7819996,
-    10.776,
-    10.9969997,
-    11.21,
-    11.3059998,
-    11.2189999,
-    11.3039999,
-    11.3260002,
-    11.5609999,
-    11.618,
-    11.5950003,
-    11.5170002,
-    11.2659998,
-    11.4139996,
-    11.4250002,
-    11.3970003,
-    11.4069996,
-    11.5810003,
-    11.4899998,
-    11.5480003,
-    11.5220003,
-    11.5539999,
-    11.5900002,
-    11.684,
-    11.6949997,
-    11.9020004,
-    11.6129999,
-    11.9399996,
-    11.7600002,
-    11.9630003,
-    11.8330002,
-    11.7810001,
-    12.1079998,
-    11.9510002,
-    11.9799995,
-    11.9350004,
-    11.8950005,
-    11.6370001,
-    11.9429998,
-    12.0570002,
-    12.0880003,
-    11.9300003,
-    12.0080004,
-    12.0179996,
-    12.198,
-    12.3249998,
-    12.3339996,
-    12.0839996,
-    12.1280003,
-    11.9949999,
-    12.0749998,
-    12.118,
-    11.9119997,
-    11.8769999,
-    11.9549999,
-    12.0249996,
-    12.0740004,
-    12.0600004,
-    11.8570004,
-    11.7559996,
-    11.882,
-    12.0170002,
-    12.0419998,
-    11.7910004,
-    12.066,
-    12.1090002,
-    12.1739998,
-    12.0209999,
-    11.9099998,
-    11.8339996,
-    12.0179996,
-    11.9449997,
-    12.099,
-    12.0419998,
-    12.2980003,
-    12.1219997,
-    11.9490004,
-    11.9589996,
-    11.7939997,
-    11.6960001,
-    11.7489996,
-    11.4729996,
-    11.2930002,
-    11.4490004,
-    11.382,
-    11.2220001,
-    11.2779999,
-    11.1929998,
-    11.1149998,
-    10.9259996,
-    11.1070004,
-    11.25,
-    11.3199997,
-    11.3179998,
-    11.1949997,
-    11.1549997,
-    10.7679996,
-    10.6599998,
-    10.6940002,
-    10.4359999,
-    10.6199999,
-    10.4820004,
-    10.677,
-    11.0139999,
-    10.8450003,
-    11.0710001,
-    10.7399998,
-    10.7480001,
-    10.3540001,
-    10.2209997,
-    10.0170002,
-    10.2819996,
-    10.6020002,
-    10.7519999,
-    10.7849998,
-    10.6920004,
-    10.9090004,
-    10.9259996,
-    10.6899996,
-    10.6370001,
-    11.0039997,
-    10.7989998,
-    10.6590004,
-    10.573,
-    10.7849998,
-    10.6149998,
-    10.3389997,
-    10.3660002,
-    10.2030001,
-    10.0570002,
-    10.0120001,
-    10.0200005,
-    9.99400043,
-    9.90400028,
-    10.0190001,
-    9.80099964,
-    9.59200001,
-    9.77200031,
-    9.98499966,
-    9.83899975,
-    9.84399986,
-    9.89900017,
-    10.29,
-    10.5360003,
-    10.1520004,
-    10.3839998,
-    10.5439997,
-    10.6599998,
-    10.2889996,
-    10.1020002,
-    10.1020002,
-    9.98900032,
-    9.87800026,
-    9.84200001,
-    9.87100029,
-    9.86999989,
-    10.0299997,
-    10.4099998,
-    10.5839996,
-    10.5880003,
-    10.5229998,
-    10.4700003,
-    10.4280005,
-    10.1709995,
-    10.1210003,
-    10.0310001,
-    10.1630001,
-    10.1199999,
-    10.1009998,
-    10.2849998,
-    10.165,
-    10.2010002,
-    10.1029997,
-    10.2370005,
-    10.3570004,
-    10.7069998,
-    10.75,
-    10.8310003,
-    11.1199999,
-    10.96,
-    11.1470003,
-    11.2209997,
-    11.1529999,
-    11.1090002,
-    10.8739996,
-    10.9300003,
-    10.677,
-    10.7600002,
-    10.7119999,
-    10.5950003,
-    10.5810003,
-    10.6140003,
-    10.7869997,
-    10.5270004,
-    10.6199999,
-    10.5939999,
-    10.651,
-    10.6190004,
-    10.6140003,
-    10.5719995,
-    10.6000004,
-    10.5909996,
-    10.559,
-    10.5459995,
-    10.7969999,
-    10.6789999,
-    10.6890001,
-    10.5410004,
-    10.5559998,
-    10.4940004,
-    10.5229998,
-    10.4799995,
-    10.3920002,
-    10.2489996,
-    10.3590002,
-    10.243,
-    10.2110004,
-    10.3830004,
-    10.4169998,
-    10.5360003,
-    10.5900002,
-    10.6359997,
-    10.566,
-    10.3909998,
-    10.3149996,
-    10.2950001,
-    10.4980001,
-    10.7049999,
-    10.8360004,
-    10.6719999,
-    10.1789999,
-    10.1370001,
-    10.0360003,
-    10.099,
-    9.9119997,
-    9.32299995,
-    9.33500004,
-    9.51900005,
-    9.41899967,
-    8.81599998,
-    8.32299995,
-    8.70199966,
-    9.3739996,
-    10.1009998,
-    10.3290005,
-    11.2060003,
-    10.3999996,
-    10.177,
-    10.2019997,
-    10.1099997,
-    9.95800018,
-    9.38599968,
-    9.36900043,
-    9.52900028,
-    9.44499969,
-    9.56900024,
-    9.47399998,
-    9.54899979,
-    9.45899963,
-    9.28899956,
-    8.8920002,
-    8.39599991,
-    8.3409996,
-    8.61299992,
-    9.12899971,
-    8.92700005,
-    8.8739996,
-    8.58399963,
-    9.07400036,
-    9.28999996,
-    9.3739996,
-    9.01500034,
-    8.69200039,
-    8.91800022,
-    8.78299999,
-    8.79500008,
-    8.88199997,
-    8.99300003,
-    9.01299953,
-    9.04800034,
-    8.86800003,
-    9.1619997,
-    9.41499996,
-    9.02700043,
-    9.01599979,
-    9.03299999,
-    9.23700047,
-    9.09399986,
-    8.7670002,
-    8.90799999,
-    8.79300022,
-    8.70800018,
-    8.41399956,
-    8.63099957,
-    8.67700005,
-    8.58699989,
-    8.46500015,
-    8.25500011,
-    8.17199993,
-    8.1079998,
-    8.15799999,
-    7.87599993,
-    7.81099987,
-    7.92199993,
-    8.24199963,
-    8.11999989,
-    8.27700043,
-    8.3380003,
-    8.30700016,
-    8.68299961,
-    9.06599998,
-    8.9989996,
-    9.03100014,
-    9.10200024,
-    8.95600033,
-    8.87699986,
-    8.8380003,
-    8.89400005,
-    8.75500011,
-    8.40299988,
-    8.3210001,
-    8.36100006,
-    8.66699982,
-    8.42300034,
-    8.18799973,
-    8.36100006,
-    8.06000042,
-    8.47000027,
-    8.58199978,
-    8.39599991,
-    8.55200005,
-    8.51799965,
-    8.57199955,
-    8.63399982,
-    8.70800018,
-    8.5909996,
-    8.86299992,
-    8.95800018,
-    8.95400047,
-    8.64400005,
-    8.7159996,
-    8.54300022,
-    8.91699982,
-    8.89400005,
-    8.78600025,
-    9.09799957,
-    8.99300003,
-    8.77200031,
-    8.81299973,
-    8.47999954,
-    8.09500027,
-    7.375,
-    7.86999989,
-    7.64699984,
-    7.96500015,
-    8.56000042,
-    8.29599953,
-    7.93599987,
-    8.32699966,
-    8.10999966,
-    8.31499958,
-    8.75500011,
-    8.51000023,
-    7.88600016,
-    7.09899998,
-    7.17000008,
-    7.82200003,
-    8.16800022,
-    7.93200016,
-    7.60699987,
-    8.51000023,
-    8.57400036,
-    8.73999977,
-    7.90500021,
-    6.54099989,
-    7.01599979,
-    7.36800003,
-    7.70300007,
-    8.24199963,
-    8.26099968,
-    8.10000038,
-    8.13500023,
-    7.96199989,
-    8.00899982,
-    7.86800003,
-    7.98899984,
-    7.76200008,
-    7.90899992,
-    7.88199997,
-    7.76100016,
-    7.17999983,
-    7.38100004,
-    7.12900019,
-    7.01100016,
-    6.58199978,
-    7.06400013,
-    7.18900013,
-    7.0999999,
-    7.17700005,
-    7.29799986,
-    7.31099987,
-    7.24100018,
-    7.15100002,
-    7.26200008,
-    7.03599977,
-    7.36100006,
-    7.74100018,
-    7.86299992,
-    7.51399994,
-    6.98699999,
-    7.16400003,
-    7.17799997,
-    6.84000015,
-    6.77099991,
-    6.33199978,
-    5.80999994,
-    5.90500021,
-    6.375,
-    6.829,
-    7.36899996,
-    7.68400002,
-    7.9380002,
-    7.65500021,
-    7,
-    7.11299992,
-    7.00400019,
-    7.1869998,
-    7.46299982,
-    7.64900017,
-    7.63999987,
-    7.86800003,
-    7.80200005,
-    7.579,
-    7.5,
-    7.50899982,
-    7.80499983,
-    7.44999981,
-    7.50099993,
-    7.47100019,
-    7.35599995,
-    7.59700012,
-    7.53499985,
-    7.58300018,
-    7.48999977,
-    7.43400002,
-    6.98500013,
-    6.71700001,
-    6.93599987,
-    6.85500002,
-    6.79899979,
-    6.83799982,
-    6.70800018,
-    6.94999981,
-    6.86800003,
-    6.74499989,
-    6.5079999,
-    6.53200006,
-    6.49300003,
-    6.72700024,
-    6.93200016,
-    6.76800013,
-    6.49800014,
-    6.44099998,
-    6.97399998,
-    6.9289999,
-    6.65600014,
-    6.72300005,
-    6.82499981,
-    6.62599993,
-    6.63800001,
-    6.37900019,
-    6.4369998,
-    6.11299992,
-    6.1420002,
-    5.72800016,
-    5.94899988,
-    6.29400015,
-    6.46299982,
-    6.9749999,
-    7.04099989,
-    6.78800011,
-    6.74399996,
-    6.34600019,
-    6.296,
-    6.56799984,
-    6.45599985,
-    6.54300022,
-    6.79899979,
-    6.78299999,
-    6.61499977,
-    6.47100019,
-    6.3670001,
-    6.63600016,
-    6.50299978,
-    6.22300005,
-    6.19500017,
-    6.35699987,
-    6.45100021,
-    6.61899996,
-    6.73000002,
-    6.55600023,
-    6.45100021,
-    6.48899984,
-    6.52299976,
-    7.05999994,
-    6.89400005,
-    6.95800018,
-    7.01200008,
-    6.99800014,
-    7.12900019,
-    7.17999983,
-    7.30800009,
-    7.32800007,
-    7.329,
-    7.38999987,
-    7.46799994,
-    7.421,
-    7.22300005,
-    6.90500021,
-    6.93900013,
-    6.88999987,
-    6.67700005,
-    6.4289999,
-    5.95100021,
-    6.01999998,
-    6.32999992,
-    6.51399994,
-    6.47900009,
-    6.42700005,
-    6.25199986,
-    6.26800013,
-    6.51000023,
-    6.55000019,
-    6.63500023,
-    6.62200022,
-    6.84399986,
-    6.69700003,
-    6.76300001,
-    6.76300001,
-    6.76300001,
-    7.0250001,
-    6.92199993,
-    6.79699993,
-    6.70300007,
-    6.55999994,
-    6.33199978,
-    6.33699989,
-    6.53900003,
-    6.6420002,
-    6.53000021,
-    6.83599997,
-    7.07399988,
-    6.63700008,
-    6.87400007,
-    7.09100008,
-    7.20800018,
-    7.17399979,
-    7.05900002,
-    6.78700018,
-    6.67500019,
-    6.63800001,
-    6.35300016,
-    6.03399992,
-    6.31699991,
-    6.22300005,
-    6.07700014,
-    6.29899979,
-    6.20300007,
-    6.32299995,
-    5.73500013,
-    5.63800001,
-    6.11800003,
-    6.39699984,
-    6.46500015,
-    6.64400005,
-    7.16200018,
-    7.16200018,
-    7.16200018,
-    7.23699999,
-    7.26399994,
-    7.23600006,
-    7.2420001,
-    7.0539999,
-    7.23099995,
-    7.13500023,
-    7.03100014,
-    6.90999985,
-    6.70900011,
-    6.35599995,
-    6.14300013,
-    6.204,
-    6.28700018,
-    6.41699982,
-    6.76999998,
-    6.84600019,
-    6.44700003,
-    6.41099977,
-    5.93599987,
-    5.50099993,
-    5.67600012,
-    5.52699995,
-    5.6500001,
-    6,
-    6.00400019,
-    6.17399979,
-    6.11600018,
-    6.11499977,
-    6.13100004,
-    5.94500017,
-    5.671,
-    5.51000023,
-    5.46799994,
-    5.88199997,
-    5.90700006,
-    5.71099997,
-    5.84700012,
-    5.77199984,
-    5.94299984,
-    6.04300022,
-    6.1880002,
-    5.92399979,
-    5.78900003,
-    5.76499987,
-    5.8670001,
-    5.96400023,
-    6.08300018,
-    5.90500021,
-    5.90700006,
-    5.66400003,
-    5.73400021,
-    6.21700001,
-    6.41300011,
-    6.59899998,
-    6.59399986,
-    6.45100021,
-    6.68900013,
-    6.9380002,
-    6.92700005,
-    6.86800003,
-    6.62799978,
-    6.67199993,
-    6.95699978,
-    6.89400005,
-    7.20800018,
-    7.46099997,
-    7.28599977,
-    7.204,
-    7.04300022,
-    7.1869998,
-    7.24499989,
-    7.15600014,
-    7.05100012,
-    6.78299999,
-    6.57399988,
-    6.37099981,
-    6.20499992,
-    6.44799995,
-    6.33500004,
-    6.32000017,
-    6.95699978,
-    6.94299984,
-    7.36199999,
-    7.78499985,
-    7.37699986,
-    7.07700014,
-    7.35699987,
-    7.48000002,
-    7.69899988,
-    7.89400005,
-    7.96799994,
-    7.75699997,
-    8.0010004,
-    7.71700001,
-    7.65799999,
-    7.58099985,
-    7.25899982,
-    7.21000004,
-    6.93400002,
-    6.16699982,
-    5.59299994,
-    6.05600023,
-    6.91599989,
-    6.86100006,
-    7.01100016,
-    7.05100012,
-    7.05299997,
-    7.06599998,
-    7.18499994,
-    7.05000019,
-    7.23400021,
-    7.01800013,
-    7.49399996,
-    7.44999981,
-    7.43300009,
-    7.21500015,
-    7.24399996,
-    7.546,
-    8.04899979,
-    8.23099995,
-    8.40299988,
-    8.12800026,
-    7.72100019,
-    7.19700003,
-    7.02400017,
-    7.00899982,
-    7.06099987,
-    7.12900019,
-    7.0539999,
-    7.1500001,
-    6.87400007,
-    7.14699984,
-    7.40600014,
-    7.28399992,
-    7.61800003,
-    6.8130002,
-    7.38100004,
-    7.04799986,
-    7.5710001,
-    7.579,
-    7.49499989,
-    7.60599995,
-    7.85699987,
-    7.64799976,
-    7.44999981,
-    7.23500013,
-    7.19299984,
-    7.44199991,
-    7.42299986,
-    7.28399992,
-    7.26000023,
-    7.50199986,
-    7.49800014,
-    7.73500013,
-    7.79500008,
-    7.54699993,
-    7.55600023,
-    7.70100021,
-    7.72599983,
-    7.77600002,
-    7.6329999,
-    7.6329999,
-    7.6329999,
-    7.03800011,
-    7.21099997,
-    7.17700005,
-    7.22900009,
-    7.42199993,
-    7.37200022,
-    7.51300001,
-    7.52299976,
-    7.82800007,
-    7.8210001,
-    7.9829998,
-    8.12699986,
-    8.08500004,
-    8.2159996,
-    8.10099983,
-    8.37800026,
-    8.29800034,
-    8.30799961,
-    7.83099985,
-    7.52099991,
-    7.26599979,
-    6.94500017,
-    6.94000006,
-    7.01999998,
-    6.84200001,
-    7.34800005,
-    7.56400013,
-    6.95599985,
-    6.84600019,
-    6.80900002,
-    6.57600021,
-    6.6880002,
-    6.89900017,
-    7.55600023,
-    7.77299976,
-    7.89699984,
-    7.37699986,
-    7.4920001,
-    7.85599995,
-    7.98799992,
-    7.47399998,
-    7.62900019,
-    7.83099985,
-    7.35500002,
-    7.28800011,
-    7.2750001,
-    7.15500021,
-    6.67299986,
-    6.63899994,
-    6.87799978,
-    6.60300016,
-    6.67299986,
-    6.72200012,
-    7.15600014,
-    7.5630002,
-    8.19900036,
-    7.97399998,
-    7.55499983,
-    7.03499985,
-    6.12300014,
-    6.9289999,
-    6.89799976,
-    6.84100008,
-    7.02099991,
-    6.85699987,
-    6.72300005,
-    6.73799992,
-    6.64499998,
-    6.85500002,
-    6.76999998,
-    6.67000008,
-    6.48199987,
-    6.2750001,
-    6.56400013,
-    6.51499987,
-    6.75500011,
-    7.16200018,
-    7.36499977,
-    6.84100008,
-    6.80999994,
-    6.53499985,
-    6.2420001,
-    6.40700006,
-    6.01100016,
-    6.03299999,
-    6.09000015,
-    6.3210001,
-    6.68100023,
-    6.62200022,
-    6.59100008,
-    6.75400019,
-    6.98600006,
-    7.04099989,
-    6.88399982,
-    7.1329999,
-    7.50600004,
-    7.57999992,
-    7.32200003,
-    7.07800007,
-    6.60699987,
-    6.08900023,
-    6.01999998,
-    6.34700012,
-    6.5170002,
-    6.94000006,
-    7.10599995,
-    7.50699997,
-    7.42299986,
-    7.40700006,
-    7.56099987,
-    7.43900013,
-    7.44799995,
-    7.47200012,
-    7.579,
-    7.70300007,
-    7.99599981,
-    7.95300007,
-    8.05000019,
-    7.8829999,
-    8.02700043,
-    8.06200027,
-    8.24199963,
-    8.1619997,
-    8.14799976,
-    8.07600021,
-    8.09799957,
-    7.89499998,
-    8.19299984,
-    8.70199966,
-    8.50899982,
-    8.09700012,
-    8.16399956,
-    7.97100019,
-    8.27200031,
-    8.26399994,
-    8.51799965,
-    8.56400013,
-    8.54399967,
-    8.60700035,
-    8.59399986,
-    8.13300037,
-    7.67500019,
-    7.79400015,
-    7.34899998,
-    7.01100016,
-    7.49800014,
-    7.58599997,
-    7.68499994,
-    7.72300005,
-    7.83400011,
-    8.04899979,
-    8.17300034,
-    8.01399994,
-    7.9460001,
-    7.64300013,
-    7.38100004,
-    7.45800018,
-    7.0079999,
-    6.8579998,
-    6.70300007,
-    6.95100021,
-    7.56699991,
-    7.50500011,
-    7.3119998,
-    7.20900011,
-    6.96400023,
-    6.8920002,
-    7.0630002,
-    7.04199982,
-    7.16300011,
-    7.58699989,
-    8.01200008,
-    7.86999989,
-    7.55999994,
-    7.35200024,
-    7.22900009,
-    7.0619998,
-    7.19799995,
-    7.0999999,
-    6.97200012,
-    6.89900017,
-    6.95100021,
-    6.91300011,
-    7.10400009,
-    6.65700006,
-    6.53999996,
-    6.52699995,
-    6.40899992,
-    6.78900003,
-    7.06500006,
-    7.79199982,
-    6.95800018,
-    6.73699999,
-    7.02299976,
-    7.06400013,
-    7.61499977,
-    8.05599976,
-    7.81799984,
-    7.69000006,
-    7.46000004,
-    7.46500015,
-    7.05100012,
-    6.95900011,
-    7.22900009,
-    7.40100002,
-    7.54500008,
-    7.17000008,
-    6.89900017,
-    7.38899994,
-    7.25199986,
-    7.00199986,
-    6.4000001,
-    6.46400023,
-    6.3499999,
-    6.079,
-    6.28900003,
-    6.29300022,
-    6.73400021,
-    7.25400019,
-    7.77600002,
-    8.38300037,
-    8.54899979,
-    8.73099995,
-    8.43400002,
-    8.19900036,
-    8.08300018,
-    8.43299961,
-    8.33899975,
-    7.95200014,
-    8.16600037,
-    8.26900005,
-    8.18599987,
-    8.1079998,
-    7.54500008,
-    7.17500019,
-    6.82499981,
-    6.59399986,
-    6.64099979,
-    7.44799995,
-    7.38399982,
-    7.16300011,
-    6.921,
-    7.18499994,
-    7.54099989,
-    7.6789999,
-    6.74399996,
-    5.64599991,
-    7.06099987,
-    7.79300022,
-    7.9289999,
-    8.46899986,
-    8.69799995,
-    8.52400017,
-    8.35700035,
-    8.53600025,
-    8.52099991,
-    8.06000042,
-    8.2130003,
-    8.43099976,
-    8.4630003,
-    8.10099983,
-    7.87900019,
-    7.37099981,
-    7.07700014,
-    7.17299986,
-    7.37200022,
-    7.60500002,
-    7.93200016,
-    8.58399963,
-    8.8920002,
-    8.98600006,
-    9.07999992,
-    8.84000015,
-    8.74699974,
-    8.94299984,
-    8.94299984,
-    9.09300041,
-    9.1960001,
-    8.99699974,
-    9.46100044,
-    9.16899967,
-    8.90100002,
-    8.95899963,
-    9.13899994,
-    9.15100002,
-    9.29399967,
-    9.09000015,
-    9.44200039,
-    9.2670002,
-    8.97399998,
-    8.27200031,
-    7.26100016,
-    7.43200016,
-    7.4460001,
-    7.63999987,
-    7.71600008,
-    7.91200018,
-    7.30200005,
-    7.00199986,
-    6.38899994,
-    5.88399982,
-    6.26499987,
-    6.875,
-    6.14699984,
-    5.62900019,
-    5.0250001,
-    5.35300016,
-    5.22300005,
-    5.31500006,
-    5.07499981,
-    4.86199999,
-    4.84399986,
-    5.0079999,
-    5.13999987,
-    5.77899981,
-    6.05999994,
-    5.96099997,
-    6.17999983,
-    6.27099991,
-    6.37400007,
-    6.69399977,
-    6.84899998,
-    6.90299988,
-    7.27799988,
-    7.36000013,
-    7.61499977,
-    7.58599997,
-    7.74599981,
-    8.02099991,
-    8.06499958,
-    8.10299969,
-    8.17399979,
-    8.43500042,
-    8.56200027,
-    8.76299953,
-    8.95300007,
-    9.00199986,
-    9.15200043,
-    9.09000015,
-    9.23900032,
-    9.13199997,
-    9.30900002,
-    9.37300014,
-    9.22200012,
-    9.03499985,
-    9.06599998,
-    8.76399994,
-    8.87699986,
-    8.84200001,
-    8.45499992,
-    8.19799995,
-    7.97100019,
-    7.87799978,
-    8.07199955,
-    8.6420002,
-    8.93900013,
-    8.46199989,
-    8.07600021,
-    8.0369997,
-    7.95200014,
-    7.56699991,
-    7.87900019,
-    7.98000002,
-    7.74399996,
-    7.39400005,
-    7.17199993,
-    6.87300014,
-    6.53999996,
-    6.67700005,
-    6.71899986,
-    6.76900005,
-    6.70100021,
-    6.49399996,
-    6.2579999,
-    5.73600006,
-    5.99900007,
-    5.56500006,
-    5.38600016,
-    5.85099983,
-    6.02899981,
-    5.84299994,
-    5.60200024,
-    5.27299976,
-    5.26300001,
-    5.35699987,
-    5.10300016,
-    5.3130002,
-    5.00899982,
-    4.91400003,
-    4.98500013,
-    4.88600016,
-    4.86499977,
-    4.88199997,
-    4.37599993,
-    4.1789999,
-    3.96600008,
-    4.16599989,
-    4.47200012,
-    4.6420002,
-    4.71500015,
-    4.76100016,
-    4.4920001,
-    4.82399988,
-    5.08699989,
-    5.15199995,
-    5.17799997,
-    5.47300005,
-    5.2420001,
-    5.05600023,
-    4.39499998,
-    4.76100016,
-    4.69000006,
-    4.65700006,
-    4.82200003,
-    5.08400011,
-    5.04300022,
-    5.53800011,
-    5.52699995,
-    5.52799988,
-    5.33199978,
-    5.03299999,
-    5.22599983,
-    5.25,
-    5.38000011,
-    5.14799976,
-    5.15199995,
-    5.40600014,
-    5.29500008,
-    5.20599985,
-    5.28999996,
-    5.37699986,
-    5.31899977,
-    5.03499985,
-    4.84200001,
-    4.80800009,
-    4.97100019,
-    4.99100018,
-    5.07000017,
-    5.15100002,
-    5.15999985,
-    5.08300018,
-    4.86499977,
-    4.95300007,
-    5.04199982,
-    5.20800018,
-    5.03000021,
-    5.11399984,
-    4.95699978,
-    4.6500001,
-    4.7249999,
-    5.01599979,
-    4.94700003,
-    5.24800014,
-    5.27199984,
-    4.72399998,
-    4.38399982,
-    3.9289999,
-    4.46600008,
-    4.75199986,
-    5.05700016,
-    4.62900019,
-    4.80499983,
-    4.52099991,
-    4.28800011,
-    4.26399994,
-    4.25299978,
-    4.37200022,
-    4.28000021,
-    4.28700018,
-    4.14799976,
-    4.30700016,
-    4.1789999,
-    4.34800005,
-    4.27699995,
-    4.40700006,
-    4.42999983,
-    4.52299976,
-    4.64400005,
-    4.85500002,
-    4.875,
-    4.67000008,
-    4.98400021,
-    5.01999998,
-    4.99300003,
-    5.06899977,
-    4.8119998,
-    5.2420001,
-    5.3670001,
-    5.47900009,
-    5.69399977,
-    5.89900017,
-    6.28499985,
-    6.23199987,
-    6.16800022,
-    6.27099991,
-    6.44899988,
-    6.53700018,
-    6.55999994,
-    6.66900015,
-    6.796,
-    6.88700008,
-    7.10200024,
-    7.10200024,
-    7.23500013,
-    7.26499987,
-    7.39900017,
-    7.62799978,
-    7.60099983,
-    7.65399981,
-    7.75600004,
-    7.8119998,
-    7.80600023,
-    7.89099979,
-    7.94999981,
-    7.97800016,
-    7.875,
-    7.875,
-    7.90199995,
-    7.88100004,
-    7.75,
-    7.88999987,
-    7.875,
-    8.16800022,
-    8.11100006,
-    8.14000034,
-    8.12899971,
-    8.25,
-    8.20600033,
-    7.88999987,
-    7.9289999,
-    7.93300009,
-    8.07999992,
-    7.89900017,
-    7.85099983,
-    7.87099981,
-    7.83799982,
-    7.69999981,
-    7.53599977,
-    7.44500017,
-    7.38700008,
-    7.38100004,
-    7.35200024,
-    7.59800005,
-    7.8670001,
-    7.89499998,
-    8.04699993,
-    7.77199984,
-    8.12800026,
-    8.09899998,
-    8.05700016,
-    8.20800018,
-    8.12100029,
-    8.06499958,
-    7.94399977,
-    7.73199987,
-    7.86499977,
-    8.15499973,
-    8.22599983,
-    8.15200043,
-    8.23900032,
-    8.18299961,
-    8.23999977,
-    8.28499985,
-    8.48200035,
-    8.50699997,
-    8.42599964,
-    8.32199955,
-    8.32199955,
-    8.32199955,
-    7.98199987,
-    8.10900021,
-    8.00899982,
-    7.84600019,
-    7.83900023,
-    8.02400017,
-    8.02900028,
-    8.14000034,
-    7.90199995,
-    7.97300005,
-    7.96099997,
-    7.8039999,
-    7.71700001,
-    7.60900021,
-    7.59600019,
-    7.40700006,
-    7.21400023,
-    7.33799982,
-    7.39499998,
-    7.42999983,
-    7.21000004,
-    7.25899982,
-    7.05100012,
-    7.1420002,
-    7.41200018,
-    7.2670002,
-    7.17199993,
-    6.95800018,
-    6.98500013,
-    7.03599977,
-    7.0710001,
-    7.30900002,
-    6.86000013,
-    6.80100012,
-    6.4369998,
-    6.36399984,
-    6.49599981,
-    6.51100016,
-    6.26499987,
-    6.34499979,
-    6.21799994,
-    6.1789999,
-    6.10099983,
-    5.87099981,
-    5.86199999,
-    5.94999981,
-    5.76300001,
-    5.75899982,
-    5.74800014,
-    5.46999979,
-    5.30999994,
-    5.26399994,
-    5.23999977,
-    5.3670001,
-    5.50199986,
-    5.5630002,
-    5.44700003,
-    5.36499977,
-    5.48899984,
-    5.43200016,
-    5.4000001,
-    4.93599987,
-    5.1329999,
-    5.33699989,
-    5.28800011,
-    5.84299994,
-    5.71099997,
-    5.75199986,
-    5.36399984,
-    5.03999996,
-    5.10099983,
-    5.03000021,
-    5.16599989,
-    5.44199991,
-    5.60900021,
-    5.625,
-    5.28800011,
-    5.39900017,
-    5.3920002,
-    5.15299988,
-    5.01200008,
-    5.09800005,
-    5.03000021,
-    5.10099983,
-    5.05800009,
-    5.01399994,
-    4.91800022,
-    5.04300022,
-    5.05900002,
-    5.14799976,
-    5.41599989,
-    5.12099981,
-    5.10200024,
-    5.18900013,
-    5.19099998,
-    5.33799982,
-    5.32999992,
-    5.46799994,
-    5.36299992,
-    5.22700024,
-    5.24499989,
-    5.37900019,
-    5.53399992,
-    5.53399992,
-    5.53399992,
-    5.35900021,
-    5.69000006,
-    5.49499989,
-    5.35599995,
-    5.25299978,
-    5.48699999,
-    5.3130002,
-    5.45200014,
-    5.3829999,
-    5.37300014,
-    5.4920001,
-    5.4369998,
-    5.6880002,
-    5.75699997,
-    5.51399994,
-    5.49599981,
-    5.49599981,
-    5.49599981,
-    5.46099997,
-    5.47300005,
-    5.29400015,
-    5.28999996,
-    5.31599998,
-    5.22599983,
-    5.18100023,
-    5.14400005,
-    5.26599979,
-    5.44299984,
-    5.40899992,
-    5.40899992,
-    5.38199997,
-    5.28700018,
-    5.41300011,
-    5.36600018,
-    5.0250001,
-    5.07800007,
-    5.28900003,
-    5.22800016,
-    5.28900003,
-    5.01200008,
-    5.31799984,
-    5.48600006,
-    5.41300011,
-    5.15799999,
-    4.98799992,
-    5.22300005,
-    5.2249999,
-    5.15700006,
-    5.38500023,
-    5.27400017,
-    5.38899994,
-    5.32399988,
-    5.35900021,
-    4.97399998,
-    5.03399992,
-    5.19999981,
-    5.21600008,
-    5.01200008,
-    4.8579998,
-    5.11999989,
-    5.10200024,
-    4.51599979,
-    5.0170002,
-    4.70499992,
-    4.55800009,
-    4.66400003,
-    4.89699984,
-    4.88500023,
-    4.84000015,
-    4.79400015,
-    4.93300009,
-    4.78299999,
-    4.90799999,
-    4.71500015,
-    4.50099993,
-    4.68300009,
-    4.67299986,
-    4.54500008,
-    4.73099995,
-    4.53200006,
-    4.46299982,
-    4.60099983,
-    4.78900003,
-    4.53599977,
-    4.45499992,
-    4.49900007,
-    4.3499999,
-    4.29400015,
-    4.25099993,
-    4.38600016,
-    4.80299997,
-    4.70300007,
-    4.31599998,
-    4.29799986,
-    4.37599993,
-    4.34000015,
-    4.5619998,
-    4.26300001,
-    4.56799984,
-    4.29300022,
-    4.40500021,
-    4.19099998,
-    4.24300003,
-    4.3039999,
-    4.27799988,
-    4.17399979,
-    4.42000008,
-    4.5630002,
-    4.27899981,
-    4.10300016,
-    4.01399994,
-    4.16900015,
-    4.21799994,
-    4.42799997,
-    4.25699997,
-    4.15299988,
-    4.39900017,
-    4.4460001,
-    4.546,
-    4.5,
-    4.5,
-    4.68499994,
-    4.79099989,
-    4.875,
-    5.03100014,
-    5.11999989,
-    5.09499979,
-    5.23899984,
-    5.46500015,
-    5.40999985,
-    5.42999983,
-    5.40700006,
-    5.53299999,
-    5.37799978,
-    5.59200001,
-    5.87900019,
-    5.59800005,
-    5.77600002,
-    5.74599981,
-    5.73600006,
-    5.86299992,
-    5.88500023,
-    5.7329998,
-    5.81599998,
-    5.9000001,
-    5.64499998,
-    5.53800011,
-    5.65600014,
-    5.75899982,
-    5.7420001,
-    5.80299997,
-    5.71600008,
-    5.71500015,
-    5.85300016,
-    5.90999985,
-    5.79199982,
-    5.64099979,
-    5.64799976,
-    5.84299994,
-    5.93400002,
-    5.96500015,
-    6.20499992,
-    6.01100016,
-    5.546,
-    5.47300005,
-    5.40700006,
-    5.74499989,
-    6.0710001,
-    5.81599998,
-    5.92799997,
-    5.82600021,
-    5.74499989,
-    5.52199984,
-    5.60699987,
-    5.55999994,
-    5.49700022,
-    5.45100021,
-    5.50500011,
-    5.30499983,
-    5.29199982,
-    5.24700022,
-    5.20800018,
-    5.06500006,
-    4.95200014,
-    4.83500004,
-    4.80499983,
-    4.57999992,
-    4.50600004,
-    4.57800007,
-    4.58799982,
-    4.65799999,
-    4.66099977,
-    4.76499987,
-    4.75500011,
-    4.54300022,
-    4.27199984,
-    4.45800018,
-    4.30100012,
-    4.35300016,
-    4.30900002,
-    4.6329999,
-    4.51399994,
-    4.21999979,
-    4.15700006,
-    4.19899988,
-    3.97600007,
-    4.1869998,
-    3.9920001,
-    4.10300016,
-    4.23899984,
-    4.07999992,
-    4.04899979,
-    3.9230001,
-    3.71399999,
-    3.71300006,
-    3.81200004,
-    4.12300014,
-    4.13700008,
-    3.78699994,
-    3.80200005,
-    3.98600006,
-    4.08300018,
-    4.12400007,
-    4.19899988,
-    3.88899994,
-    3.977,
-    3.79900002,
-    3.77800012,
-    3.78699994,
-    4.08199978,
-    3.98000002,
-    3.852,
-    3.82800007,
-    4.06599998,
-    4.11800003,
-    4.3130002,
-    4.10200024,
-    4.14799976,
-    3.94199991,
-    3.98300004,
-    4.11499977,
-    4.12799978,
-    3.98300004,
-    4.12200022,
-    3.98799992,
-    4.03999996,
-    4.16499996,
-    4.33300018,
-    4.20900011,
-    4.11100006,
-    4.02199984,
-    4.01999998,
-    4.08199978,
-    4.26599979,
-    4.29799986,
-    4.17799997,
-    4.21299982,
-    4.19000006,
-    4.30000019,
-    4.1170001,
-    4.07700014,
-    4.10400009,
-    4.41800022,
-    4.17600012,
-    4.204,
-    4.17199993,
-    4.05000019,
-    4.01399994,
-    4.21799994,
-    4.22599983,
-    4.26599979,
-    4.421,
-    4.73000002,
-    4.72200012,
-    4.65999985,
-    4.66699982,
-    4.41099977,
-    4.34299994,
-    4.41800022,
-    4.42799997,
-    4.49900007,
-    4.62099981,
-    4.70599985,
-    4.85500002,
-    4.69999981,
-    4.83500004,
-    4.78599977,
-    4.85099983,
-    4.80999994,
-    4.71000004,
-    4.65100002,
-    4.83500004,
-    5.03000021,
-    5.05700016,
-    5.28299999,
-    5.32399988,
-    5.22900009,
-    5.03299999,
-    5.51300001,
-    5.4920001,
-    5.55000019,
-    5.56899977,
-    5.57800007,
-    5.74300003,
-    5.65199995,
-    5.86399984,
-    5.796,
-    5.64099979,
-    5.81699991,
-    5.70200014,
-    5.66800022,
-    5.43499994,
-    5.57200003,
-    5.51399994,
-    5.51499987,
-    5.71099997,
-    5.66800022,
-    5.59000015,
-    5.57399988,
-    5.85300016,
-    5.99900007,
-    5.90299988,
-    5.90700006,
-    5.83599997,
-    5.57299995,
-    5.61800003,
-    5.15999985,
-    5.43100023,
-    5.55100012,
-    5.70699978,
-    5.84200001,
-    5.49700022,
-    6.19000006,
-    5.68100023,
-    6.27299976,
-    6.34200001,
-    6.30800009,
-    5.72300005,
-    5.84299994,
-    5.62900019,
-    5.40199995,
-    5.46299982,
-    5.42399979,
-    5.95800018,
-    6.26399994,
-    6.39400005,
-    5.93499994,
-    5.59800005,
-    5.63700008,
-    5.57600021,
-    5.6869998,
-    5.75099993,
-    5.83500004,
-    5.75500011,
-    5.75500011,
-    5.75500011,
-    6.12900019,
-    5.80000019,
-    5.65500021,
-    5.46600008,
-    5.55800009,
-    5.77899981,
-    5.71199989,
-    5.73699999,
-    5.25500011,
-    5.33400011,
-    5.28200006,
-    5.25099993,
-    5.38600016,
-    5.03800011,
-    5.13800001,
-    5.09700012,
-    5.18200016,
-    4.9829998,
-    4.67999983,
-    4.61100006,
-    4.65500021,
-    4.5250001,
-    4.11800003,
-    4.37400007,
-    4.80600023,
-    4.53800011,
-    4.40600014,
-    4.329,
-    4.25099993,
-    4.21899986,
-    4.3210001,
-    4.45499992,
-    4.65199995,
-    4.76300001,
-    4.89099979,
-    4.84200001,
-    4.70900011,
-    4.54899979,
-    4.13999987,
-    4.19799995,
-    4.05499983,
-    4.19000006,
-    4.26200008,
-    4.22900009,
-    4.14400005,
-    4.07800007,
-    4.12099981,
-    4.40799999,
-    4.18499994,
-    4.31500006,
-    4.25400019,
-    4.06099987,
-    4.04699993,
-    3.8900001,
-    4.05999994,
-    4.49499989,
-    4.21700001,
-    4.35200024,
-    4.44099998,
-    4.47900009,
-    4.375,
-    4.43900013,
-    4.34600019,
-    4.46799994,
-    4.22599983,
-    4.11100006,
-    4.24599981,
-    4.19899988,
-    4.1079998,
-    4.17600012,
-    4.03700018,
-    4.17600012,
-    4.11399984,
-    4.06799984,
-    4.11999989,
-    3.97399998,
-    4.12099981,
-    4.53999996,
-    4.75,
-    4.37200022,
-    4.20200014,
-    4.2670002,
-    4.25899982,
-    4.49300003,
-    3.81699991,
-    4.11000013,
-    4.28100014,
-    4.51999998,
-    4.79099989,
-    4.98699999,
-    5.23799992,
-    5.14300013,
-    5.23400021,
-    5.47900009,
-    5.22300005,
-    5.13700008,
-    5.06500006,
-    5.08900023,
-    5.1789999,
-    5.11899996,
-    5.68499994,
-    5.73400021,
-    5.59200001,
-    6.03800011,
-    5.62300014,
-    5.43300009,
-    5.45100021,
-    5.88899994,
-    5.83099985,
-    5.66800022,
-    5.7579999,
-    6.05900002,
-    5.78299999,
-    6.29500008,
-    6.74900007,
-    6.36399984,
-    6.3210001,
-    6.0250001,
-    5.55600023,
-    5.17799997,
-    5.11899996,
-    6.05700016,
-    6.6500001,
-    6.56699991,
-    6.43400002,
-    6.75299978,
-    6.78399992,
-    7.04699993,
-    6.82600021,
-    6.65799999,
-    6.5079999,
-    6.57999992,
-    6.61100006,
-    6.71999979,
-    6.82999992,
-    6.27299976,
-    6.6880002,
-    6.79500008,
-    6.79899979,
-    6.42600012,
-    6.37300014,
-    6.62599993,
-    6.52600002,
-    6.55800009,
-    6.70699978,
-    6.57399988,
-    6.59499979,
-    6.66099977,
-    6.66099977,
-    6.84299994,
-    6.84100008,
-    6.8499999,
-    6.78000021,
-    6.9460001,
-    6.92700005,
-    6.97100019,
-    6.86600018,
-    7.11800003,
-    6.94199991,
-    7.10699987,
-    6.98999977,
-    6.92299986,
-    7.0539999,
-    6.93499994,
-    6.88899994,
-    7.35300016,
-    7.16800022,
-    7.5630002,
-    7.48799992,
-    7.68100023,
-    7.60699987,
-    7.87599993,
-    8.0170002,
-    7.89099979,
-    8.21899986,
-    8.26500034,
-    8.09200001,
-    8.10499954,
-    8.00899982,
-    8.34700012,
-    8.54199982,
-    8.88099957,
-    8.60900021,
-    8.82499981,
-    8.78899956,
-    8.62100029,
-    8.82699966,
-    8.92700005,
-    9.17700005,
-    9.03100014,
-    9.02099991,
-    8.55200005,
-    8.92700005,
-    9.39299965,
-    8.79899979,
-    9.12800026,
-    9.17099953,
-    8.88500023,
-    8.79800034,
-    8.87300014,
-    9.09500027,
-    9.40999985,
-    9.20899963,
-    8.90799999,
-    9.22799969,
-    9.20699978,
-    9.49300003,
-    9.19200039,
-    9.34500027,
-    9.0010004,
-    8.89000034,
-    8.60299969,
-    8.67199993,
-    8.55700016,
-    8.55000019,
-    8.39400005,
-    8.73799992,
-    8.86900043,
-    8.72000027,
-    8.51399994,
-    8.74100018,
-    9.05300045,
-    9.10400009,
-    9.06900024,
-    8.89099979,
-    8.92399979,
-    8.82699966,
-    8.63300037,
-    8.72299957,
-    8.84000015,
-    8.73999977,
-    8.5,
-    8.52000046,
-    8.6420002,
-    8.6619997,
-    8.55099964,
-    8.31400013,
-    8.52799988,
-    8.56999969,
-    8.46000004,
-    8.38599968,
-    8.1590004,
-    8.30900002,
-    8.35400009,
-    8.51500034,
-    8.41399956,
-    8.42199993,
-    8.24800014,
-    7.96500015,
-    8.1260004,
-    8.04599953,
-    8.11999989,
-    8.11800003,
-    8.1260004,
-    8.07900047,
-    7.98999977,
-    7.95699978,
-    7.70800018,
-    7.82999992,
-    7.86299992,
-    7.59700012,
-    7.45499992,
-    7.40399981,
-    7.12400007,
-    6.84200001,
-    6.88399982,
-    6.79199982,
-    6.65500021,
-    6.42700005,
-    6.58699989,
-    6.59800005,
-    6.48400021,
-    6.40700006,
-    6.07499981,
-    5.91200018,
-    5.8579998,
-    5.70699978,
-    5.64400005,
-    5.78200006,
-    5.51900005,
-    5.33599997,
-    5.12099981,
-    4.98000002,
-    5.26100016,
-    4.77099991,
-    4.76399994,
-    4.50400019,
-    5.03700018,
-    4.41400003,
-    4.45200014,
-    4.58400011,
-    4.47700024,
-    4.42799997,
-    4.6329999,
-    4.579,
-    4.69000006,
-    4.55000019,
-    4.60400009,
-    4.454,
-    4.046,
-    4.25699997,
-    4.28399992,
-    4.21400023,
-    4.1869998,
-    3.99900007,
-    4.01200008,
-    4.16599989,
-    4.28100014,
-    4.09700012,
-    4.04899979,
-    4.35500002,
-    4.67700005,
-    4.42700005,
-    4.83300018,
-    4.43200016,
-    4.14300013,
-    4.03999996,
-    4.30999994,
-    4.32999992,
-    3.94499993,
-    4.09499979,
-    3.977,
-    4.19000006,
-    4.1869998,
-    4.33199978,
-    4.11000013,
-    3.82399988,
-    3.67700005,
-    3.39400005,
-    3.31299996,
-    3.51900005,
-    3.54999995,
-    3.27200007,
-    3.0940001,
-    2.51399994,
-    2.07299995,
-    1.52100003,
-    0.823000014,
-    1.14100003,
-    1.39199996,
-    0.90200001,
-    0.430999994,
-    0.324999988,
-    0.483999997,
-    0.648999989,
-    0.273999989,
-    0.180999994,
-    0.280000001,
-    0.0390000008,
-    0.226999998,
-    -0.261999995,
-    -0.259000003,
-    -0.00899999961,
-    -0.00899999961,
-    0.263999999,
-    0.174999997,
-    0.0160000008,
-    0.0890000015,
-    0.0769999996,
-    -0.0460000001,
-    -0.169,
-    0.00999999978,
-    0.246999994,
-    0.277999997,
-    0.289000005,
-    0.175999999,
-    0.0599999987,
-    -0.0170000009,
-    0.229000002,
-    0.356000006,
-    0.165000007,
-    0.140000001,
-    0.0590000004,
-    -0.00400000019,
-    -0.352999985,
-    -0.286000013,
-    -0.25999999,
-    -0.340999991,
-    -0.155000001,
-    -0.119999997,
-    0.165999994,
-    0.0130000003,
-    -0.118000001,
-    -0.158999994,
-    -0.0820000023,
-    -0.00400000019,
-    -0.228,
-    -0.228,
-    -0.228,
-    0.0839999989,
-    -0.00600000005,
-    0.0130000003,
-    0.0480000004,
-    0.166999996,
-    0.305000007,
-    0.314999998,
-    0.209000006,
-    0.238999993,
-    0.338999987,
-    0.257999986,
-    0.331,
-    0.0710000023,
-    0.142000005,
-    0.0260000005,
-    -0.0759999976,
-    -0.023,
-    0.0939999968,
-    0.138999999,
-    0.120999999,
-    0.162,
-    -0.0460000001,
-    0.00800000038,
-    -0.127000004,
-    -0.186000004,
-    -0.136000007,
-    0.061999999,
-    0.108999997,
-    -0.063000001,
-    0.0590000004,
-    -0.0439999998,
-    -0.00899999961,
-    -0.0719999969,
-    -0.199000001,
-    0.0270000007,
-    -0.129999995,
-    -0.252999991,
-    -0.324999988,
-    -0.254999995,
-    -0.0799999982,
-    -0.158999994,
-    -0.127000004,
-    -0.0579999983,
-    0.0710000023,
-    0.0170000009,
-    -0.0240000002,
-    -0.0949999988,
-    -0.165999994,
-    -0.0909999982,
-    -0.134000003,
-    0.0839999989,
-    0.00499999989,
-    -0.0399999991,
-    -0.0930000022,
-    -0.050999999,
-    -0.0359999985,
-    -0.177000001,
-    -0.0170000009,
-    -0.0359999985,
-    0.0299999993,
-    0.189999998,
-    0.246999994,
-    0.0949999988,
-    0.00200000009,
-    -0.061999999,
-    -0.170000002,
-    -0.119999997,
-    0.111000001,
-    0.156000003,
-    0.180000007,
-    0.0560000017,
-    -0.0500000007,
-    -0.0160000008,
-    -0.0379999988,
-    0.112000003,
-    0.0280000009,
-    0.128999993,
-    0.174999997,
-    0.181999996,
-    0.147,
-    0.0820000023,
-    -0.0289999992,
-    -0.0130000003,
-    0.0869999975,
-    0.0860000029,
-    -0.0289999992,
-    -0.0419999994,
-    0.0130000003,
-    0.0410000011,
-    0.128999993,
-    0.196999997,
-    0.0680000037,
-    0.0549999997,
-    0.108999997,
-    -0.00400000019,
-    0.0209999997,
-    0.0469999984,
-    -0.0719999969,
-    -0.187999994,
-    -0.0350000001,
-    -0.172999993,
-    -0.109999999,
-    -0.159999996,
-    -0.141000003,
-    -0.182999998,
-    -0.248999998,
-    -0.143000007,
-    -0.075000003,
-    0.138999999,
-    0.160999998,
-    0.108000003,
-    0.177000001,
-    0.259000003,
-    0.0799999982,
-    0.00600000005,
-    0.0439999998,
-    0.064000003,
-    0.0930000022,
-    0.0939999968,
-    0.075000003,
-    -0.0270000007,
-    0.112000003,
-    0.136000007,
-    0.215000004,
-    0.119999997,
-    0.181999996,
-    0.0799999982,
-    -0.129999995,
-    -0.186000004,
-    0.0240000002,
-    0.0560000017,
-    0.112999998,
-    0.0769999996,
-    0.191,
-    0.182999998,
-    0.209000006,
-    0.111000001,
-    -0.0320000015,
-    0.165000007,
-    0.152999997,
-    -0.101000004,
-    -0.0759999976,
-    -0.363999993,
-    -0.391000003,
-    -0.273000002,
-    -0.0780000016,
-    -0.0109999999,
-    -0.160999998,
-    -0.0140000004,
-    -0.00400000019,
-    0.0460000001,
-    -0.0869999975,
-    0.193000004,
-    0.0869999975,
-    0.0170000009,
-    0.0549999997,
-    0.105999999,
-    0.194999993,
-    0.166999996,
-    -0.166999996,
-    -0.200000003,
-    -0.419,
-    -0.279000014,
-    -0.219999999,
-    0.166999996,
-    0.27700001,
-    0.185000002,
-    -0.0120000001,
-    -0.0649999976,
-    -0.150999993,
-    0.00600000005,
-    -0.142000005,
-    -0.0839999989,
-    -0.128999993,
-    -0.182999998,
-    -0.115999997,
-    -0.133000001,
-    -0.275000006,
-    -0.116999999,
-    -0.141000003,
-    -0.00100000005,
-    -0.0320000015,
-    -0.0970000029,
-    0.0820000023,
-    0.244000003,
-    0.490999997,
-    0.504999995,
-    0.312000006,
-    -0.0480000004,
-    -0.0719999969,
-    0.0480000004,
-    0.214000002,
-    0.437999994,
-    0.291000009,
-    0.226999998,
-    0.0549999997,
-    -0.158000007,
-    -0.125,
-    -0.159999996,
-    -0.231000006,
-    -0.307000011,
-    -0.312000006,
-    -0.140000001,
-    -0.0879999995,
-    0.0309999995,
-    -0.0450000018,
-    -0.0599999987,
-    0.101000004,
-    0.27700001,
-    0.254000008,
-    0.134000003,
-    0.0810000002,
-    0.0610000007,
-    0.112000003,
-    0.142000005,
-    0.100000001,
-    0.109999999,
-    -0.0710000023,
-    0.0960000008,
-    0.149000004,
-    0.250999987,
-    0.228,
-    0.389999986,
-    0.398000002,
-    0.136000007,
-    0.208000004,
-    0.0700000003,
-    -0.136999995,
-    -0.250999987,
-    -0.144999996,
-    -0.0410000011,
-    -0.0529999994,
-    0.0130000003,
-    -0.0399999991,
-    -0.0289999992,
-    -0.0949999988,
-    -0.0540000014,
-    -0.0979999974,
-    -0.196999997,
-    -0.237000003,
-    -0.202999994,
-    0.243000001,
-    0.222000003,
-    0.351000011,
-    0.240999997,
-    0.257999986,
-    0.294,
-    0.116999999,
-    -0.0979999974,
-    0.00600000005,
-    -0.00200000009,
-    -0.175999999,
-    -0.289999992,
-    -0.419999987,
-    -0.455000013,
-    -0.375,
-    -0.148000002,
-    -0.0240000002,
-    0.138999999,
-    0.0780000016,
-    -0.0219999999,
-    -0.00800000038,
-    -0.0209999997,
-    -0.150000006,
-    -0.125,
-    -0.187000006,
-    -0.138999999,
-    -0.192000002,
-    -0.219999999,
-    -0.0579999983,
-    0.00499999989,
-    -0.0390000008,
-    -0.0199999996,
-    0.0689999983,
-    0.0799999982,
-    0.181999996,
-    0.147,
-    0.324000001,
-    0.074000001,
-    0.0460000001,
-    -0.174999997,
-    -0.134000003,
-    0.170000002,
-    0.303000003,
-    0.123000003,
-    0.131999999,
-    0.0370000005,
-    0.0370000005,
-    0.0370000005,
-    -0.238999993,
-    -0.142000005,
-    -0.141000003,
-    0.0350000001,
-    0.0120000001,
-    0.00600000005,
-    0.00899999961,
-    -0.170000002,
-    -0.289999992,
-    -0.239999995,
-    -0.213,
-    -0.0590000004,
-    -0.0900000036,
-    -0.158000007,
-    -0.331,
-    -0.405999988,
-    -0.405000001,
-    -0.324000001,
-    -0.256999999,
-    -0.261999995,
-    -0.0710000023,
-    -0.0450000018,
-    -0.127000004,
-    -0.127000004,
-    -0.236000001,
-    -0.0299999993,
-    -0.101000004,
-    -0.00200000009,
-    -0.0890000015,
-    -0.0430000015,
-    -0.128999993,
-    -0.0130000003,
-    0.123000003,
-    0.103,
-    0.123000003,
-    0.237000003,
-    0.233999997,
-    0.0860000029,
-    -0.0149999997,
-    -0.0419999994,
-    -0.0780000016,
-    -0.0920000002,
-    0.108999997,
-    0.172999993,
-    0.130999997,
-    0.0289999992,
-    -0.108999997,
-    -0.0820000023,
-    0.0860000029,
-    0.0729999989,
-    -0.259000003,
-    -0.462000012,
-    -0.319000006,
-    -0.372000009,
-    -0.442000002,
-    -0.317000002,
-    -0.0839999989,
-    0.144999996,
-    0.197999999,
-    0.118000001,
-    0.179000005,
-    0.0170000009,
-    -0.101999998,
-    0.108999997,
-    -0.0829999968,
-    -0.0829999968,
-    -0.0829999968,
-    -0.155000001,
-    -0.0719999969,
-    0.00600000005,
-    0.0289999992,
-    -0.023,
-    0.172999993,
-    0.105999999,
-    0.140000001,
-    0.00700000022,
-    0.0379999988,
-    -0.0820000023,
-    -0.150000006,
-    -0.232999995,
-    -0.151999995,
-    -0.126000002,
-    -0.0579999983,
-    0.0410000011,
-    0.0890000015,
-    -0.00700000022,
-    0.0370000005,
-    0.0520000011,
-    0.0379999988,
-    0.0280000009,
-    0.185000002,
-    -0.0869999975,
-    -0.0359999985,
-    0.0149999997,
-    0.0460000001,
-    0.125,
-    0.108000003,
-    0.0359999985,
-    0.0250000004,
-    -0.00600000005,
-    0.0379999988,
-    0.0460000001,
-    -0.064000003,
-    0.0869999975,
-    0.00800000038,
-    0.118000001,
-    0.00600000005,
-    0.0340000018,
-    0.0820000023,
-    0.0359999985,
-    0.0560000017,
-    0.101999998,
-    0.216999993,
-    0.352999985,
-    -0.108999997,
-    -0.178000003,
-    -0.128999993,
-    0.0219999999,
-    -0.0149999997,
-    0.131999999,
-    0.214000002,
-    0.25,
-    0.298999995,
-    0.264999986,
-    0.317000002,
-    0.241999999,
-    0.26699999,
-    -0.057,
-    -0.165999994,
-    0.0130000003,
-    0.185000002,
-    -0.0270000007,
-    0.0689999983,
-    0.206,
-    0.0540000014,
-    -0.00499999989,
-    0.0829999968,
-    0.0140000004,
-    -0.109999999,
-    -0.057,
-    0.115000002,
-    0.0909999982,
-    0.270999998,
-    0.314999998,
-    0.166999996,
-    -0.0209999997,
-    -0.133000001,
-    0.0680000037,
-    0.148000002,
-    0.130999997,
-    -0.0560000017,
-    -0.342000008,
-    -0.248999998,
-    -0.165999994,
-    -0.149000004,
-    -0.310000002,
-    0.101000004,
-    0.104999997,
-    -0.164000005,
-    -0.224000007,
-    -0.268000007,
-    -0.356999993,
-    -0.291000009,
-    -0.257999986,
-    -0.0579999983,
-    0.057,
-    -0.0430000015,
-    0.00800000038,
-    -0.0689999983,
-    -0.194999993,
-    0.0130000003,
-    -0.0890000015,
-    -0.130999997,
-    -0.129999995,
-    -0.103,
-    -0.382999986,
-    -0.316000015,
-    -0.125,
-    0.0350000001,
-    -0.112999998,
-    -0.0930000022,
-    -0.0480000004,
-    -0.131999999,
-    -0.00899999961,
-    0.175999999,
-    0.123000003,
-    0.189999998,
-    -0.128999993,
-    -0.143000007,
-    0.0659999996,
-    0.0930000022,
-    0.112999998,
-    -0.050999999,
-    -0.263999999,
-    -0.136000007,
-    -0.0140000004,
-    0.0790000036,
-    0.202000007,
-    -0.0529999994,
-    0.0460000001,
-    0.063000001,
-    0.0590000004,
-    -0.0329999998,
-    0.0250000004,
-    0.0170000009,
-    0.0109999999,
-    -0.0909999982,
-    -0.159999996,
-    0.0340000018,
-    0.119999997,
-    0.140000001,
-    0.0329999998,
-    0.263000011,
-    0.107000001,
-    -0.0350000001,
-    -0.061999999,
-    0.172000006,
-    -0.0460000001,
-    0.296000004,
-    0.105999999,
-    -0.201000005,
-    -0.0289999992,
-    0.136000007,
-    -0.00400000019,
-    -0.057,
-    -0.0989999995,
-    -0.0140000004,
-    -0.123000003,
-    0.0979999974,
-    -0.194999993,
-    -0.245000005,
-    -0.483999997,
-    0.0879999995,
-    0.167999998,
-    0.130999997,
-    -0.202999994,
-    -0.0549999997,
-    -0.0780000016,
-    -0.0909999982,
-    -0.109999999,
-    -0.109999999,
-    -0.298999995,
-    -0.228,
-    -0.202000007,
-    -0.0329999998,
-    0.061999999,
-    0.0790000036,
-    0.00400000019,
-    0.141000003,
-    0.115000002,
-    -0.0219999999,
-    -0.395000011,
-    0.0989999995,
-    -0.105999999,
-    0.0649999976,
-    -0.122000001,
-    -0.063000001,
-    -0.0120000001,
-    0.0189999994,
-    0.0270000007,
-    -0.0879999995,
-    -0.191,
-    -0.158000007,
-    -0.120999999,
-    -0.0689999983,
-    -0.162,
-    -0.296000004,
-    -0.0979999974,
-};
-
-const float GPS_DATA_VDOWN[3230] = {
-    0.887000024,
-    0.926999986,
-    0.451999992,
-    0.173999995,
-    -0.0500000007,
-    -0.356000006,
-    -0.523000002,
-    -2.94899988,
-    -4.19099998,
-    -8.46800041,
-    -11.2600002,
-    -12.1190004,
-    -13.8149996,
-    -14.1789999,
-    -15.29,
-    -17.2830009,
-    -22.0170002,
-    -23.5720005,
-    -24.8190002,
-    -26.6420002,
-    -27.3470001,
-    -29.0820007,
-    -29.2049999,
-    -32.2130013,
-    -35.1910019,
-    -34.2019997,
-    -36.7260017,
-    -39.473999,
-    -34.9869995,
-    -40.5239983,
-    -47.9729996,
-    -49.7010002,
-    -50.9900017,
-    -53.5519981,
-    -49.4539986,
-    -49.4539986,
-    -49.4539986,
-    -52.6020012,
-    -49.3289986,
-    -58.7989998,
-    -53.5859985,
-    -58.7360001,
-    -58.7010002,
-    -60.6669998,
-    -72.1989975,
-    -75.3610001,
-    -74.1819992,
-    -79.6240005,
-    -79.7610016,
-    -77.6809998,
-    -81.151001,
-    -85.6190033,
-    -86.1910019,
-    -90.5179977,
-    -86.1780014,
-    -85.4860001,
-    -94.8349991,
-    -94.5059967,
-    -95.4140015,
-    -105.388,
-    -104.223999,
-    -104.851997,
-    -102.608002,
-    -100.344002,
-    -98.2070007,
-    -96.0039978,
-    -97.6480026,
-    -92.4150009,
-    -87.9179993,
-    -83.2040024,
-    -83.6259995,
-    -78.6070023,
-    -71.3130035,
-    -66.7009964,
-    -62.1199989,
-    -56.5229988,
-    -52.0639992,
-    -50.0309982,
-    -47.9589996,
-    -51.6619987,
-    -54.9090004,
-    -58.2169991,
-    -61.1240005,
-    -65.0950012,
-    -69.336998,
-    -73.5660019,
-    -76.9000015,
-    -80.2580032,
-    -83.0400009,
-    -85.9609985,
-    -92.6529999,
-    -95.8430023,
-    -100.533997,
-    -103.805,
-    -104.806999,
-    -111.615997,
-    -112.871002,
-    -113.622002,
-    -114.472,
-    -114.945999,
-    -115.884003,
-    -117.073997,
-    -122.567001,
-    -127.203003,
-    -131.337006,
-    -139.498993,
-    -145.725998,
-    -149.934998,
-    -153.384003,
-    -155.048004,
-    -156.699005,
-    -157.007004,
-    -157.404007,
-    -154.720993,
-    -156.815994,
-    -157.481995,
-    -157.863998,
-    -158.151001,
-    -158.153,
-    -157.686005,
-    -156.987,
-    -156.065994,
-    -155.492996,
-    -154.919998,
-    -154.125,
-    -153.177002,
-    -152.350006,
-    -151.606995,
-    -151.110001,
-    -150.149002,
-    -149.186005,
-    -147.979004,
-    -146.792999,
-    -145.949005,
-    -145.177002,
-    -144.274002,
-    -143.488998,
-    -142.580002,
-    -141.977997,
-    -141.358002,
-    -140.546005,
-    -140.945999,
-    -140.585999,
-    -140,
-    -139.416,
-    -139.363007,
-    -139.013,
-    -137.914001,
-    -137.632996,
-    -135.457001,
-    -133.399994,
-    -132.313995,
-    -131.365997,
-    -130.927002,
-    -130.307007,
-    -129.817001,
-    -128.841003,
-    -127.945,
-    -127.211998,
-    -126.176003,
-    -125.475998,
-    -124.287003,
-    -123.955002,
-    -124.319,
-    -123.207001,
-    -122.612999,
-    -121.155998,
-    -120.389,
-    -119.831001,
-    -118.950996,
-    -118.517998,
-    -117.668999,
-    -117.278,
-    -117.142998,
-    -116.588997,
-    -116.130997,
-    -114.972,
-    -114.300003,
-    -114.135002,
-    -113.837997,
-    -113.296997,
-    -112.650002,
-    -111.845001,
-    -111.556,
-    -110.568001,
-    -109.933998,
-    -109.514,
-    -109.097,
-    -108.413002,
-    -108.147003,
-    -107.002998,
-    -106.335999,
-    -105.963997,
-    -105.567001,
-    -104.919998,
-    -104.334999,
-    -103.620003,
-    -103.179001,
-    -102.696999,
-    -102.211998,
-    -102.141998,
-    -102.005997,
-    -101.365997,
-    -100.674004,
-    -100.129997,
-    -99.6910019,
-    -99.3190002,
-    -99.0350037,
-    -98.1169968,
-    -97.3769989,
-    -97.2389984,
-    -96.6220016,
-    -96.0830002,
-    -95.0579987,
-    -94.9540024,
-    -94.5339966,
-    -94.5,
-    -93.4369965,
-    -93.0650024,
-    -92.9779968,
-    -92.4329987,
-    -91.5630035,
-    -91.1669998,
-    -90.75,
-    -90.0289993,
-    -89.5049973,
-    -89.2580032,
-    -88.7689972,
-    -87.6419983,
-    -87.2330017,
-    -86.7949982,
-    -86.4680023,
-    -86.2570038,
-    -85.9100037,
-    -84.9850006,
-    -84.2099991,
-    -83.6119995,
-    -83.3209991,
-    -82.9639969,
-    -82.6380005,
-    -81.8389969,
-    -81.2860031,
-    -80.9960022,
-    -80.0690002,
-    -80.0930023,
-    -79.6449966,
-    -79.3410034,
-    -78.6159973,
-    -77.7770004,
-    -77.5910034,
-    -77.2310028,
-    -76.8840027,
-    -76.5500031,
-    -76.1090012,
-    -75.8470001,
-    -75.4639969,
-    -74.8700027,
-    -74.689003,
-    -74.1480026,
-    -73.6139984,
-    -73.2269974,
-    -72.7990036,
-    -72.3470001,
-    -72.0149994,
-    -71.413002,
-    -71.2399979,
-    -70.7310028,
-    -70.3720016,
-    -69.9140015,
-    -69.0419998,
-    -68.8310013,
-    -68.4909973,
-    -68.2809982,
-    -67.9850006,
-    -67.2929993,
-    -66.8089981,
-    -66.3700027,
-    -65.7850037,
-    -65.3980026,
-    -65.0699997,
-    -64.8909988,
-    -64.262001,
-    -63.8370018,
-    -63.137001,
-    -62.7280006,
-    -62.5009995,
-    -62.2089996,
-    -61.5250015,
-    -60.9309998,
-    -60.5550003,
-    -60.0900002,
-    -60.0439987,
-    -59.6080017,
-    -59.3330002,
-    -58.7989998,
-    -58.1189995,
-    -57.8149986,
-    -57.7550011,
-    -57.4000015,
-    -56.8209991,
-    -56.1450005,
-    -55.7220001,
-    -55.2680016,
-    -54.7029991,
-    -54.5250015,
-    -54.0480003,
-    -53.9860001,
-    -53.6749992,
-    -53.2029991,
-    -52.5449982,
-    -52.0999985,
-    -51.7560005,
-    -51.4840012,
-    -51.0229988,
-    -50.2639999,
-    -50.2470016,
-    -50.1699982,
-    -49.637001,
-    -49.3219986,
-    -48.5629997,
-    -48.0970001,
-    -47.4760017,
-    -47.3409996,
-    -47.0169983,
-    -46.7560005,
-    -46.2890015,
-    -45.8889999,
-    -45.5330009,
-    -45.1300011,
-    -44.7029991,
-    -44.0229988,
-    -43.5760002,
-    -43.1259995,
-    -42.9090004,
-    -42.6689987,
-    -42.0079994,
-    -41.7739983,
-    -41.2900009,
-    -40.9280014,
-    -40.5670013,
-    -40.243,
-    -39.7089996,
-    -39.2319984,
-    -38.8400002,
-    -38.5159988,
-    -38.019001,
-    -37.6529999,
-    -37.1819992,
-    -36.9389992,
-    -36.5810013,
-    -36.0620003,
-    -35.5519981,
-    -35.2519989,
-    -34.8390007,
-    -34.5169983,
-    -34.230999,
-    -33.7630005,
-    -33.3230019,
-    -32.9840012,
-    -32.4990005,
-    -32.1879997,
-    -31.8099995,
-    -31.4909992,
-    -31.0170002,
-    -30.6700001,
-    -30.3969994,
-    -29.9869995,
-    -29.4680004,
-    -29.1749992,
-    -28.6650009,
-    -28.3799992,
-    -27.9209995,
-    -27.5909996,
-    -27.2649994,
-    -26.684,
-    -26.1940002,
-    -25.941,
-    -25.5909996,
-    -24.9290009,
-    -24.3859997,
-    -24.0569992,
-    -23.8059998,
-    -23.5009995,
-    -22.9080009,
-    -22.6170006,
-    -22.2299995,
-    -21.8770008,
-    -21.1779995,
-    -20.8519993,
-    -20.4510002,
-    -20.2590008,
-    -19.7390003,
-    -19.4430008,
-    -19.2409992,
-    -18.5939999,
-    -18.2280006,
-    -17.8180008,
-    -17.6660004,
-    -17.1429996,
-    -16.7119999,
-    -16.0990009,
-    -15.7229996,
-    -15.4209995,
-    -15.0299997,
-    -14.7469997,
-    -14.2869997,
-    -14.0340004,
-    -13.6049995,
-    -13.2740002,
-    -12.8780003,
-    -12.408,
-    -12.1330004,
-    -11.4799995,
-    -11.1339998,
-    -10.9119997,
-    -10.5340004,
-    -10.2849998,
-    -9.82199955,
-    -9.50500011,
-    -9.06499958,
-    -8.55000019,
-    -8.1239996,
-    -7.78200006,
-    -7.51499987,
-    -7.23500013,
-    -6.72399998,
-    -6.3670001,
-    -6.15500021,
-    -5.78000021,
-    -5.32000017,
-    -4.89799976,
-    -4.54699993,
-    -3.92000008,
-    -3.79299998,
-    -3.3440001,
-    -3.06200004,
-    -2.75200009,
-    -2.46199989,
-    -1.949,
-    -1.42799997,
-    -1.08299994,
-    -0.709999979,
-    -0.421000004,
-    -0.064000003,
-    0.289000005,
-    0.603999972,
-    0.954999983,
-    1.30799997,
-    1.79499996,
-    2.31200004,
-    2.50500011,
-    3.03600001,
-    3.30100012,
-    3.64400005,
-    3.79699993,
-    3.84200001,
-    3.58299994,
-    3.40199995,
-    3.4000001,
-    3.796,
-    4.59899998,
-    4.95300007,
-    5.67399979,
-    6.34800005,
-    7.34000015,
-    7.58900023,
-    8.07900047,
-    8.37800026,
-    8.89599991,
-    9.17399979,
-    8.98099995,
-    9.0010004,
-    9.14299965,
-    9.33500004,
-    9.25699997,
-    9.24499989,
-    9.47399998,
-    9.86699963,
-    10.2519999,
-    10.7449999,
-    11.2200003,
-    11.776,
-    11.7580004,
-    12.5509996,
-    13.0699997,
-    12.8929996,
-    13.184,
-    14.0889997,
-    14.283,
-    14.3319998,
-    13.9209995,
-    13.974,
-    13.1750002,
-    13.5860004,
-    13.3690004,
-    13.5310001,
-    14.0869999,
-    14.1590004,
-    14.125,
-    14.2229996,
-    14.1789999,
-    14.316,
-    14.3079996,
-    14.6000004,
-    14.948,
-    15.757,
-    16.2709999,
-    17.2369995,
-    18.2740002,
-    18.0119991,
-    17.1870003,
-    17.1060009,
-    16.9650002,
-    17.1399994,
-    17.2880001,
-    17.4120007,
-    17.7530003,
-    17.9309998,
-    18.1550007,
-    18.3390007,
-    18.5610008,
-    18.684,
-    18.743,
-    18.8560009,
-    19.3689995,
-    19.8829994,
-    20.0760002,
-    19.8220005,
-    19.7099991,
-    19.7140007,
-    19.5550003,
-    19.7460003,
-    19.8199997,
-    19.9449997,
-    20.0100002,
-    20.0849991,
-    20.1849995,
-    20.2240009,
-    20.5620003,
-    20.698,
-    20.5450001,
-    20.6760006,
-    20.6989994,
-    20.8479996,
-    21.2859993,
-    21.1800003,
-    21.0459995,
-    21.0869999,
-    21.3029995,
-    21.559,
-    21.8180008,
-    22.2530003,
-    22.2630005,
-    22.1429996,
-    22.4139996,
-    22.5750008,
-    22.7660007,
-    22.8279991,
-    22.8419991,
-    22.7439995,
-    22.8360004,
-    22.9839993,
-    22.9139996,
-    22.9449997,
-    22.9160004,
-    23.0830002,
-    23.1830006,
-    23.2830009,
-    23.5790005,
-    23.4580002,
-    23.2450008,
-    23.4829998,
-    23.5009995,
-    23.2159996,
-    23.6229992,
-    23.6620007,
-    24.0289993,
-    24.1639996,
-    24.1110001,
-    24.3649998,
-    24.2880001,
-    24.1509991,
-    24.3530006,
-    24.5620003,
-    24.7830009,
-    24.7670002,
-    24.9470005,
-    24.7220001,
-    24.6240005,
-    24.6289997,
-    24.5569992,
-    24.6410007,
-    24.4740009,
-    24.2290001,
-    24.1870003,
-    24.1599998,
-    24.2910004,
-    24.3339996,
-    24.2530003,
-    24.2980003,
-    24.1019993,
-    24.0410004,
-    24.1079998,
-    24.3619995,
-    24.1219997,
-    24.0739994,
-    24.1210003,
-    24.0090008,
-    23.9209995,
-    23.8589993,
-    23.8279991,
-    23.7889996,
-    24.4689999,
-    24.2159996,
-    24.132,
-    24.1660004,
-    23.8990002,
-    23.6989994,
-    23.8689995,
-    23.8029995,
-    24.0009995,
-    24.3250008,
-    24.2830009,
-    24.4669991,
-    24.5809994,
-    24.6389999,
-    24.5879993,
-    24.3199997,
-    24.3369999,
-    24.7759991,
-    24.8110008,
-    24.7590008,
-    25.2099991,
-    25.4309998,
-    25.1919994,
-    25.2080002,
-    25.2040005,
-    24.9459991,
-    24.4799995,
-    25.1189995,
-    25.0370007,
-    24.7759991,
-    25.0240002,
-    24.882,
-    24.8950005,
-    25.1959991,
-    25.2870007,
-    25.552,
-    25.7049999,
-    25.4309998,
-    25.5389996,
-    25.6040001,
-    25.5750008,
-    25.375,
-    25.3589993,
-    25.1870003,
-    24.6989994,
-    25.2810001,
-    25.4400005,
-    25.5259991,
-    25.5510006,
-    25.5330009,
-    25.9540005,
-    26.2630005,
-    26.1800003,
-    26.5160007,
-    26.5680008,
-    26.6399994,
-    26.4519997,
-    26.4220009,
-    26.4139996,
-    26.3069992,
-    26.1889992,
-    26.3080006,
-    25.9950008,
-    26.2029991,
-    26.0109997,
-    25.8740005,
-    25.6749992,
-    25.7789993,
-    25.9829998,
-    25.9629993,
-    25.9860001,
-    25.9570007,
-    25.6329994,
-    25.7590008,
-    25.3169994,
-    25.4319992,
-    25.5790005,
-    25.5259991,
-    25.2970009,
-    25.5060005,
-    25.6100006,
-    25.6849995,
-    25.7029991,
-    25.927,
-    26.0890007,
-    25.743,
-    25.6119995,
-    25.5620003,
-    25.4519997,
-    25.6499996,
-    25.6089993,
-    25.8260002,
-    25.6380005,
-    25.4370003,
-    25.8080006,
-    25.9640007,
-    26.1049995,
-    26.1019993,
-    26.0860004,
-    26.0830002,
-    25.9769993,
-    26.132,
-    26.0240002,
-    25.8579998,
-    26.0300007,
-    26.0760002,
-    26.0370007,
-    25.9769993,
-    25.757,
-    25.6070004,
-    25.6289997,
-    25.8850002,
-    25.9669991,
-    26.2299995,
-    26.3290005,
-    26.5240002,
-    26.5860004,
-    26.6760006,
-    26.8700008,
-    26.8040009,
-    26.9850006,
-    26.8810005,
-    26.8859997,
-    27.0179996,
-    26.6599998,
-    26.8479996,
-    27.0890007,
-    27.1669998,
-    27.2019997,
-    26.927,
-    26.552,
-    26.2029991,
-    26.0739994,
-    26.0580006,
-    25.9890003,
-    25.8470001,
-    26.0230007,
-    26.4640007,
-    26.8880005,
-    27.7910004,
-    28.1340008,
-    27.6380005,
-    27.4689999,
-    26.9370003,
-    26.8519993,
-    26.8220005,
-    26.7789993,
-    26.7019997,
-    26.5489998,
-    26.5319996,
-    26.5779991,
-    26.6049995,
-    26.6529999,
-    26.8509998,
-    26.8029995,
-    26.7980003,
-    26.8649998,
-    26.7999992,
-    27.0139999,
-    27.4549999,
-    27.2469997,
-    26.7439995,
-    26.9309998,
-    27.4400005,
-    27.1100006,
-    27.2040005,
-    27.1369991,
-    27.6240005,
-    27.6959991,
-    27.6860008,
-    27.6730003,
-    27.6079998,
-    27.7539997,
-    27.6739998,
-    27.3110008,
-    27.0739994,
-    26.8780003,
-    26.5620003,
-    26.6520004,
-    26.5869999,
-    26.8579998,
-    26.9020004,
-    27.1580009,
-    27.1270008,
-    27.2719994,
-    27.2240009,
-    27.1030006,
-    26.8309994,
-    26.6000004,
-    26.7889996,
-    27.1900005,
-    27.4960003,
-    27.9209995,
-    28.0100002,
-    28.4130001,
-    27.7380009,
-    27.3490009,
-    27.7000008,
-    27.4750004,
-    27.4260006,
-    27.2870007,
-    27.4249992,
-    27.6299992,
-    27.5599995,
-    27.4080009,
-    27.6539993,
-    27.5200005,
-    27.6860008,
-    27.5049992,
-    27.4820004,
-    27.5860004,
-    27.2999992,
-    27.3589993,
-    27.4290009,
-    27.5610008,
-    27.7900009,
-    28.0599995,
-    28.3829994,
-    28.4890003,
-    28.3829994,
-    28.0090008,
-    27.6849995,
-    27.1560001,
-    27.1070004,
-    27.0020008,
-    27.1259995,
-    27.0400009,
-    26.9540005,
-    26.75,
-    26.8910007,
-    26.8470001,
-    26.9829998,
-    27.2250004,
-    27.0720005,
-    27.1210003,
-    27.3139992,
-    27.5650005,
-    27.5919991,
-    27.3059998,
-    27.427,
-    27.6079998,
-    27.5349998,
-    27.1060009,
-    26.6210003,
-    26.5079994,
-    26.6900005,
-    26.6359997,
-    26.75,
-    26.7889996,
-    26.5790005,
-    26.4759998,
-    26.3640003,
-    25.7159996,
-    25.7770004,
-    25.7290001,
-    25.9769993,
-    26.8239994,
-    27.7590008,
-    27.9529991,
-    27.8129997,
-    27.3549995,
-    26.9650002,
-    26.7049999,
-    26.7010002,
-    26.7350006,
-    26.4230003,
-    26.2549992,
-    26.3279991,
-    26.2959995,
-    26.4549999,
-    26.375,
-    26.4060001,
-    26.6580009,
-    26.2080002,
-    26.4920006,
-    26.1159992,
-    25.9669991,
-    25.8610001,
-    25.7549992,
-    26.0900002,
-    25.9909992,
-    26.1270008,
-    26.4220009,
-    26.6420002,
-    26.5639992,
-    26.5690002,
-    26.5569992,
-    26.2490005,
-    26.2700005,
-    26.1189995,
-    25.7229996,
-    25.9829998,
-    26.0349998,
-    25.927,
-    25.9470005,
-    25.8080006,
-    25.6420002,
-    25.7070007,
-    25.6580009,
-    25.9300003,
-    25.8040009,
-    26.0149994,
-    26.3199997,
-    26.1289997,
-    26.3010006,
-    26.323,
-    26.6030006,
-    26.8759995,
-    26.6490002,
-    26.1959991,
-    25.4880009,
-    25.7689991,
-    25.9990005,
-    26.2360001,
-    26.7789993,
-    26.7789993,
-    26.3360004,
-    25.9829998,
-    25.9640007,
-    26.1200008,
-    26.6389999,
-    26.9629993,
-    26.6529999,
-    26.3780003,
-    26.4309998,
-    27.2840004,
-    27.6140003,
-    27.1639996,
-    26.684,
-    26.6860008,
-    26.1709995,
-    26.1000004,
-    26.1240005,
-    26.052,
-    25.8929996,
-    25.5809994,
-    25.7980003,
-    25.3239994,
-    25.3579998,
-    25.2919998,
-    25.0330009,
-    24.9319992,
-    24.7169991,
-    24.4699993,
-    24.5680008,
-    24.6019993,
-    25.2360001,
-    25.4909992,
-    26.0270004,
-    26.3549995,
-    26.4869995,
-    26.6830006,
-    27.2129993,
-    27.3829994,
-    27.6480007,
-    27.2169991,
-    26.8889999,
-    26.5900002,
-    26.4120007,
-    26.6009998,
-    26.7770004,
-    26.6860008,
-    27.1849995,
-    27.191,
-    26.8470001,
-    26.6480007,
-    26.2290001,
-    26.2660007,
-    26.1459999,
-    26.4790001,
-    26.7840004,
-    26.4810009,
-    26.3850002,
-    26.4589996,
-    26.2269993,
-    26.6200008,
-    26.5279999,
-    26.4069996,
-    26.4150009,
-    26.8490009,
-    26.9570007,
-    26.0470009,
-    26.3780003,
-    26.6000004,
-    26.441,
-    26.2059994,
-    26.5249996,
-    26.3400002,
-    26.4619999,
-    26.6350002,
-    26.6130009,
-    27.0139999,
-    27.0020008,
-    27.4939995,
-    27.7709999,
-    27.5209999,
-    26.7950001,
-    26.2479992,
-    25.7059994,
-    25.5079994,
-    25.8099995,
-    26.0709991,
-    25.9769993,
-    26.3320007,
-    26.3950005,
-    26.0100002,
-    26.0970001,
-    26.4080009,
-    26.5939999,
-    26.6210003,
-    26.6889992,
-    26.2080002,
-    26.2000008,
-    26.0470009,
-    25.2870007,
-    24.6879997,
-    24.4559994,
-    24.8439999,
-    24.9489994,
-    25.0219994,
-    24.9979992,
-    25.3670006,
-    25.4009991,
-    25.7590008,
-    26.0139999,
-    26.0419998,
-    25.948,
-    25.7110004,
-    25.5130005,
-    25.0149994,
-    25.0209999,
-    25.2350006,
-    25.4570007,
-    25.2339993,
-    25.007,
-    25.2770004,
-    25.2660007,
-    25.3269997,
-    25.3269997,
-    25.3269997,
-    26.0489998,
-    25.9060001,
-    25.8910007,
-    26.0330009,
-    25.9419994,
-    25.5139999,
-    25.6070004,
-    25.382,
-    25.6060009,
-    25.3920002,
-    25.5189991,
-    25.7019997,
-    25.5289993,
-    25.3180008,
-    25.4109993,
-    25.7619991,
-    26.3869991,
-    26.118,
-    25.8139992,
-    25.6550007,
-    25.4650002,
-    25.5079994,
-    25.5319996,
-    25.9230003,
-    25.8670006,
-    25.7740002,
-    26.4179993,
-    26.6940002,
-    26.9060001,
-    26.7089996,
-    26.1569996,
-    25.8299999,
-    25.2029991,
-    24.8059998,
-    24.7119999,
-    25.3549995,
-    25.3549995,
-    25.3549995,
-    25.3570004,
-    25.566,
-    25.8789997,
-    25.9960003,
-    25.9750004,
-    25.7880001,
-    25.6219997,
-    25.4650002,
-    25.5330009,
-    25.8770008,
-    25.9799995,
-    26.1119995,
-    25.7919998,
-    25.2129993,
-    25.25,
-    25.2310009,
-    25.3290005,
-    25.7460003,
-    25.6019993,
-    25.7679996,
-    26.0580006,
-    25.7759991,
-    25.8029995,
-    25.8180008,
-    26.0429993,
-    26.3589993,
-    26.1049995,
-    26.2670002,
-    26.2940006,
-    26.2369995,
-    26.1079998,
-    25.9890003,
-    26.1280003,
-    26.184,
-    26.2810001,
-    26.2849998,
-    26.5170002,
-    26.5540009,
-    26.5540009,
-    26.6870003,
-    26.7980003,
-    26.7310009,
-    26.6329994,
-    26.9169998,
-    27.1149998,
-    27.0769997,
-    27.1720009,
-    27.4069996,
-    27.2460003,
-    26.5830002,
-    26.6079998,
-    26.9640007,
-    27.2140007,
-    26.7169991,
-    26.1590004,
-    25.5720005,
-    25.6340008,
-    25.8540001,
-    25.9880009,
-    26.1900005,
-    26.3850002,
-    26.6130009,
-    26.5119991,
-    26.2019997,
-    26.5079994,
-    26.6749992,
-    26.8999996,
-    26.8190002,
-    26.8869991,
-    27.1949997,
-    27.4839993,
-    27.3500004,
-    27.2910004,
-    27.1550007,
-    27.0890007,
-    26.8250008,
-    26.8430004,
-    27.3419991,
-    27.4020004,
-    28.0079994,
-    27.1970005,
-    26.8869991,
-    26.4400005,
-    26.2950001,
-    26.5839996,
-    26.4580002,
-    26.4080009,
-    26.4729996,
-    26.5690002,
-    26.3029995,
-    26.2320004,
-    26.2460003,
-    26.0079994,
-    26.4589996,
-    26.1639996,
-    26.4659996,
-    26.4510002,
-    26.5030003,
-    26.1399994,
-    26.2299995,
-    25.9249992,
-    26.3150005,
-    26.3579998,
-    26.8050003,
-    26.2649994,
-    26.2329998,
-    26.6350002,
-    27.1159992,
-    27.3080006,
-    27.0919991,
-    27.0389996,
-    26.9160004,
-    27.1450005,
-    26.6240005,
-    26.7089996,
-    27.0629997,
-    27.0209999,
-    27.3990002,
-    27.5760002,
-    27.3439999,
-    26.6760006,
-    26.8500004,
-    27.1709995,
-    27.8430004,
-    27.8689995,
-    27.2159996,
-    27.1889992,
-    27.2290001,
-    27.1849995,
-    27.7159996,
-    27.7859993,
-    27.6200008,
-    28.0739994,
-    28.3889999,
-    28.3069992,
-    27.6800003,
-    27.6660004,
-    27.2639999,
-    27.1609993,
-    27.2959995,
-    27.3260002,
-    27.2989998,
-    27.2390003,
-    27.0179996,
-    27.2609997,
-    27.4869995,
-    27.6970005,
-    27.6970005,
-    27.6529999,
-    28.1420002,
-    28.2189999,
-    28.2590008,
-    28.1739998,
-    27.9220009,
-    27.5480003,
-    27.5300007,
-    27.4009991,
-    27.3369999,
-    27.2970009,
-    27.2080002,
-    27.2390003,
-    27.0109997,
-    27.0109997,
-    27.0109997,
-    26.7119999,
-    26.2189999,
-    26.0720005,
-    26.0869999,
-    26.0300007,
-    26.1580009,
-    26.5489998,
-    26.9330006,
-    27.1170006,
-    27.3850002,
-    27.4780006,
-    27.7019997,
-    27.3689995,
-    27.0709991,
-    26.7779999,
-    26.9090004,
-    26.8649998,
-    26.6439991,
-    26.6550007,
-    26.3050003,
-    26.7630005,
-    27.2679996,
-    27.7339993,
-    27.6760006,
-    27.2290001,
-    27.4829998,
-    27.9379997,
-    28.3840008,
-    27.7010002,
-    27.4570007,
-    27.5209999,
-    27.5380001,
-    27.2220001,
-    27.441,
-    27.4220009,
-    27.0599995,
-    26.8330002,
-    27.2250004,
-    26.7469997,
-    26.8990002,
-    27.1089993,
-    27.4860001,
-    27.5860004,
-    27.6019993,
-    27.4640007,
-    27.2810001,
-    27.3540001,
-    27.6590004,
-    27.5049992,
-    27.5249996,
-    27.3770008,
-    27.8859997,
-    28.0279999,
-    27.7229996,
-    28.0139999,
-    27.2369995,
-    27.2639999,
-    26.9470005,
-    26.6830006,
-    27.0799999,
-    26.6060009,
-    26.2040005,
-    26.2169991,
-    25.9759998,
-    25.2649994,
-    25.3880005,
-    25.8470001,
-    25.25,
-    25.5270004,
-    25.757,
-    26.2770004,
-    26.6749992,
-    27.0930004,
-    27.0119991,
-    27.0370007,
-    26.8320007,
-    26.6650009,
-    26.3260002,
-    26.2779999,
-    26.4540005,
-    25.9029999,
-    26.3309994,
-    27.1030006,
-    26.823,
-    26.6620007,
-    26.9740009,
-    27.2290001,
-    27.3110008,
-    26.8610001,
-    26.9239998,
-    26.9750004,
-    26.7210007,
-    26.8279991,
-    26.823,
-    26.8029995,
-    27.0090008,
-    26.9440002,
-    26.8670006,
-    27.0109997,
-    26.8869991,
-    26.8899994,
-    26.6119995,
-    26.5100002,
-    26.6450005,
-    26.7169991,
-    26.941,
-    26.8110008,
-    26.8560009,
-    27.1289997,
-    27.0769997,
-    27.1130009,
-    27.2199993,
-    27.5510006,
-    27.4860001,
-    27.4330006,
-    27.1730003,
-    27.2749996,
-    27.0979996,
-    27.073,
-    27.4619999,
-    27.3710003,
-    27.3479996,
-    27.4330006,
-    27.6189995,
-    27.6630001,
-    28.2420006,
-    28.4130001,
-    28.559,
-    28.6089993,
-    27.8889999,
-    27.2719994,
-    26.9489994,
-    26.7639999,
-    27.3939991,
-    28.4200001,
-    29.1509991,
-    28.8789997,
-    28.3670006,
-    27.9370003,
-    28.0629997,
-    28.4050007,
-    28.3360004,
-    28.0090008,
-    27.8409996,
-    28.0349998,
-    27.7439995,
-    27.8999996,
-    27.7940006,
-    27.7549992,
-    27.6420002,
-    27.4549999,
-    27.4860001,
-    27.0709991,
-    26.6270008,
-    27.1130009,
-    27.3379993,
-    27.0119991,
-    27.0440006,
-    26.9349995,
-    26.7360001,
-    26.8309994,
-    26.7549992,
-    26.7660007,
-    26.4080009,
-    26.7460003,
-    26.9589996,
-    27.2029991,
-    27.257,
-    27.4309998,
-    27.4669991,
-    27.3719997,
-    27.2229996,
-    26.9179993,
-    26.9869995,
-    26.8610001,
-    26.493,
-    26.1819992,
-    26.441,
-    26.8099995,
-    26.8029995,
-    26.8449993,
-    27.0370007,
-    27.5030003,
-    27.448,
-    27.5580006,
-    27.316,
-    27.2950001,
-    27.2210007,
-    26.9950008,
-    26.4389992,
-    26.2119999,
-    26.5550003,
-    27.2159996,
-    27.2759991,
-    26.9880009,
-    26.8120003,
-    26.8150005,
-    26.8479996,
-    27.073,
-    27.802,
-    28.0690002,
-    28.0550003,
-    27.9360008,
-    27.7789993,
-    27.5690002,
-    27.3409996,
-    27.5459995,
-    27.2380009,
-    25.5739994,
-    25.5400009,
-    25.7959995,
-    25.7329998,
-    26.0779991,
-    26.3729992,
-    26.5839996,
-    26.448,
-    26.2240009,
-    25.6609993,
-    25.9990005,
-    26.1989994,
-    26.2670002,
-    26.7049999,
-    27.0450001,
-    27.4570007,
-    27.8120003,
-    27.6200008,
-    27.2549992,
-    27.7010002,
-    28.2019997,
-    28.0349998,
-    28.1509991,
-    28.5400009,
-    28.3320007,
-    27.5160007,
-    27.007,
-    26.1819992,
-    25.6639996,
-    25.9009991,
-    26.5270004,
-    26.4950008,
-    26.2759991,
-    26.4139996,
-    26.6219997,
-    27.1289997,
-    27.7339993,
-    28.3360004,
-    29.0919991,
-    28.4799995,
-    27.9139996,
-    27.7919998,
-    27.4419994,
-    27.2759991,
-    27.1800003,
-    27.4349995,
-    27.632,
-    27.7250004,
-    27.5100002,
-    27.6170006,
-    27.4990005,
-    27.4899998,
-    27.2250004,
-    27.0020008,
-    26.1630001,
-    25.8059998,
-    26.0809994,
-    26.4200001,
-    26.566,
-    27.2040005,
-    27.1000004,
-    27.3889999,
-    27.6189995,
-    28.2310009,
-    28.1790009,
-    28.2810001,
-    28,
-    27.8199997,
-    27.8479996,
-    28.1609993,
-    28.5240002,
-    28.9029999,
-    29.2660007,
-    29.6800003,
-    30.0400009,
-    29.8880005,
-    29.1630001,
-    29.0410004,
-    28.4920006,
-    27.4750004,
-    27.2670002,
-    27.9200001,
-    27.9899998,
-    28.6749992,
-    28.7970009,
-    28.4279995,
-    27.5410004,
-    26.9099998,
-    26.8439999,
-    26.8349991,
-    26.1550007,
-    24.6350002,
-    22.5879993,
-    19.7719994,
-    18.4950008,
-    17.1030006,
-    15.8509998,
-    14.3000002,
-    13.0430002,
-    12.165,
-    11.3940001,
-    11.1700001,
-    10.7919998,
-    10.2779999,
-    9.63899994,
-    9,
-    8.91600037,
-    8.69900036,
-    8.75699997,
-    8.80900002,
-    9.03999996,
-    8.43200016,
-    8.46100044,
-    8.18799973,
-    7.74300003,
-    7.57999992,
-    7.17999983,
-    7.15399981,
-    7.33599997,
-    7.3829999,
-    7.36299992,
-    7.2420001,
-    6.98600006,
-    6.98000002,
-    7.13999987,
-    7.3039999,
-    6.93900013,
-    6.95800018,
-    6.91900015,
-    6.84600019,
-    6.93499994,
-    6.8579998,
-    6.97399998,
-    6.92299986,
-    7.06500006,
-    7.11600018,
-    7.32600021,
-    7.15999985,
-    7.52699995,
-    7.68599987,
-    7.704,
-    7.86000013,
-    7.11499977,
-    7.13399982,
-    7.64799976,
-    7.76900005,
-    6.99599981,
-    6.66699982,
-    6.69399977,
-    6.57499981,
-    6.52600002,
-    6.66200018,
-    6.68400002,
-    5.97700024,
-    6.2249999,
-    6.54099989,
-    6.64699984,
-    6.33099985,
-    6.64499998,
-    6.47700024,
-    6.35900021,
-    6.14099979,
-    6.12200022,
-    6.2670002,
-    6.29400015,
-    6.60200024,
-    6.90899992,
-    6.94199991,
-    7.05999994,
-    7.05800009,
-    7.04400015,
-    7.19199991,
-    7.76100016,
-    7.69000006,
-    7.81400013,
-    8.0170002,
-    8.0340004,
-    7.92299986,
-    7.46700001,
-    6.75199986,
-    6.671,
-    6.8119998,
-    6.76300001,
-    6.5,
-    6.92700005,
-    7.31400013,
-    7.51999998,
-    7.579,
-    7.68599987,
-    7.65299988,
-    7.56799984,
-    7.01900005,
-    6.60300016,
-    6.70699978,
-    6.94700003,
-    6.46299982,
-    6.70200014,
-    6.82999992,
-    6.68599987,
-    6.86600018,
-    6.80000019,
-    6.84899998,
-    6.61399984,
-    6.829,
-    7.25299978,
-    7.56500006,
-    7.67299986,
-    7.77799988,
-    7.59200001,
-    7.60400009,
-    7.4000001,
-    7.58199978,
-    7.29500008,
-    7.17299986,
-    6.93499994,
-    7.27299976,
-    7.05100012,
-    6.66099977,
-    6.61499977,
-    6.83900023,
-    7.06599998,
-    7.28299999,
-    6.94099998,
-    7.171,
-    7.33199978,
-    7.454,
-    7.32299995,
-    7.32800007,
-    7.22300005,
-    7.23400021,
-    7.69500017,
-    7.9920001,
-    8.0909996,
-    8.0539999,
-    7.97800016,
-    7.62400007,
-    7.58799982,
-    7.44399977,
-    7.1170001,
-    6.82299995,
-    6.88600016,
-    6.98199987,
-    7.08400011,
-    7.03999996,
-    7.41099977,
-    7.4369998,
-    7.39300013,
-    7.34399986,
-    7.04400015,
-    7.43100023,
-    7.16300011,
-    7.53399992,
-    7.97800016,
-    8.39999962,
-    8.27900028,
-    8.15100002,
-    8.03499985,
-    7.86600018,
-    7.69700003,
-    7.6170001,
-    7.40899992,
-    7.2249999,
-    7.06400013,
-    6.9380002,
-    6.65100002,
-    6.69199991,
-    6.8920002,
-    6.921,
-    6.97900009,
-    6.79099989,
-    7.08599997,
-    6.96400023,
-    6.93300009,
-    6.89599991,
-    6.53599977,
-    6.13800001,
-    6.00199986,
-    6.50400019,
-    6.36999989,
-    6.6170001,
-    6.546,
-    6.6500001,
-    6.61800003,
-    6.57499981,
-    6.58799982,
-    6.61899996,
-    6.59899998,
-    6.73000002,
-    6.6420002,
-    6.6960001,
-    6.72900009,
-    6.52199984,
-    6.43900013,
-    6.60699987,
-    6.28299999,
-    6.32700014,
-    6.56899977,
-    6.45100021,
-    6.43400002,
-    6.54199982,
-    6.69999981,
-    7.04899979,
-    6.95900011,
-    6.79799986,
-    6.87200022,
-    6.91800022,
-    6.829,
-    6.83400011,
-    6.69399977,
-    6.3670001,
-    6.40700006,
-    6.296,
-    6.05999994,
-    6.20599985,
-    6.13199997,
-    6.18599987,
-    5.92600012,
-    5.83199978,
-    5.73500013,
-    5.70900011,
-    6.08500004,
-    6.43200016,
-    6.55900002,
-    6.3920002,
-    6.23699999,
-    6.204,
-    6.2420001,
-    6.24599981,
-    5.86100006,
-    5.8579998,
-    5.57499981,
-    5.6869998,
-    6.01200008,
-    6.05900002,
-    6.22200012,
-    6.54300022,
-    6.29099989,
-    6.14300013,
-    5.99700022,
-    6.02099991,
-    5.9369998,
-    6.04099989,
-    5.91200018,
-    5.81799984,
-    5.89400005,
-    6.10699987,
-    6.24900007,
-    6.14499998,
-    6.05299997,
-    6.15899992,
-    5.94000006,
-    5.96099997,
-    6.13000011,
-    5.93400002,
-    6.00899982,
-    5.65799999,
-    5.87900019,
-    5.92700005,
-    5.78599977,
-    5.78599977,
-    5.78599977,
-    6.60599995,
-    6.02899981,
-    5.921,
-    6.12799978,
-    6.07800007,
-    6.03999996,
-    5.94899988,
-    5.9829998,
-    6.10500002,
-    6.13800001,
-    6.21400023,
-    6.10500002,
-    6.17999983,
-    6.33400011,
-    6.15500021,
-    6.25699997,
-    6.22900009,
-    6.07000017,
-    6.28100014,
-    6.3829999,
-    6.65600014,
-    6.86100006,
-    6.84399986,
-    6.79300022,
-    6.42000008,
-    6.46000004,
-    6.27099991,
-    6.15899992,
-    5.93200016,
-    5.81899977,
-    5.71799994,
-    5.77799988,
-    6.0999999,
-    6.38500023,
-    6.40399981,
-    6.51300001,
-    6.64699984,
-    6.71400023,
-    7.0539999,
-    7.13700008,
-    7.21400023,
-    7.25299978,
-    6.81099987,
-    6.84200001,
-    6.92799997,
-    7.00099993,
-    6.83900023,
-    7.00299978,
-    7.19999981,
-    6.89599991,
-    6.77799988,
-    6.74499989,
-    6.48000002,
-    6.4829998,
-    6.37699986,
-    6.26800013,
-    6.34600019,
-    6.25699997,
-    6.1500001,
-    6.25199986,
-    6.20200014,
-    6.65399981,
-    6.58599997,
-    6.45900011,
-    6.49100018,
-    6.15399981,
-    6.15299988,
-    6.15700006,
-    6.4749999,
-    6.64900017,
-    6.69500017,
-    6.44199991,
-    6.29799986,
-    6.20699978,
-    6.07800007,
-    6.29799986,
-    6.01999998,
-    5.89499998,
-    5.81699991,
-    6.00099993,
-    6.04899979,
-    6.31699991,
-    6.171,
-    6.329,
-    6.44500017,
-    6.05700016,
-    6.21999979,
-    6.13899994,
-    6.22100019,
-    6.15399981,
-    6.43300009,
-    6.36100006,
-    5.90100002,
-    6.06799984,
-    6.14300013,
-    6.26300001,
-    6.21400023,
-    6.2750001,
-    6.44899988,
-    6.48500013,
-    6.60500002,
-    6.59399986,
-    6.25899982,
-    6.25899982,
-    6.25899982,
-    6.34200001,
-    6.15399981,
-    6.28800011,
-    6.53800011,
-    6.50600004,
-    6.36999989,
-    6.44799995,
-    6.48600006,
-    6.57000017,
-    6.43499994,
-    6.33699989,
-    6.68499994,
-    6.93599987,
-    7.03800011,
-    6.78399992,
-    6.68400002,
-    6.68400002,
-    6.68400002,
-    6.58699989,
-    6.58699989,
-    6.62699986,
-    6.58900023,
-    6.22300005,
-    6.25400019,
-    6.49599981,
-    6.63100004,
-    6.61800003,
-    6.65299988,
-    6.64499998,
-    6.78200006,
-    6.69999981,
-    6.421,
-    6.53299999,
-    6.11899996,
-    6.50500011,
-    6.5079999,
-    6.45699978,
-    6.43300009,
-    6.87699986,
-    6.87799978,
-    6.97800016,
-    7.07700014,
-    6.94899988,
-    6.89499998,
-    6.80700016,
-    6.83900023,
-    6.89400005,
-    6.78999996,
-    6.7249999,
-    6.78900003,
-    6.81799984,
-    6.76900005,
-    6.63700008,
-    6.53499985,
-    6.3670001,
-    6.28200006,
-    6.32499981,
-    6.44500017,
-    6.74100018,
-    6.71000004,
-    6.78999996,
-    6.66699982,
-    6.50199986,
-    6.71600008,
-    6.47200012,
-    6.61199999,
-    6.61399984,
-    6.64300013,
-    6.79400015,
-    6.78100014,
-    6.86000013,
-    6.68300009,
-    6.75299978,
-    6.54699993,
-    6.68599987,
-    6.60300016,
-    6.67199993,
-    6.86299992,
-    6.88199997,
-    7.12400007,
-    7.10900021,
-    6.94399977,
-    6.70200014,
-    6.65600014,
-    6.50400019,
-    6.37300014,
-    6.34800005,
-    6.53900003,
-    6.63600016,
-    6.71999979,
-    6.97900009,
-    7.05100012,
-    7.09200001,
-    6.91400003,
-    6.63000011,
-    6.3499999,
-    6.19899988,
-    6.30299997,
-    6.26999998,
-    6.57299995,
-    6.53000021,
-    6.58199978,
-    6.59499979,
-    6.71899986,
-    6.73199987,
-    6.72900009,
-    6.56799984,
-    6.39799976,
-    6.41099977,
-    6.53599977,
-    6.49800014,
-    6.41400003,
-    6.40999985,
-    6.21199989,
-    6.35300016,
-    6.69099998,
-    6.64900017,
-    6.7579999,
-    6.65100002,
-    6.70699978,
-    6.70100021,
-    6.67000008,
-    6.57399988,
-    6.54899979,
-    6.43300009,
-    6.64900017,
-    6.57800007,
-    6.52099991,
-    6.39900017,
-    6.55499983,
-    6.64499998,
-    6.73600006,
-    6.70599985,
-    6.89900017,
-    6.86000013,
-    6.74900007,
-    6.80000019,
-    6.76900005,
-    6.68499994,
-    6.76900005,
-    6.7420001,
-    6.58300018,
-    6.83199978,
-    6.67700005,
-    6.73500013,
-    6.6880002,
-    6.88399982,
-    6.56099987,
-    6.41200018,
-    6.48899984,
-    6.38600016,
-    6.34899998,
-    6.37900019,
-    6.29899979,
-    6.21299982,
-    6.3499999,
-    6.41400003,
-    6.51599979,
-    6.49499989,
-    6.59700012,
-    6.56400013,
-    6.35500002,
-    6.44000006,
-    6.6500001,
-    6.56599998,
-    6.42500019,
-    6.11600018,
-    5.92700005,
-    6.08900023,
-    6.00199986,
-    6.26200008,
-    6.3670001,
-    6.1420002,
-    6.31500006,
-    6.75699997,
-    6.52199984,
-    6.37599993,
-    6.44500017,
-    6.46299982,
-    6.47200012,
-    6.3210001,
-    6.63500023,
-    6.72700024,
-    6.62799978,
-    6.66800022,
-    6.71999979,
-    6.65199995,
-    6.61399984,
-    6.57200003,
-    6.53200006,
-    6.58699989,
-    6.73799992,
-    6.74399996,
-    6.92799997,
-    6.92700005,
-    7.03100014,
-    7.01499987,
-    7,
-    6.96299982,
-    7.07399988,
-    6.94999981,
-    6.88800001,
-    6.81699991,
-    6.99700022,
-    6.88500023,
-    6.31699991,
-    6.21999979,
-    6.49900007,
-    6.46999979,
-    6.48799992,
-    6.42799997,
-    6.671,
-    6.671,
-    6.57600021,
-    6.64099979,
-    6.41499996,
-    6.40100002,
-    6.32200003,
-    6.25400019,
-    6.17299986,
-    6.09399986,
-    6.05499983,
-    5.96299982,
-    6.06400013,
-    6.20699978,
-    6.21299982,
-    6.20100021,
-    6.2249999,
-    6.35400009,
-    6.15700006,
-    6.38199997,
-    6.53299999,
-    6.72399998,
-    6.57800007,
-    6.56400013,
-    6.48899984,
-    6.51499987,
-    6.53100014,
-    6.61800003,
-    6.58699989,
-    6.24700022,
-    6.19199991,
-    6.28800011,
-    6.30900002,
-    6.4829998,
-    6.49900007,
-    6.55299997,
-    6.57600021,
-    6.63000011,
-    6.546,
-    6.66699982,
-    6.65100002,
-    6.53700018,
-    6.44000006,
-    6.22700024,
-    6.35400009,
-    6.25,
-    6.25600004,
-    6.07700014,
-    6.09700012,
-    6.11100006,
-    6.07999992,
-    5.92299986,
-    5.99800014,
-    6.23999977,
-    6.19099998,
-    6.36899996,
-    6.58500004,
-    6.35400009,
-    6.13100004,
-    6.07399988,
-    5.90799999,
-    5.8670001,
-    5.87900019,
-    5.90299988,
-    5.76100016,
-    6.04500008,
-    5.96700001,
-    5.78599977,
-    5.96199989,
-    6.02099991,
-    6.3210001,
-    6.01599979,
-    6.05200005,
-    6.28000021,
-    6.03700018,
-    6.19000006,
-    6.13999987,
-    5.89799976,
-    6.03599977,
-    6.15600014,
-    5.9829998,
-    5.5630002,
-    5.48099995,
-    5.59800005,
-    5.38100004,
-    5.58900023,
-    5.65999985,
-    5.27299976,
-    4.99900007,
-    4.83099985,
-    4.94199991,
-    4.84899998,
-    4.6880002,
-    4.68300009,
-    4.38999987,
-    4.41699982,
-    4.50600004,
-    4.94299984,
-    4.81699991,
-    4.96600008,
-    5.06099987,
-    5.15999985,
-    5.27600002,
-    5.25500011,
-    5.40199995,
-    5.80299997,
-    5.7329998,
-    5.51800013,
-    5.59299994,
-    5.44999981,
-    5.5250001,
-    5.44000006,
-    5.11299992,
-    4.87400007,
-    5.01100016,
-    5.33500004,
-    5.15299988,
-    5.06099987,
-    5.08400011,
-    5.08799982,
-    5.09299994,
-    5.0170002,
-    5.36199999,
-    5.12300014,
-    4.63700008,
-    4.70800018,
-    4.34499979,
-    4.59100008,
-    4.44000006,
-    4.76800013,
-    4.93100023,
-    5.16900015,
-    4.85599995,
-    4.69700003,
-    4.71700001,
-    4.64400005,
-    4.7329998,
-    5.10400009,
-    4.92799997,
-    4.84200001,
-    4.74300003,
-    4.60900021,
-    5.01599979,
-    5.01599979,
-    5.01599979,
-    5.02099991,
-    4.84000015,
-    4.79699993,
-    4.85699987,
-    4.98600006,
-    5.0539999,
-    4.96000004,
-    4.96099997,
-    5.19099998,
-    5.47300005,
-    5.23899984,
-    5.42600012,
-    5.39300013,
-    4.96299982,
-    5.05000019,
-    5.33400011,
-    5.47900009,
-    5.92600012,
-    5.93400002,
-    5.54699993,
-    5.65199995,
-    5.42399979,
-    5.71899986,
-    5.70100021,
-    5.43900013,
-    5.51399994,
-    5.42999983,
-    5.30499983,
-    5.46199989,
-    5.65600014,
-    5.81099987,
-    5.829,
-    5.76499987,
-    5.90799999,
-    5.37799978,
-    5.47900009,
-    5.32999992,
-    5.18499994,
-    5.15199995,
-    4.86000013,
-    4.70699978,
-    4.6079998,
-    4.97200012,
-    5.16300011,
-    5.59899998,
-    5.34899998,
-    5.421,
-    5.26100016,
-    5.17700005,
-    5.00500011,
-    5.04500008,
-    5.00299978,
-    4.91800022,
-    4.89499998,
-    4.59299994,
-    4.45499992,
-    4.52899981,
-    4.47599983,
-    4.42799997,
-    4.46000004,
-    4.5539999,
-    4.62799978,
-    4.55800009,
-    4.63199997,
-    4.63399982,
-    4.77600002,
-    4.65999985,
-    4.50099993,
-    4.53299999,
-    4.67399979,
-    4.6880002,
-    4.47399998,
-    4.57200003,
-    4.61800003,
-    4.51499987,
-    4.54300022,
-    4.46299982,
-    4.46999979,
-    4.45599985,
-    5.01499987,
-    5.03599977,
-    4.59000015,
-    4.40399981,
-    4.16200018,
-    4.8130002,
-    4.7579999,
-    4.64599991,
-    4.80999994,
-    4.73600006,
-    4.6960001,
-    4.32299995,
-    4.60699987,
-    4.69000006,
-    4.45499992,
-    4.70699978,
-    4.71500015,
-    4.61199999,
-    4.71000004,
-    4.87099981,
-    5.31400013,
-    4.71799994,
-    4.52099991,
-    4.62400007,
-    4.68400002,
-    5.00899982,
-    5.22200012,
-    5.19500017,
-    5.06599998,
-    4.93100023,
-    4.8670001,
-    4.829,
-    5.05200005,
-    5.52400017,
-    4.86299992,
-    4.44899988,
-    4.78599977,
-    4.86499977,
-    5.079,
-    5.32299995,
-    5.50600004,
-    5.88000011,
-    5.954,
-    5.63100004,
-    5.33199978,
-    5.55200005,
-    5.51300001,
-    5.68599987,
-    5.78499985,
-    5.68499994,
-    5.55100012,
-    5.30200005,
-    5.58400011,
-    5.47399998,
-    5.32600021,
-    5.079,
-    4.93100023,
-    5.13800001,
-    5.18900013,
-    4.921,
-    4.70100021,
-    4.89400005,
-    5.25099993,
-    5.28800011,
-    5.09700012,
-    5.27600002,
-    5.07999992,
-    4.74300003,
-    4.75500011,
-    5.04300022,
-    4.93900013,
-    4.829,
-    4.92199993,
-    5.04300022,
-    5.06899977,
-    4.67500019,
-    5.04300022,
-    5.046,
-    4.53700018,
-    4.68200016,
-    4.58900023,
-    4.07299995,
-    3.76099992,
-    3.9849999,
-    4.71000004,
-    5.15199995,
-    4.58500004,
-    4.22900009,
-    4.28100014,
-    4.60500002,
-    4.78800011,
-    4.63800001,
-    4.56099987,
-    4.58500004,
-    4.88899994,
-    4.954,
-    4.73099995,
-    4.68599987,
-    4.53599977,
-    4.54199982,
-    4.51999998,
-    4.83900023,
-    4.84299994,
-    4.65600014,
-    4.38800001,
-    4.45800018,
-    4.35099983,
-    4.24499989,
-    4.454,
-    4.0619998,
-    3.977,
-    4.12699986,
-    4.05499983,
-    4.01999998,
-    4.16499996,
-    4.28499985,
-    4.00199986,
-    3.97900009,
-    4.00699997,
-    4.46799994,
-    4.44799995,
-    3.95700002,
-    3.76300001,
-    3.76699996,
-    3.76999998,
-    3.31399989,
-    3.15799999,
-    3.14199996,
-    3.53800011,
-    3.33599997,
-    3.54099989,
-    3.69300008,
-    3.77900004,
-    3.64700007,
-    3.92799997,
-    3.977,
-    4.26399994,
-    4.43300009,
-    4.39599991,
-    4.68900013,
-    4.97700024,
-    4.72200012,
-    4.58799982,
-    4.30100012,
-    4.38199997,
-    4.41699982,
-    4.46199989,
-    4.5,
-    4.26499987,
-    4.17000008,
-    4.14099979,
-    4.2329998,
-    4.7249999,
-    5.15100002,
-    5.17799997,
-    5.24900007,
-    5.16300011,
-    5.37599993,
-    5.31699991,
-    5.28700018,
-    4.86600018,
-    4.90199995,
-    5.17199993,
-    5.45900011,
-    5.46999979,
-    5.33699989,
-    5.15999985,
-    5.28000021,
-    5.35900021,
-    5.01499987,
-    4.72200012,
-    4.7670002,
-    4.73199987,
-    4.74100018,
-    5.03599977,
-    4.95100021,
-    4.83300018,
-    4.71199989,
-    4.83400011,
-    4.66499996,
-    4.59299994,
-    4.28900003,
-    4.12900019,
-    3.88899994,
-    3.7349999,
-    3.66599989,
-    3.43499994,
-    3.43499994,
-    3.31800008,
-    3.19400001,
-    3.13599992,
-    3.04399991,
-    3.03200006,
-    3.32299995,
-    3.31299996,
-    3.24699998,
-    3.3829999,
-    3.49399996,
-    3.5710001,
-    3.83599997,
-    3.5940001,
-    3.61800003,
-    3.8900001,
-    3.90799999,
-    3.94400001,
-    3.99399996,
-    3.79399991,
-    3.6730001,
-    3.75300002,
-    3.66300011,
-    3.33500004,
-    3.37299991,
-    3.61800003,
-    3.74399996,
-    3.67799997,
-    3.85899997,
-    3.9230001,
-    3.90400004,
-    4.07999992,
-    4.0079999,
-    4.15999985,
-    4.21400023,
-    4.21999979,
-    4.24599981,
-    4.28299999,
-    4.55100012,
-    4.56699991,
-    4.51599979,
-    4.37400007,
-    4.47599983,
-    4.3130002,
-    4.23400021,
-    4.23000002,
-    4.14400005,
-    3.84100008,
-    3.8269999,
-    3.86100006,
-    4.08199978,
-    4.01200008,
-    4.03499985,
-    4.47399998,
-    4.53999996,
-    4.6079998,
-    4.39799976,
-    4.36899996,
-    4.28800011,
-    4.4000001,
-    4.47599983,
-    4.46600008,
-    4.48999977,
-    4.50299978,
-    4.32299995,
-    4.23699999,
-    4.12200022,
-    4.48799992,
-    4.24100018,
-    4.22599983,
-    4.12300014,
-    3.94899988,
-    3.83299994,
-    3.56299996,
-    3.30299997,
-    2.58899999,
-    1.77600002,
-    0.961000025,
-    0.261000007,
-    0.0879999995,
-    -0.75999999,
-    -0.771000028,
-    -0.499000013,
-    -0.497999996,
-    -0.0250000004,
-    0.263999999,
-    0.263999999,
-    -0.063000001,
-    0.147,
-    -0.00999999978,
-    -0.0189999994,
-    -0.0610000007,
-    -0.0839999989,
-    0.158999994,
-    0.372000009,
-    0.344000012,
-    0.379000008,
-    0.279000014,
-    0.298000008,
-    0.284999996,
-    -0.0160000008,
-    0.305000007,
-    0.144999996,
-    0.356999993,
-    0.513999999,
-    0.578999996,
-    0.633000016,
-    0.455000013,
-    0.658999979,
-    0.419,
-    0.194999993,
-    0.331,
-    0.268000007,
-    0.202999994,
-    0.156000003,
-    0.138999999,
-    0.108000003,
-    0.00400000019,
-    -0.147,
-    -0.349999994,
-    -0.0599999987,
-    -0.0599999987,
-    -0.0599999987,
-    0.119000003,
-    0.0989999995,
-    -0.0909999982,
-    -0.103,
-    0.0909999982,
-    0.00600000005,
-    -0.023,
-    0.232999995,
-    0.0379999988,
-    -0.180000007,
-    -0.204999998,
-    -0.0379999988,
-    0.0370000005,
-    0.074000001,
-    0.0439999998,
-    0.137999997,
-    0.0989999995,
-    -0.101000004,
-    -0.192000002,
-    -0.133000001,
-    -0.0340000018,
-    -0.057,
-    -0.101999998,
-    -0.0610000007,
-    0.00400000019,
-    -0.158000007,
-    -0.0700000003,
-    -0.0719999969,
-    -0.111000001,
-    -0.057,
-    -0.0320000015,
-    -0.195999995,
-    -0.166999996,
-    0.00400000019,
-    0.057,
-    0.284000009,
-    0.368000001,
-    0.319000006,
-    0.129999995,
-    -0.0370000005,
-    0.150000006,
-    -0.023,
-    0.0170000009,
-    0.0549999997,
-    0.170000002,
-    0.349000007,
-    0.245000005,
-    0.193000004,
-    0.0790000036,
-    0.0930000022,
-    0.0590000004,
-    0.112999998,
-    0.200000003,
-    0.0710000023,
-    0.201000005,
-    0.0900000036,
-    -0.122000001,
-    0.0560000017,
-    0.107000001,
-    0.0250000004,
-    0.131999999,
-    0.101000004,
-    0.222000003,
-    -0.0659999996,
-    0.0810000002,
-    0.232999995,
-    0.0579999983,
-    -0.0419999994,
-    0.074000001,
-    -0.0359999985,
-    -0.0379999988,
-    0.0560000017,
-    0.0189999994,
-    -0.0839999989,
-    -0.112000003,
-    -0.0649999976,
-    -0.061999999,
-    0.0860000029,
-    0.0350000001,
-    0.119999997,
-    0.0160000008,
-    -0.0309999995,
-    -0.194000006,
-    -0.219999999,
-    -0.194000006,
-    0.180999994,
-    0.0590000004,
-    0.0280000009,
-    -0.00200000009,
-    -0.147,
-    0.00700000022,
-    0.116999999,
-    0.0149999997,
-    -0.186000004,
-    0.00100000005,
-    -0.00899999961,
-    -0.163000003,
-    -0.00200000009,
-    0.136000007,
-    0.0850000009,
-    0.0520000011,
-    0.0560000017,
-    -0.0540000014,
-    -0.0769999996,
-    0.0219999999,
-    0.112000003,
-    -0.0649999976,
-    0.0710000023,
-    -0.127000004,
-    -0.00999999978,
-    -0.00400000019,
-    -0.246999994,
-    -0.203999996,
-    -0.201000005,
-    0.0189999994,
-    -0.0769999996,
-    -0.050999999,
-    -0.287999988,
-    -0.143000007,
-    -0.231999993,
-    -0.128999993,
-    -0.0549999997,
-    -0.225999996,
-    -0.173999995,
-    -0.264999986,
-    -0.167999998,
-    0.0130000003,
-    0.0979999974,
-    -0.0450000018,
-    -0.180000007,
-    -0.158999994,
-    -0.138999999,
-    -0.0689999983,
-    -0.0469999984,
-    -0.103,
-    -0.133000001,
-    -0.023,
-    0.0149999997,
-    -0.263999999,
-    -0.0729999989,
-    -0.155000001,
-    -0.0500000007,
-    0.0810000002,
-    0.0219999999,
-    -0.0890000015,
-    0.0879999995,
-    0.192000002,
-    0.280000001,
-    -0.181999996,
-    -0.133000001,
-    -0.0120000001,
-    0.169,
-    0.0189999994,
-    -0.0610000007,
-    -0.0729999989,
-    -0.0500000007,
-    -0.0790000036,
-    -0.104999997,
-    -0.0399999991,
-    -0.0829999968,
-    -0.109999999,
-    0.0920000002,
-    0.0939999968,
-    0.0460000001,
-    -0.116999999,
-    -0.00400000019,
-    -0.0340000018,
-    -0.123999998,
-    -0.181999996,
-    0.307999998,
-    -0.128000006,
-    0.00800000038,
-    -0.199000001,
-    0.0469999984,
-    0.245000005,
-    -0.063000001,
-    -0.0469999984,
-    0.0439999998,
-    0.143999994,
-    0.108999997,
-    0.171000004,
-    0.00400000019,
-    0.170000002,
-    0.201000005,
-    0.101000004,
-    -0.050999999,
-    0,
-    0.00899999961,
-    0.170000002,
-    0.499000013,
-    0.219999999,
-    0.122000001,
-    -0.0820000023,
-    0.202000007,
-    0.216000006,
-    0.324999988,
-    0.261999995,
-    0.324999988,
-    0.104999997,
-    0.131999999,
-    0.351999998,
-    0.398000002,
-    0.147,
-    0.101000004,
-    -0.165000007,
-    0.229000002,
-    0.144999996,
-    0.0989999995,
-    -0.0820000023,
-    -0.277999997,
-    -0.145999998,
-    0.122000001,
-    0.252000004,
-    0.171000004,
-    -0.0379999988,
-    -0.216999993,
-    -0.0780000016,
-    0.167999998,
-    0.115000002,
-    0.135000005,
-    -0.115000002,
-    -0.0419999994,
-    0.131999999,
-    -0.0839999989,
-    0.134000003,
-    0.0820000023,
-    0.0939999968,
-    0.202999994,
-    0.126000002,
-    0.163000003,
-    0.143999994,
-    0.188999996,
-    0.291000009,
-    0.312000006,
-    0.115000002,
-    0.0460000001,
-    -0.075000003,
-    -0.00300000003,
-    -0.232999995,
-    0.127000004,
-    0.136000007,
-    -0.107000001,
-    -0.0109999999,
-    0.0130000003,
-    0.0399999991,
-    0.231999993,
-    0.0970000029,
-    -0.133000001,
-    0.293000013,
-    0.298000008,
-    0.218999997,
-    0.236000001,
-    0.344999999,
-    0.270999998,
-    0.372999996,
-    0.208000004,
-    0.232999995,
-    0.187000006,
-    0.150000006,
-    0.245000005,
-    0.0179999992,
-    -0.00899999961,
-    0.0930000022,
-    0.0689999983,
-    0.0649999976,
-    0.0989999995,
-    0.293000013,
-    0.291999996,
-    0.159999996,
-    0.131999999,
-    0.237000003,
-    0.32100001,
-    0.280999988,
-    0.0719999969,
-    0.197999999,
-    0.149000004,
-    0.116999999,
-    -0.00700000022,
-    0.0860000029,
-    0.280999988,
-    0.175999999,
-    0.367000014,
-    0.00899999961,
-    -0.111000001,
-    0.123000003,
-    0.075000003,
-    0.0500000007,
-    0.0500000007,
-    0.0500000007,
-    0.00300000003,
-    0.0309999995,
-    0.173999995,
-    -0.0209999997,
-    0.0710000023,
-    0.0729999989,
-    0.172999993,
-    0.140000001,
-    0.0460000001,
-    0.180999994,
-    0.238000005,
-    0.248999998,
-    -0.125,
-    0.0869999975,
-    0.254000008,
-    0.30399999,
-    0.233999997,
-    0.233999997,
-    0.301999986,
-    0.279000014,
-    0.209000006,
-    0.184,
-    0.0890000015,
-    0.122000001,
-    0.256999999,
-    0.202000007,
-    0.335000008,
-    -0.0869999975,
-    0.0170000009,
-    -0.0839999989,
-    0.0419999994,
-    0.0930000022,
-    -0.0179999992,
-    -0.0939999968,
-    -0.266000003,
-    -0.189999998,
-    -0.0829999968,
-    -0.201000005,
-    -0.0989999995,
-    -0.0500000007,
-    0.0860000029,
-    -0.0769999996,
-    -0.0700000003,
-    0.127000004,
-    0.00600000005,
-    0.209000006,
-    -0.00300000003,
-    -0.0130000003,
-    -0.00499999989,
-    -0.0199999996,
-    0.143000007,
-    0.170000002,
-    0.127000004,
-    0.0769999996,
-    0.163000003,
-    0.104000002,
-    -0.0399999991,
-    0.0170000009,
-    -0.159999996,
-    -0.100000001,
-    -0.0689999983,
-    -0.0540000014,
-    0.0480000004,
-    0.134000003,
-    -0.00100000005,
-    -0.00100000005,
-    -0.00100000005,
-    -0.0540000014,
-    0.0309999995,
-    0.064000003,
-    -0.0370000005,
-    0.230000004,
-    0.0450000018,
-    0.00899999961,
-    -0.142000005,
-    0.133000001,
-    0.119999997,
-    0.123999998,
-    0.050999999,
-    -0.0299999993,
-    -0.023,
-    0.108999997,
-    0.238000005,
-    0.0240000002,
-    0.210999995,
-    0.118000001,
-    0.159999996,
-    -0.0299999993,
-    0.0489999987,
-    0.0560000017,
-    -0.0419999994,
-    -0.0379999988,
-    -0.0270000007,
-    0.108999997,
-    0.128999993,
-    0.064000003,
-    -0.0989999995,
-    0.0489999987,
-    -0.0160000008,
-    -0.064000003,
-    0.0869999975,
-    0.0359999985,
-    -0.120999999,
-    -0.0170000009,
-    0.0289999992,
-    0.0450000018,
-    -0.0189999994,
-    -0.0960000008,
-    0.0350000001,
-    -0.0520000011,
-    0.111000001,
-    0.00400000019,
-    -0.138999999,
-    -0.128999993,
-    0.188999996,
-    0.137999997,
-    0.064000003,
-    -0.0390000008,
-    -0.0450000018,
-    0.0320000015,
-    -0.0299999993,
-    -0.123999998,
-    -0.111000001,
-    0.0829999968,
-    0.239999995,
-    0.0790000036,
-    -0.0109999999,
-    0.0680000037,
-    0.213,
-    0.209000006,
-    0.188999996,
-    0.0410000011,
-    0.145999998,
-    0.050999999,
-    0.0109999999,
-    0.0599999987,
-    0.141000003,
-    0.0850000009,
-    0.0540000014,
-    0.0979999974,
-    0.0769999996,
-    0.0610000007,
-    0.0170000009,
-    -0.023,
-    0.00200000009,
-    0.230000004,
-    0.175999999,
-    0.0900000036,
-    0.0399999991,
-    -0.0109999999,
-    0.074000001,
-    0.0920000002,
-    0.063000001,
-    0.0780000016,
-    0.116999999,
-    0.187999994,
-    -0.0199999996,
-    -0.120999999,
-    0.0759999976,
-    0.252000004,
-    0.192000002,
-    0.0979999974,
-    0.187000006,
-    0.158000007,
-    -0.0560000017,
-    -0.061999999,
-    0.331999987,
-    0.246999994,
-    -0.00100000005,
-    0.286000013,
-    -0.0780000016,
-    0.149000004,
-    0.130999997,
-    0.233999997,
-    0.175999999,
-    0.377999991,
-    0.453000009,
-    0.44600001,
-    0.303000003,
-    0.0549999997,
-    0.218999997,
-    0.147,
-    0.101000004,
-    0.111000001,
-    0.075000003,
-    0.179000005,
-    0.159999996,
-    0.330000013,
-    0.270999998,
-    0.294,
-    0.0649999976,
-    0.074000001,
-    -0.0820000023,
-    -0.0590000004,
-    -0.0500000007,
-    0.111000001,
-    0.216999993,
-    0.261000007,
-    0.114,
-    0.0599999987,
-    -0.0160000008,
-    0.291999996,
-    0.238000005,
-    0.303000003,
-    0.393000007,
-    0.0540000014,
-    0.0379999988,
-    -0.140000001,
-    -0.143000007,
-    -0.0250000004,
-    -0.187000006,
-    -0.116999999,
-    -0.328000009,
-    -0.0649999976,
-    -0.123000003,
-    -0.247999996,
-    -0.261000007,
-    -0.108999997,
-    -0.171000004,
-    -0.194000006,
-    -0.312000006,
-    -0.333999991,
-    -0.330000013,
-    -0.107000001,
-    -0.138999999,
-    -0.0340000018,
-    0.143999994,
-    -0.231999993,
-    -0.0700000003,
-    -0.0199999996,
-    0.160999998,
-    0.344999999,
-    0.0320000015,
-    -0.00899999961,
-    0.0379999988,
-    0.0649999976,
-    -0.236000001,
-    -0.216999993,
-    -0.109999999,
-    -0.0469999984,
-    0.0949999988,
-    -0.0810000002,
-    0.165999994,
-    0.187999994,
-    0.0769999996,
-    -0.134000003,
-    -0.149000004,
-    0.175999999,
-    0.0450000018,
-    0.0109999999,
-    -0.0689999983,
-    0.157000005,
-    -0.123999998,
-    0.0810000002,
-    -0.00300000003,
-    0.0599999987,
-    -0.0209999997,
-    0.0149999997,
-    -0.0179999992,
-    0.0920000002,
-    0.0829999968,
-    0.0399999991,
-    0.115000002,
-    0.150000006,
-    0.0480000004,
-    0.32100001,
-    0.381999999,
-    0.0500000007,
-};
-
-const uint8_t GPS_DATA_NSATS[3230] = {
-    16, 16, 16, 16, 16, 16, 16, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15,
-    15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15,
-    15, 15, 15, 15, 15, 15, 15, 16, 16, 16, 16, 16, 16, 16, 16, 15, 15, 15, 14,
-    14, 13, 13, 12, 12, 12, 13, 13, 13, 13, 13, 14, 13, 13, 14, 15, 14, 14, 14,
-    14, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 14, 13, 13, 13, 13,
-    13, 13, 14, 14, 14, 14, 14, 14, 13, 12, 12, 12, 11, 11, 11, 12, 13, 13, 12,
-    9,  8,  8,  8,  8,  8,  8,  9,  9,  9,  10, 10, 10, 10, 10, 10, 10, 11, 11,
-    10, 10, 10, 10, 10, 10, 10, 10, 10, 10, 11, 11, 8,  8,  8,  8,  10, 10, 10,
-    10, 10, 10, 10, 11, 11, 11, 11, 11, 11, 11, 11, 11, 10, 11, 11, 11, 11, 11,
-    11, 11, 11, 10, 11, 11, 11, 10, 10, 10, 11, 12, 12, 11, 11, 11, 12, 12, 12,
-    12, 12, 12, 12, 12, 12, 12, 12, 11, 11, 10, 10, 9,  10, 10, 9,  8,  8,  8,
-    8,  9,  9,  8,  8,  8,  8,  9,  9,  10, 10, 10, 10, 10, 10, 9,  10, 11, 11,
-    11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 12, 12, 12, 11, 12, 12,
-    12, 12, 12, 13, 13, 13, 13, 13, 13, 13, 13, 13, 12, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 12, 12, 12, 12, 10, 10, 9,  9,
-    9,  9,  10, 11, 11, 11, 10, 11, 11, 10, 10, 10, 11, 12, 12, 12, 12, 13, 12,
-    12, 12, 12, 12, 12, 12, 12, 12, 13, 13, 13, 13, 13, 12, 12, 13, 13, 13, 13,
-    13, 12, 13, 13, 13, 14, 14, 15, 15, 15, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    15, 15, 16, 16, 16, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 14, 14,
-    13, 13, 14, 13, 13, 12, 13, 13, 13, 13, 13, 13, 13, 13, 12, 12, 12, 12, 12,
-    12, 12, 12, 12, 12, 13, 13, 12, 14, 14, 14, 14, 14, 14, 14, 13, 14, 14, 12,
-    12, 12, 12, 12, 12, 13, 12, 11, 11, 11, 12, 12, 12, 12, 10, 11, 11, 11, 11,
-    11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 12,
-    12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 13, 13, 13, 13, 13, 13, 14, 14,
-    14, 15, 15, 16, 16, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 14, 13, 11, 11,
-    11, 11, 11, 12, 12, 12, 12, 11, 11, 11, 10, 10, 9,  9,  9,  9,  11, 13, 14,
-    12, 13, 13, 13, 14, 14, 10, 10, 11, 11, 11, 15, 16, 15, 15, 14, 15, 14, 14,
-    14, 14, 15, 15, 15, 15, 16, 16, 16, 16, 16, 13, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 15, 15, 15, 15, 14, 14, 15,
-    15, 15, 15, 15, 15, 15, 14, 14, 14, 14, 14, 14, 12, 12, 12, 12, 12, 12, 12,
-    12, 12, 12, 12, 11, 11, 11, 11, 11, 11, 12, 12, 12, 12, 12, 12, 12, 12, 11,
-    11, 11, 13, 13, 13, 12, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14, 13, 13, 14,
-    13, 13, 13, 12, 12, 12, 12, 12, 12, 12, 12, 12, 11, 11, 12, 12, 12, 12, 12,
-    12, 12, 12, 12, 12, 12, 12, 12, 12, 13, 13, 13, 13, 13, 13, 12, 12, 13, 13,
-    13, 13, 13, 13, 13, 13, 12, 11, 11, 11, 9,  12, 12, 13, 12, 10, 10, 11, 12,
-    12, 14, 14, 14, 15, 14, 14, 14, 14, 12, 13, 13, 13, 13, 13, 14, 14, 14, 13,
-    13, 14, 14, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15, 15, 14, 14, 14, 14, 14,
-    13, 13, 13, 13, 13, 13, 14, 14, 14, 14, 13, 13, 14, 14, 14, 14, 14, 14, 14,
-    13, 13, 11, 13, 13, 13, 14, 13, 13, 14, 14, 13, 13, 12, 12, 11, 11, 12, 12,
-    12, 12, 12, 13, 13, 13, 13, 13, 12, 13, 13, 13, 13, 13, 13, 12, 12, 12, 11,
-    12, 12, 13, 13, 13, 13, 13, 13, 12, 13, 13, 13, 14, 13, 12, 13, 13, 13, 13,
-    13, 13, 12, 12, 12, 12, 13, 13, 13, 13, 14, 12, 12, 14, 14, 13, 14, 14, 14,
-    14, 14, 13, 13, 14, 13, 13, 13, 13, 13, 12, 12, 12, 12, 12, 12, 13, 13, 13,
-    13, 12, 12, 13, 13, 13, 13, 13, 14, 13, 14, 12, 12, 13, 13, 13, 12, 13, 13,
-    13, 13, 13, 13, 13, 12, 13, 14, 15, 15, 14, 13, 14, 15, 15, 15, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 13, 13, 13, 15, 14, 13, 13, 12, 13, 13, 13,
-    13, 14, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 14, 14, 14,
-    15, 15, 15, 15, 15, 15, 14, 15, 15, 15, 15, 15, 15, 15, 15, 15, 16, 16, 15,
-    15, 15, 15, 16, 16, 16, 16, 16, 16, 16, 14, 14, 14, 13, 13, 13, 13, 13, 15,
-    15, 15, 15, 15, 15, 15, 14, 14, 14, 14, 14, 15, 14, 15, 15, 15, 14, 13, 13,
-    13, 13, 12, 12, 12, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 12, 13, 13, 12,
-    13, 14, 14, 13, 12, 11, 12, 12, 12, 12, 12, 13, 13, 12, 12, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 12, 13, 13, 13, 14, 13, 12, 13, 13, 13, 13, 13, 13,
-    13, 14, 14, 13, 13, 13, 13, 13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 13, 13, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 13, 13, 13, 13, 13, 13, 12, 13, 13, 13, 13, 13, 13, 13, 13,
-    11, 10, 10, 11, 10, 10, 10, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 13, 13, 13, 13, 13,
-    13, 13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 13, 14, 14, 14, 14, 14, 13, 13, 13, 14, 13, 12,
-    12, 12, 12, 12, 12, 13, 13, 14, 13, 14, 14, 14, 13, 13, 13, 12, 12, 12, 13,
-    14, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 13, 13, 13, 13, 15, 14, 14, 14, 13, 14, 13, 13,
-    13, 13, 15, 14, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 15, 15, 15,
-    15, 15, 15, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 15, 16, 14, 14, 16, 15,
-    15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 14, 14, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 14, 14, 14, 14, 14, 13, 13, 14, 15, 15, 16, 15, 16, 15,
-    15, 14, 13, 13, 13, 12, 12, 12, 12, 12, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 14, 13, 13, 13, 13, 13, 13, 14, 14, 14, 14, 14,
-    14, 14, 14, 13, 13, 13, 14, 14, 14, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 13, 13, 14, 13, 13, 14, 13, 13, 13, 13, 13, 14, 14, 14, 15,
-    15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 14, 14, 15, 15, 15, 15, 15, 15, 15,
-    15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 14, 15, 14, 14, 14, 15, 15,
-    14, 14, 14, 14, 14, 14, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    14, 13, 13, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15, 15, 15, 15, 14, 14, 14,
-    14, 14, 13, 14, 15, 15, 15, 15, 15, 15, 15, 16, 15, 16, 15, 15, 15, 15, 15,
-    15, 16, 15, 16, 16, 15, 15, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 15, 16,
-    16, 16, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15,
-    16, 16, 16, 16, 16, 16, 15, 15, 15, 15, 15, 15, 16, 16, 15, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 15, 15, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15, 15,
-    14, 14, 15, 15, 14, 14, 14, 14, 14, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15,
-    15, 15, 15, 15, 15, 15, 15, 14, 15, 15, 15, 13, 13, 13, 15, 15, 15, 15, 15,
-    15, 15, 15, 15, 14, 15, 14, 14, 14, 15, 15, 14, 13, 13, 13, 13, 13, 12, 12,
-    12, 14, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 13, 13, 14, 14, 13, 14, 13, 12, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 15, 15, 15, 14, 15, 16, 16, 16,
-    16, 16, 16, 16, 16, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15,
-    15, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15, 15, 14, 14, 14, 14, 15, 15, 15,
-    15, 15, 15, 15, 15, 15, 15, 15, 15, 14, 14, 14, 14, 14, 14, 14, 13, 14, 14,
-    14, 14, 14, 14, 14, 14, 13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 13, 13, 13, 14, 14,
-    14, 14, 14, 15, 15, 15, 15, 15, 15, 15, 15, 14, 14, 15, 15, 15, 15, 15, 15,
-    16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16,
-    16, 16, 16, 16, 16, 16, 16, 16, 15, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 15, 15, 15, 16, 15, 15, 15, 14, 14, 14, 14, 15, 15,
-    15, 15, 15, 15, 15, 14, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15, 15, 15, 15,
-    15, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 14, 14, 14, 14, 14, 13, 13, 13, 13, 13, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 14, 14, 14, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    12, 13, 13, 13, 13, 14, 14, 14, 14, 14, 13, 13, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15,
-    15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15,
-    15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15,
-    15, 15, 15, 15, 14, 14, 14, 14, 14, 14, 14, 14, 15, 14, 15, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 15, 15, 15, 15, 14, 14, 14, 14, 14, 14, 15, 15, 15, 15, 15, 15,
-    15, 15, 16, 16, 16, 16, 15, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16,
-    16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 16, 15, 15,
-    15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 15, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 13, 13, 13, 13, 14, 14, 14, 14, 14, 13, 13, 13, 13,
-    13, 14, 14, 14, 14, 13, 14, 13, 13, 13, 13, 12, 13, 13, 13, 13, 14, 14, 13,
-    13, 13, 13, 14, 13, 13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 15, 15, 15, 15,
-    15, 15, 15, 15, 15, 15, 15, 15, 14, 14, 14, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 13, 14, 14,
-    14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 13, 13, 13, 13, 13, 13, 13, 13, 14,
-    14, 14, 13, 13, 13, 13, 13, 14, 15, 14, 14, 14, 14, 15, 15, 15, 14, 14, 14,
-    14, 14, 14, 14, 13, 14, 13, 13, 13, 13, 13, 14, 15, 14, 14, 14, 14, 14, 14,
-    13, 14, 13, 13, 13, 13, 13, 14, 13, 14, 14, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 12, 12, 12,
-    12, 12, 12, 12, 12, 12, 12, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11, 11,
-    12, 13, 14, 15, 15, 15, 15, 14, 14, 14, 14, 14, 14, 13, 14, 14, 14, 14, 13,
-    13, 14, 14, 15, 15, 15, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14, 14,
-    14, 14, 15, 16, 15, 15, 15, 15, 15, 14, 13, 14, 14, 14, 14, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 14, 13, 14, 14, 14,
-    14, 14, 13, 13, 13, 13, 13, 13, 13, 13, 12, 12, 12, 12, 12, 12, 12, 12, 12,
-    12, 13, 13, 13, 13, 13, 13, 13, 13, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12,
-    12, 12, 11, 11, 11, 11, 11, 12, 12, 12, 12, 12, 12, 12, 13, 13, 13, 14, 13,
-    13, 13, 13, 13, 13, 13, 13, 14, 14, 14, 14, 14, 14, 14, 14, 13, 13, 13, 13,
-    13, 13, 15, 14, 14, 14, 14, 13, 13, 13, 15, 15, 14, 14, 15, 15, 15, 15, 14,
-    14, 14, 14, 14, 14, 14, 14, 12, 13, 12, 12, 12, 13, 13, 14, 14, 14, 14, 14,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 12, 12,
-    11, 11, 11, 11, 11, 11, 11, 11, 11, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12,
-    12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12,
-    12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 12, 12, 12, 12, 12, 12, 12, 12,
-    12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 12, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 14, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-    13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13, 13,
-};
diff --git a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_gps_data.h b/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_gps_data.h
deleted file mode 100644
index a82162aca..000000000
--- a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_gps_data.h
+++ /dev/null
@@ -1,37 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Authors: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <Common.h>
-
-/**
- * Ublox Neo-M9N GPS data from Lynx flight test in Roccaraso.
- * Sampled at 25 Hz (40 ms period).
- */
-static constexpr unsigned GPS_DATA_SIZE = 3230;
-extern const float GPS_DATA_LAT[GPS_DATA_SIZE];
-extern const float GPS_DATA_LON[GPS_DATA_SIZE];
-extern const float GPS_DATA_VNORD[GPS_DATA_SIZE];
-extern const float GPS_DATA_VEAST[GPS_DATA_SIZE];
-extern const float GPS_DATA_VDOWN[GPS_DATA_SIZE];
-extern const uint8_t GPS_DATA_NSATS[GPS_DATA_SIZE];
\ No newline at end of file
diff --git a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_imu_data.cpp b/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_imu_data.cpp
deleted file mode 100644
index 1bcd87d3c..000000000
--- a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_imu_data.cpp
+++ /dev/null
@@ -1,19421 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Authors: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include "lynx_imu_data.h"
-
-const float ACCEL_DATA[IMU_DATA_SIZE][MOTION_SENSOR_AXIS_NUM] = {
-    {9.7706089, 0.0505036227, -1.17231905},
-    {75.051712, 0.957256854, -0.897318244},
-    {72.1530991, 0.702976704, -0.742024541},
-    {67.3247223, 1.02599335, 0.031463787},
-    {70.7685852, 1.14938974, -0.39391765},
-    {71.4871674, 1.0382731, -0.149140865},
-    {71.2697906, 2.24065208, -0.558500826},
-    {71.6616135, 0.718285263, -1.28442919},
-    {73.3524475, 0.89712429, -0.325761735},
-    {73.1448441, 0.871322751, -0.736510754},
-    {72.9840164, 0.786987901, -1.06586242},
-    {72.6989136, 1.21296668, -1.61752141},
-    {72.1249847, 1.35529983, -1.23485363},
-    {71.6802063, -0.729544878, 0.636282563},
-    {73.0008621, 2.1558466, -1.4900341},
-    {73.6755981, 1.56671011, -1.52887225},
-    {71.5215378, 0.495066375, -3.8517313},
-    {72.5661011, -1.15156245, 2.10670543},
-    {71.9102859, 2.75893283, -2.81235266},
-    {72.6114883, 0.52327311, 0.931658208},
-    {72.9401245, 1.74450696, -1.73914695},
-    {73.4833069, 0.600096405, 0.46086511},
-    {73.627121, 0.91890651, 0.468178928},
-    {73.6072693, 0.65073216, 0.593248487},
-    {73.7902222, 0.76572305, 0.461609632},
-    {73.9439468, 0.788648784, 0.547009885},
-    {74.1002731, 0.672277272, 0.49049446},
-    {74.255661, 0.598946691, 0.560050547},
-    {74.5455246, 0.696001709, 0.687057495},
-    {74.7175598, 0.634838998, 0.811056614},
-    {74.9134979, 0.619264722, 0.844705939},
-    {74.8948975, 0.595154524, 0.863168478},
-    {75.1726761, 0.626879454, 0.943907917},
-    {75.3604736, 0.759868145, 0.834086716},
-    {75.638916, 0.715038896, 0.983938098},
-    {75.8006592, 0.683658421, 0.836345553},
-    {75.9352875, 0.709865212, 0.777407289},
-    {76.2230225, 0.59126091, 0.769218326},
-    {76.4927597, 0.532258332, 0.834134698},
-    {76.6945038, 0.423687547, 0.81448108},
-    {77.0323715, 0.270789891, 0.889968812},
-    {77.2938461, 0.272700369, 0.779893279},
-    {77.4908829, 0.209396094, 0.936293006},
-    {77.8033295, 0.253418565, 0.924213707},
-    {78.059082, 0.149939343, 0.880737543},
-    {78.3719482, -0.0100329062, 0.813244879},
-    {78.7745438, -0.147020459, 0.891011},
-    {79.0569, -0.0399472341, 0.983630776},
-    {79.4110031, -0.291531891, 0.757455885},
-    {79.7106323, -0.270866007, 0.805845439},
-    {80.0920639, -0.221901387, 0.770797431},
-    {80.333847, -0.1850577, 0.76698488},
-    {80.7624741, 0.0204621498, 0.873884022},
-    {80.8398972, 0.000708246836, 1.10919869},
-    {81.1752014, 0.0334316678, 1.03528631},
-    {81.3601837, 0.10570325, 1.07976866},
-    {81.4876862, 0.21125105, 1.11350214},
-    {81.5111237, 0.302387744, 1.2144022},
-    {81.4834595, 0.0692225546, 1.38101101},
-    {81.3648758, 0.0828501135, 1.47362125},
-    {81.4239578, 0.169557005, 1.55536222},
-    {81.131752, 0.226912349, 1.7064867},
-    {80.977623, 0.174948126, 2.11504316},
-    {80.9268036, 0.355327666, 2.13113713},
-    {80.7909088, 0.62750113, 2.02704859},
-    {80.640564, 0.766206026, 2.23239326},
-    {80.3874283, 0.776954412, 2.369349},
-    {80.344429, 0.468313873, 2.3242352},
-    {80.2328491, 0.716903627, 2.23460269},
-    {79.9205475, 0.676170886, 2.20348406},
-    {79.8310928, 0.369558752, 2.06789899},
-    {79.6953201, 0.401673853, 1.67641044},
-    {79.4943237, 0.19381693, 1.46007204},
-    {79.4044266, 0.0387358218, 1.6726402},
-    {79.2284698, -0.583195984, 2.21401048},
-    {78.9426498, -0.855051756, 2.67963743},
-    {78.762207, -1.29367781, 1.93607628},
-    {78.7069855, -1.53957188, 1.52394629},
-    {78.6626663, -1.73126447, 1.32824492},
-    {78.5219803, -1.84331918, 0.805960715},
-    {78.3508224, -1.32198119, -0.0401527658},
-    {78.1511612, -1.11831701, -0.185470343},
-    {78.0072403, -1.11671555, -0.425383151},
-    {77.7883606, -0.802353382, -0.503511071},
-    {77.7134781, -0.374495029, -0.78892535},
-    {77.474968, -0.15855138, -0.611000299},
-    {77.279335, 0.425185114, -0.659390092},
-    {77.0293961, 0.925296009, -0.422784269},
-    {77.0096054, 1.29779482, -0.370541722},
-    {76.7065735, 1.60899556, -0.333679199},
-    {76.3198776, 1.85412633, -0.292225182},
-    {76.0791016, 2.03967476, -0.00408513844},
-    {75.7581253, 2.24486327, 0.278031647},
-    {75.6265106, 2.37526608, 0.587551475},
-    {75.3557434, 2.16005802, 1.04049754},
-    {75.0951385, 2.36014128, 1.40408909},
-    {74.857254, 1.92436051, 1.45515895},
-    {74.6294937, 1.78278971, 1.76744604},
-    {74.8337173, 1.54206097, 1.85784125},
-    {74.5409622, 1.50999451, 2.0778203},
-    {73.9470444, 1.08110249, 2.8541379},
-    {73.8226166, 1.00835896, 2.94846678},
-    {73.4979095, 1.24556971, 3.07294512},
-    {73.069725, 0.848386526, 3.24259448},
-    {72.7636871, 0.466367066, 3.15653515},
-    {72.6318207, 0.0984425545, 2.26916313},
-    {72.2974091, -0.318487376, 2.09836745},
-    {72.1057587, -0.643750608, 1.33728027},
-    {71.8909531, -0.684333503, 0.616605043},
-    {71.7098999, -1.02876484, -0.107153609},
-    {71.4926758, -1.17029965, -0.62347126},
-    {71.1438065, -1.11382437, -1.05275977},
-    {70.9560089, -0.891051471, -1.59658635},
-    {70.7279739, -0.89428705, -1.70773125},
-    {70.4152451, -0.4075903, -1.93970335},
-    {70.2566986, -0.19252111, -1.46071625},
-    {69.9983521, -0.518284917, -1.19622302},
-    {69.6812515, -0.279706329, -1.18422055},
-    {69.3382492, 0.0744639933, -0.580328941},
-    {68.9313583, 0.266896307, 0.137920842},
-    {68.8928223, 0.67826736, 0.695070565},
-    {68.7627869, 0.595903277, 1.68400395},
-    {68.1628265, 1.33654451, 2.1639111},
-    {67.85466, 0.755240321, 3.01211071},
-    {67.6846008, 0.406166464, 3.58772302},
-    {67.6248627, 0.146363467, 3.85386777},
-    {67.3586807, -0.12844117, 4.0591321},
-    {67.1351776, -0.123209752, 3.65338421},
-    {67.0844269, -0.303947777, 3.24271107},
-    {67.0426788, -0.188347369, 2.83687115},
-    {66.9468307, -0.495794773, 2.64494586},
-    {66.9843063, -0.438416809, 1.97693992},
-    {66.7452316, 0.289508998, 1.50548387},
-    {66.6272583, 0.620313048, 0.695219457},
-    {66.629631, 1.25616348, -0.104920343},
-    {66.7605438, 1.88618267, -0.39390859},
-    {66.5896225, 2.11185575, -0.635380268},
-    {66.6467514, 2.47455263, -0.525090456},
-    {66.7836227, 2.28182054, -0.252768964},
-    {66.901886, 2.76147914, -0.239517659},
-    {65.3644409, 3.05843854, -0.248748943},
-    {62.1886749, 2.79367566, 0.173207983},
-    {59.5514832, 1.99698174, -0.0133253215},
-    {56.4851265, 1.96902084, 0.109266527},
-    {51.5297508, 1.82083631, -0.10500598},
-    {46.4091454, 1.99788916, 0.00615235511},
-    {41.924736, 1.12737608, -0.00933246315},
-    {38.2426605, 0.506041884, 0.358865261},
-    {33.2051277, -0.0161319654, 0.506006181},
-    {28.9737568, -0.590438664, -0.454962879},
-    {26.0372162, -0.941309571, -0.293416172},
-    {24.5942497, -1.80034482, -0.878523886},
-    {22.8606892, -1.99962175, -0.617118537},
-    {22.0657787, -2.48361397, -1.03027737},
-    {21.1462059, -2.93858099, -1.52165341},
-    {23.7900963, -3.08591986, -0.429949343},
-    {18.825798, -2.27027917, -0.872837126},
-    {10.97019, -2.44617534, -1.02774656},
-    {5.77373171, -0.763253391, 0.697155118},
-    {3.50414991, -0.542966843, 1.288252},
-    {0.437992066, 0.436067104, 1.15181375},
-    {-2.65251064, 0.475801528, 1.82887459},
-    {-4.52059841, 0.000553662481, 2.22609186},
-    {-5.14936018, -0.0411089584, 2.57726836},
-    {-5.19878817, 0.167503893, 2.57928038},
-    {-5.25758314, -0.0326092914, 2.78877521},
-    {-5.16727638, -0.542966962, 3.00034881},
-    {-5.29795599, -0.461360723, 2.5990696},
-    {-5.3477416, -0.273561686, 2.296839},
-    {-5.49473381, -0.0067019905, 1.63754988},
-    {-5.63669729, 0.743922591, 1.00238144},
-    {-5.74196863, 0.698354185, 0.859446228},
-    {-5.74893808, 1.56061101, 0.282940507},
-    {-5.79704714, 1.58337343, 0.386568606},
-    {-5.84465551, 1.56779921, -0.00173888565},
-    {-5.88006353, 2.33243704, -0.0816933215},
-    {-5.82159472, 2.05404663, -0.533875048},
-    {-5.90386868, 2.29305196, 0.429598063},
-    {-5.88661051, 1.22771049, -0.962681055},
-    {-5.78916168, 0.95516032, -1.21862447},
-    {-5.85744953, 0.961749434, -0.821532249},
-    {-5.89315605, 0.395534039, -0.594324648},
-    {-5.90864229, -0.414601445, -0.948613048},
-    {-6.16705322, -0.850559235, -1.20537305},
-    {-6.31077194, -0.954936981, -1.20716},
-    {-6.65929079, -0.285580546, -1.06987286},
-    {-7.12130356, 0.33158958, -0.00531226443},
-    {-7.67660666, -0.190898135, 0.624443769},
-    {-8.11472607, -0.236422896, 0.381919384},
-    {-8.71274853, -1.52317643, 2.24422789},
-    {-9.53423882, -1.96796477, 1.82202148},
-    {-9.82665062, -1.70115507, 2.49650168},
-    {-10.419755, -3.08974957, 1.91630077},
-    {-10.8686428, -2.17026329, 1.00145924},
-    {-10.7904263, -1.99691701, 0.837261379},
-    {-11.4611111, 0.181537271, 0.838899195},
-    {-12.0942993, 0.998139381, 1.08114457},
-    {-12.3490038, 2.17669415, 0.722466588},
-    {-12.4366217, 2.49289012, 0.356573731},
-    {-12.4525547, 3.27992368, -0.124573745},
-    {-12.7668352, 2.68845248, 0.454923838},
-    {-12.9533348, 2.45029259, 1.70469987},
-    {-13.1494484, 2.86696339, 0.407972783},
-    {-14.0614195, 1.74974871, 0.740631163},
-    {-13.837719, 0.931146741, 0.409584433},
-    {-14.04461, 0.375317305, 1.39783573},
-    {-12.9821978, -0.63281858, -1.32642126},
-    {-13.0937443, -1.49293721, -1.16981459},
-    {-12.9227142, -1.97641504, -1.88260591},
-    {-13.3251286, -2.55744171, -1.38553095},
-    {-13.1361818, -1.98194206, -1.10993409},
-    {-12.8970985, -2.52030301, -0.750213444},
-    {-12.9870462, -1.59808159, -1.9745959},
-    {-12.2217903, -1.09564483, -1.44070041},
-    {-12.5779715, -0.767146826, -1.14343452},
-    {-13.0131426, -2.51176691, -0.965807855},
-    {-12.1018867, -0.932324171, -0.609064877},
-    {-13.2053452, 0.174569279, 0.706281126},
-    {-12.6312246, -0.91977489, 1.09560704},
-    {-12.8337173, 0.37007603, 2.99290419},
-    {-12.7057695, 0.329493016, 2.54444456},
-    {-12.741169, 0.301452905, 3.88259935},
-    {-12.7306166, -0.807130933, 3.40175891},
-    {-12.5092897, 0.212487742, 3.61502361},
-    {-12.4422884, -0.913604975, 3.04263377},
-    {-12.2818213, -0.187630728, 2.40127015},
-    {-11.9965553, 0.237694561, 2.1790669},
-    {-11.9848309, -0.496432662, 0.86021471},
-    {-11.8724747, -0.340950489, 0.537246287},
-    {-11.2723789, 0.994853914, -0.466964513},
-    {-12.2122841, 0.0624292269, -0.242310435},
-    {-11.5859013, 1.64511156, -0.83179605},
-    {-11.6754646, 1.71933079, -0.738541424},
-    {-11.4207897, 2.09552813, -0.306816399},
-    {-11.1852427, 1.92858589, -1.38940227},
-    {-11.7244406, 2.19166923, -0.949280977},
-    {-10.6644115, 1.36099052, -0.477892041},
-    {-11.745121, 0.618366182, -0.55561316},
-    {-11.118206, 1.18450916, -0.874527872},
-    {-10.8655539, -0.195240766, 0.0204458684},
-    {-11.0867081, 0.468595177, 0.313404471},
-    {-11.1461554, -0.662609696, 0.64135468},
-    {-10.9355421, -0.383991182, -0.26707986},
-    {-10.7245073, -1.10938239, -0.190333948},
-    {-10.9926443, -2.06191897, -0.550848782},
-    {-10.5742683, -2.55274534, -0.728579223},
-    {-10.456789, -2.69460535, -0.539413989},
-    {-10.3782444, -1.70942688, -0.947844505},
-    {-10.8738642, -1.4738642, -0.704542339},
-    {-10.9145622, -0.177990243, -0.543778658},
-    {-10.3464661, -1.23056388, -0.433179557},
-    {-10.761713, -0.470486611, 0.997021377},
-    {-10.1700277, -0.0643433779, -0.292554438},
-    {-10.4572153, -0.881036401, 0.755241752},
-    {-10.2613773, -0.508374214, 0.483943135},
-    {-10.2783375, 0.447498232, 1.32487917},
-    {-10.0779362, -0.147619471, 1.95915461},
-    {-10.1771688, 0.57538718, 0.69789958},
-    {-9.87312603, 0.15188162, 1.31857157},
-    {-10.0823975, 0.554571569, 0.662463427},
-    {-10.3848801, -0.411102414, 1.61054814},
-    {-9.53222561, -0.267122239, 0.952502966},
-    {-10.1579857, -0.285048515, 0.767799437},
-    {-9.89190292, -0.137489438, 0.672708154},
-    {-9.67182827, -0.432744026, 0.343034804},
-    {-9.83423996, -0.27700597, 1.02545965},
-    {-9.88393021, -1.01528716, 0.257480145},
-    {-9.7248888, 0.130171925, 0.90162605},
-    {-9.79653358, -0.610669613, -0.0544175729},
-    {-8.88532066, 0.0913270786, 0.765166581},
-    {-9.53683567, 0.435108691, 0.199561551},
-    {-9.39415359, 0.591156542, 0.297089726},
-    {-9.4475708, 0.00797365233, -0.125764981},
-    {-9.08396149, 0.431474626, -0.584200323},
-    {-9.53758049, 0.186628804, -0.163136721},
-    {-8.97327137, 0.719898641, -0.335403442},
-    {-9.34476566, 0.599497437, -0.14244093},
-    {-8.87619877, 0.319459498, -0.382269174},
-    {-9.12073898, 1.08172119, -0.0940909609},
-    {-8.9206686, 0.0720134899, 0.106798038},
-    {-8.88683224, -0.203477308, -0.126807138},
-    {-8.90513134, 0.384751737, 0.572533369},
-    {-8.87292862, -0.606650591, -0.152166784},
-    {-8.98991585, 0.13285853, 0.716077745},
-    {-8.66729259, -0.804672003, 0.407432497},
-    {-8.42577457, -0.529639006, 0.13628304},
-    {-8.43857002, -0.967516065, 0.950567305},
-    {-8.90912819, -0.467895329, 0.492723286},
-    {-8.25334263, -0.835134447, 0.473818719},
-    {-8.67728806, -1.41556752, 0.0360522978},
-    {-8.19412899, -1.28424358, 0.288449496},
-    {-8.19689083, -1.01490593, 0.0765295923},
-    {-7.98331356, -0.808628142, 0.0682397783},
-    {-8.26390553, -1.12340879, 0.508956909},
-    {-8.28845501, -0.112577341, -0.534470499},
-    {-8.29499912, -0.640755415, -0.37411496},
-    {-8.14056969, 0.173450634, -0.334956616},
-    {-7.836236, -0.807245433, -0.0515560582},
-    {-8.07414722, 0.225215137, 0.0963306427},
-    {-8.27651119, 0.0118945716, 0.64605391},
-    {-7.79252577, 0.785838127, 0.35287118},
-    {-7.99134779, 0.501109838, 1.20338428},
-    {-8.08192253, -0.150028333, 0.745234132},
-    {-7.53941679, 0.678866327, 0.837430835},
-    {-7.65169191, 0.335483134, 1.0641712},
-    {-7.77344894, 0.190073118, 0.771230578},
-    {-7.45768595, 0.122983828, 0.846045911},
-    {-7.7396183, 0.519229829, 0.619433999},
-    {-7.46095991, 0.269591898, 0.818798959},
-    {-7.59307384, 0.906490684, 0.75403136},
-    {-7.69498587, -0.476177275, 0.883417606},
-    {-7.20566082, -0.846066833, 0.462354034},
-    {-7.25981522, -0.0176340844, 0.260160208},
-    {-7.22842312, -0.293029457, 0.605885029},
-    {-7.15567064, -0.710091174, 0.317781001},
-    {-7.22018147, -0.94550693, 0.276010334},
-    {-7.14510775, -0.808029473, -0.150034219},
-    {-6.90485859, -0.121567391, -0.360114545},
-    {-6.96047592, 0.236945719, -1.02432156},
-    {-7.12933779, -0.223244548, -1.39208257},
-    {-6.75159407, -0.110031515, -0.744257927},
-    {-6.70413589, 1.00517774, -0.978910267},
-    {-7.15845585, 0.91025579, -0.247553363},
-    {-6.9449687, 0.981263757, -0.350410461},
-    {-7.05239773, 1.30880833, -0.0430675969},
-    {-6.99648094, 0.940933764, 0.711746335},
-    {-6.72600508, 0.231854215, 0.569853306},
-    {-7.05033779, 0.910833538, 0.814481139},
-    {-6.81348562, 0.443754345, 0.837856948},
-    {-6.66143513, 0.0554452799, 1.07682681},
-    {-6.79191303, 0.141103998, 1.08903599},
-    {-6.54911089, -0.0739411488, 1.03707302},
-    {-6.33972788, -1.01671243, 0.31152761},
-    {-6.74846125, -1.94604218, 0.284090549},
-    {-6.29812384, -2.12795043, 0.359172672},
-    {-6.40997362, -1.98466456, 0.231108516},
-    {-6.09920216, -1.49164164, 0.0588548556},
-    {-6.02949667, -1.62274635, -0.752639532},
-    {-5.91034365, -1.7577517, -0.525596678},
-    {-5.19076538, -1.2931515, -0.841483533},
-    {-5.47983122, -1.18788445, -1.12043798},
-    {-5.50685549, -1.1854018, -0.77896744},
-    {-4.9841733, -0.372053534, -1.08707249},
-    {-5.16606617, -1.08046961, -0.994424522},
-    {-4.9110837, -0.112128057, 0.101293646},
-    {-4.49871111, -0.187195092, 0.126433656},
-    {-4.61397696, 0.113249965, 0.189585939},
-    {-4.51583815, -0.0336093046, 0.543297887},
-    {-4.64373302, 0.0704205483, 0.51208365},
-    {-4.44446659, 0.242350504, 0.713478923},
-    {-4.29931545, 0.3297925, 0.981238902},
-    {-4.5749979, 0.636785805, 0.613180578},
-    {-4.52310944, 0.649831951, 0.924467683},
-    {-4.44337082, 0.500281096, 1.01619852},
-    {-4.48141718, 0.938537717, 1.43252742},
-    {-4.35126972, 0.531908929, 1.54466915},
-    {-4.42169666, 0.34944877, 1.79405856},
-    {-4.38590384, 0.274383962, 1.86460853},
-    {-4.46326637, 0.373819828, 1.44726741},
-    {-4.26312208, -0.118363269, 1.50655305},
-    {-4.14602852, -0.0656081513, 1.00791442},
-    {-4.41580677, -0.23148115, 0.902028918},
-    {-3.96114683, -0.280599952, 0.416644543},
-    {-3.98194432, -0.704014719, 0.452297181},
-    {-4.07793617, -0.506277561, 0.115438238},
-    {-4.04543543, -0.405537248, 0.0345713049},
-    {-4.02089691, -0.284198493, -0.0624142028},
-    {-3.96823835, -0.15016523, -0.306992322},
-    {-4.05219316, -0.164077714, -0.448949605},
-    {-3.83840632, -0.135938764, -0.644650042},
-    {-3.92529154, -0.0394979455, -0.906548917},
-    {-4.02036047, 0.287112951, -1.18691075},
-    {-4.04498959, 0.48021242, -1.4774735},
-    {-3.8663671, 0.0245141499, -1.29119194},
-    {-3.92529154, 0.625853837, -1.16100347},
-    {-3.9199357, 0.648915827, -1.04650652},
-    {-3.98524857, 0.697884977, -0.849672794},
-    {-3.92335725, 0.864859283, -0.724455476},
-    {-3.94919491, 0.762945771, -0.36185652},
-    {-3.82674408, 0.658461273, -0.293104112},
-    {-3.87411284, 0.361390352, -0.11281158},
-    {-3.79050064, 0.241438434, -0.224181876},
-    {-3.82029057, 0.0176948421, 0.278584421},
-    {-3.58975148, -0.105439141, 0.292469531},
-    {-3.74719143, -0.707438886, 0.491810471},
-    {-3.90743828, -0.347988844, 0.726784348},
-    {-3.77115941, -0.667111993, 0.867039561},
-    {-3.90700078, -0.593151808, 0.695631146},
-    {-3.5469532, -1.10948205, 0.445827216},
-    {-3.6550467, -1.0960623, 0.15214707},
-    {-3.66790819, -1.18061435, -0.0453640297},
-    {-3.57150197, -1.63900781, -0.0590619221},
-    {-3.46771479, -1.55739677, -0.114011131},
-    {-3.56444287, -1.23499513, -0.207968235},
-    {-3.51318145, -1.08881617, -0.468511969},
-    {-3.50053525, -0.946550906, -0.0589129999},
-    {-3.49815512, -0.754567802, -0.146162942},
-    {-3.45486116, -0.618521631, -0.326075882},
-    {-3.406142, -0.643590748, -0.0840854794},
-    {-3.43026328, -0.374522299, -0.231193349},
-    {-3.45294189, -0.073182635, -0.181983486},
-    {-3.36361146, -0.436819404, 0.236306056},
-    {-3.40184307, -0.329941273, 0.165416017},
-    {-3.43958044, -0.431352735, -0.0253694318},
-    {-3.4122436, -0.208134159, 0.458766282},
-    {-3.3478868, 0.17046918, 0.483483076},
-    {-3.20893383, 0.29714641, 0.782916188},
-    {-3.45708823, 0.425658494, 0.753858507},
-    {-3.26565409, 0.129954174, 0.838366866},
-    {-3.36633968, 0.230656162, 1.00461483},
-    {-3.34476709, 0.255515128, 0.614818394},
-    {-3.42521405, 0.265439659, 1.42165828},
-    {-3.41179729, 0.261228412, 1.06403136},
-    {-3.22841454, 0.310802907, 1.13532662},
-    {-3.36648822, 0.411557525, 0.909175694},
-    {-3.24508691, 0.369477004, 0.53188616},
-    {-3.20075154, 0.393287718, 0.820287824},
-    {-3.32795477, 0.333985597, 0.829667985},
-    {-3.17282009, -0.00145581504, 0.839004874},
-    {-3.22976255, 0.158924624, 0.714277506},
-    {-3.25093818, -0.151617303, 0.647786438},
-    {-3.12521124, 0.111390121, 0.553902745},
-    {-3.26736784, -0.0661627799, 0.247907355},
-    {-3.09357429, -0.197931543, 0.0855976343},
-    {-3.02727818, -0.342448026, 0.0529040284},
-    {-3.07161331, -0.236858457, -0.0267525353},
-    {-2.99210763, -0.422356009, -0.581659079},
-    {-2.99543977, -0.556365192, -0.990584731},
-    {-2.94030643, -0.643905103, -1.1879096},
-    {-2.95482445, -0.487708181, -1.26701427},
-    {-2.95422935, -0.12485712, -1.54439747},
-    {-2.9515512, -0.560038686, -1.35247743},
-    {-2.87193823, -0.184132695, -1.2396003},
-    {-2.85483646, -0.126364604, -1.15022373},
-    {-2.85425162, -0.278503418, -1.07241356},
-    {-2.8510282, -0.0427063107, -0.928255737},
-    {-2.91777849, -0.245258331, -0.720435381},
-    {-2.73221159, -0.0858584344, -0.47815147},
-    {-2.91718388, -0.0382998958, -0.363841534},
-    {-2.81229687, -0.355626196, 0.0470973477},
-    {-2.72853565, -0.140730843, 0.282940537},
-    {-2.7642417, -0.271764576, 0.286067247},
-    {-2.75141311, 0.00208623405, 0.30458504},
-    {-2.7364502, -0.327792138, 0.355837524},
-    {-2.86377311, -0.275208801, 0.530099452},
-    {-2.7615633, -0.406242669, 0.365426093},
-    {-2.68915892, -0.393545449, 0.527951837},
-    {-2.74028873, -0.384079158, 0.549455225},
-    {-2.74603319, -0.676985979, 0.374388397},
-    {-2.716187, -0.584149063, 0.504639149},
-    {-2.64150119, -0.911358654, 0.607224882},
-    {-2.67646337, -0.792605042, 0.574617863},
-    {-2.70589423, -0.983553469, 0.78306967},
-    {-2.63177252, -1.07673907, 1.06539583},
-    {-2.60836911, -1.20674872, 0.968885481},
-    {-2.54256511, -1.24800313, 0.853043795},
-    {-2.60412931, -1.25760186, 0.694686413},
-    {-2.58082676, -1.15734994, 0.537841797},
-    {-2.48237967, -1.05810654, 0.609944701},
-    {-2.56782985, -0.944345295, 0.554228783},
-    {-2.57217121, -1.20128036, 0.526972711},
-    {-2.42384195, -1.03879857, 0.186459199},
-    {-2.56143594, -0.780711472, 0.213778302},
-    {-2.4767971, -0.979632616, 0.233707249},
-    {-2.32047558, -0.726452708, -0.0030836768},
-    {-2.38396955, -0.600322366, -0.129338548},
-    {-2.51786828, -0.614997864, -0.0815444589},
-    {-2.36756921, -0.681664467, -0.0938760862},
-    {-2.3283267, -0.440835625, -0.0639752299},
-    {-2.43946314, -0.273262173, 0.161445543},
-    {-2.39706111, 0.000186573059, 0.0899779201},
-    {-2.31479359, -0.133933961, 0.196103558},
-    {-2.37696338, 0.199947789, 0.0800879374},
-    {-2.42160964, 0.390142918, 0.28934288},
-    {-2.32922935, 0.314976662, 0.358250499},
-    {-2.42577577, 0.698334217, 0.406073332},
-    {-2.28875256, 0.59440577, 0.568513334},
-    {-2.28439498, 0.689719021, 0.876262009},
-    {-2.4185853, 0.869431794, 0.819424272},
-    {-2.36325788, 0.907724977, 0.936544538},
-    {-2.36270905, 0.515935302, 0.747249663},
-    {-2.22820091, 0.716604173, 0.440467119},
-    {-2.32304144, 1.09535539, 0.476043284},
-    {-2.24998474, 0.789239049, 0.392985314},
-    {-2.23459792, 0.551726162, 0.324183315},
-    {-2.20191503, 0.66201669, 0.379613966},
-    {-2.15854168, 0.678866386, 0.234862313},
-    {-2.07472181, 0.730853319, 0.211906001},
-    {-1.95665538, 0.673455954, 0.0560883805},
-    {-1.88765192, 0.555619776, 0.0465017557},
-    {-1.74423158, 0.527616024, 0.0764288604},
-    {-1.70421052, 0.574338913, 0.161296636},
-    {-1.53169775, 0.362733603, 0.180286974},
-    {-1.39625812, -0.00609334605, 0.0401042253},
-    {-1.29343927, 0.137210429, -0.0385149941},
-    {-1.20819044, -0.121562503, -0.00382335647},
-    {-1.13127315, -0.11647097, 0.0101723764},
-    {-1.0546037, -0.352449566, -0.145720854},
-    {-1.02549338, -0.395610213, -0.323045343},
-    {-1.01076448, -0.559739351, -0.357588202},
-    {-0.981450796, -0.695381582, -0.535632908},
-    {-0.972677708, -0.789909542, -0.664898932},
-    {-0.968161881, -1.01837921, -0.800284743},
-    {-0.956878603, -1.13130724, -0.808900774},
-    {-0.94628191, -1.19391346, -0.79937166},
-    {-0.958088696, -1.20703924, -0.823580623},
-    {-0.936971307, -1.28289545, -0.710459888},
-    {-0.932985842, -1.33221424, -0.716162801},
-    {-0.952732146, -1.19777787, -0.675340414},
-    {-0.906918466, -1.09884942, -0.740386784},
-    {-0.940690815, -0.967366219, -0.769420564},
-    {-0.944094658, -0.802034736, -0.690896213},
-    {-0.931895316, -0.745793939, -0.629743278},
-    {-0.932354033, -0.626399934, -0.52275449},
-    {-0.916588902, -0.606761515, -0.455409467},
-    {-0.941209137, -0.494034022, -0.324028969},
-    {-0.953653574, -0.427024394, -0.233163357},
-    {-0.953599393, -0.260947138, -0.107749172},
-    {-0.926537156, -0.180994362, -0.0475576259},
-    {-0.950009584, -0.263723344, -0.0199668407},
-    {-0.947049797, -0.315106004, 0.0531683005},
-    {-0.913365424, -0.274033576, 0.169169843},
-    {-0.92822504, -0.221320629, 0.330008119},
-    {-0.895294785, -0.212153181, 0.429871857},
-    {-0.952732027, -0.246625409, 0.543451607},
-    {-0.94092077, -0.234389886, 0.635802925},
-    {-0.903199017, -0.310700297, 0.697750628},
-    {-0.912720799, -0.227138296, 0.808376491},
-    {-0.934590876, -0.199284285, 0.897115588},
-    {-0.939202964, -0.249900758, 0.964116514},
-    {-0.949432611, -0.220304132, 1.18545413},
-    {-0.936760008, -0.280324668, 1.29639769},
-    {-0.936673939, -0.180415273, 1.24462688},
-    {-0.93947798, -0.381202042, 1.19397247},
-    {-0.9009673, -0.556145191, 1.2537092},
-    {-0.899033248, -0.537426054, 1.01786613},
-    {-0.863773346, -0.461052209, 0.724848747},
-    {-0.867343843, -0.530773282, 0.713045776},
-    {-0.88146776, -0.40877831, 0.705552518},
-    {-0.849310637, -0.407921642, 0.723296702},
-    {-0.861839175, -0.347988725, 0.663207948},
-    {-0.832789481, -0.366891325, 0.610462129},
-    {-0.853061318, -0.451362222, 0.51093632},
-    {-0.803456306, -0.428261071, 0.416500479},
-    {-0.817206323, -0.450569451, 0.389099747},
-    {-0.785688281, -0.407340825, 0.314559519},
-    {-0.791631103, -0.339220941, 0.316445798},
-    {-0.790016353, -0.250654012, 0.321345329},
-    {-0.761223197, -0.254200071, 0.203634426},
-    {-0.766324818, -0.290333927, 0.0902756676},
-    {-0.780012131, -0.274909317, 0.0322082713},
-    {-0.736271977, -0.155256882, -0.0499795564},
-    {-0.769186616, -0.0847673044, -0.109991342},
-    {-0.784187973, 0.0894393176, -0.200974852},
-    {-0.766771138, 0.234699488, -0.289842725},
-    {-0.776887953, 0.116993867, -0.336296827},
-    {-0.774953902, 0.144398615, -0.315600991},
-    {-0.762749672, 0.101492159, -0.268298805},
-    {-0.741627932, 0.108757384, -0.0958380327},
-    {-0.780756116, 0.286214411, 0.0377171971},
-    {-0.746172786, 0.309875399, 0.0633119717},
-    {-0.765878439, 0.402123123, 0.162338898},
-    {-0.763165474, 0.409804553, 0.24370341},
-    {-0.777041495, 0.425040126, 0.149534315},
-    {-0.755694389, 0.398297191, 0.15076381},
-    {-0.740099549, 0.419076979, 0.139283359},
-    {-0.7523399, 0.547533154, 0.171123445},
-    {-0.773107052, 0.580910385, 0.190593213},
-    {-0.764033675, 0.509066641, 0.2656295},
-    {-0.777032197, 0.43853575, 0.288138181},
-    {-0.754619479, 0.332444578, 0.329202414},
-    {-0.753232479, 0.312720716, 0.363490492},
-    {-0.738354862, 0.26405102, 0.396246493},
-    {-0.711872578, 0.163417116, 0.40964669},
-    {-0.706516802, 0.125379965, 0.424089104},
-    {-0.751298428, 0.0681744367, 0.525483847},
-    {-0.721989393, -0.0114940163, 0.470989764},
-    {-0.678730547, -0.0830760375, 0.471839309},
-    {-0.686432004, -0.115023255, 0.529106855},
-    {-0.698550522, -0.174416214, 0.467456967},
-    {-0.711723804, -0.25933513, 0.457738459},
-    {-0.702946067, -0.300067812, 0.422153533},
-    {-0.665852904, -0.264247954, 0.373005092},
-    {-0.640121877, -0.41619876, 0.281641126},
-    {-0.626076818, -0.477418721, 0.229147643},
-    {-0.636082351, -0.54485935, 0.18346335},
-    {-0.632723749, -0.614698648, 0.126009449},
-    {-0.593149245, -0.664266825, 0.0713665411},
-    {-0.615740657, -0.698061109, -0.0114483666},
-    {-0.588834703, -0.70664686, -0.0638263673},
-    {-0.581991196, -0.754417956, -0.0964335352},
-    {-0.577700555, -0.693371952, -0.0673277453},
-    {-0.610556185, -0.682386756, -0.161498889},
-    {-0.596985936, -0.537888706, -0.252994627},
-    {-0.58384347, -0.58701843, -0.339827091},
-    {-0.601332009, -0.495944619, -0.38706851},
-    {-0.542416573, -0.472433239, -0.428758204},
-    {-0.550747991, -0.317606628, -0.421506196},
-    {-0.560745835, -0.294407159, -0.452223361},
-    {-0.569575012, -0.199538291, -0.47533834},
-    {-0.585072219, -0.252345115, -0.474462539},
-    {-0.563227236, -0.146534905, -0.51172179},
-    {-0.600876927, -0.146641672, -0.501802146},
-    {-0.58021605, -0.0411040075, -0.514703989},
-    {-0.561906219, 0.00288203172, -0.506925821},
-    {-0.566256821, 0.0360001586, -0.491653293},
-    {-0.582139909, -0.0102962041, -0.462109625},
-    {-0.588685989, 0.0230987631, -0.404339999},
-    {-0.57231617, -0.0165675636, -0.306126058},
-    {-0.584918618, 0.00194510072, -0.237466812},
-    {-0.54464829, 0.00767432619, -0.218226358},
-    {-0.583925188, 0.0335815102, -0.139463052},
-    {-0.57231617, 0.0380332582, -0.0902794003},
-    {-0.572939634, 0.0306974351, 0.0365693383},
-    {-0.572171807, -0.0162862819, 0.100251444},
-    {-0.573903024, -0.0949837714, 0.170180559},
-    {-0.568303645, -0.0326093212, 0.203134999},
-    {-0.564185977, -0.0704001188, 0.27848345},
-    {-0.5479213, -0.106587119, 0.351877034},
-    {-0.538846016, -0.126953602, 0.40101102},
-    {-0.558633149, -0.200781643, 0.459078461},
-    {-0.547213495, -0.21493116, 0.541667819},
-    {-0.523303151, -0.242342561, 0.522427201},
-    {-0.511867881, -0.255271941, 0.547688425},
-    {-0.526943922, -0.278952718, 0.610947192},
-    {-0.533219516, -0.334442914, 0.538780212},
-    {-0.536912024, -0.389919311, 0.494663417},
-    {-0.510741651, -0.410793126, 0.529311776},
-    {-0.513256371, -0.421517491, 0.584146857},
-    {-0.503734767, -0.455810726, 0.6213696},
-    {-0.496742278, -0.567676246, 0.62315625},
-    {-0.50292325, -0.59190917, 0.642733157},
-    {-0.496138513, -0.671798646, 0.574976921},
-    {-0.468911022, -0.674155653, 0.553038895},
-    {-0.473533183, -0.681338549, 0.55407089},
-    {-0.457045972, -0.759051263, 0.530261874},
-    {-0.465744138, -0.77638334, 0.446931869},
-    {-0.439848572, -0.836702526, 0.368421435},
-    {-0.470131159, -0.791187286, 0.321533054},
-    {-0.436271429, -0.81176424, 0.239482492},
-    {-0.445164979, -0.769272506, 0.244209662},
-    {-0.449544102, -0.748160064, 0.193281189},
-    {-0.382171005, -0.761084139, 0.155453831},
-    {-0.40170297, -0.724288702, 0.149534315},
-    {-0.395723104, -0.744683981, 0.0716644153},
-    {-0.393045217, -0.701705039, 0.0526063666},
-    {-0.405542344, -0.662769437, -0.0359837636},
-    {-0.364628971, -0.665015519, -0.0821400806},
-    {-0.404203445, -0.627577305, -0.104473695},
-    {-0.378316283, -0.60241884, -0.14244093},
-    {-0.371174932, -0.56662792, -0.130827457},
-    {-0.371928006, -0.531644702, -0.157126829},
-    {-0.363416106, -0.458456278, -0.16766654},
-    {-0.368249118, -0.407181084, -0.15888837},
-    {-0.362262011, -0.348964304, -0.166222647},
-    {-0.37444815, -0.324477524, -0.169092417},
-    {-0.359162509, -0.2817159, -0.178448483},
-    {-0.356491119, -0.269531876, -0.160158902},
-    {-0.34779799, -0.253272444, -0.150629893},
-    {-0.362262011, -0.213479027, -0.136047557},
-    {-0.366994947, -0.199477494, -0.106980734},
-    {-0.385606408, -0.176671609, -0.0726110712},
-    {-0.364425957, -0.123010099, -0.0397467464},
-    {-0.374150515, -0.125156507, -0.0137990676},
-    {-0.377869964, -0.0898149386, -0.000547759526},
-    {-0.358082712, -0.0812789425, 0.0578175709},
-    {-0.342610031, -0.0695982948, 0.0573708713},
-    {-0.349854887, -0.0440131947, 0.0639175251},
-    {-0.363616228, -0.055714868, 0.0957413912},
-    {-0.346775681, -0.0510290228, 0.0969758481},
-    {-0.354958445, -0.0770860463, 0.155341089},
-    {-0.339634448, -0.0751391724, 0.156532243},
-    {-0.33749032, -0.018523654, 0.188631326},
-    {-0.344762295, -0.0386691317, 0.191620797},
-    {-0.343056351, -0.0248220637, 0.190926015},
-    {-0.345287979, -0.0436910801, 0.228744239},
-    {-0.353470623, -0.0772357732, 0.239166558},
-    {-0.379862696, -0.0723301694, 0.255075365},
-    {-0.342461139, -0.100597128, 0.279218227},
-    {-0.361926943, -0.0758107156, 0.276485384},
-    {-0.336807638, -0.0880179033, 0.31897217},
-    {-0.340910286, -0.121412717, 0.309506297},
-    {-0.359754294, -0.135507241, 0.318394095},
-    {-0.348888308, -0.169333756, 0.336779535},
-    {-0.306903601, -0.167986006, 0.354705989},
-    {-0.336807579, -0.163942605, 0.36215052},
-    {-0.343800128, -0.186105996, 0.352174848},
-    {-0.317683131, -0.198086217, 0.338382125},
-    {-0.329666406, -0.209467411, 0.321652144},
-    {-0.306639582, -0.216327101, 0.321056604},
-    {-0.31627652, -0.208718628, 0.33311677},
-    {-0.324756712, -0.230732232, 0.321205497},
-    {-0.315086216, -0.227112517, 0.324323684},
-    {-0.316892177, -0.272446215, 0.305613041},
-    {-0.280570209, -0.234925434, 0.304827482},
-    {-0.299018472, -0.24465932, 0.270135939},
-    {-0.320739865, -0.259484857, 0.259862453},
-    {-0.304024279, -0.273490995, 0.251971245},
-    {-0.284299523, -0.265814394, 0.236089498},
-    {-0.304266214, -0.259512067, 0.237894297},
-    {-0.275310248, -0.323608071, 0.249127895},
-    {-0.273825705, -0.296541929, 0.21926941},
-    {-0.288540989, -0.274469197, 0.235439852},
-    {-0.268092215, -0.269194603, 0.217620641},
-    {-0.28533107, -0.25933519, 0.17946133},
-    {-0.290538162, -0.258736014, 0.152214348},
-    {-0.272833824, -0.279102504, 0.125413984},
-    {-0.266585201, -0.257837564, 0.110227153},
-    {-0.292025954, -0.243161798, 0.09801808},
-    {-0.264651179, -0.223693952, 0.079555653},
-    {-0.256914794, -0.231630936, 0.0719621629},
-    {-0.249155879, -0.24194099, 0.0659387782},
-    {-0.248723105, -0.253703535, 0.0708477795},
-    {-0.283756942, -0.222355872, 0.0497870184},
-    {-0.253046572, -0.225640759, 0.0266992226},
-    {-0.262419552, -0.180714965, 0.0246148407},
-    {-0.244395047, -0.213914663, 0.00428892206},
-    {-0.246054113, -0.173976064, 0.0128523502},
-    {-0.220345616, -0.192974642, -0.00213600672},
-    {-0.260553062, -0.160185158, -0.0162130501},
-    {-0.220464602, -0.142078713, -0.0179680698},
-    {-0.242632285, -0.128750756, -0.00173894502},
-    {-0.228237033, -0.111247793, -0.0411905237},
-    {-0.246130913, -0.154802889, -0.0462717861},
-    {-0.230978116, -0.134772599, -0.0329610519},
-    {-0.230730221, -0.126953721, -0.0286883228},
-    {-0.231387675, -0.126359537, -0.0507289022},
-    {-0.223764762, -0.104858324, -0.043789424},
-    {-0.235193446, -0.0779844448, -0.0274970792},
-    {-0.231848434, -0.113219775, -0.0107684694},
-    {-0.207521081, -0.0955054164, -0.0202014595},
-    {-0.225225449, -0.0937085673, -0.0401527062},
-    {-0.227570876, -0.0744784251, -0.0118986275},
-    {-0.19431971, -0.0829163492, -0.0475576855},
-    {-0.196809202, -0.108384326, -0.0246681236},
-    {-0.212223306, -0.0694259033, -0.0258863531},
-    {-0.204396814, -0.0823272988, -0.0209458247},
-    {-0.210050285, -0.0911628008, -0.0091834832},
-    {-0.233384132, -0.106881969, -0.0132275838},
-    {-0.199933469, -0.117669113, 0.0134479729},
-    {-0.233854458, -0.108833551, 0.0127034299},
-    {-0.213521704, -0.0955647081, 0.0074651204},
-    {-0.180942684, -0.0963247195, 0.0269182138},
-    {-0.209237039, -0.0827566087, 0.0436034985},
-    {-0.197553083, -0.0869696662, 0.0368239135},
-    {-0.180628687, -0.085108988, 0.0341754295},
-    {-0.188031435, -0.061960876, 0.0255080964},
-    {-0.204545587, -0.0663037971, 0.0377172567},
-    {-0.203283384, -0.0717915222, 0.0290382691},
-    {-0.19785063, -0.0598644577, 0.0548397265},
-    {-0.193089828, -0.0770859867, 0.0649643019},
-    {-0.189370394, -0.0892159864, 0.056775365},
-    {-0.193612784, -0.0692805946, 0.0617519543},
-    {-0.189615205, -0.0818393603, 0.0691524297},
-    {-0.186543673, -0.0766866282, 0.0841307044},
-    {-0.182675466, -0.0990996584, 0.07687556},
-    {-0.198829696, -0.0818394199, 0.0983543247},
-    {-0.158398673, -0.0505179949, 0.0906786621},
-    {-0.152583048, -0.0509690419, 0.110941835},
-    {-0.174569383, -0.0864159912, 0.143037274},
-    {-0.203206584, -0.0433914848, 0.126902893},
-    {-0.178464636, -0.0470626801, 0.132642016},
-    {-0.173643291, -0.0435025543, 0.151224956},
-    {-0.164822325, -0.0528259352, 0.180950269},
-    {-0.16883935, -0.0854721367, 0.190330386},
-    {-0.164822325, -0.066153951, 0.179759145},
-    {-0.142505914, -0.0686997771, 0.191819295},
-    {-0.158538714, -0.0832169876, 0.197880074},
-    {-0.142928213, -0.0932786018, 0.187189296},
-    {-0.166458875, -0.0863705948, 0.21832186},
-    {-0.142654628, -0.0737914294, 0.216684118},
-    {-0.149378359, -0.0867860615, 0.196257249},
-    {-0.151342317, -0.100501925, 0.203243345},
-    {-0.150837347, -0.108983397, 0.222937524},
-    {-0.147074804, -0.12063989, 0.227457061},
-    {-0.141315669, -0.125006899, 0.233806521},
-    {-0.14771308, -0.121862128, 0.235742137},
-    {-0.157978594, -0.127473399, 0.233894125},
-    {-0.145124376, -0.130837262, 0.234660134},
-    {-0.133885875, -0.146680146, 0.242947549},
-    {-0.125267014, -0.139499187, 0.24098213},
-    {-0.141532093, -0.147261024, 0.231397226},
-    {-0.159132779, -0.148568034, 0.243958205},
-    {-0.143849701, -0.16330494, 0.260962307},
-    {-0.127925843, -0.163193926, 0.230977595},
-    {-0.152473882, -0.189400613, 0.244973361},
-    {-0.143993646, -0.19179666, 0.214450687},
-    {-0.124075696, -0.189228162, 0.242803156},
-    {-0.133560136, -0.176444575, 0.236371323},
-    {-0.107989818, -0.17053172, 0.214748472},
-    {-0.131198928, -0.182961226, 0.241995513},
-    {-0.0966827944, -0.160048977, 0.229935363},
-    {-0.107989803, -0.161863714, 0.255334407},
-    {-0.110052831, -0.152561456, 0.261659056},
-    {-0.107989818, -0.146122068, 0.281451643},
-    {-0.114982292, -0.13309361, 0.269838125},
-    {-0.135215878, -0.139383227, 0.267009228},
-    {-0.115419567, -0.164832056, 0.26648131},
-    {-0.118701696, -0.142228439, 0.278027177},
-    {-0.10257978, -0.167736441, 0.26648128},
-    {-0.105291963, -0.17907767, 0.258006275},
-    {-0.0968089625, -0.198667154, 0.263160586},
-    {-0.0895955861, -0.182257757, 0.270523936},
-    {-0.112827413, -0.187883705, 0.279251873},
-    {-0.104716726, -0.177420408, 0.286365062},
-    {-0.0867147669, -0.170082554, 0.280260533},
-    {-0.104865514, -0.178019345, 0.300509661},
-    {-0.0927695036, -0.179208308, 0.306907475},
-    {-0.086873129, -0.163150445, 0.301844895},
-    {-0.0905829743, -0.159000784, 0.289045036},
-    {-0.085078232, -0.208419293, 0.286811739},
-    {-0.0813723207, -0.220449314, 0.305896789},
-    {-0.0704631433, -0.207952291, 0.30045712},
-    {-0.0816409662, -0.207339913, 0.30495587},
-    {-0.0780857205, -0.209018126, 0.296340734},
-    {-0.083103545, -0.207089499, 0.289004505},
-    {-0.0845695287, -0.225292936, 0.298309952},
-    {-0.0630418211, -0.237268686, 0.334088981},
-    {-0.0522879176, -0.222046763, 0.298186988},
-    {-0.0554040857, -0.216964111, 0.320767879},
-    {-0.0750478134, -0.236268342, 0.329509765},
-    {-0.0780541524, -0.216238111, 0.284528732},
-    {-0.0760344118, -0.206218243, 0.291603297},
-    {-0.0618403181, -0.20102334, 0.274026304},
-    {-0.0899877995, -0.208269447, 0.304083049},
-    {-0.0593399256, -0.220099881, 0.31093204},
-    {-0.0815166235, -0.210574701, 0.310083866},
-    {-0.0639904067, -0.217409223, 0.309375882},
-    {-0.0501158051, -0.215457574, 0.29857406},
-    {-0.0442954898, -0.21086508, 0.304886162},
-    {-0.0560668521, -0.232529387, 0.305423051},
-    {-0.0583080947, -0.211380407, 0.325206339},
-    {-0.0538352244, -0.228935316, 0.32939449},
-    {-0.0520859547, -0.236422896, 0.335927635},
-    {-0.0749614835, -0.230882078, 0.324629992},
-    {-0.0602325983, -0.236572742, 0.318078786},
-    {-0.069605507, -0.234775767, 0.318078816},
-    {-0.0698309243, -0.24600707, 0.31643647},
-    {-0.043242339, -0.256070524, 0.314545125},
-    {-0.0769000128, -0.240198418, 0.341269702},
-    {-0.0473250896, -0.25254184, 0.328564346},
-    {-0.066140458, -0.258219272, 0.345032871},
-    {-0.0489120707, -0.265611172, 0.346467376},
-    {-0.0547758676, -0.276923776, 0.332583666},
-    {-0.047036618, -0.259221584, 0.334917009},
-    {-0.045057416, -0.269069105, 0.321652204},
-    {-0.0446398593, -0.258682996, 0.343803316},
-    {-0.0499669984, -0.251547813, 0.355599314},
-    {-0.0377673544, -0.282397002, 0.367361695},
-    {-0.0591911338, -0.27386117, 0.398479909},
-    {-0.045057416, -0.262929201, 0.384484142},
-    {-0.0453549847, -0.273561567, 0.376444042},
-    {-0.0307342969, -0.276792645, 0.389781058},
-    {-0.0315859616, -0.278624207, 0.386837572},
-    {-0.0243775174, -0.277305335, 0.394013137},
-    {-0.0655885115, -0.298420578, 0.399968803},
-    {-0.0493719243, -0.303811729, 0.39237535},
-    {-0.0378034301, -0.314258069, 0.389347911},
-    {-0.0483349673, -0.304964215, 0.400320709},
-    {-0.0407428779, -0.299618572, 0.401308835},
-    {-0.0420290902, -0.289599627, 0.421572387},
-    {-0.0169387106, -0.302613646, 0.425578058},
-    {-0.0289895628, -0.324776977, 0.406073332},
-    {-0.0289895777, -0.296922982, 0.41396454},
-    {-0.027204264, -0.325226396, 0.416793466},
-    {-0.0359820575, -0.32462731, 0.425578028},
-    {-0.0388088189, -0.311299294, 0.407562226},
-    {-0.0131336441, -0.33052209, 0.41461426},
-    {-0.0100950226, -0.317439139, 0.414708972},
-    {-0.013814426, -0.327322751, 0.390886426},
-    {-0.0120818699, -0.358698338, 0.386837572},
-    {-0.0225110594, -0.353030324, 0.368990481},
-    {-0.0249822233, -0.370292366, 0.376232713},
-    {-0.0266091451, -0.375692934, 0.385973036},
-    {-0.0164923668, -0.400402099, 0.392673105},
-    {-0.0278489403, -0.40487203, 0.368412942},
-    {-0.0179801285, -0.403397232, 0.372870654},
-    {-0.00979744084, -0.401450276, 0.372572869},
-    {-0.00824250653, -0.405691803, 0.369009107},
-    {-0.00505463406, -0.411551923, 0.361915886},
-    {-0.0172362477, -0.415677011, 0.352323741},
-    {-0.0132779013, -0.401967824, 0.351520598},
-    {-0.00532455603, -0.403527558, 0.359941155},
-    {-0.000573327008, -0.398605078, 0.348005861},
-    {0.00210466585, -0.409087837, 0.33192566},
-    {-0.0203605462, -0.407440573, 0.349048138},
-    {-0.014707068, -0.426459134, 0.343539178},
-    {0.0129788583, -0.409664214, 0.338815272},
-    {0.000319344661, -0.447125047, 0.333563417},
-    {0.00493141264, -0.424662054, 0.322992176},
-    {-0.00235863333, -0.43933785, 0.297680736},
-    {0.0157152899, -0.458404988, 0.297234058},
-    {-0.0211044569, -0.438439339, 0.287109464},
-    {0.0122574968, -0.429994255, 0.286694407},
-    {0.03306932, -0.457322806, 0.331354052},
-    {-0.663669229, -0.388571739, 0.262393564},
-    {0.317064047, -0.455062091, 0.353217065},
-    {0.14253144, -0.52903074, 0.220568791},
-    {0.0369087048, -0.419604272, 0.293084323},
-    {0.0405340083, -0.456278265, 0.222445697},
-    {0.0326037891, -0.435444415, 0.204623908},
-    {0.0144530935, -0.404744953, 0.25539571},
-    {-0.00101515162, -0.423169225, 0.228942767},
-    {-0.0280537494, -0.347877592, 0.229147643},
-    {-0.00801212713, -0.375093997, 0.240059942},
-    {0.00924591348, -0.424811929, 0.176632375},
-    {0.011923884, -0.394861221, 0.272964835},
-    {-21.6728153, -2.02522016, 2.18055534},
-    {-93.3423538, -0.359420091, -1.53046119},
-    {-44.9157181, -0.00547503866, -2.04967117},
-    {7.87356091, -2.95338845, 3.24214745},
-    {11.4889727, 0.73352617, -1.41650009},
-    {3.41842341, -0.447710544, 0.0520783514},
-    {0.299830019, -0.273522973, 0.278790772},
-    {0.222600117, -0.440595061, 0.233562917},
-    {0.152219936, -0.43020317, -0.0358349606},
-    {0.407222509, -0.484862864, -0.228053212},
-    {-0.0931121707, -0.210815161, 0.0180635862},
-    {-0.0360396877, -0.508335471, 0.183346897},
-    {0.0425537601, -0.6078825, 0.240637466},
-    {-0.142357141, -0.422715515, 0.170974523},
-    {-0.285777479, -0.426459253, 0.0457572713},
-    {-0.338746369, -0.410245091, 0.0169943068},
-    {-0.39141345, -0.537242472, 0.0523997396},
-    {-0.401079059, -0.457607806, 0.0252103433},
-    {-0.402801245, -0.523948312, 0.0530889779},
-    {-0.388879418, -0.51136899, 0.108738154},
-    {-0.409842491, -0.621645272, 0.0922065079},
-    {-0.207074761, -1.78696382, -0.264978141},
-    {3.57333088, -5.98288918, -0.581073523},
-    {24.1139774, -6.64794016, -2.38533378},
-    {36.8880005, -4.86863184, 1.87226534},
-    {32.5338478, -10.0189686, 2.42191625},
-    {33.7533264, -6.53227091, 4.55114698},
-    {35.9800758, -6.16364002, 4.67150021},
-    {14.4775686, -3.15538692, 5.88398266},
-    {-0.538845837, 1.59894764, -0.176296279},
-    {-0.560486257, -0.577387333, 1.48128676},
-    {-0.431131959, -1.54047048, 1.13965893},
-    {-0.432322115, -1.13089657, 1.87532866},
-    {-0.476955056, -1.60950649, 2.10328078},
-    {-0.530216932, -1.61100423, 2.44974995},
-    {-1.66880178, 0.113400012, 1.29703629},
-    {0.223781198, -2.12570477, 4.82262468},
-    {-0.595232069, 0.567749739, 3.8164196},
-    {-0.72377497, -0.686280251, 3.37391615},
-    {-1.05157399, 0.253822386, 4.18695021},
-    {-0.737265468, -0.0860131085, 3.84479547},
-    {-0.726750314, -0.142827377, 4.27693939},
-    {-0.66843009, 0.0657782778, 4.72495174},
-    {-0.796675146, 0.964744508, 5.34538031},
-    {-0.811800718, 0.539750516, 5.7736764},
-    {-0.960329175, 1.34032464, 5.69304037},
-    {-11.4198961, 6.95291138, 18.2003231},
-    {-9.94299507, 4.95206308, 20.1092587},
-    {-5.9100852, 3.66593623, 14.0516529},
-    {-5.7616477, 3.52025628, 13.5717945},
-    {-5.36864805, 5.06072426, 13.8321972},
-    {-4.79652596, 4.11629295, 12.7565756},
-    {-5.52508354, 5.0464077, 15.0840359},
-    {-5.80032015, 5.265347, 15.7559834},
-    {-5.41975021, 4.9075861, 13.7724581},
-    {-5.49636936, 3.58541846, 13.690567},
-    {-5.46423435, 2.69274211, 11.7875919},
-    {-5.42318058, 0.531763673, 10.2579479},
-    {-4.94461966, 0.83545953, 11.5253372},
-    {-4.16422653, 0.282770127, 10.8669996},
-    {-4.02675724, -0.116470851, 9.64386082},
-    {-3.36098313, 0.373670101, 8.46807003},
-    {-2.14562988, -0.0324595422, 9.26374245},
-    {-0.44526571, -0.588791192, 8.18338966},
-    {2.63098168, -0.645996928, 5.99782085},
-    {3.39909077, -0.211010337, 4.09036112},
-    {2.39736462, -0.311550409, 1.23399818},
-    {3.85194802, 0.394245207, -1.35836077},
-    {5.10520792, 2.95356345, -4.98337984},
-    {3.22891355, 3.03402877, -8.13564873},
-    {0.60043788, 2.7038877, -7.44364834},
-    {3.65372419, 5.26707506, -11.3678722},
-    {2.57474422, 7.46477509, -16.1246471},
-    {2.02709866, 7.26080179, -15.2359591},
-    {0.990425646, 6.19665909, -14.7120113},
-    {0.698107243, 6.41281986, -15.5002909},
-    {0.0138723673, 5.47203875, -14.5726471},
-    {-0.302886754, 5.17639256, -14.0833969},
-    {-0.539440989, 3.54498553, -12.2846451},
-    {-0.867790341, 2.66683531, -11.928793},
-    {-1.0778625, 3.83251119, -14.466939},
-    {-0.815263212, 3.12820506, -11.3111305},
-    {-0.763373196, 3.33399343, -10.5898218},
-    {-0.474425793, 3.13735819, -10.1278105},
-    {-0.651469588, 3.85063124, -9.22031975},
-    {-0.288901657, 4.70901442, -8.01711464},
-    {-0.0935485736, 5.93882465, -6.88891649},
-    {0.133176565, 6.16805601, -5.81265306},
-    {0.138059124, 6.23812675, -5.1796422},
-    {0.422843903, 6.74026155, -5.44385099},
-    {0.822033286, 8.14145851, -6.14510489},
-    {1.18657506, 10.3233337, -7.37408733},
-    {1.59058893, 9.08359528, -6.3596797},
-    {2.14969039, 8.31461239, -5.35645199},
-    {2.54762197, 7.25811672, -5.30857229},
-    {2.94701147, 6.25546789, -4.32249594},
-    {4.1418047, 5.00282955, -2.78823209},
-    {4.52341557, 3.26000595, -0.924862623},
-    {4.12201738, 1.20944059, 1.24298918},
-    {2.89675021, -3.12314892, 5.10029316},
-    {-2.03298211, -9.96189404, 10.5775089},
-    {-5.0461731, -12.2217398, 13.9777803},
-    {1.86909819, -1.45181692, 6.13450289},
-    {2.23970008, -1.27825332, 10.3156576},
-    {-0.0976747498, -5.33912754, 15.2986517},
-    {-7.37615824, -8.42311096, 24.5322075},
-    {-7.93069983, -7.42644644, 24.9254131},
-    {1.92696249, 1.45348442, 2.38793206},
-    {5.97547245, 4.66992855, -1.85453749},
-    {7.67071962, 5.41272593, -3.62294722},
-    {8.05800533, 5.92837, -7.7384944},
-    {6.53680611, 5.09507656, -8.78526115},
-    {5.58166122, 4.49876118, -8.85598278},
-    {5.7908411, 4.93798637, -10.1398726},
-    {5.24081564, 5.97442579, -10.2892065},
-    {5.41086721, 7.29000473, -11.1627512},
-    {4.80397129, 7.66079569, -11.7855625},
-    {4.71935368, 8.80190659, -12.5176601},
-    {4.14250374, 8.52395248, -11.9004869},
-    {3.39138722, 7.16671753, -10.6088867},
-    {3.15244293, 6.854074, -9.56500435},
-    {3.07650781, 6.40933609, -9.83615398},
-    {3.08031464, 6.5392828, -9.39423943},
-    {3.14321804, 5.22431374, -8.96035576},
-    {3.09165597, 4.51631355, -7.83881474},
-    {3.16568351, 3.65430474, -6.78342247},
-    {3.13621664, 3.10443687, -6.09888887},
-    {3.25857425, 2.15976715, -6.0802784},
-    {3.1154604, 1.09969902, -4.87529039},
-    {3.1402092, -0.229157463, -2.14157963},
-    {2.84298801, -1.06096208, -1.87017131},
-    {2.38252544, -2.10518789, 0.443742663},
-    {3.4605577, -2.9074142, -0.689466},
-    {4.84358263, -2.7959981, 1.1858151},
-    {5.52735853, -3.25798607, 0.699686229},
-    {3.92682338, -4.50036669, 4.95028257},
-    {3.38715887, -4.267344, 5.90198803},
-    {3.05469656, -4.32197905, 8.89583492},
-    {2.14554715, -3.52466822, 8.85256004},
-    {0.589622259, -4.544662, 10.3622608},
-    {1.19456112, -3.73835802, 10.044651},
-    {4.83748293, -4.06111002, 4.48672724},
-    {6.23776484, -4.61579418, 3.32939792},
-    {6.8215642, -4.69785976, 2.78922129},
-    {7.15749979, -4.61070299, 0.875377476},
-    {7.66423178, -5.27680349, 0.264329135},
-    {7.6848588, -5.40461922, -0.113524392},
-    {7.65355253, -5.321702, -1.21571422},
-    {7.59281969, -5.98767996, -1.87835968},
-    {7.65855455, -5.95137596, -1.90750396},
-    {7.54223537, -5.56492805, -3.00576234},
-    {7.69235086, -5.81216955, -3.35729337},
-    {7.4409194, -5.14487171, -4.41278124},
-    {7.43354368, -4.94051218, -5.15379763},
-    {7.30077219, -4.02591801, -5.63294268},
-    {7.20811701, -3.53090715, -5.55220079},
-    {7.05023146, -3.38886952, -5.34454012},
-    {6.76368952, -3.55269909, -5.32116556},
-    {6.79612255, -3.08756733, -5.65319157},
-    {6.79046965, -2.34179759, -6.35789251},
-    {6.5611558, -2.17707467, -6.57059002},
-    {6.40900707, -2.09844971, -6.15063572},
-    {6.59244823, -2.15700316, -6.36623001},
-    {6.71593189, -2.81621432, -6.11862469},
-    {6.38049841, -2.46180773, -5.28200674},
-    {6.34815693, -2.6505878, -5.08532143},
-    {6.56533909, -2.7325213, -4.86186314},
-    {6.44960833, -3.26085091, -3.86079907},
-    {6.30911922, -3.2680738, -3.2969389},
-    {6.2224412, -3.072891, -2.81399083},
-    {6.41376829, -2.83328676, -1.98734808},
-    {6.92168951, -2.93526793, -1.32939911},
-    {6.94474983, -2.70599627, -0.201699466},
-    {6.83450747, -2.63711023, 0.493472248},
-    {7.00470686, -2.26961756, 1.08561134},
-    {7.53539276, -2.13858294, 1.60658085},
-    {7.28202534, -1.86932755, 1.61923635},
-    {7.03651857, -2.17968798, 1.70565176},
-    {7.35816097, -1.5424993, 2.2757349},
-    {7.30136633, -0.864635825, 2.91696978},
-    {7.03996706, -0.753519297, 3.78500319},
-    {7.19618273, -0.412232786, 4.14963722},
-    {7.33796644, 0.156378701, 4.433424},
-    {7.42232227, 0.333087087, 4.30805779},
-    {7.35073423, 0.686272323, 4.24932241},
-    {7.15274048, 0.649215281, 4.48657751},
-    {7.29196978, 0.672528446, 4.42391396},
-    {7.41248083, 1.12293327, 4.67278624},
-    {7.31103754, 1.1877265, 4.86967468},
-    {6.89952135, 1.1138984, 4.36895418},
-    {6.8996706, 1.03108501, 4.09916353},
-    {7.12798452, 0.82146734, 3.84419465},
-    {6.9188633, 0.833261549, 2.88168263},
-    {6.74969435, 0.791557789, 2.68963242},
-    {5.68208456, -0.0516279712, 2.5621624},
-    {4.89044714, -0.0967034996, 2.31187701},
-    {3.53095102, -0.424476177, 2.13821149},
-    {2.47384501, -0.497669041, 1.2613554},
-    {5.34882689, 0.0969268605, 1.22869563},
-    {7.66571999, 0.490477294, 0.608118296},
-    {8.34086704, 0.348212123, 0.253162324},
-    {7.64446354, -0.0611486174, -0.458301753},
-    {5.93961859, -1.09136188, -0.255895764},
-    {7.53702831, -0.774484754, -0.709268332},
-    {7.46993017, -1.15320957, -1.21936882},
-    {7.02901602, -1.19353402, -1.4911896},
-    {6.11109781, -1.8852216, -0.766998529},
-    {5.10468531, -2.28474212, -1.21162641},
-    {4.47475243, -2.80629039, -1.17153442},
-    {3.63596559, -3.10418892, -0.912206948},
-    {4.70536947, -3.46973586, -1.41158724},
-    {5.2591157, -3.94145751, -1.53144407},
-    {5.88352871, -4.20906591, -1.66812634},
-    {7.14559889, -4.11936378, -3.50395131},
-    {6.90710974, -4.68638706, -3.73946023},
-    {7.34311056, -4.50725794, -4.34785461},
-    {7.13607693, -4.86513233, -4.49481964},
-    {7.54238415, -5.29911757, -4.85870981},
-    {6.99540234, -5.86407995, -5.06644773},
-    {6.25636292, -6.01598358, -5.44310713},
-    {7.15221643, -5.74732685, -6.3275857},
-    {7.17996597, -5.97689772, -6.11773109},
-    {6.7096076, -5.87831068, -6.03898573},
-    {6.87170219, -5.74163675, -6.05430317},
-    {7.23944759, -6.05572033, -6.1741991},
-    {6.88979816, -6.2288599, -5.49222231},
-    {6.97048855, -6.58384562, -5.10988808},
-    {6.24708414, -6.99501324, -4.02403212},
-    {6.62086439, -6.87017393, -3.23133183},
-    {6.57518911, -6.44757032, -3.00591087},
-    {6.14107513, -7.07442665, -2.73868036},
-    {6.00344276, -6.60585928, -2.38786507},
-    {6.54186392, -5.96192312, -2.53288436},
-    {7.0460391, -5.77796698, -2.12212586},
-    {6.92707539, -5.78519917, -1.38940203},
-    {7.12253809, -5.4409318, -0.776120484},
-    {6.64422178, -5.11986208, -0.287609518},
-    {7.31221437, -4.5556941, -0.56485343},
-    {7.27109766, -4.21138954, -0.553591728},
-    {6.98264837, -4.20587063, 0.118564919},
-    {7.0843029, -3.54820633, 0.50717026},
-    {6.89967108, -3.15106201, 0.123776093},
-    {6.7087903, -2.99427032, 0.251226753},
-    {7.37049818, -2.4529829, -0.0933113694},
-    {6.49678373, -2.26767039, 0.453420639},
-    {6.70923805, -1.69801009, 0.309889793},
-    {7.35754585, -1.50663614, 0.360094815},
-    {7.56453753, -1.11961973, 0.195591211},
-    {7.40655136, -0.998365402, 0.135985136},
-    {7.25093222, -0.547309875, 0.0238702968},
-    {7.48480749, -0.423613757, 0.270284802},
-    {7.12452173, -0.125478685, -0.0852261335},
-    {7.29244089, 0.120138615, 0.148640975},
-    {6.72020864, 0.019258311, 0.134164885},
-    {7.32353354, 0.601593852, -0.492632091},
-    {7.64831305, 0.578831494, 0.0116612837},
-    {6.76731348, -0.194601014, 0.303731114},
-    {7.12887239, 0.0254416559, 0.0694597587},
-    {7.47037554, 0.17839241, -0.187256962},
-    {8.04628944, 0.206246376, -0.503352344},
-    {8.13410759, 0.160449281, -0.0462438539},
-    {8.6464529, -0.0604633503, -0.085862264},
-    {8.73676109, -0.485911161, -0.417293489},
-    {8.66631794, -0.562594116, -0.258830339},
-    {9.19938278, -0.601347864, -0.85245645},
-    {9.37906075, -0.787049353, -0.543010235},
-    {9.46948433, -1.23841882, -0.233859926},
-    {9.53278542, -1.77148879, -0.574526846},
-    {10.0735159, -1.81347013, -0.885406494},
-    {9.67553902, -2.91774702, -0.0936045796},
-    {9.64978695, -2.57496238, -1.11768079},
-    {9.54523087, -3.45160651, -0.258830339},
-    {9.81732368, -2.93377066, -0.774035931},
-    {9.85046196, -3.39339375, -0.994236767},
-    {9.77432728, -3.487257, -1.32240129},
-    {9.79524994, -4.11013317, -1.12381923},
-    {9.6773243, -3.70889091, -1.44568324},
-    {9.53792, -4.0843215, -1.60916519},
-    {9.53241539, -4.06829882, -2.53258705},
-    {9.95390034, -4.08941317, -2.15380836},
-    {9.80328846, -4.15736914, -2.87448549},
-    {9.12774372, -4.73859167, -1.95042348},
-    {9.46874142, -4.43953514, -2.8236692},
-    {9.71990013, -4.95314646, -2.70989299},
-    {9.4724102, -5.47705317, -1.55314267},
-    {9.48618793, -4.9010148, -2.58024073},
-    {9.70365715, -5.7913537, -1.68599319},
-    {9.59103489, -5.28818512, -1.96590805},
-    {9.48748684, -5.19309187, -1.57030475},
-    {9.52393627, -5.52599192, -0.832550228},
-    {9.31505489, -5.65343189, 0.566131055},
-    {8.61163902, -6.01074219, 0.433320343},
-    {9.06466389, -5.85589695, 0.136282951},
-    {9.13220882, -5.49334574, -0.101495765},
-    {9.02866077, -5.68697643, 0.514019191},
-    {8.74899483, -5.25923824, 1.09893286},
-    {8.57816505, -5.30869055, 1.04589725},
-    {8.54141617, -5.63381433, 0.182588071},
-    {8.52862263, -5.8311882, 0.828625679},
-    {8.68925095, -5.76969004, -0.80986464},
-    {8.49078083, -5.49396467, -1.23509371},
-    {8.66761017, -6.10920238, -1.9266367},
-    {8.29589367, -5.78875589, -2.30495644},
-    {8.20071983, -6.34723616, -2.67001319},
-    {8.49102592, -5.77361059, -4.77667999},
-    {8.40097237, -5.585145, -4.73915052},
-    {8.19744587, -5.18949747, -4.47635698},
-    {8.37954807, -5.09620237, -5.00655842},
-    {8.39855194, -4.21197033, -6.20704317},
-    {8.40677452, -3.00779819, -7.11326933},
-    {8.55123615, -2.76844382, -7.32121658},
-    {8.25398254, -1.63137066, -7.14433479},
-    {7.94303894, -1.87172341, -7.10964251},
-    {7.4427042, -1.14706981, -5.57353449},
-    {7.01616287, -1.11562192, -4.01896524},
-    {6.38774538, -1.48396373, -3.90434146},
-    {6.99065447, -2.07534933, -6.4987998},
-    {7.50986147, -3.01394749, -7.97828531},
-    {7.45267248, -3.72401643, -7.53442812},
-    {6.93894863, -3.57995367, -5.49730301},
-    {6.40645361, -3.8457942, -4.90084505},
-    {6.46132183, -5.86146593, -4.13419247},
-    {5.83800364, -5.92807913, -3.14854884},
-    {5.40268373, -6.77418184, -2.8805449},
-    {6.60732126, -9.14027214, -4.28882217},
-    {6.95846891, -8.7561779, -3.30459046},
-    {6.28661346, -8.29448318, -2.24717236},
-    {5.92102003, -6.51346254, -2.97628164},
-    {5.75692081, -6.83662939, -3.71746016},
-    {5.58270359, -6.79799318, -5.247612},
-    {5.22563982, -4.46229792, -6.57437944},
-    {5.06704473, -4.05946207, -6.88407373},
-    {4.29355621, -2.91280556, -6.94869137},
-    {4.16531181, -3.10179305, -7.79751778},
-    {4.33841944, -2.81006551, -9.31509113},
-    {4.1676302, -2.48839617, -9.03674698},
-    {3.65292621, -2.59128618, -7.90948439},
-    {3.61111975, -2.50907159, -8.30687428},
-    {3.34643364, -3.1854465, -8.22459602},
-    {2.89654732, -4.19229317, -7.47278643},
-    {2.68716121, -4.54482079, -7.18765593},
-    {2.63797402, -6.15076065, -7.04874611},
-    {2.18986011, -5.88225412, -5.27515745},
-    {1.99853826, -6.36812115, -4.75560045},
-    {2.66043901, -8.04468441, -6.61904716},
-    {2.53737879, -7.73125362, -6.02786875},
-    {1.97902429, -6.02063036, -4.65447378},
-    {2.23479033, -6.38347769, -5.9992137},
-    {2.8163929, -6.47557926, -8.24350929},
-    {2.22106004, -4.69739532, -6.78298044},
-    {2.03394246, -3.60556197, -6.74337053},
-    {2.7456882, -4.02846432, -8.17391396},
-    {4.11191845, -5.06888294, -10.5346622},
-    {3.54042745, -2.995121, -8.69754601},
-    {3.01095629, -3.2711637, -6.78535748},
-    {4.58515787, -3.44802213, -9.01723385},
-    {5.25726128, -3.72361231, -8.39972687},
-    {5.91075516, -4.13972998, -7.85990334},
-    {4.963305, -3.51591325, -5.2099247},
-    {6.01077271, -3.87057018, -4.5205512},
-    {6.82755661, -4.67621756, -4.2511816},
-    {6.78303957, -4.36633348, -4.05680466},
-    {6.36759853, -4.27120829, -3.34561801},
-    {6.78260803, -4.90130424, -2.69025779},
-    {7.52839994, -5.49304581, -1.64847291},
-    {7.2936306, -5.41727161, -0.218077391},
-    {7.38765669, -5.29222822, 0.626134098},
-    {7.7469511, -5.19788361, 1.65705478},
-    {8.48607159, -5.29237795, 2.50409532},
-    {8.29772186, -4.87846088, 3.38136029},
-    {7.72076559, -4.38232994, 3.7885766},
-    {7.39242744, -3.52960539, 3.875669},
-    {8.20620537, -4.07705164, 5.32532835},
-    {8.2267561, -2.6174922, 5.32513142},
-    {8.07946777, -2.28504133, 5.64792728},
-    {7.8882761, -1.39509237, 5.4625392},
-    {8.16114426, -1.1028924, 5.41922951},
-    {7.6049571, -0.624736845, 5.11983967},
-    {7.3686142, 0.164465323, 4.57665682},
-    {7.70336008, 0.325898975, 4.06983232},
-    {7.7627635, 1.01257014, 3.75107074},
-    {8.12722397, 1.46072578, 2.85443521},
-    {8.11114216, 2.18203712, 2.24115396},
-    {7.91194439, 2.92545843, 1.22467554},
-    {8.02128983, 3.01769662, 0.904059291},
-    {7.91684055, 4.3210001, 0.60837096},
-    {7.80506563, 4.88462162, 0.390065163},
-    {7.51679516, 5.35235262, 0.225170836},
-    {7.60189533, 6.12522602, -0.194999292},
-    {7.24007082, 6.67077637, -0.347612649},
-    {7.0353651, 7.25782585, -0.46667558},
-    {7.43187761, 7.24341059, -0.378711462},
-    {7.07612085, 7.61931133, -0.537001848},
-    {7.29392862, 8.17624187, -0.782969415},
-    {7.51736307, 8.53702354, -0.676313996},
-    {7.06913185, 8.97644806, -0.703927696},
-    {7.47335196, 9.6887455, -1.69477761},
-    {7.62183189, 9.54722881, -2.21723557},
-    {7.1217804, 9.74172497, -3.3868866},
-    {7.61721945, 10.2046423, -3.19574738},
-    {7.65087605, 10.0115414, -3.01317739},
-    {6.92436886, 10.1070042, -3.06710458},
-    {6.7465806, 9.34101963, -3.47968149},
-    {6.72432184, 9.27079391, -4.00670671},
-    {6.44114351, 8.65230656, -5.02442503},
-    {6.40361547, 8.46325493, -4.9110961},
-    {6.65671873, 7.53200436, -5.31535769},
-    {6.6202693, 6.64217329, -5.70828247},
-    {6.51091719, 5.41210365, -5.77825928},
-    {6.21336651, 3.85662222, -5.31386852},
-    {6.10252714, 2.42751551, -5.40004396},
-    {5.89245605, 1.08829057, -4.57938957},
-    {5.54818773, 0.726487756, -3.11192203},
-    {5.91858673, 0.147670418, -3.06708694},
-    {6.01713991, -0.929266334, -2.89683151},
-    {5.59355021, -1.35515821, -1.35345173},
-    {5.39851713, -1.28469276, -0.29148069},
-    {5.41086626, -1.13508976, 0.430342495},
-    {5.33083868, -1.10030603, 0.0860074759},
-    {6.20504475, -1.68059897, -0.239567354},
-    {6.57325506, -1.29622376, -1.15281451},
-    {6.71321392, -1.19295299, -0.327493995},
-    {7.28991127, -0.245707557, -1.08402717},
-    {7.79339409, 0.38732174, -1.11259949},
-    {7.99128199, 0.993547082, -1.76522124},
-    {8.55108929, 1.6633414, -1.98288107},
-    {8.67516613, 2.05659223, -1.53531516},
-    {9.12596035, 2.62789917, -2.11301231},
-    {8.89050388, 2.22758269, -0.059237767},
-    {9.93485451, 2.61157632, -0.773291647},
-    {9.70755863, 2.49568701, -0.779391527},
-    {9.44746304, 2.15318298, 0.233955413},
-    {9.21567154, 1.75304317, 0.373168409},
-    {11.2181997, 1.38045835, -0.275251567},
-    {10.8412008, -0.116321132, 0.27326262},
-    {11.0582752, -0.75513047, -0.222241819},
-    {10.9516754, -2.67745209, -0.737740397},
-    {11.5414295, -3.26850867, -0.20780395},
-    {9.96520615, -2.80423522, -0.589113533},
-    {10.9984579, -3.70260239, -1.45282984},
-    {10.8470898, -3.77252197, -2.37304282},
-    {11.1791725, -4.81446648, -3.33664322},
-    {12.2318144, -5.1664362, -4.12080574},
-    {11.4839134, -5.41367817, -5.87087059},
-    {11.1305714, -4.32751989, -6.28880644},
-    {9.97517395, -3.75770998, -4.61065817},
-    {10.1300507, -3.06420565, -5.47347975},
-    {10.0256081, -2.41362929, -5.1065855},
-    {9.78102207, -2.58469701, -5.75979662},
-    {9.95727348, -3.58764005, -2.77526021},
-    {9.09679985, -3.3288188, -2.06715417},
-    {6.11829758, -2.86653113, 1.92580283},
-    {6.30407, -2.47854042, 0.69543153},
-    {5.8868022, 0.326048672, 2.56514072},
-    {9.32427979, 0.574638426, -2.74639344},
-    {9.60604668, 2.07243705, -1.82727599},
-    {9.84022141, 2.92461419, -1.89285207},
-    {10.2456894, 2.65861797, -2.05520391},
-    {10.5185061, 4.36593056, -1.80406368},
-    {10.1804848, 5.19211674, -2.37669802},
-    {9.65642262, 5.95089197, -1.0382725},
-    {9.55235195, 6.95740414, -2.27396321},
-    {9.94207382, 7.81530476, -3.30098128},
-    {9.5176878, 8.25725746, -3.51005578},
-    {8.71024036, 7.85448027, -3.60090256},
-    {8.65240479, 8.76671696, -4.26091194},
-    {8.92793846, 9.15382862, -4.19986773},
-    {8.356637, 8.8499794, -4.67840338},
-    {7.71094942, 9.35883904, -4.13673782},
-    {8.08750153, 9.17913532, -4.69746017},
-    {7.60918427, 9.06831837, -4.39134121},
-    {7.73371077, 8.56395149, -5.67046261},
-    {7.54939079, 8.2752018, -6.26493931},
-    {7.16342831, 7.43695021, -5.85728312},
-    {7.20778656, 6.71285677, -5.35034704},
-    {6.62949371, 6.66763163, -5.124331},
-    {7.1021595, 6.05893087, -4.26052427},
-    {7.55027008, 5.7217927, -4.58772802},
-    {6.8264823, 3.85617638, -3.56555343},
-    {7.62325573, 4.94905424, -3.13451123},
-    {7.77492285, 4.01805592, -2.81145954},
-    {8.18003941, 3.08524442, -2.85374451},
-    {8.18732929, 2.82826829, -1.68093097},
-    {9.304492, 1.42643237, -1.04025304},
-    {9.27681923, 0.469661623, -0.571544468},
-    {9.10751152, -0.617094457, -0.190532506},
-    {8.73869514, -0.847863674, 0.829221249},
-    {8.99741554, -2.03764963, 1.06506455},
-    {8.81784344, -3.11317492, 0.905602336},
-    {8.02769279, -1.47323143, 3.36900282},
-    {8.62770653, -3.23761916, 2.35490632},
-    {8.37258244, -3.87158704, 3.22249866},
-    {8.47298145, -3.32207966, 3.22547174},
-    {8.25795937, -4.18634224, 2.98026752},
-    {8.1098175, -3.84127283, 3.94952869},
-    {7.94467592, -3.89533329, 4.00699997},
-    {7.38362694, -3.05126762, 4.79911804},
-    {7.34710407, -3.0759685, 4.89898205},
-    {7.12759638, -2.51131821, 5.67249393},
-    {7.10100555, -1.83262503, 5.35107946},
-    {7.17433214, -1.79508889, 4.60204506},
-    {8.5087719, -1.80822825, 3.90440083},
-    {8.87140369, -1.5767107, 3.7433145},
-    {7.48718882, -0.356075436, 3.7406342},
-    {8.61149216, -0.30515945, 3.35694242},
-    {8.60961533, -0.42796126, 2.4304347},
-    {8.84354401, 0.315594971, 1.46592224},
-    {8.58322239, 0.461724728, 0.47322318},
-    {9.34162998, 0.600450277, -0.153084382},
-    {8.65433884, 1.16255832, -0.428508341},
-    {8.78035164, 0.848236859, -1.03489304},
-    {10.0638456, 1.15882409, -1.20775545},
-    {10.2212324, 1.28600967, -2.01846194},
-    {10.491869, 1.84519899, -3.0763464},
-    {10.1317844, 2.82615852, -3.62121367},
-    {10.2501402, 3.11649418, -3.90890574},
-    {9.77715302, 3.34566474, -3.60147429},
-    {9.46368313, 2.78244424, -3.15033507},
-    {9.62684727, 2.52570891, -2.86495686},
-    {9.53345776, 2.25681186, -3.0221405},
-    {8.67092419, 1.79557776, -2.82090688},
-    {8.95367718, 2.70771742, -2.12626338},
-    {9.77977276, 2.58757043, -2.10913229},
-    {8.70439911, 1.80428123, -1.36211467},
-    {9.03612614, 1.62970984, -0.610328078},
-    {10.0464382, 0.902297616, -0.192021593},
-    {11.0201883, -0.0488053076, 0.231108487},
-    {12.3807364, -1.23512435, 0.664994657},
-    {12.2139587, -1.77812791, 1.39887798},
-    {11.4493999, -1.83952689, 2.67189527},
-    {9.99966049, -2.97224283, 2.6183188},
-    {8.38966656, -3.11377406, 2.56692719},
-    {5.90372562, -3.41575694, 2.40112591},
-    {5.9320302, -3.22893357, 1.93592739},
-    {7.97046709, -4.57357359, 0.864364326},
-    {8.78504372, -4.22169971, 1.19252861},
-    {8.47327328, -3.92803288, 0.913853765},
-    {7.88582325, -3.47006774, 0.74914062},
-    {7.38766623, -2.97706294, 0.64172256},
-    {7.71026468, -3.67075372, -0.255607814},
-    {6.43766212, -2.7614193, -0.720927179},
-    {6.09330416, -2.13978124, -0.795029759},
-    {7.14455652, -2.02656817, -1.35917747},
-    {6.70760107, -1.08492255, -1.29723883},
-    {6.97405815, -0.555246592, -2.46052361},
-    {7.29660559, -0.948797107, -3.95970654},
-    {7.49908972, -0.583699822, -5.36598015},
-    {7.24245214, 0.0723673925, -6.1613555},
-    {7.18308973, -0.184608415, -6.82883406},
-    {7.8030405, 0.271089405, -7.50182056},
-    {7.14991236, 0.306131572, -8.17048931},
-    {5.18094444, 0.0206073988, -8.20914745},
-    {3.65862966, -0.745546281, -8.24986172},
-    {4.48876143, -1.88586032, -9.40283012},
-    {5.71734619, -2.95848012, -10.7460051},
-    {6.20920086, -3.27071476, -9.81186295},
-    {5.94195795, -4.21893978, -8.70249081},
-    {6.23890209, -5.00919008, -8.71875572},
-    {5.27696753, -4.82365131, -6.99678421},
-    {4.72322273, -4.71567965, -5.39903498},
-    {5.49804592, -4.21080828, -4.85002613},
-    {7.72017241, -4.47981882, -5.11569548},
-    {8.38196087, -2.49828959, -4.1486311},
-    {7.9231658, -1.63385832, -2.58821392},
-    {8.18167496, -1.00510454, -1.14894331},
-    {9.1484251, -0.612452328, -0.246217832},
-    {9.03862667, 0.38550058, 1.61447203},
-    {8.9615612, 1.01865554, 3.80793262},
-    {9.45639324, 2.39024138, 5.23966837},
-    {8.66668701, 2.61232471, 6.92347527},
-    {8.20797348, 2.94494414, 8.334095},
-    {7.95971632, 2.79898047, 9.14800262},
-    {8.60009384, 2.20841455, 10.9249773},
-    {8.26231194, 1.81938386, 10.9983225},
-    {6.8059411, 0.688899815, 10.4445972},
-    {6.75307274, -0.214008376, 11.2585249},
-    {6.8238678, -0.831513166, 11.9369297},
-    {7.11950445, -1.31526148, 12.8823004},
-    {7.0920372, -2.71363354, 12.6737938},
-    {6.71697426, -3.3144424, 12.3429556},
-    {5.94585228, -3.76645088, 11.1292725},
-    {6.0709343, -2.86394072, 10.8236237},
-    {6.41525507, -1.64200294, 11.9653673},
-    {5.69086361, -0.181313857, 11.3543224},
-    {4.72203684, -0.572332919, 10.6171608},
-    {4.82736683, -0.571420133, 10.3689594},
-    {5.91901875, -0.523222387, 10.8650618},
-    {5.65715837, -0.00315633253, 10.0148373},
-    {3.37084627, -0.190598458, 8.01812172},
-    {0.555700958, -1.00630212, 6.68614292},
-    {0.341612101, 0.459628224, 6.37734318},
-    {1.57318223, 2.44729733, 7.89960337},
-    {0.304688543, 3.69004178, 7.77520466},
-    {2.78422141, 7.16581011, 10.1368675},
-    {3.6304605, 8.85447216, 12.6861496},
-    {4.69961977, 10.4736185, 16.4332237},
-    {4.07488537, 10.4606409, 16.8146763},
-    {5.26566124, 9.12612438, 16.9481506},
-    {6.11897421, 6.42167807, 15.0221672},
-    {5.38155794, 4.16181707, 12.0433874},
-    {4.12603474, 2.2286582, 8.72386456},
-    {4.77886486, 0.128374949, 6.37451363},
-    {5.51932478, -1.99017811, 3.83294678},
-    {6.67055559, -3.066751, 2.35222626},
-    {7.23992205, -2.6985085, 1.06417108},
-    {8.2755518, -2.37758923, 0.446720541},
-    {10.4688129, -2.30810356, 0.805398822},
-    {12.0086498, -1.55245101, 2.3726244},
-    {13.2772598, -0.684991539, 4.22333431},
-    {14.04391, -0.175024241, 5.72415829},
-    {13.6919222, 0.142616019, 7.64564419},
-    {12.4341488, 0.0174081009, 7.77617455},
-    {11.6737509, -0.689874411, 7.97806931},
-    {10.400527, -0.955086708, 7.40677547},
-    {9.27369595, -1.83713114, 6.54693031},
-    {7.84946775, -1.78862441, 5.50311041},
-    {7.25732803, -1.63436532, 4.90570593},
-    {7.47052622, -1.3082037, 4.19564486},
-    {7.7102046, -1.14931607, 3.9271946},
-    {8.47905254, -0.589730501, 3.71367621},
-    {8.83847523, 0.252988607, 3.53141379},
-    {9.30092049, 0.850632846, 2.90520787},
-    {10.2001247, 2.56590152, 2.72787857},
-    {9.85987186, 3.94647288, 2.35490632},
-    {9.17673397, 4.72687578, 1.65627408},
-    {10.4958925, 6.83011246, 1.55298018},
-    {9.48318386, 7.43045712, 1.1671412},
-    {8.04361153, 7.21737432, 1.19772649},
-    {8.11102581, 8.38672638, 1.39509261},
-    {6.92553902, 8.09068394, 1.74149525},
-    {5.76956654, 7.49845886, 2.19410443},
-    {6.8168025, 8.76027679, 3.48424363},
-    {6.7003746, 8.54704285, 3.84419441},
-    {7.09416533, 8.54144955, 4.68196535},
-    {7.67360544, 8.63751125, 5.34718132},
-    {7.03242826, 7.68011045, 5.52497578},
-    {6.09851074, 6.47519922, 5.63914299},
-    {5.29809427, 5.14958668, 5.99186468},
-    {6.97448254, 5.57173586, 7.19826555},
-    {7.61588097, 4.82986498, 6.56985998},
-    {7.17356825, 4.14549446, 5.20869827},
-    {7.44389391, 4.05010128, 4.24552393},
-    {8.44560528, 4.09218264, 3.08983207},
-    {9.4032774, 4.07286358, 1.83929729},
-    {8.98168278, 4.00646496, 0.0962583497},
-    {8.67278671, 4.44275379, -2.00908661},
-    {6.88852692, 4.67825222, -3.70772052},
-    {7.07121086, 5.41704655, -3.61576819},
-    {6.28401661, 5.26402617, -2.94061136},
-    {6.5924325, 4.8014555, -2.16017675},
-    {7.25420475, 4.55536795, -1.78396332},
-    {7.56797409, 3.62749958, -1.22502649},
-    {8.1517086, 2.89833045, -0.734787643},
-    {9.09202862, 1.98417008, 0.00152710348},
-    {9.26327896, 0.864560008, 0.186608151},
-    {9.62004566, -0.119765468, 0.546179652},
-    {10.2806711, -0.944054782, 0.157763869},
-    {10.1316881, -1.89837956, -0.213164076},
-    {9.32131481, -2.58052802, -0.829188347},
-    {9.76375866, -3.72985649, -1.32977343},
-    {9.84023476, -4.69621181, -1.54261088},
-    {9.52914238, -5.73160362, -1.7105602},
-    {9.53196907, -6.41492462, -1.99568558},
-    {10.4082632, -6.77388287, -2.8728025},
-    {9.33647728, -6.6792388, -2.80892849},
-    {9.33677673, -6.814466, -2.84347081},
-    {9.60992813, -7.04388618, -3.32349515},
-    {8.95278358, -7.15365505, -3.71552539},
-    {8.66043854, -7.18704987, -3.91727185},
-    {8.75744057, -7.05616713, -4.24766064},
-    {8.71551037, -6.45829868, -4.42655993},
-    {8.634552, -5.7001543, -4.52236462},
-    {8.66677761, -5.46459389, -4.26286268},
-    {7.12447119, -5.03150797, -3.65626693},
-    {8.33134556, -5.87686205, -4.18289375},
-    {9.37658691, -6.97480583, -5.69932222},
-    {7.77650166, -5.51081467, -4.85980892},
-    {7.81504822, -5.2925415, -4.7482276},
-    {8.10713005, -4.87937784, -4.26687765},
-    {8.98015785, -4.62358189, -3.89553475},
-    {7.78340197, -3.18295932, -2.65959072},
-    {8.08130741, -2.0138526, -1.97933519},
-    {8.62776947, -1.27986193, -1.12151396},
-    {9.37530994, -0.32687363, -0.327958763},
-    {7.97621679, 0.822629035, 0.95339632},
-    {9.31999111, 1.77567422, 4.01831627},
-    {11.4967127, 2.64006805, 6.76774502},
-    {12.5646248, 3.94946837, 9.05231762},
-    {11.5005779, 4.10985327, 9.67691517},
-    {9.78593159, 3.86770272, 10.2172413},
-    {8.98312473, 3.28779674, 10.4099779},
-    {7.75100613, 2.34063959, 10.4182825},
-    {6.01192713, 1.32870281, 9.65169716},
-    {4.78408194, 1.00828385, 9.15015316},
-    {3.71922183, 0.257598072, 8.388381},
-    {2.04383373, 0.233047411, 7.3608489},
-    {1.13408482, -0.0289108399, 6.18371296},
-    {0.821986854, -0.124349736, 4.80937767},
-    {2.4392767, -0.670615315, 3.43228126},
-    {5.38780546, -0.940560579, 2.31634355},
-    {7.43258762, -1.00899792, 1.39917564},
-    {8.17661762, -0.358321816, 0.0953378975},
-    {7.54342556, 0.412456065, -1.14373231},
-    {7.29303646, 1.57393909, -2.50414872},
-    {8.90031528, 2.46457338, -4.841362},
-    {8.58738995, 3.51548433, -6.49829483},
-    {8.46568871, 4.96434307, -7.23783779},
-    {7.73252106, 6.39628029, -7.64341688},
-    {8.20280266, 6.97177982, -8.46722984},
-    {8.28299141, 7.26624727, -9.35537243},
-    {7.74200249, 7.56989241, -9.56927204},
-    {6.70641041, 7.07031775, -10.0130129},
-    {6.36318445, 7.45503235, -9.60847664},
-    {6.90927362, 6.96536303, -10.505497},
-    {8.05708313, 6.85231543, -10.1275129},
-    {8.60687447, 6.60493946, -10.0420408},
-    {8.0085001, 5.48952627, -9.02021027},
-    {7.7537961, 4.25226831, -8.46335888},
-    {7.99431229, 3.63108468, -7.62498999},
-    {8.18025017, 3.02900004, -6.68507671},
-    {7.97681189, 2.26385021, -6.25471163},
-    {8.30823898, 2.29815722, -4.78505373},
-    {7.88599968, 2.29472876, -4.01003551},
-    {7.84127522, 2.22341657, -2.88962746},
-    {8.11919022, 1.95805514, -1.86257708},
-    {8.09360123, 1.56540322, -0.853990495},
-    {8.62145996, 1.81384289, -0.211079493},
-    {8.55272388, 2.31626391, 0.706684053},
-    {8.83943272, 3.03163695, 1.19483876},
-    {8.81144619, 3.35420036, 1.63129663},
-    {8.78180695, 3.80129957, 1.99047923},
-    {8.68944931, 3.82172847, 2.61531639},
-    {8.96007347, 4.09442949, 2.87379146},
-    {8.80594158, 4.23864079, 3.30408597},
-    {8.60197067, 4.22123718, 3.42419624},
-    {8.30352497, 4.44484997, 3.38761377},
-    {8.02307987, 4.56749821, 3.4404707},
-    {8.12796688, 4.85008144, 3.95548415},
-    {7.82422066, 4.78292847, 3.95709872},
-    {7.8946867, 4.70242453, 3.90307403},
-    {8.15967178, 4.7723937, 3.76410651},
-    {8.14641571, 4.87553978, 3.40071654},
-    {8.29682827, 4.92765379, 3.13241482},
-    {8.92645073, 4.75798321, 2.81319308},
-    {9.13964748, 4.74735165, 2.64688158},
-    {8.10594845, 4.5001092, 2.57794523},
-    {7.32055759, 4.59460306, 2.77105665},
-    {7.71717453, 4.3490262, 2.88133025},
-    {6.54454184, 4.32325172, 3.16159749},
-    {5.91270924, 5.19162416, 3.58044219},
-    {7.24354267, 5.87407255, 4.47671938},
-    {7.46566439, 6.52537203, 4.78709269},
-    {7.72568655, 7.19465637, 5.00153732},
-    {8.9335928, 8.48054028, 4.72286749},
-    {8.52698708, 8.94147968, 4.00819063},
-    {7.83101988, 8.85247231, 3.00747132},
-    {9.55904293, 9.97015095, 2.25862336},
-    {9.26326561, 9.75292015, 0.271567166},
-    {9.09738541, 9.10452271, -0.727424145},
-    {9.96163654, 8.52561569, -1.59576535},
-    {9.97532368, 7.81503868, -1.90441597},
-    {8.43086815, 6.28619242, -2.03954101},
-    {10.177659, 6.27677679, -2.61775231},
-    {9.16806412, 5.18193388, -3.60579276},
-    {8.38465977, 4.22207594, -3.17732239},
-    {10.09375, 3.9003489, -2.79463434},
-    {10.8522596, 3.88535547, -1.91248775},
-    {11.400425, 3.62461042, -0.845479786},
-    {10.9611139, 3.28935742, 0.0405461229},
-    {11.1072149, 2.65515375, 0.646532118},
-    {11.7227736, 2.94407272, 1.44692457},
-    {11.8820353, 3.35254407, 1.99278462},
-    {10.99119, 3.64124942, 2.30237079},
-    {10.6445236, 3.59477615, 2.53870535},
-    {10.4240332, 4.23220158, 2.21048236},
-    {10.8049011, 3.48478532, 2.65119934},
-    {9.85306168, 3.98686075, 1.75474095},
-    {9.78637695, 3.39193869, 1.57978034},
-    {10.1107101, 3.54633331, 1.17494595},
-    {9.81553841, 3.67212534, 0.719042063},
-    {9.17669296, 2.95630741, 0.241846651},
-    {8.61639977, 2.02274847, 0.122585058},
-    {9.02776718, 1.68505573, -0.0285392255},
-    {8.98328209, 1.08619404, 0.0628797412},
-    {7.86195564, 0.170605272, 0.171123415},
-    {7.37396955, -0.804585159, 0.259862483},
-    {7.17609644, -1.48101842, 0.923618138},
-    {7.22430086, -1.7700417, 1.21961331},
-    {7.34629822, -2.95788121, 1.7516005},
-    {7.69250011, -3.10299158, 2.29639244},
-    {9.08858585, -4.22373295, 1.55578625},
-    {9.40253639, -4.56997061, 1.85537744},
-    {8.99875546, -5.25014734, 2.06665373},
-    {8.72206497, -5.21865082, 1.70829737},
-    {9.52825069, -6.16124344, 2.00977755},
-    {9.67200565, -6.31279373, 3.74009776},
-    {9.59281921, -6.04623318, 3.4368968},
-    {9.69993877, -6.57935381, 4.0311203},
-    {10.1522198, -6.54146671, 3.24869871},
-    {9.96773529, -6.344841, 3.42081642},
-    {9.32130241, -5.35197926, 3.65517044},
-    {9.70960903, -5.72022104, 3.99627972},
-    {9.99778748, -4.93057442, 4.72048521},
-    {9.55324459, -5.12225819, 4.22676325},
-    {9.42645931, -4.21835947, 4.49563313},
-    {10.0407534, -4.85396481, 3.89617062},
-    {9.27372456, -3.94502163, 3.89157963},
-    {9.08192062, -3.69361615, 4.30641937},
-    {9.15754414, -4.23810863, 3.79929233},
-    {9.27063751, -3.88845921, 3.67911386},
-    {8.9824028, -3.86272788, 4.79392052},
-    {9.14439869, -3.75010705, 5.03715277},
-    {10.1149073, -4.51924467, 5.25463438},
-    {9.86942863, -3.09436417, 5.93733788},
-    {9.46887493, -2.51092362, 6.59360552},
-    {9.2628336, -2.50982046, 6.76743698},
-    {9.22489452, -1.27316177, 7.6983037},
-    {8.86054325, -0.982191861, 8.27763844},
-    {8.64005661, -1.22793627, 8.70331669},
-    {8.24996471, 0.965493262, 8.85280514},
-    {8.70774937, 1.28251994, 9.47993183},
-    {8.31393814, 2.97367859, 9.59383392},
-    {8.12350368, 3.85976648, 8.55725479},
-    {7.7177515, 1.92495513, 8.64927483},
-    {8.2297039, 3.34728742, 8.51124668},
-    {7.7579608, 1.05160129, 9.36781693},
-    {8.16916561, 3.35764503, 10.4449177},
-    {8.31810379, 1.4897778, 11.0791702},
-    {7.67539072, 0.345366776, 10.6394939},
-    {7.66616583, 1.04111838, 11.0881033},
-    {7.99273539, 0.162248105, 11.3701067},
-    {7.13711786, -0.449371368, 9.96918869},
-    {6.31272602, -0.437400222, 9.16961765},
-    {6.04599285, -1.06844974, 7.61224556},
-    {5.21992874, -1.82631481, 5.6396327},
-    {4.47258854, -2.44122052, 4.35154295},
-    {5.46710396, -5.09994602, 3.39476061},
-    {6.05982399, -4.83958864, 4.02741194},
-    {5.1958847, -3.29856873, 3.49168897},
-    {6.28896809, -4.29764271, 4.47263479},
-    {5.51471186, -3.33346105, 3.92823696},
-    {5.01646042, -3.37299609, 3.84009361},
-    {5.99570656, -4.42770481, 4.53541422},
-    {6.34428978, -4.17492199, 5.28642035},
-    {6.80653715, -3.71712804, 6.09445095},
-    {6.22095299, -2.56912231, 6.26210213},
-    {6.69316864, -3.66171932, 6.4541707},
-    {6.74330759, -3.31609011, 7.79344368},
-    {6.47640324, -3.18625331, 8.57869625},
-    {7.06704426, -1.33665705, 9.54782677},
-    {7.75309753, 0.134746343, 10.8291111},
-    {8.37047195, -0.425560683, 10.9220896},
-    {8.30962467, -0.184009403, 10.4177971},
-    {7.70170927, -1.23070443, 9.52332306},
-    {7.96654606, 0.506201267, 10.065073},
-    {8.46217346, -0.190825492, 9.85584927},
-    {7.36162138, -1.09899914, 10.0174313},
-    {6.95590878, -1.92069292, 9.52221775},
-    {7.09575844, -1.45945454, 8.78669643},
-    {6.88910818, -0.920344174, 8.32453918},
-    {7.69740868, -0.854303062, 8.4105978},
-    {6.81144762, -1.03310764, 7.19028807},
-    {5.89406013, -1.02871513, 6.39378595},
-    {5.16218424, -2.36534786, 5.56478262},
-    {4.91101933, -2.21047401, 5.20323467},
-    {5.35630417, -2.63602424, 6.96631813},
-    {4.8294487, -1.36181533, 7.23748589},
-    {4.34533072, -0.331965238, 8.0636816},
-    {3.48302341, 1.05369759, 8.3546133},
-    {4.15950918, 1.69628716, 10.9453192},
-    {3.20000124, 2.19578099, 9.28916359},
-    {3.49742603, 1.3172965, 9.47137356},
-    {3.61491561, 1.92161524, 8.81227779},
-    {4.14284611, 1.6016432, 8.71731281},
-    {5.03941727, 1.04190361, 9.15416813},
-    {5.30931044, -0.17891787, 8.69368172},
-    {4.73646355, -0.0860711485, 7.37297678},
-    {4.50481892, -0.149865732, 5.60251474},
-    {5.99897957, -0.55120331, 5.22537374},
-    {9.61796188, -0.547609389, 5.27942276},
-    {10.1657572, 0.753143728, 2.93290067},
-    {10.4732676, 1.13643825, 1.68096304},
-    {11.3979225, 1.19326723, 1.33947039},
-    {11.3931599, 0.817088246, 0.869719625},
-    {10.8718157, 1.77331793, 0.40574193},
-    {10.753273, 1.75139618, -0.36056599},
-    {9.95275021, 3.00782228, 0.552929401},
-    {9.94222355, 2.1304059, 0.69376421},
-    {10.6824579, 2.52352166, 2.19544458},
-    {11.5925207, 1.14339972, 3.14090133},
-    {10.3148613, 1.92393851, 2.69407105},
-    {10.1395664, 0.372790903, 3.45164633},
-    {11.6901693, 0.478615046, 3.86426306},
-    {12.7899733, -0.0312904492, 4.45326948},
-    {11.5875921, -0.368713588, 4.27993059},
-    {10.9988356, -0.928952456, 4.32800913},
-    {10.4166183, -1.09266114, 3.67127514},
-    {10.5542126, -0.989529848, 3.51893616},
-    {9.7597456, -1.42276478, 2.55337834},
-    {9.64325523, -1.6750983, 2.26869893},
-    {9.91120052, -2.81022549, 2.15315914},
-    {9.79578876, -2.7442832, 1.47146916},
-    {9.15315151, -3.47123885, 0.719123662},
-    {9.11807442, -3.69196939, 0.360363811},
-    {10.1911964, -5.31319332, 0.361108243},
-    {9.73375225, -5.74180841, -0.256748527},
-    {9.68559742, -6.10178709, -0.562529325},
-    {9.64712238, -6.17142773, -0.819596946},
-    {9.17572308, -6.29943371, -0.987017989},
-    {8.1914959, -5.81321764, -0.373668343},
-    {7.92845917, -6.13294077, -0.651349962},
-    {7.78832722, -6.44403458, -0.382246464},
-    {7.22013521, -6.1224575, 0.0104701575},
-    {7.06302834, -6.1241045, 0.295298487},
-    {7.13000441, -5.44440985, 1.24046254},
-    {7.38564682, -4.7271924, 1.67923045},
-    {7.48240328, -4.4927268, 2.24668694},
-    {7.68997049, -3.40010095, 3.20358491},
-    {7.98003101, -2.59369636, 4.26866961},
-    {7.89632177, -2.00185847, 4.61105061},
-    {7.47318888, -0.334583402, 4.66475201},
-    {7.42901659, 1.05579412, 4.87369394},
-    {6.67382908, 1.4632715, 4.50399828},
-    {6.81397581, 1.61646867, 4.31326818},
-    {6.05217791, 1.75708652, 3.94295001},
-    {5.87472916, 1.41583157, 3.91205311},
-    {5.34920311, 1.1804384, 4.23144865},
-    {5.76540041, 1.44979382, 5.71641684},
-    {7.79320335, 2.53195333, 6.91037321},
-    {8.40600681, 2.72771668, 8.44992352},
-    {8.64221954, 3.08609319, 9.24151802},
-    {8.54698849, 3.06099892, 8.44500637},
-    {6.82588768, 2.40387392, 6.20219469},
-    {5.91209412, 2.60775971, 5.47702265},
-    {7.09393644, 0.233201951, 5.83316135},
-    {8.19209003, -4.3793354, 5.84029484},
-    {8.10966873, -6.20661831, 4.75100803},
-    {6.84015942, -6.98503304, 3.82892704},
-    {5.5340538, -6.15630198, 2.63392806},
-    {4.39540529, -6.14565134, 2.18008137},
-    {4.65738106, -7.16315699, 2.66703963},
-    {5.26104879, -8.05142307, 3.760288},
-    {5.10810709, -7.25833273, 4.84614992},
-    {3.66839886, -4.72736073, 5.94094419},
-    {2.52497172, -2.95949221, 6.45817757},
-    {2.4802711, -1.12745214, 9.14686584},
-    {2.26559639, -0.751804709, 10.064785},
-    {1.21487463, -0.105874769, 11.3487301},
-    {0.932105243, 1.05234981, 12.3657351},
-    {1.35044014, 1.70854723, 13.015707},
-    {2.15463614, 1.97955585, 13.2003899},
-    {2.72340512, 1.69710839, 11.7735538},
-    {4.45008278, 1.50150847, 12.4808073},
-    {4.87333775, -0.168435007, 13.1092987},
-    {3.83383799, 0.301489204, 12.2896538},
-    {3.30731893, -0.0507293679, 11.9856176},
-    {2.63708138, -0.862090051, 10.761735},
-    {3.64968467, -0.44698441, 10.0919094},
-    {6.61976957, -0.925710917, 10.2243195},
-    {8.3210783, -1.68453264, 8.73741341},
-    {8.18465042, -2.98453689, 6.57387924},
-    {7.026577, -3.13458896, 4.59958649},
-    {8.6120863, -4.64245081, 3.19971371},
-    {9.3035984, -4.79879284, 1.88351798},
-    {8.0693512, -4.55244875, 1.06312895},
-    {8.72828102, -5.24640465, -0.471489787},
-    {8.92481422, -6.32372522, -1.57774925},
-    {7.48138666, -5.56762314, -1.55422413},
-    {7.43571186, -5.57301521, -1.69596863},
-    {7.64831352, -5.85365105, -1.72902274},
-    {7.92391014, -5.09356928, -1.45523918},
-    {7.6911602, -4.83083963, -1.41233134},
-    {8.51954746, -5.32981682, -1.00645494},
-    {8.33818817, -4.53867149, -0.913398087},
-    {8.2380619, -4.02681684, -0.628420591},
-    {9.57923985, -4.07358074, -0.961462677},
-    {10.0890408, -2.83960986, -1.40185118},
-    {10.0410833, -2.33056593, -1.17857277},
-    {9.49552059, -1.28529167, -0.983376801},
-    {9.97086143, -0.955086708, -1.03176653},
-    {10.1519213, -0.975902319, -0.544595063},
-    {9.89763832, -0.352740079, -0.46797505},
-    {10.1331167, -0.351742238, -0.515038013},
-    {9.86835289, -0.0472849347, -0.646436691},
-    {9.47498894, 0.119389854, -0.625591874},
-    {9.30391312, 0.177670106, -0.481482685},
-    {9.90675545, 0.18080847, 0.123805985},
-    {9.82848072, 0.568798006, 0.771600544},
-    {10.4830799, 0.719816923, 1.15022564},
-    {10.6152105, 0.884327233, 1.11509192},
-    {9.74635601, 0.833860457, 0.842472494},
-    {10.5007772, 0.707618892, 0.877889395},
-    {10.6100349, 0.887540102, 0.933512449},
-    {10.1395712, 1.30108929, 0.922873557},
-    {9.61409473, 1.4033705, 0.520868182},
-    {9.54357433, 1.28326869, 0.487516642},
-    {9.95642853, 0.54184252, 0.0590085797},
-    {9.84990501, -0.0405462459, 0.313165367},
-    {10.1839085, -0.491302133, 0.692986131},
-    {10.5511732, -0.640410781, 0.974949419},
-    {9.64628124, -0.753968716, 1.06724024},
-    {8.85592937, -1.06919849, 1.52871084},
-    {8.71072578, -1.36451089, 1.96406782},
-    {8.41257763, -1.88445258, 2.82793307},
-    {7.12307835, -2.27480364, 3.29988527},
-    {6.41347075, -2.57735896, 3.85438657},
-    {6.88849878, -2.35046077, 3.77344871},
-    {6.51963902, -2.17227292, 3.30056548},
-    {6.74360514, -2.01234174, 3.13881731},
-    {8.0378809, -2.15630817, 3.30147338},
-    {8.20098305, -2.38080621, 3.32638597},
-    {7.67468119, -3.05803704, 3.27935553},
-    {7.82782793, -3.28317642, 3.15261841},
-    {8.40379906, -3.14042997, 2.74961615},
-    {8.00790691, -3.40174818, 2.31440806},
-    {8.81382751, -3.2307303, 1.39828217},
-    {9.07098579, -3.1582911, 0.388770372},
-    {9.4574337, -3.51990342, -0.606384993},
-    {9.92652512, -3.96811366, -1.17231917},
-    {9.32638359, -3.96405125, -2.05812383},
-    {8.99369812, -3.77448273, -2.85627556},
-    {9.53812504, -3.81843805, -3.5683713},
-    {9.42651749, -3.55826902, -4.52660179},
-    {8.64913273, -2.87297106, -5.29004574},
-    {9.19439507, -2.99082685, -6.72877979},
-    {8.62808037, -2.11201763, -7.34027433},
-    {8.26686764, -1.73016405, -7.35272264},
-    {8.61610794, -1.65894783, -7.69934416},
-    {9.11108017, -1.39925349, -7.73974895},
-    {8.98878765, -1.11262667, -7.39059877},
-    {9.25122833, -1.26552427, -7.05470181},
-    {9.64336681, -0.834970653, -7.120646},
-    {9.32143402, -0.902813852, -6.69851065},
-    {9.53628445, -1.04568708, -6.37575865},
-    {9.68208408, -0.935319424, -5.8396039},
-    {9.84541321, -0.676859498, -5.21125984},
-    {9.71953964, -0.73449111, -4.56625366},
-    {10.0315599, -0.755466282, -4.01137066},
-    {10.1589079, -0.441030562, -3.62698865},
-    {10.0587883, -0.0123926224, -3.17088199},
-    {9.92625237, 0.10288801, -2.41146612},
-    {9.73430538, 0.361839622, -1.72574711},
-    {9.65500927, 0.538547933, -1.05841756},
-    {10.0385523, 0.617767155, -0.229542002},
-    {9.8911171, 1.33313644, 0.450740606},
-    {9.54893112, 1.44350433, 0.928382576},
-    {9.88292408, 1.66734409, 1.44504762},
-    {10.0314112, 1.91792107, 2.07022691},
-    {9.21077919, 1.71947587, 2.57423639},
-    {8.98823166, 1.95883358, 3.14085245},
-    {8.89021778, 2.06828213, 3.60394788},
-    {8.61059761, 1.53500342, 5.31634665},
-    {7.85778999, 1.5523746, 6.05886555},
-    {8.03498268, 1.64162719, 6.12899256},
-    {9.1751461, 2.08846712, 7.83512163},
-    {9.43158627, 2.22222853, 8.30683517},
-    {8.4935112, 0.949320018, 8.53730392},
-    {7.51456356, -0.128750578, 8.86843681},
-    {7.36578655, -0.483215541, 8.91816616},
-    {7.88233757, -1.01753378, 9.53159809},
-    {8.28861904, -0.510733902, 10.377203},
-    {7.01050854, -0.0868197605, 9.28592873},
-    {5.5459547, -0.246156678, 7.68162775},
-    {5.0176506, -0.665764272, 6.5758152},
-    {5.81426716, -0.406773925, 7.10510302},
-    {3.71660209, -1.14901662, 4.72048521},
-    {4.94319057, -1.38507247, 5.91415787},
-    {3.88428307, -1.07828486, 4.81521845},
-    {3.00411201, -0.386924416, 4.50652933},
-    {2.84849238, -0.926783323, 4.87309837},
-    {4.19876814, -1.08433247, 6.89232588},
-    {4.00210381, -1.05407333, 7.68058586},
-    {2.68707013, -0.453115404, 6.90009975},
-    {2.7764852, -0.284343868, 8.34404373},
-    {4.0043354, -1.44837248, 10.0723686},
-    {4.14716053, -0.699458599, 11.6250038},
-    {4.69748402, -0.49100256, 12.7072897},
-    {6.31791973, 0.613084018, 14.7240238},
-    {5.81887436, -0.381576866, 13.2250366},
-    {4.60182142, 1.18997276, 11.9211473},
-    {6.42165327, 1.46357095, 13.3299522},
-    {7.15318584, 1.22546422, 13.6378584},
-    {6.92511225, -0.30246374, 11.9489908},
-    {5.8656764, -0.35502708, 9.62569809},
-    {8.52148056, -0.855650783, 10.6010799},
-    {8.09356785, -1.30636597, 8.85905743},
-    {6.27222919, -2.19066811, 6.45928192},
-    {6.92499876, -2.71262622, 5.87820721},
-    {7.9845953, -2.81054854, 5.78763962},
-    {7.76495361, -3.30590701, 4.92163706},
-    {6.39841986, -3.32165813, 3.59485173},
-    {6.76255369, -3.19503021, 3.27721834},
-    {8.08854294, -3.09520507, 4.03022718},
-    {6.53607082, -2.90438032, 4.18814754},
-    {6.21515083, -2.39406133, 4.65184689},
-    {6.33223772, -1.51710892, 4.54821873},
-    {7.51332331, -1.11511791, 6.08105993},
-    {9.32008743, -0.529513359, 7.2122283},
-    {8.64169216, 0.588864863, 7.21247339},
-    {9.16196346, 1.27697909, 8.42429638},
-    {8.35812473, 2.14300013, 9.57492352},
-    {6.06501722, 2.5319531, 8.49175739},
-    {7.47288084, 3.73776603, 11.0247583},
-    {7.37411833, 3.25820875, 11.6635656},
-    {7.45229864, 3.3148067, 12.4886036},
-    {6.51917362, 2.65988731, 11.4476299},
-    {5.45140362, 1.20487809, 9.04995537},
-    {6.28418398, -0.0511787161, 8.43724823},
-    {6.66574955, -1.51140904, 6.76180744},
-    {5.5777607, -1.85692239, 4.80707216},
-    {5.03306913, -1.47931683, 4.19806767},
-    {6.45364046, -1.99332297, 4.07176733},
-    {7.10870123, -1.87411988, 3.76758385},
-    {6.95546198, -0.994322062, 3.17916679},
-    {6.47993231, -0.522641361, 1.66277134},
-    {6.79761124, -0.322525948, 0.474443048},
-    {7.76703691, 0.0136643136, 0.320609897},
-    {8.4563179, 0.467864603, -0.461811781},
-    {9.40597343, 0.841361821, -1.74096501},
-    {9.3827467, 1.43661547, -2.74743629},
-    {10.6459064, 1.57916081, -4.64586687},
-    {12.2947474, 1.971982, -9.47105217},
-    {11.2148056, 2.24239469, -10.7334709},
-    {10.0702429, 2.19271779, -10.3356628},
-    {8.52763939, 2.40494609, -10.5039082},
-    {7.25301409, 1.17409897, -8.41362762},
-    {7.35347414, 2.42173529, -8.03372669},
-    {7.84752321, 1.31306958, -7.96382952},
-    {7.52457523, 1.32492733, -6.16343975},
-    {8.26498985, 2.52262282, -6.03628778},
-    {8.13310242, 1.46476936, -4.10824585},
-    {9.12134743, 2.39143968, -3.03628445},
-    {9.27399063, 3.49811292, -1.81835699},
-    {9.87037373, 1.76420224, 0.463269979},
-    {9.85883141, 3.54159904, 1.9546684},
-    {10.2368727, 1.90803754, 3.79780841},
-    {10.488452, 2.24992299, 5.84371901},
-    {10.7211208, 1.98797822, 7.0011878},
-    {10.7238607, 1.39826071, 9.60852909},
-    {10.0432348, 1.0607959, 9.81402397},
-    {10.1316872, -1.248752, 11.4016647},
-    {9.64994907, -1.26687205, 12.2868252},
-    {8.64124489, -3.07229185, 12.5692711},
-    {8.37954903, -1.54855716, 13.0824976},
-    {7.34674454, -3.02182531, 13.0013533},
-    {6.87320709, -1.93282247, 12.6924658},
-    {5.9785924, -1.65302682, 12.8841457},
-    {4.47749376, -1.45129049, 10.8937912},
-    {4.07500458, -2.31349444, 10.8939514},
-    {3.55250216, -0.64914155, 10.0607557},
-    {5.16241074, 1.40756357, 12.9882498},
-    {5.93229198, 2.73365712, 14.4104309},
-    {5.81881142, 3.19890666, 13.7137938},
-    {4.78945684, 2.59292054, 12.9356327},
-    {4.22571468, 0.334434837, 12.9462614},
-    {3.99005294, -0.3277722, 12.2771454},
-    {4.09836245, -0.260832548, 12.4604282},
-    {2.53576565, -1.29532516, 9.80853462},
-    {0.617592096, -3.36580753, 5.37515879},
-    {-0.35897544, -4.04703331, 0.847981632},
-    {-0.279163659, -1.73228121, -0.777234972},
-    {1.33469391, 0.912181258, 0.703706205},
-    {4.23687315, 1.13486373, 5.24860144},
-    {5.12210178, -1.75597942, 5.88169956},
-    {5.60249472, -3.01902962, 7.26424599},
-    {5.79199791, -3.78906226, 9.89679718},
-    {5.61111975, -2.90217233, 10.7444639},
-    {5.02836323, -0.954936862, 11.2983389},
-    {4.72909689, -0.498535484, 12.0671625},
-    {5.17847776, 1.9334954, 13.3753662},
-    {5.50828743, 3.02263379, 13.9498634},
-    {5.24235201, 2.53108644, 13.0681181},
-    {5.4116106, 1.69059646, 12.2969484},
-    {6.05953598, 1.14021385, 12.2824278},
-    {6.33908224, 1.72384155, 11.3837996},
-    {6.21448469, 1.01075733, 10.3746328},
-    {6.53710413, 0.332787573, 9.53427887},
-    {6.71399832, 0.747303426, 8.8866024},
-    {6.5722146, 0.985709846, 7.51025486},
-    {6.70849371, 0.829966962, 5.94853735},
-    {7.08268452, 0.113109246, 4.89715195},
-    {7.40640211, -0.65408349, 4.17167377},
-    {7.78875971, -0.879910767, 3.03757167},
-    {7.6977067, -1.07728493, 2.17474842},
-    {7.74824238, -0.956937015, 1.60209489},
-    {7.73895979, -0.73886627, 1.27987802},
-    {7.97770357, -0.676696181, 0.985556662},
-    {7.95249796, -1.26254857, 0.828553736},
-    {8.27505684, -1.42645836, 0.169025421},
-    {8.21872044, -1.4151274, -0.33525458},
-    {8.35797596, -1.47817338, -0.527026117},
-    {8.54692173, -1.59408188, -0.284929425},
-    {8.88003254, -1.53358197, -0.154947698},
-    {8.70834446, -1.70085585, -0.0876488909},
-    {8.61342525, -1.88220608, 0.0269970633},
-    {8.07351589, -2.16383004, -0.0497343205},
-    {7.75707912, -2.28408289, 0.0364565924},
-    {7.14604425, -2.2404151, 0.200901568},
-    {7.25762653, -2.31753802, 0.628962994},
-    {8.00879955, -2.34434366, 1.22795129},
-    {9.14440823, -2.46953702, 1.81592131},
-    {9.34682465, -2.76563001, 1.92222059},
-    {9.10800076, -2.66987729, 2.0664041},
-    {8.97539902, -2.62992239, 1.86892664},
-    {9.28853989, -2.32011104, 1.86316967},
-    {9.83368874, -2.11986446, 1.65377915},
-    {9.81062794, -2.00844812, 1.49744368},
-    {9.1920166, -1.98314011, 1.56191349},
-    {9.65988731, -1.98931158, 0.692543924},
-    {9.53371239, -2.11693215, -0.0538027361},
-    {9.74739647, -2.34359503, -0.512136936},
-    {8.97822571, -3.08921432, -1.36007059},
-    {8.40707111, -3.33420944, -2.30269885},
-    {8.55346775, -3.91989303, -2.36582899},
-    {8.89610004, -4.33695507, -2.10124969},
-    {8.81952667, -4.76175261, -2.20413351},
-    {9.07175636, -5.13332033, -2.36013269},
-    {9.01183414, -5.52776194, -2.35197759},
-    {8.73601818, -5.91609812, -2.63532138},
-    {9.0679369, -6.38392544, -2.9268496},
-    {9.66839695, -6.98121309, -2.8167572},
-    {9.54331779, -6.9707613, -2.3131392},
-    {9.79589748, -6.77522945, -2.40037131},
-    {9.67092705, -6.40534019, -2.12224364},
-    {9.31520271, -5.95922756, -1.78098536},
-    {9.51042271, -5.58555841, -1.82571578},
-    {9.32392693, -5.32979631, -1.66835666},
-    {9.60204506, -5.18785095, -1.47888553},
-    {9.80571747, -4.84716225, -1.10531819},
-    {9.58091736, -4.50752306, -0.570800066},
-    {9.29987907, -4.23946571, 0.0666021854},
-    {8.93790531, -3.6790905, 0.35842818},
-    {8.86307144, -3.11017942, 0.41709125},
-    {8.49663544, -3.0156858, 0.780682862},
-    {8.32511806, -3.0633204, 0.900449812},
-    {8.76230145, -3.15573287, 0.97102797},
-    {8.5867939, -3.23117995, 1.13742554},
-    {8.04227257, -3.04324031, 0.969178796},
-    {8.181427, -2.73295712, 0.788556039},
-    {8.28462887, -2.34898591, 0.634323061},
-    {8.80944824, -1.55733931, 0.213931993},
-    {9.14098644, -0.696014345, -0.137080684},
-    {8.89565372, -0.0484831966, -0.404935509},
-    {8.73022366, 0.246271268, -0.27667281},
-    {7.10885, -0.745283067, 0.087446779},
-    {6.6992197, -0.29015246, 0.722286046},
-    {8.13448715, 1.94227779, 1.3019309},
-    {8.56328678, 3.02174878, 1.80966794},
-    {8.39552307, 3.40091896, 2.73363113},
-    {8.19376469, 3.50820899, 3.44181061},
-    {8.3457756, 4.16106892, 3.55943465},
-    {8.31765842, 4.90548944, 4.34125948},
-    {8.30307674, 4.56974363, 5.95151615},
-    {9.16359997, 4.5746851, 7.50117207},
-    {9.86552525, 4.23953867, 8.76748848},
-    {9.27429008, 3.56879616, 9.28503418},
-    {8.60716343, 3.32497168, 9.08385658},
-    {8.90562248, 2.18537974, 9.83563232},
-    {9.17910576, 1.23614001, 9.81165123},
-    {9.18978405, -0.20048219, 9.13197422},
-    {8.17081451, -0.835733712, 7.19639254},
-    {7.24743795, -0.815394521, 6.22644949},
-    {7.18723154, -1.41063964, 6.44406605},
-    {6.8661375, -1.22039878, 6.35509157},
-    {6.95040369, -1.05901515, 7.17167616},
-    {7.01854229, -0.540271282, 7.79850769},
-    {6.16784096, 1.25406694, 7.97836781},
-    {5.64385033, 2.11918902, 7.87116671},
-    {5.17222977, 1.94562566, 8.26438713},
-    {4.84030914, 2.15812492, 8.23714066},
-    {4.90487909, 2.11035371, 9.03728008},
-    {5.5186758, 2.58945847, 9.38719654},
-    {6.05737734, 2.04337549, 9.74694729},
-    {6.21009302, 2.3974297, 9.41605854},
-    {6.42120695, 1.75753593, 9.12170029},
-    {6.69676733, 0.309004188, 9.02812481},
-    {6.70853567, -0.695226729, 9.14800262},
-    {6.46330976, -1.0139395, 8.73845577},
-    {6.94965935, -1.67360127, 8.91444397},
-    {6.83435869, -2.62483048, 9.03727913},
-    {6.45050144, -2.97227097, 8.45176411},
-    {5.72121334, -2.68593001, 7.91896009},
-    {4.9858799, -2.99032879, 7.08635187},
-    {4.55212927, -3.28868508, 7.49789572},
-    {4.56333303, -1.3438313, 8.2603178},
-    {4.85662985, -1.18946791, 9.41376114},
-    {4.95086527, -1.61592662, 10.5091133},
-    {4.87780094, -1.55424774, 10.6846085},
-    {5.08742762, -1.65053892, 11.1406612},
-    {4.91544151, -1.6629684, 11.4402304},
-    {4.4629221, -1.07257009, 10.9757977},
-    {4.44406557, -0.717023194, 10.8146591},
-    {4.76235104, -0.689574957, 11.0383739},
-    {4.43905973, -0.200631976, 10.3271208},
-    {4.48369741, -0.226693481, 10.0224638},
-    {4.05659437, 0.0327070914, 8.61345482},
-    {3.57347941, -0.584298909, 7.08561659},
-    {3.76257396, 0.731878996, 7.38086843},
-    {3.98395324, -0.182838634, 7.38667917},
-    {3.28128314, 0.158625022, 6.92347622},
-    {3.02257085, 1.15714777, 7.4006567},
-    {4.00969172, 0.0815023631, 9.96442318},
-    {3.14336729, 0.655954182, 9.32106781},
-    {2.4600513, 1.03173852, 8.63757992},
-    {2.85310459, 0.557566583, 9.96144485},
-    {4.33712149, 0.515354395, 12.3927345},
-    {3.19023204, -0.927232742, 10.471694},
-    {2.33804107, -0.491601825, 8.72490597},
-    {4.36258936, -0.208269387, 12.0314751},
-    {4.30992222, -0.459105343, 11.4040499},
-    {3.14573812, -1.29068279, 9.97963905},
-    {2.73705935, -2.03839874, 8.8117094},
-    {3.3061285, -1.60396552, 8.11504936},
-    {6.20057058, -1.65083838, 10.9273005},
-    {3.34347224, -1.73604727, 6.04278517},
-    {2.61701465, -2.06845307, 4.22752142},
-    {3.2428987, -2.35901952, 3.82907534},
-    {7.58597565, -2.62393236, 7.81577826},
-    {4.85013771, -1.10742164, 4.59034586},
-    {5.06767941, -0.709242582, 3.73975086},
-    {5.36549044, -0.743935108, 3.46771717},
-    {8.65361691, -1.57530415, 4.75840282},
-    {9.36539268, -0.99960196, 4.51075077},
-    {8.37389469, -1.00764978, 3.42394352},
-    {7.64085674, -0.508119822, 2.65710998},
-    {9.45832443, -0.281498432, 2.29535007},
-    {10.5301113, -0.183410391, 1.70931542},
-    {10.0793171, 0.0292385928, 1.59213841},
-    {8.98038483, 0.193993941, 0.886444986},
-    {8.8223505, -0.0863222182, 0.527160048},
-    {8.88568592, 0.488081247, 0.579084516},
-    {8.7547617, 1.1129998, 1.09171593},
-    {7.66795206, 0.804508984, 0.0381637812},
-    {8.01341057, 1.51014435, 0.963074267},
-    {8.29727459, 1.61167669, 1.48940361},
-    {8.88978386, 1.37386465, 2.04811907},
-    {8.82649612, 1.7533766, 2.82734227},
-    {9.49296856, 1.9708432, 4.17092466},
-    {9.36961937, 1.90622222, 2.94543481},
-    {9.17178154, 1.00098467, 3.59606099},
-    {8.86397457, 0.545805931, 4.41345263},
-    {7.76882315, -0.434786469, 3.5857563},
-    {6.8669405, 0.056942869, 3.0645206},
-    {6.36586142, -0.12635459, 2.49962854},
-    {6.78719568, 0.384302557, 3.45491242},
-    {6.52668905, 0.683957994, 4.32562637},
-    {7.49165201, 0.779949486, 6.11127567},
-    {8.53401947, 0.804186821, 8.11117268},
-    {8.59200287, 1.0146122, 8.45288277},
-    {7.19629192, 1.84380805, 7.5451293},
-    {6.98075438, 1.91268003, 8.00010586},
-    {6.62190533, 1.35919344, 8.01365471},
-    {6.01250362, 1.32594383, 7.8648634},
-    {5.09367609, 1.89830351, 6.03474569},
-    {5.19841433, 1.33598185, 5.99201345},
-    {5.58159971, 1.49290335, 5.83912659},
-    {5.13896227, 0.523631692, 5.51538277},
-    {5.31314993, 0.622134209, 4.71792984},
-    {5.97666264, 0.503655553, 5.80366659},
-    {6.45482969, 0.527166724, 5.52911139},
-    {5.65082455, 0.179617628, 2.99481273},
-    {5.64980078, -1.00959659, 3.25465441},
-    {6.63487673, -1.69365418, 4.4524641},
-    {6.90815115, -1.74742889, 4.02531385},
-    {6.71606159, -2.40182948, 3.6389997},
-    {7.67137384, -3.99102569, 3.24467826},
-    {8.38207722, -4.6394558, 3.70981359},
-    {8.02918053, -4.29292727, 4.13787556},
-    {7.64013052, -3.67115378, 5.72996521},
-    {7.86255121, -4.43878746, 6.56807232},
-    {8.7028389, -3.21979809, 7.48762274},
-    {8.23612881, -2.81307006, 8.02764988},
-    {9.34927654, -1.5577327, 8.43140697},
-    {10.2960615, -0.475563705, 9.56866264},
-    {9.95895672, 0.476250768, 9.99985981},
-    {10.2745113, 0.256263822, 9.60872364},
-    {10.2131529, 1.02651072, 7.89431572},
-    {11.3980703, 1.99189901, 6.18497705},
-    {11.6782408, 3.31250644, 4.15141439},
-    {11.4815588, 3.12951207, 2.95380855},
-    {11.3427277, 3.19606137, 1.73075581},
-    {10.5894728, 2.9828136, 0.041737251},
-    {10.34027, 2.84039855, -0.73458004},
-    {9.39450169, 2.31865954, -1.7961725},
-    {9.12804222, 3.41215491, -3.48816848},
-    {8.96438694, 3.08524442, -3.79101253},
-    {8.14016914, 2.62610245, -4.77056599},
-    {7.58419132, 3.97402716, -5.61939383},
-    {7.66556978, 4.79781723, -6.21912718},
-    {7.45773077, 7.05579138, -6.57780504},
-    {7.16672468, 7.63278866, -7.19897556},
-    {6.80612183, 6.83031321, -7.33868647},
-    {6.71771765, 7.89335871, -7.56108141},
-    {6.68657589, 8.52861977, -7.3688612},
-    {6.3753829, 8.81014538, -7.68019104},
-    {6.36586237, 8.03876877, -7.16026592},
-    {6.36581659, 8.27243996, -7.10522509},
-    {6.07227373, 7.9512496, -7.36179161},
-    {5.84187126, 6.48927593, -6.36891031},
-    {5.180511, 4.21020126, -4.6513586},
-    {4.27620649, 2.50434351, -3.60290098},
-    {4.01424932, 1.15560663, -2.76880026},
-    {4.26350403, 0.839101851, -1.87046897},
-    {4.88152027, 3.06547737, -1.84292364},
-    {5.61216164, 4.70017862, -2.98372602},
-    {5.99779034, 5.91792822, -3.04268694},
-    {5.65224409, 6.50357485, -1.8841424},
-    {5.38334274, 6.58961058, -0.559781969},
-    {5.48938894, 7.15704584, -0.370230347},
-    {5.24572945, 6.67083502, 0.198869884},
-    {5.41518164, 5.21682644, 1.81398582},
-    {6.18822289, 6.46067429, 4.69487619},
-    {7.24772644, 9.31697369, 6.33906555},
-    {7.15882015, 9.60668468, 7.35577869},
-    {6.5816412, 8.9360733, 8.58603477},
-    {5.38517523, 6.17060137, 7.74739027},
-    {4.74150419, 4.64410257, 7.32907248},
-    {4.93904018, 3.71983433, 7.49225807},
-    {4.67470789, 2.26025605, 6.54264021},
-    {5.45921946, 4.01206541, 5.97414732},
-    {6.76981354, 3.64316058, 5.6317935},
-    {7.20617771, 2.6929965, 4.48336029},
-    {8.23523617, 4.44020796, 3.91007209},
-    {8.59028435, 5.2707057, 3.78514361},
-    {9.56504059, 7.39938688, 3.00777841},
-    {10.0572977, 8.72987843, 2.12159419},
-    {8.48972893, 9.95853233, 3.67902493},
-    {7.16568327, 11.2786694, 4.09871674},
-    {7.05767107, 13.04321, 4.75368786},
-    {4.7029891, 10.4954624, 4.80252409},
-    {5.35492182, 10.5456257, 5.10370207},
-    {6.00864983, 8.81239223, 4.43684816},
-    {10.428401, 7.48857212, 6.7775445},
-    {8.63559246, 4.26784277, 4.71497679},
-    {6.3829565, 2.94969893, 2.51811004},
-    {7.77242851, 1.84247291, 2.17011929},
-    {8.53278828, 0.589314163, 2.1528616},
-    {9.55235195, 0.721396208, 1.38354218},
-    {9.14672375, 0.241914824, 1.14574981},
-    {10.4994822, 0.336551368, 0.804971874},
-    {11.6314507, -0.249492213, 0.686046898},
-    {11.8698406, -0.447424442, 0.226064175},
-    {11.2631321, -0.351283342, -0.12636067},
-    {11.7932205, -0.753968716, -0.548764229},
-    {11.8266954, -0.300367385, -1.21758211},
-    {11.7326689, -0.926933169, -1.31763673},
-    {11.8491602, -1.09480596, -1.51447058},
-    {12.5165701, -0.813270867, -1.67571974},
-    {12.2221451, -1.46185029, -1.76430929},
-    {11.4446373, -1.34279668, -2.30508184},
-    {11.5526495, -2.30720496, -2.30344343},
-    {11.6476097, -3.10848284, -2.21611667},
-    {11.0236015, -3.05941296, -2.84391785},
-    {11.2411661, -3.72707438, -2.52089596},
-    {10.4645004, -4.11756754, -2.60569239},
-    {10.0944939, -4.87861156, -2.61700821},
-    {9.937603, -5.28597975, -2.09281707},
-    {9.29935551, -5.29408741, -2.98336148},
-    {9.35552025, -6.11407089, -1.34011948},
-    {8.33030319, -6.30545473, -1.50360143},
-    {8.44760227, -6.90657711, -0.718184114},
-    {8.19313145, -7.19303989, 0.357385963},
-    {7.77531433, -6.31235743, -0.0624142624},
-    {7.25204086, -5.84672403, 0.569886982},
-    {7.4034276, -6.44487429, 1.6013695},
-    {6.02977562, -5.82864189, 2.29460549},
-    {4.36511803, -4.70429802, 1.32621908},
-    {3.15675688, -2.79300284, 2.24160051},
-    {2.33164358, -1.82829535, 3.22770524},
-    {2.05268836, -0.890093982, 2.94094086},
-    {3.74821925, -0.569545567, 5.65239763},
-    {5.06343555, -0.389615268, 7.26463699},
-    {5.25942612, 0.465836167, 8.11940384},
-    {5.80393267, 1.47450304, 9.2272644},
-    {5.43526649, 1.79452479, 9.3301487},
-    {5.2018075, 2.51068139, 8.79312325},
-    {4.78781462, 3.01145244, 9.4276228},
-    {4.05121899, 2.97164989, 8.67339516},
-    {4.73299265, 2.93158436, 9.13193417},
-    {6.16841173, 3.19115853, 9.09113503},
-    {7.38781023, 3.2914269, 9.1673069},
-    {7.78627872, 3.81056976, 8.77170849},
-    {7.35953808, 3.97028351, 8.11534691},
-    {7.12700081, 3.71944785, 7.7697711},
-    {7.39640236, 3.80299997, 7.664855},
-    {7.62391376, 3.72738504, 7.63174868},
-    {7.14471912, 4.03289413, 7.01418209},
-    {7.39686203, 3.15405822, 7.46259546},
-    {7.19142103, 2.8053565, 7.98566294},
-    {6.60330868, 2.2464788, 7.68966818},
-    {6.80832195, 2.43696451, 7.71393728},
-    {6.92451715, 1.78194582, 8.13648987},
-    {7.52702951, 1.92481017, 7.92506886},
-    {7.90596437, 1.38716841, 8.25995922},
-    {7.46629143, 1.06310475, 7.66056728},
-    {7.77589035, 0.393373936, 7.45829201},
-    {7.72121477, -0.117259614, 6.90846729},
-    {6.89267874, -0.45700869, 5.78699017},
-    {7.7158742, -0.681215763, 5.69729948},
-    {8.67829132, -0.834835112, 5.42578173},
-    {8.43712521, -0.693169057, 4.75011396},
-    {7.68030071, -1.20038199, 3.94387054},
-    {7.84320974, -1.98942935, 3.73661447},
-    {8.26097393, -2.7065959, 3.63864398},
-    {8.13079453, -3.54101872, 2.61859226},
-    {6.42031288, -3.48021889, 2.2261157},
-    {6.58307409, -3.96422052, 2.20854664},
-    {6.48056793, -4.35312891, 2.84029102},
-    {6.17538261, -4.52476263, 2.93388438},
-    {6.1892643, -4.68692732, 3.82371545},
-    {5.34586143, -4.04768085, 4.73422194},
-    {4.26082611, -3.42900372, 5.65120268},
-    {4.08214569, -3.20242691, 7.21649265},
-    {2.41123867, -3.33675599, 7.80103874},
-    {0.837037325, -3.22334743, 8.94019794},
-    {0.778031588, -3.29261494, 10.5402079},
-    {1.82729197, -3.1333189, 12.3938627},
-    {2.93180728, -2.05322433, 12.7461519},
-    {4.72823143, -1.6018784, 12.7090693},
-    {5.69428539, -1.37080073, 12.3052883},
-    {5.6923275, -1.92973089, 11.7189932},
-    {5.43481922, -2.25089788, 11.1950092},
-    {5.69577265, -1.72990799, 10.3577929},
-    {6.74137259, -0.685381889, 10.078475},
-    {6.7312479, -0.286667317, 9.0497818},
-    {6.63841915, -0.707695007, 8.12174797},
-    {6.46696281, -0.363181412, 6.50293207},
-    {6.8147192, -0.165440068, 5.54072523},
-    {7.89173794, 0.659698009, 4.70556068},
-    {7.30010891, 0.787538588, 3.35466599},
-    {7.16102076, 2.26185346, 2.44270682},
-    {8.40247345, 3.4146862, 2.19350886},
-    {8.84347439, 4.30822086, 1.62609911},
-    {8.03450775, 5.7377677, 0.554671228},
-    {9.18105984, 6.75305891, 1.55102205},
-    {8.58530617, 8.08414364, 2.20437765},
-    {8.30397034, 8.86255836, 4.12119913},
-    {9.34681129, 9.67145538, 6.47879982},
-    {9.4075613, 10.1364183, 7.7272687},
-    {8.97599316, 8.56529903, 9.93449783},
-    {9.67806721, 8.23479462, 11.5161638},
-    {9.96133804, 5.63059282, 13.1521769},
-    {9.6193018, 3.78563833, 12.2976923},
-    {9.53524303, 1.61766672, 10.885313},
-    {9.57996178, -0.5906021, 8.78022575},
-    {8.66147995, -2.45006919, 6.83667135},
-    {6.79361773, -3.35777378, 4.34383917},
-    {7.86835432, -5.27470684, 2.93930316},
-    {7.21310186, -5.00484371, 1.71070504},
-    {8.56173229, -6.34154606, -0.00554285059},
-    {10.1406136, -7.9470458, -1.72321534},
-    {11.3864651, -8.55144882, -3.54147196},
-    {11.0721245, -6.69165945, -4.26211214},
-    {10.1549244, -5.96266174, -4.39780617},
-    {10.1681376, -4.16818333, -5.13534975},
-    {9.72321987, -2.93146563, -4.83659744},
-    {9.58716583, -2.198035, -4.80897951},
-    {8.89059639, -0.948048174, -4.14641523},
-    {8.53710365, 0.823377848, -3.59596539},
-    {8.81843853, 1.40322089, -3.42756987},
-    {6.69495535, 3.99214745, -1.91349828},
-    {4.03111601, 5.80370712, -1.42037153},
-    {0.703436077, 6.28321552, 0.296191812},
-    {-0.569047391, 8.75279045, -0.0029300712},
-    {2.0009141, 6.71136045, 0.335499018},
-    {5.05633307, 4.76996326, -0.320216447},
-    {7.15616083, 2.3866477, 0.252566725},
-    {7.41607237, 2.20709395, 0.722317636},
-    {7.3904829, 1.97692382, 0.939251661},
-    {7.67940712, 1.83720458, 1.43431401},
-    {8.71767139, 0.998339057, 2.01996541},
-    {9.21656418, 1.20345056, 2.73517394},
-    {9.81306553, 1.03780925, 3.18299007},
-    {9.94720364, 1.41894484, 4.08129692},
-    {10.6048393, 1.31519783, 4.11360598},
-    {11.0741434, 1.07094646, 4.06754923},
-    {11.4246883, 0.685822606, 4.33016062},
-    {11.5713949, 0.930301309, 4.00119352},
-    {10.976737, 1.91956854, 3.81835532},
-    {11.3921204, 1.9478718, 4.21857357},
-    {11.492692, 1.72309279, 4.24105644},
-    {11.969758, 1.66748905, 4.18666124},
-    {11.8202972, 1.1052078, 4.05965948},
-    {11.4682951, 0.583473802, 4.168993},
-    {11.4546061, 0.441508114, 4.12700605},
-    {10.8304644, 1.29197192, 3.90284657},
-    {10.8932037, 0.69995153, 4.21921968},
-    {10.9267464, 0.74715364, 4.39426565},
-    {11.1101894, -0.182062581, 4.70515013},
-    {10.4830961, 0.0696718767, 4.79314375},
-    {10.6779842, 0.1983504, 5.18951941},
-    {10.8656731, -0.244461223, 5.2612381},
-    {10.5448284, -0.451776505, 5.68011951},
-    {10.5698853, -1.2562108, 6.07904339},
-    {10.4589863, 0.144911274, 6.47174978},
-    {10.5851555, -0.345442951, 6.55333376},
-    {10.1376381, -0.583400249, 6.86213255},
-    {9.70306206, -1.49629343, 6.71994114},
-    {9.75186062, -2.1625433, 7.21798229},
-    {9.20644665, -2.30945086, 7.81384373},
-    {8.63470078, -1.90212345, 8.05757809},
-    {8.51121616, -2.81142259, 7.94963074},
-    {8.40692329, -3.1064353, 7.51218987},
-    {8.1479044, -3.26068139, 7.5060854},
-    {8.09919548, -2.96733379, 7.83208895},
-    {7.61468935, -1.51920569, 8.32439041},
-    {6.5850091, -1.81167293, 7.97017908},
-    {6.73869562, -1.68513179, 7.47094774},
-    {7.42276812, -0.938464344, 8.3639946},
-    {7.02338982, -0.688331485, 7.74921608},
-    {7.19387102, -0.775213718, 7.7430501},
-    {6.5164237, -0.251547933, 7.99340582},
-    {5.65241241, 2.15090919, 7.90139151},
-    {5.37887955, 0.566102386, 7.53690624},
-    {5.94680214, 0.319150418, 7.65993738},
-    {7.52298927, -1.55221486, 8.00476646},
-    {7.07418585, -1.09750199, 7.64916945},
-    {5.45793867, -0.172092766, 5.99587584},
-    {4.23151684, 0.271388948, 3.88729143},
-    {4.19373751, -0.601394653, 2.93139291},
-    {3.64563584, -0.942507327, 2.02481556},
-    {3.74634385, -1.49209583, 2.16795349},
-    {4.67872906, -2.41744208, 2.27496648},
-    {5.45639229, -3.51541066, 3.16278863},
-    {5.37188673, -4.26132965, 3.93672347},
-    {4.91390419, -4.79762173, 3.49797392},
-    {4.43776894, -5.43367577, 4.01739311},
-    {5.16077375, -5.69820786, 6.41665077},
-    {5.40845442, -5.36787987, 8.23981667},
-    {5.50935602, -4.46469307, 10.2983866},
-    {4.96810865, -3.99342179, 10.8812933},
-    {4.52453899, -3.6704967, 11.684412},
-    {4.37746668, -3.61799121, 12.7796497},
-    {4.38698816, -3.47348022, 13.8683443},
-    {4.45311213, -0.754259288, 14.2152309},
-    {4.17395353, -0.0527261384, 13.8755093},
-    {3.98902059, 0.765278518, 13.3201752},
-    {4.40350199, -1.40030169, 13.9173298},
-    {3.58317709, -2.00354242, 13.327878},
-    {3.65247989, -2.91520095, 13.6341391},
-    {3.98825336, -2.78658795, 13.6841221},
-    {3.85347652, -2.56253338, 12.9691906},
-    {3.60457325, -1.5551461, 12.4833612},
-    {2.25948715, -2.17946553, 9.02596474},
-    {1.73981178, -2.59652758, 7.22229862},
-    {1.58582807, -2.59862375, 5.62559366},
-    {2.66341519, -3.95927763, 6.02119637},
-    {1.76251578, -2.84157729, 4.33970356},
-    {1.43407655, -2.7212708, 3.87731647},
-    {1.82160997, -2.93205094, 5.64224529},
-    {1.48970509, -1.47452497, 5.78565931},
-    {2.72248435, -1.15449452, 7.45229769},
-    {4.4987011, -0.503327727, 9.45086575},
-    {5.35864639, -0.428256333, 8.7956295},
-    {4.25820637, -0.81176424, 7.02587652},
-    {4.78899622, -1.06035328, 7.95917988},
-    {4.79165983, -0.0513284989, 6.7331934},
-    {5.41160965, 0.909635484, 7.09276485},
-    {5.70544386, 2.42124057, 6.70385933},
-    {6.39725256, 3.39762878, 6.25182772},
-    {6.9126153, 4.89994907, 6.08239126},
-    {6.91720819, 6.0937829, 5.56519365},
-    {7.3245759, 6.75553703, 6.00958252},
-    {7.37158966, 7.08813858, 7.25311852},
-    {6.61224461, 7.35888577, 8.31390476},
-    {7.84439993, 6.69548655, 10.4605274},
-    {8.00094891, 6.10002708, 11.6229038},
-    {7.88154602, 5.42056274, 12.3260851},
-    {8.56879139, 3.8161881, 11.8386641},
-    {8.97867012, 2.61921358, 11.1160955},
-    {8.98442364, 0.484133214, 9.44393826},
-    {8.51289558, -1.32639146, 7.17626238},
-    {8.53647137, -3.19125485, 5.67997408},
-    {7.98904943, -4.46861219, 4.57837629},
-    {8.28631115, -5.09792519, 2.84451365},
-    {8.11294174, -4.84656334, 2.67129946},
-    {9.23233414, -5.12001276, 1.87979555},
-    {9.25316334, -4.66940641, 1.72286487},
-    {8.99607658, -4.55484486, 1.30016327},
-    {9.00530052, -4.27720356, 0.831901312},
-    {9.44463921, -3.7346487, 1.38637102},
-    {9.88233852, -3.71053886, 1.42835844},
-    {10.4533415, -2.83673072, 1.17539275},
-    {10.5711737, -2.48031902, 1.00387037},
-    {10.6873655, -1.44717431, 1.25877154},
-    {11.0549927, -0.455511093, 1.45798779},
-    {10.9814978, 0.120737597, 2.0404489},
-    {10.5588236, 0.769167304, 1.99533486},
-    {10.2966795, 0.848536253, 1.72837353},
-    {10.7360182, 1.62440562, 1.88307118},
-    {10.175643, 1.45257103, 1.62494397},
-    {9.85615444, 1.89096546, 1.69040632},
-    {9.32532787, 1.77901411, 1.71936798},
-    {9.66732216, 1.79202259, 1.4487083},
-    {10.0382557, 1.92735589, 1.31430805},
-    {9.37397003, 1.26709545, 0.143876404},
-    {9.64489174, 0.663142323, 0.175739065},
-    {9.23769093, 1.09982157, 0.369148374},
-    {9.63060856, 0.457232147, 0.867039442},
-    {9.83681297, -0.0183828194, 1.04541099},
-    {9.31803036, -0.0625598878, 0.649658799},
-    {9.56514645, 0.114897214, 1.71527123},
-    {9.1839819, -0.179666549, 2.88600087},
-    {9.16211224, 0.308527678, 3.38820982},
-    {8.75922012, -0.0610033683, 3.70068169},
-    {8.32785988, 1.2621944, 5.21276379},
-    {8.39868069, 1.09705615, 6.81587696},
-    {8.22735119, 2.19810891, 7.91300392},
-    {8.2578907, 2.47067237, 9.36842537},
-    {7.88185358, 3.81799436, 10.2741156},
-    {8.2962656, 5.11488914, 11.4928198},
-    {8.18009663, 6.69618654, 10.2733488},
-    {8.21735191, 6.13052225, 10.2439413},
-    {8.78288269, 6.82352352, 9.91648102},
-    {8.76844978, 7.07331133, 7.64232063},
-    {8.73393345, 5.92590666, 8.17907238},
-    {8.58991814, 6.24982119, 7.34528399},
-    {8.85905552, 6.31541252, 6.6084218},
-    {8.70581436, 6.59290552, 5.80857992},
-    {8.71118069, 5.97964478, 5.15400219},
-    {8.94275379, 5.28622961, 5.77119446},
-    {8.9746542, 4.80515575, 6.0856657},
-    {8.61293221, 5.51030922, 5.72487688},
-    {8.6034584, 4.35424948, 6.40846109},
-    {8.03773308, 3.2806623, 6.18924046},
-    {8.37136555, 2.61127639, 7.84927893},
-    {7.76059818, 1.30735636, 8.11492825},
-    {7.64920568, 1.05489564, 7.28989601},
-    {7.95970201, -0.955236495, 8.26974678},
-    {7.52154732, -1.22954702, 6.07614994},
-    {7.50037146, -2.60804367, 6.08811092},
-    {7.06344891, -1.64761603, 3.84402728},
-    {6.73355579, -2.76359797, 3.89602685},
-    {6.66603756, -3.09701037, 3.77142763},
-    {5.78954029, -3.18154883, 5.16087532},
-    {5.63894033, -2.32577419, 5.3552084},
-    {6.36779642, -1.40973639, 7.79463625},
-    {5.99129725, -0.948411524, 8.34766769},
-    {5.83874702, 0.944677591, 8.42042446},
-    {5.90318632, 1.39968956, 8.75208664},
-    {6.21306896, 0.453338563, 8.79682159},
-    {6.16575813, 0.0744639635, 9.4035511},
-    {6.06444073, 0.588715196, 9.73974514},
-    {7.10825539, 1.08888972, 11.2146597},
-    {6.15846825, 1.64716816, 9.00392914},
-    {6.1007967, -0.386284739, 8.906847},
-    {5.9507947, 0.537267804, 7.57048798},
-    {7.30745316, -0.372634411, 8.72175217},
-    {5.77525902, -1.06978285, 6.64217806},
-    {3.74561381, 0.0675753355, 3.6928401},
-    {4.70630264, -0.616304934, 4.61907721},
-    {6.58279657, -2.51455331, 6.13245821},
-    {4.12915897, -0.850559354, 3.83979583},
-    {3.54549527, -1.50416267, 5.46349955},
-    {3.96401739, -1.93072641, 8.67190266},
-    {5.05871439, -2.45590949, 12.2303944},
-    {3.99853325, -0.840226471, 9.64907169},
-    {4.3381896, 0.322005391, 10.5115967},
-    {5.80497456, -1.07443976, 13.4000816},
-    {8.21425629, 0.341772765, 13.70397},
-    {6.77611351, -2.62709498, 9.31875992},
-    {5.75067139, -2.43314719, 8.48444748},
-    {6.40796471, -2.10608697, 9.46638393},
-    {7.77066565, -2.31634474, 9.95996666},
-    {6.71220446, -1.69263768, 7.21674585},
-    {5.81611013, -2.11600423, 6.23550415},
-    {6.45006847, -2.43793869, 6.10174656},
-    {7.1710391, -2.47013593, 5.49337864},
-    {7.04921436, -2.1107111, 4.84979439},
-    {7.25911283, -2.11911559, 4.73984146},
-    {9.28068733, -1.5278914, 5.76748657},
-    {9.1320591, -0.0483333245, 5.10268736},
-    {8.36853886, 0.514737248, 3.9082849},
-    {7.43080187, 1.05070257, 4.20323849},
-    {8.78389072, 0.965956151, 4.65531635},
-    {8.49124146, 0.861274958, 4.35137081},
-    {8.08958244, 1.21378338, 4.62415314},
-    {7.81166887, 1.53335595, 4.49714899},
-    {8.47134399, 1.96179867, 4.87682056},
-    {8.09345245, 1.35769594, 4.53124523},
-    {8.08000755, 0.785599291, 4.80821276},
-    {9.66943932, 1.28341842, 4.8148818},
-    {9.86820316, 1.20255196, 3.77636766},
-    {9.93917179, 0.627800643, 4.17509794},
-    {9.50775719, 0.283596188, 3.62777972},
-    {9.31133556, 0.248476729, 3.21192265},
-    {9.82117748, -0.377281368, 2.62462497},
-    {8.84922504, -0.409401953, 2.67118955},
-    {8.33565903, -0.343196869, 3.22428107},
-    {8.43221569, -1.06590354, 3.89845896},
-    {8.06817722, -0.716212988, 4.66657782},
-    {7.3369236, 0.142002478, 4.82054043},
-    {7.34123898, -0.22788696, 5.52955914},
-    {7.11956263, -0.157053977, 5.94243336},
-    {7.27339697, -0.0454880223, 7.37223291},
-    {7.80864096, 0.254693717, 8.8550148},
-    {7.42342997, 1.09005857, 9.15276718},
-    {6.978374, 1.10700977, 9.90054989},
-    {6.98045731, 1.02599335, 10.5062361},
-    {7.12595987, 1.17305064, 10.9408512},
-    {6.58664608, 1.23789382, 10.8150377},
-    {6.16283178, 0.788213134, 10.657732},
-    {6.45329475, 0.398451775, 10.5252523},
-    {6.21634197, -0.121562503, 9.9676981},
-    {5.70781088, -0.508410454, 8.14885616},
-    {5.89037228, -0.451767474, 6.96322966},
-    {6.08609581, -0.648697436, 6.21598387},
-    {6.34691763, -1.01680756, 5.55869579},
-    {5.83923817, -1.63876295, 4.10176659},
-    {5.65424061, -0.471389949, 3.28750157},
-    {5.34302521, 0.517732322, 3.52325368},
-    {4.71414709, 1.41055858, 3.53620696},
-    {5.43496847, 1.17948997, 4.49491549},
-    {6.00165653, 1.30962527, 5.4451375},
-    {6.30411959, 1.38629866, 5.72177601},
-    {6.16860199, 1.71163416, 6.08163643},
-    {6.06505537, 1.58426225, 5.98575163},
-    {5.64191628, 1.63593662, 5.59358263},
-    {5.21816492, 1.5430398, 5.55090046},
-    {5.82044792, 1.74375868, 6.27535248},
-    {6.8472147, 1.6516608, 6.89177656},
-    {6.39120817, 1.60678935, 6.64514828},
-    {6.70024443, 0.949542105, 7.05361652},
-    {6.58887672, 0.230057135, 6.77443647},
-    {6.4352088, 0.157109335, 6.39436197},
-    {6.67700195, 0.156673729, 7.01894712},
-    {7.15800667, 0.14566648, 7.4635334},
-    {6.63336134, -0.223843545, 6.94923353},
-    {5.61937475, -0.382944733, 5.96266985},
-    {5.81152058, -0.484563351, 6.27475739},
-    {5.20153809, -0.716830015, 5.98918486},
-    {5.63537073, -1.18510699, 7.00819445},
-    {4.97197676, -0.879162192, 6.81389141},
-    {4.88196659, -0.754867256, 6.84158611},
-    {5.14833975, -0.58479321, 7.58707857},
-    {5.63120461, -0.561666667, 8.55335999},
-    {4.80936384, -0.204226106, 7.98744965},
-    {6.12900925, -0.292580187, 9.72455978},
-    {6.4630537, -0.640120149, 10.9837389},
-    {5.6108222, -0.828395605, 11.0778294},
-    {3.74637175, -1.37400317, 9.26250362},
-    {2.64794207, -1.60905731, 7.5379467},
-    {2.79433799, -1.31569159, 6.92228508},
-    {3.51664639, -1.387573, 6.0340004},
-    {4.94117117, -1.09812784, 6.02908278},
-    {6.27261925, -0.800147057, 6.05203962},
-    {4.99570894, -0.493495375, 4.10776615},
-    {6.04331446, -0.235224932, 3.66916656},
-    {6.75057936, 0.619909108, 3.02672076},
-    {9.64090633, 1.7968148, 4.0930109},
-    {11.0780544, 3.82068062, 5.07424927},
-    {9.32933617, 4.49516678, 4.78316832},
-    {9.83621693, 6.0795517, 6.3835969},
-    {9.26789093, 6.50320148, 6.89384556},
-    {8.87006474, 7.03946638, 7.77632236},
-    {9.00277233, 6.08074903, 8.88407135},
-    {9.01303673, 3.70132732, 8.81736851},
-    {8.07019711, 2.03560901, 7.07222223},
-    {8.24582863, 0.28065908, 5.72616196},
-    {8.06920147, -1.15201175, 3.52295613},
-    {7.48540306, -1.82170618, 1.8732444},
-    {7.16077375, -2.44932032, 0.449549466},
-    {7.61349964, -2.42595887, -0.451687455},
-    {8.11131382, -4.00068283, -1.00174463},
-    {8.56983376, -4.39296341, -1.27014065},
-    {8.42537117, -2.9494946, -1.64489949},
-    {8.03266525, -2.58903003, -1.87768769},
-    {7.86476088, -2.61359048, -1.35013115},
-    {8.10282516, -3.10329103, -0.393917531},
-    {7.20972157, -0.915701687, -0.842228234},
-    {7.58716631, -1.33500957, 0.204474956},
-    {7.84340811, -2.96326733, 1.40592086},
-    {7.30932331, -2.82971621, 2.06794095},
-    {6.68706989, -3.47063494, 3.64147305},
-    {6.76488018, -4.25728607, 3.25346303},
-    {6.13700771, -4.02623987, 4.22752094},
-    {5.89120817, -4.45129871, 4.53134584},
-    {5.52959061, -4.73754406, 4.03633165},
-    {8.14061451, -4.23991489, 5.98397398},
-    {8.84194565, -3.56572723, 7.30389214},
-    {7.93977976, -3.52307057, 7.35116243},
-    {8.60658169, -3.41852069, 7.99787283},
-    {11.3583422, -2.81163073, 9.80166054},
-    {11.0335684, -1.09989774, 9.41054821},
-    {8.85140896, -1.23230672, 6.99108076},
-    {10.8084021, -0.740173161, 9.3274231},
-    {11.0764961, 0.408273011, 10.3081026},
-    {9.16822052, -0.389624447, 8.60047531},
-    {10.4921703, 1.62605286, 9.56048298},
-    {10.0389986, 1.24088871, 8.73607349},
-    {9.01630783, 1.25261009, 7.88031101},
-    {8.58615208, 2.06084323, 6.72240496},
-    {10.5409698, 1.43436933, 7.41436958},
-    {9.67747307, 1.3045336, 5.491889},
-    {9.09132671, 1.04567909, 4.1315093},
-    {10.4739008, 1.018641, 4.68442488},
-    {10.1261816, 1.76712012, 3.82267332},
-    {10.0674171, 2.30742836, 3.9471457},
-    {10.5120754, 2.29394627, 3.93789649},
-    {11.748291, 2.44579983, 4.82872915},
-    {10.932785, 5.38639975, 4.22902966},
-    {10.8553343, 4.84933329, 5.12770224},
-    {10.953228, 3.5316577, 7.06358242},
-    {10.7084246, 5.49999952, 6.53628635},
-    {10.8001394, 1.01191664, 8.61234474},
-    {10.0999031, 2.75703621, 8.04576969},
-    {9.86954308, 1.15792561, 8.43933392},
-    {9.99436665, 1.13246763, 8.33793831},
-    {9.31947517, -0.116620637, 7.86634779},
-    {8.84434032, -2.12871766, 7.32849455},
-    {8.83847618, -2.67977095, 7.42985773},
-    {8.87943649, -2.57316637, 7.1013999},
-    {8.99756527, -2.01099396, 6.45923328},
-    {8.66519928, -2.21930027, 6.69716167},
-    {8.81680298, -2.33086562, 6.89161205},
-    {8.50040245, -1.61088157, 7.89114046},
-    {7.57169247, -1.23138082, 8.55338383},
-    {7.47097111, 1.18967319, 8.76123714},
-    {7.80344629, 1.29515815, 10.063611},
-    {7.38573265, 1.76874745, 9.80290508},
-    {6.82781267, 2.22566319, 9.99360561},
-    {7.29850912, 2.78012562, 10.927721},
-    {7.28659439, 3.82232308, 8.91684437},
-    {6.63023758, 2.8492341, 9.42320442},
-    {6.82112503, 2.54676509, 9.16326427},
-    {7.5211091, 3.46262169, 9.55601501},
-    {7.60710239, 2.38200521, 9.27342129},
-    {6.72694111, 1.58741677, 7.90392303},
-    {6.76298666, 1.13004887, 9.35572243},
-    {8.13863182, 2.22516584, 8.48450565},
-    {7.86656761, 1.65720141, 8.35089207},
-    {8.66043854, 0.480743408, 10.8466043},
-    {7.90138292, 0.457681417, 8.03524303},
-    {8.86232758, -1.3468399, 8.76332092},
-    {8.89193249, -1.37289691, 7.84660101},
-    {7.2849474, 0.201254711, 3.08750415},
-    {5.15834522, 1.87951684, -0.672881663},
-    {2.78133583, 3.56152678, -5.03482962},
-    {3.34198356, 1.966591, -2.60405445},
-    {4.46658373, -2.00425529, 1.67566609},
-    {5.0162878, -2.55904078, 4.81245232},
-    {4.96728373, -3.60279369, 6.00540495},
-    {6.65210581, -4.4515152, 8.65522575},
-    {6.00612068, -4.07967901, 7.23331785},
-    {5.19305372, -5.13687611, 7.543437},
-    {4.84177017, -4.52970123, 8.34088039},
-    {7.12551308, -4.70714331, 11.8328571},
-    {6.82704115, -4.44170094, 11.0012112},
-    {5.13815928, -4.70354891, 8.30488586},
-    {4.828619, -4.38714647, 6.99075603},
-    {8.19075108, -3.94639945, 11.7518587},
-    {6.24684, -4.4986887, 8.89181232},
-    {4.52356529, -5.35572386, 6.70594645},
-    {4.32514715, -2.62709451, 7.51431036},
-    {7.73400879, -3.39635706, 10.5129375},
-    {6.63282299, -1.9859997, 8.5267725},
-    {6.19673395, -1.95634747, 7.77823544},
-    {4.305233, -1.43599129, 5.83251762},
-    {7.40952682, -1.34129906, 8.79771519},
-    {9.50504017, -2.44572592, 9.70475864},
-    {9.55673409, -2.5418539, 7.68337917},
-    {8.56432915, -2.2911818, 6.0813489},
-    {8.68131828, -1.41847169, 5.50224352},
-    {9.57496548, -1.60501337, 5.26572418},
-    {9.14178753, -0.554710329, 5.36959219},
-    {7.81226349, -0.478573233, 3.91200805},
-    {9.23679829, -0.654233336, 4.16363335},
-    {10.9417734, -0.136986881, 4.40364552},
-    {9.38155651, -0.274909437, 3.42409205},
-    {8.02575874, 0.949020505, 2.9476409},
-    {8.60226822, 1.30019081, 3.70043325},
-    {10.4270077, 2.94732237, 5.87066793},
-    {8.9648037, 3.47701097, 5.96180296},
-    {9.53770447, 4.42365265, 7.19854879},
-    {10.5961666, 5.69723272, 10.018918},
-    {8.64913177, 5.41255283, 10.1070614},
-    {6.47329521, 4.34307289, 9.55871868},
-    {8.19655418, 4.33613014, 11.6896229},
-    {7.99304247, 2.43323517, 10.8616867},
-    {7.44292068, 1.1968478, 9.40279007},
-    {6.62299585, 0.403553039, 7.05960941},
-    {6.89787579, -0.732186556, 6.56371927},
-    {7.34838009, -2.22424197, 4.76723671},
-    {7.64295721, -3.61589479, 2.639884},
-    {6.64184093, -3.13428926, 0.234550983},
-    {5.85169077, -2.11162758, -0.401957631},
-    {5.84841776, -1.42710769, -0.242346674},
-    {4.56834698, 0.624056876, -0.146311969},
-    {2.84819484, 2.79083014, 0.540075123},
-    {2.95724821, 1.78104711, 0.692688346},
-    {4.72128868, 0.127326682, 2.74425626},
-    {6.17538214, -0.534839571, 4.43889189},
-    {6.39903879, -0.0980513617, 5.0624876},
-    {6.77626371, 0.176778898, 5.39986992},
-    {7.38200283, 0.69459039, 5.80515528},
-    {7.33305597, 0.656702936, 5.21465492},
-    {7.51101494, 1.17985761, 4.84315348},
-    {8.82680321, 1.82757664, 5.03269434},
-    {8.39308834, 2.21547985, 4.17926693},
-    {7.82854939, 3.18295193, 2.78748441},
-    {8.79808426, 4.14633036, 2.56959796},
-    {9.01529694, 4.96270418, 1.99830806},
-    {9.12357903, 5.51468468, 0.811205506},
-    {9.89662075, 5.83919859, 0.382697433},
-    {9.17178345, 5.67626762, 0.361257166},
-    {8.1121788, 6.33512974, 0.463703126},
-    {9.28353691, 7.2380023, 0.926302969},
-    {9.6850605, 7.70422029, 1.94471192},
-    {10.3766079, 8.5156765, 3.18366027},
-    {10.4940186, 8.76497746, 3.97359014},
-    {10.023675, 8.37915707, 5.02303171},
-    {9.14485264, 7.85891533, 5.5361104},
-    {9.9526062, 7.30777836, 7.15408468},
-    {8.55942917, 6.12778187, 6.89131498},
-    {8.2009058, 4.75548267, 6.69553757},
-    {7.94681597, 4.21496534, 5.66406822},
-    {7.74293566, 3.73292494, 4.94441795},
-    {6.6553793, 3.09902167, 3.66678452},
-    {7.68500328, 3.25584912, 2.97012424},
-    {7.64756918, 2.84548998, 2.19767761},
-    {6.30755043, 3.60930681, 0.961191475},
-    {5.27310038, 4.54473543, 0.412028939},
-    {7.93083477, 7.19407654, 0.178121284},
-    {8.67641163, 9.68262482, 1.53499579},
-    {8.47649956, 11.5238295, 3.54632163},
-    {8.9881916, 12.3684216, 6.97186422},
-    {9.18163776, 13.4518194, 9.7136364},
-    {8.44947338, 12.4644127, 11.9096842},
-    {7.70693064, 11.1353569, 13.9490414},
-    {7.65604925, 8.40820885, 15.8724155},
-    {6.30816603, 4.95712137, 14.2941313},
-    {5.54699755, 2.19346619, 12.9239273},
-    {3.98005748, 0.594496548, 9.86436844},
-    {3.21552372, -0.542966962, 7.49804592},
-    {2.67702579, -1.99991238, 6.39334726},
-    {0.723065555, -2.32083678, 4.8471961},
-    {-1.59145272, -1.82909739, 4.22211409},
-    {-2.61514997, -1.30956089, 4.77327394},
-    {-1.96637666, -1.53464341, 5.08339977},
-    {0.0319790021, 0.444533169, 5.95937634},
-    {3.7805357, 0.871856868, 5.27296972},
-    {7.03624725, 1.08005416, 3.70609117},
-    {7.91298628, 2.33692956, 2.45823693},
-    {9.25732899, 2.2792747, 0.516848087},
-    {9.73832226, 2.03233218, -1.02089739},
-    {9.73549557, 1.97003531, -2.64395738},
-    {9.36474419, 1.23834288, -4.44523954},
-    {9.34510708, 0.113549441, -6.17758512},
-    {10.0272446, -1.51486278, -7.26538229},
-    {10.0903282, -3.25528979, -8.08681297},
-    {9.97576904, -5.90786171, -7.84903431},
-    {9.8622942, -7.87254524, -7.61589336},
-    {9.45892143, -9.49668694, -5.95573854},
-    {9.32485104, -10.2600851, -5.07298279},
-    {8.78154278, -11.4304476, -3.10551858},
-    {8.10832977, -11.1069803, -1.18497527},
-    {7.14846849, -9.86823559, -0.789651394},
-    {6.88253832, -7.67251015, -0.122964978},
-    {8.35634041, -7.81346655, 1.06446886},
-    {8.83108521, -7.45525694, 2.54191351},
-    {9.4975853, -6.20765781, 3.52555013},
-    {10.5625439, -5.28444052, 4.78495502},
-    {10.8695726, -3.56953979, 5.68026304},
-    {10.8237448, -1.48885882, 5.23941278},
-    {11.034462, 0.209840581, 5.4501996},
-    {10.6092577, 1.7022773, 5.32051563},
-    {9.72478485, 1.88901889, 4.63770199},
-    {7.96327305, 3.06367993, 3.10055232},
-    {5.75245714, 3.35584807, 2.17683315},
-    {6.99994612, 3.39014149, 3.63253951},
-    {9.67604542, 3.14577651, 4.08963919},
-    {10.5021591, 2.91986442, 4.06196499},
-    {10.8576002, 2.56680465, 4.26246071},
-    {10.7020969, 2.33977485, 4.48166418},
-    {10.0662251, 2.47080874, 4.93637705},
-    {10.0656967, 2.20522428, 5.25632},
-    {9.92707062, 1.93018281, 5.61529303},
-    {10.1091595, 1.75476789, 6.05107069},
-    {10.2167854, 1.59864807, 6.72202682},
-    {10.6708546, 1.83151364, 7.52901554},
-    {10.1613617, 2.09413028, 7.78213263},
-    {9.09882832, 1.96590567, 8.12907696},
-    {7.08266592, 2.22326708, 8.35297775},
-    {4.43920851, 1.47045982, 8.79428959},
-    {5.56270981, 1.40231729, 7.6385746},
-    {7.55800581, 0.776205778, 7.44578457},
-    {6.00038576, 0.337175816, 6.4825778},
-    {2.51822829, 0.206304431, 6.96047783},
-    {-0.294555306, -0.673551261, 6.16785526},
-    {-0.829108298, -0.886799455, 6.38032103},
-    {2.50243902, -2.2741096, 5.71135426},
-    {5.63373327, -2.37758899, 4.08784819},
-    {7.87904167, -2.81296992, 3.83307767},
-    {8.65157509, -3.22266746, 2.81735206},
-    {10.1877766, -3.86508322, 1.53928232},
-    {10.541173, -4.30871344, 0.638036609},
-    {11.3066034, -4.4588933, 0.173197985},
-    {11.2830658, -4.21999788, -1.22175109},
-    {11.2345715, -4.71020317, -2.36453819},
-    {10.7677059, -5.00335455, -2.11182094},
-    {10.6461544, -5.22079515, -3.60921645},
-    {11.1585417, -5.16059494, -3.43486571},
-    {10.5737009, -5.45186424, -3.9469018},
-    {10.0836315, -5.51221418, -4.17798042},
-    {10.0007629, -6.01613283, -4.37823868},
-    {9.38929272, -5.99337101, -5.16185141},
-    {9.01512051, -7.12475348, -5.29555416},
-    {9.40833759, -7.9447999, -5.26145935},
-    {9.26762104, -9.13243103, -5.23421764},
-    {9.0051527, -8.887043, -5.6639123},
-    {8.49339104, -9.04753017, -4.1131649},
-    {8.87765217, -9.44951534, -4.11455297},
-    {9.13310146, -9.16693211, -3.54266286},
-    {9.03163528, -9.11706448, -2.46841478},
-    {9.1243639, -8.59324932, -2.52970791},
-    {8.55421734, -7.50268364, -2.29668045},
-    {8.91756725, -7.09328604, -1.31055725},
-    {10.0828886, -6.86942482, -1.10740292},
-    {10.6510067, -5.77680492, -1.07508898},
-    {10.6994171, -4.30385923, -1.28220057},
-    {11.185111, -3.84533048, -0.935544312},
-    {11.4169645, -2.96237278, -1.62450111},
-    {10.5536156, -2.37444353, -1.82237709},
-    {10.141655, -1.82589912, -1.5941273},
-    {10.0085812, -2.14135146, -2.071738},
-    {8.95605659, -2.30855274, -1.67065728},
-    {8.21572685, -2.58686638, -1.30763721},
-    {6.7860055, -2.21720362, -0.41550678},
-    {5.02830935, -0.752661884, -0.0232874528},
-    {3.29501343, 0.607448697, 0.662256956},
-    {2.62622094, 1.13651085, 2.23847365},
-    {2.71816444, 0.833111763, 3.00809121},
-    {3.17634153, -0.39717567, 5.09134102},
-    {4.02157927, -0.704192698, 6.21045065},
-    {4.52755404, -0.353320777, 7.50651503},
-    {4.53814507, -0.110181302, 7.17897177},
-    {4.77425289, -0.213211268, 7.0707283},
-    {5.20411062, -1.09559834, 7.50024986},
-    {5.53685331, -0.994589508, 7.56801987},
-    {6.41213036, -0.219650656, 7.98298311},
-    {7.65664434, 1.18967319, 8.45064926},
-    {8.02814007, 2.06947088, 8.21525192},
-    {8.79641914, 1.45773077, 8.94258404},
-    {8.05090141, 1.52167511, 9.17619514},
-    {4.31937551, 0.925876856, 7.49770689},
-    {4.83049011, 0.694889903, 7.49476862},
-    {4.86071539, -0.13888067, 7.46259546},
-    {4.31468296, -0.317588955, 6.03727722},
-    {1.77073932, 1.05540848, 1.72254407},
-    {0.783285856, 1.38809574, 2.04058337},
-    {4.77306175, 0.11205212, 0.341901332},
-    {1.31520426, -0.250050366, 0.679139256},
-    {1.61781514, -1.72037375, 1.92799544},
-    {1.95260966, -3.16284394, 2.18029118},
-    {2.19551325, -0.169782862, 0.886395454},
-    {2.20339847, -4.21850395, 0.318890929},
-    {1.89900219, -2.05157661, 0.021488104},
-    {2.2175324, -3.37194729, -1.11559188},
-    {1.73058748, -3.48650837, -2.69413376},
-    {1.1561625, -3.6108036, -1.97305489},
-    {0.660737276, -1.58869088, -4.46399975},
-    {0.622799277, -1.12879992, -4.59219408},
-    {0.365862817, -0.472732812, -6.66073656},
-    {-1.06908464, 0.296846837, -6.01469994},
-    {1.85511363, -0.0645065829, -15.2484674},
-    {5.82372236, 6.05619144, -23.2132339},
-    {4.00180674, 4.80740213, -14.3449965},
-    {4.89119101, 9.00497437, -18.2477245},
-    {7.25301456, 15.1126432, -21.9930763},
-    {5.90807724, 12.0927248, -16.4190502},
-    {3.1702826, 10.2238379, -7.71262693},
-    {16.2251167, 27.6954746, -26.3555832},
-    {13.4912004, 32.4409904, -23.3153687},
-    {3.73877072, 15.3568878, -5.82128954},
-    {8.00253582, 14.8368778, -5.55762529},
-    {11.444047, 16.147007, -3.72964239},
-    {8.51811695, 8.12886715, 0.839619696},
-    {10.7593737, 6.4714551, 3.79483056},
-    {11.9595509, 0.091086477, 8.80739212},
-    {4.24416256, -17.8072186, 18.1075649},
-    {1.45609534, -28.9067535, 22.4152775},
-    {16.0431633, -11.6066008, 20.7711983},
-    {21.6115055, 0.943977177, 6.68444395},
-    {21.1467857, 3.19007158, 2.04432011},
-    {21.249588, 2.4287281, 0.475903034},
-    {22.8794518, 2.01008081, -1.87468171},
-    {25.9990368, 1.99796927, -6.75757456},
-    {32.6168404, -1.28424323, -12.5117025},
-    {37.6747894, -5.50113249, -17.2546234},
-    {36.3737411, -8.29731846, -15.1423063},
-    {36.5993156, -10.9579268, -12.158782},
-    {37.1303101, -12.2314911, -8.10597706},
-    {40.1021423, -12.5894146, -5.84739399},
-    {44.5906982, -10.6983309, -1.51758301},
-    {55.4099846, -8.84751987, -12.2211542},
-    {56.1023712, -0.152411312, -6.45496845},
-    {50.6311264, 7.25960398, 8.15554714},
-    {44.2477264, 8.6800108, 18.7579231},
-    {38.2456474, 17.3146076, 22.6794109},
-    {37.5593452, 7.2479248, -0.219416961},
-    {51.928299, -5.4311986, -37.56007},
-    {51.7512589, -11.4934921, -43.3694916},
-    {37.8781624, -12.6343107, -26.1058903},
-    {16.9945889, -4.0235219, -3.3960042},
-    {9.34870052, -0.347947866, 6.06445551},
-    {14.2327051, -1.50722528, -5.19326687},
-    {28.2605247, -4.38727188, -17.7249699},
-    {30.4484272, -1.69336808, -24.5589142},
-    {32.677845, -1.7971468, -19.6744003},
-    {33.2836113, -1.71950257, -15.1555157},
-    {31.7640991, -1.40090096, -7.9501338},
-    {29.3156433, -1.09615397, -2.34840846},
-    {23.6569004, -2.8497088, 1.02938032},
-    {24.3817787, -0.624581873, -0.721775115},
-    {30.85429, -4.70115328, 8.01678085},
-    {28.0607185, -1.84686458, 7.41034889},
-    {25.237833, -2.02806568, 8.00695515},
-    {20.7852497, 0.295353919, 3.7955389},
-    {19.5983219, 0.644722641, 1.31847692},
-    {14.1228561, 0.571585357, -4.70119762},
-    {13.2080832, 0.565653265, -5.14324045},
-    {19.8306293, 0.260937989, 3.22697425},
-    {20.4200668, 5.3618207, 10.6620407},
-    {20.2047348, 7.01490784, 9.29158401},
-    {17.2793484, 2.96828794, 2.19827294},
-    {14.4797306, -1.00954688, -1.1666255},
-    {10.7445011, -7.16284895, -4.18616915},
-    {14.2060757, -5.99172306, -5.4151144},
-    {18.023241, 0.67915684, 0.435404807},
-    {18.8578644, 8.44864178, 3.72782946},
-    {16.5850086, 9.39208317, 2.97965288},
-    {14.0093641, 6.90270996, 1.77884257},
-    {12.3172112, 1.63219285, 0.862870634},
-    {13.9412527, -0.259185374, -0.169687793},
-    {15.3490915, 2.70664644, 0.0344641693},
-    {14.6228456, 7.53170109, 0.962821543},
-    {12.62749, 7.53603888, 1.36187148},
-    {11.7066345, 4.86700344, 1.19876862},
-    {11.5557098, 2.436692, 0.94044286},
-    {12.8785429, 2.19481421, 0.586975813},
-    {13.102499, 2.03270888, 0.833318174},
-    {12.9954815, 3.17958832, 1.03275514},
-    {12.5226717, 3.68994617, 1.33649266},
-    {12.2786798, 2.74665356, 1.68549299},
-    {12.2239275, 1.4024719, 1.83676612},
-    {12.7087889, 1.63533783, 1.91016948},
-    {12.6018219, 2.40746307, 1.8127948},
-    {12.151104, 2.78143239, 1.81523561},
-    {12.0820017, 3.06605315, 1.73712659},
-    {12.1499071, 2.68994665, 1.65353131},
-    {12.295373, 2.10618305, 1.62075722},
-    {12.5889425, 2.06223464, 1.58780146},
-    {12.5895367, 2.38528609, 1.36231828},
-    {12.1288595, 2.19930649, 0.764007032},
-    {11.8654556, 1.80733097, 0.444500715},
-    {11.9959888, 1.51408124, 0.276946455},
-    {12.0748549, 0.975227237, 0.0722598284},
-    {11.9361944, 0.395534009, -0.283738256},
-    {11.5910339, -0.201081321, -0.548168778},
-    {11.5239363, -0.479172319, -0.722222209},
-    {11.6371546, -0.526643932, -0.941984951},
-    {11.6695366, -0.710985243, -1.07494462},
-    {11.6439991, -1.19199538, -1.38255286},
-    {11.6084414, -1.85060906, -1.67125297},
-    {11.6685667, -2.08957005, -1.84372175},
-    {11.4668083, -2.16958189, -2.01429725},
-    {11.1249266, -2.0317142, -2.1860857},
-    {11.03829, -1.81070209, -2.14280939},
-    {10.8269176, -1.5797056, -2.19460416},
-    {10.3878784, -1.39446115, -2.41928053},
-    {10.2030563, -1.12513793, -2.5122385},
-    {10.1718178, -0.629528701, -2.53718758},
-    {10.1801176, 0.0486340262, -2.58746028},
-    {10.1318359, 0.554571509, -2.38741755},
-    {10.0726233, 0.69773519, -2.30597448},
-    {9.86061668, 0.611926794, -2.15782785},
-    {9.64831352, 0.760481715, -1.93121648},
-    {9.44305229, 1.09461653, -1.60741496},
-    {9.16190624, 1.42287707, -1.31562877},
-    {8.84105206, 1.84903491, -0.902677834},
-    {8.38460732, 2.1114018, -0.577351153},
-    {7.99719477, 2.40566635, -0.2063151},
-    {7.74546432, 3.04810548, 0.505830228},
-    {7.86865044, 4.2089901, 1.23197126},
-    {7.66140509, 5.602139, 1.46379423},
-    {7.41608715, 6.72067547, 1.2439276},
-    {7.24820042, 7.51934338, 1.30285287},
-    {6.63797379, 7.75618553, 1.27023613},
-    {6.16620398, 7.77699947, 1.0978204},
-    {5.64861107, 7.62604904, 1.01205921},
-    {5.41840935, 7.65803862, 0.835623562},
-    {5.50569153, 7.92900753, 0.638113022},
-    {5.50995159, 8.05029869, 0.428853601},
-    {5.80996609, 8.04879284, 0.127556041},
-    {6.53650808, 8.35010529, -0.141994178},
-    {7.81419849, 8.45807648, -0.293416113},
-    {9.35492611, 8.12068367, -0.615913868},
-    {11.2681875, 7.57183933, -0.799198687},
-    {10.7726135, 6.73876429, -1.29396319},
-    {7.9607439, 5.52606535, -1.31555235},
-    {2.97510123, 5.10046768, -2.70619392},
-    {3.19052935, 3.59560204, -2.95439434},
-    {10.8034115, 0.00363079505, 1.49282825},
-    {13.4601107, -0.835583866, 3.00496411},
-    {13.8736658, -1.70280266, 3.7535243},
-    {13.1178436, -3.03747225, 5.0633316},
-    {13.2471218, -3.06886744, 5.90331459},
-    {12.8641129, -2.67634535, 6.01211405},
-    {11.4694386, -1.56136358, 4.55179596},
-    {11.1795807, -1.45716918, 4.55317116},
-    {11.8745413, -1.36677504, 5.24005175},
-    {11.5839453, -0.655344367, 4.27667522},
-    {12.5914097, -0.918642461, 4.37998533},
-    {13.6573868, -1.59243453, 4.96049786},
-    {12.4354887, -1.32048345, 3.81195307},
-    {11.0161619, -1.53927219, 2.45883203},
-    {11.8326454, -2.58080339, 1.24760485},
-    {11.4754333, -3.06764984, 0.244824439},
-    {9.20024967, -4.73256445, -0.0640024543},
-    {6.06176376, -7.51216412, -3.63140202},
-    {3.17015672, -10.117713, -6.90931702},
-    {10.314682, -4.34998417, -0.917864978},
-    {10.8779392, -3.26734757, 0.196457505},
-    {10.9212427, -3.26891732, 0.110971548},
-    {10.7191601, -3.26842475, 0.597551823},
-    {10.3627367, -3.2804482, 0.552433074},
-    {10.0730705, -3.34823203, 0.673919022},
-    {9.77923775, -3.62592816, 1.02352405},
-    {9.20778561, -4.93641567, 1.12625873},
-    {7.76665735, -8.62171078, 2.56802797},
-    {5.42710304, -10.492425, 3.06618309},
-    {8.93433666, -6.68507957, 0.385377377},
-    {10.4750614, -3.60825729, -1.56583798},
-    {11.9918327, 0.569664776, -1.77518344},
-    {13.4388304, 4.61379051, -4.19954062},
-    {13.0032177, 6.06936932, -5.82337427},
-    {11.8969183, 5.33438206, -5.39054728},
-    {10.5709391, 3.69236565, -3.7387383},
-    {9.76953125, 2.54894352, -3.49603701},
-    {9.9859457, 3.59453368, -4.94880867},
-    {8.61446762, 1.95296311, -3.65522408},
-    {8.61997223, 2.710114, -4.23128319},
-    {8.43444729, 3.23230267, -4.82223129},
-    {7.52706051, 2.04835606, -3.07603836},
-    {7.46516943, 0.321106851, -0.0876490101},
-    {7.77387285, -1.10408175, 0.102899745},
-    {7.16649914, -2.61685467, 1.19127119},
-    {7.81917191, -0.906444311, 0.104632378},
-    {7.81658411, 0.249587789, -0.366569847},
-    {8.16545868, 2.80236149, -2.49581099},
-    {7.66913366, 3.43707752, -4.21129131},
-    {7.16895485, 3.68452406, -4.53628874},
-    {7.28485346, 5.44714642, -6.07023478},
-    {6.38817835, 5.23243475, -5.47950268},
-    {5.99719334, 5.1058588, -4.87449217},
-    {5.95241261, 4.95715523, -4.39372349},
-    {5.77700472, 4.41849375, -3.83031988},
-    {5.52944136, 3.45857835, -2.64633942},
-    {5.58210707, 2.65455532, -1.50419736},
-    {5.67866421, 2.31326866, -0.658199131},
-    {6.01625586, 2.23426247, -0.161458269},
-    {6.75491142, 2.31087279, 0.371679485},
-    {7.87281704, 2.69304204, -0.191276982},
-    {8.48985863, 2.31868887, -0.226862028},
-    {9.050354, 1.67533076, 0.555383861},
-    {10.259202, 1.83515155, 0.447392941},
-    {11.0291052, 1.96179879, 0.258224636},
-    {11.1816006, 1.68400729, 0.577297866},
-    {11.8221731, 1.53970015, 0.5997082},
-    {12.0625048, 1.26814377, 0.407859981},
-    {11.7657652, 0.733612359, 0.462403715},
-    {11.3013659, -0.0787477344, 0.818256259},
-    {11.2481041, -1.25593984, 1.47287667},
-    {11.4083376, -2.41352963, 2.19410443},
-    {11.3248816, -2.20335817, 2.58896279},
-    {11.2833977, -2.85104918, 2.27404428},
-    {10.9914656, -3.85250425, 2.16462374},
-    {9.91938114, -3.50238204, 1.93875659},
-    {8.93969154, -4.67000437, 3.26358771},
-    {9.66586876, -5.29492378, 2.48801494},
-    {8.6373148, -5.00847387, 1.76181531},
-    {6.73304224, -4.39296246, 1.26993847},
-    {5.57600784, -5.09350586, 0.842174828},
-    {4.92779016, -4.56353092, 0.637896538},
-    {4.19742346, -3.42177153, 0.362246543},
-    {4.67293596, -2.70854259, -0.83999449},
-    {6.0668931, -1.75522494, -1.75569177},
-    {8.22294426, -0.773909628, -1.9170332},
-    {10.1098566, 0.240898326, -1.87437141},
-    {11.5981741, 1.43721485, -1.73825336},
-    {12.5955687, 2.28316832, -1.64787674},
-    {12.6985226, 2.84803629, -1.13048077},
-    {12.0927086, 3.08194971, 0.509403646},
-    {12.4546795, 3.57882977, 0.994490206},
-    {12.4057322, 3.90723777, 1.26800287},
-    {11.3857632, 3.42807436, 2.42552614},
-    {11.2881584, 2.80655456, 3.31562757},
-    {11.1540766, 2.31716204, 4.3643384},
-    {10.1755753, 2.03367996, 5.18830061},
-    {9.98578644, 1.96837413, 5.51740456},
-    {10.1801109, 1.53804183, 5.53358364},
-    {10.3579998, 0.411525816, 4.87953758},
-    {10.3049679, -0.272595525, 3.99556923},
-    {10.1593599, -0.585796058, 3.55303216},
-    {9.5705843, -0.711566091, 2.56124234},
-    {9.09278202, 0.200406015, 0.668568134},
-    {8.9518137, 1.46152294, -0.887591958},
-    {8.66285038, 2.13943744, -1.91118836},
-    {8.98514462, 3.47352624, -3.45445609},
-    {9.06622791, 5.30307817, -4.34170771},
-    {8.99949837, 6.48014069, -4.08715725},
-    {9.10855293, 7.1143446, -3.48667979},
-    {8.85831165, 6.74685144, -2.90660048},
-    {7.96059513, 5.55407, -2.64172363},
-    {7.20183706, 4.13546085, -2.75428557},
-    {6.95659399, 2.8990562, -3.08744454},
-    {7.09631491, 2.55102754, -3.27722383},
-    {7.46249199, 3.23230124, -2.99965787},
-    {7.86865568, 4.2711916, -1.693753},
-    {8.10847855, 4.75124502, -0.625591636},
-    {8.35148811, 4.73374796, -0.300327539},
-    {8.46477032, 4.02185774, 0.0676714629},
-    {8.29415226, 3.01516056, 0.547519684},
-    {8.3527689, 2.75024724, 0.923022628},
-    {8.8663435, 4.13785696, 0.889522076},
-    {8.7274828, 4.52284956, 0.661069274},
-    {8.52164841, 4.46369028, 0.305687219},
-    {8.63437366, 4.45132351, 0.18964842},
-    {8.41571808, 3.50794244, 0.695720255},
-    {8.20518398, 2.32644677, 1.43386745},
-    {8.52713585, 1.75244451, 1.8199414},
-    {9.21239853, 1.81444204, 1.83646834},
-    {9.66006756, 2.1829834, 1.80922115},
-    {10.0331955, 2.22176957, 1.91448689},
-    {10.3533802, 1.89852583, 2.10529304},
-    {10.7624693, 1.39319694, 2.40007329},
-    {11.0064917, 0.930301189, 2.6181457},
-    {11.0999231, 0.559663057, 2.61606169},
-    {11.2523146, 0.594351351, 2.28013587},
-    {11.590291, 0.880882919, 1.64752567},
-    {11.6833086, 0.861584008, 1.24613988},
-    {11.4065533, 0.309126645, 1.16541696},
-    {11.4145851, -0.164990842, 1.02322614},
-    {11.479393, -0.207960814, 0.438581169},
-    {11.3236799, -0.255591363, -0.256193548},
-    {11.3328161, -0.500713944, -0.811597228},
-    {11.3873701, -0.817657232, -1.03467691},
-    {11.2787514, -1.16758561, -1.18318844},
-    {10.8871737, -1.73155534, -1.31605756},
-    {10.4714441, -2.22405815, -1.39140022},
-    {10.1096678, -2.56118608, -1.46146536},
-    {9.69086266, -2.71737766, -1.5195328},
-    {9.28604412, -2.7808733, -1.52563763},
-    {8.7839222, -2.89228892, -1.52742422},
-    {8.4415884, -2.85784602, -1.55511808},
-    {8.20681858, -2.55130196, -1.6687218},
-    {7.95608044, -2.31038141, -1.86224401},
-    {7.65976906, -1.88894522, -2.00729942},
-    {7.72612715, -1.28712749, -2.21350861},
-    {7.97472906, -0.456110269, -2.42955446},
-    {7.95300722, 0.0666769147, -2.31148362},
-    {8.15385532, 0.45258984, -2.22840238},
-    {8.56804848, 1.1510371, -2.346771},
-    {8.72456074, 2.12353182, -2.41228294},
-    {8.7621069, 2.91866016, -2.25481033},
-    {8.67933369, 3.1295712, -1.92987633},
-    {8.55971622, 3.30777669, -1.6843549},
-    {8.47670078, 3.52761459, -1.48454368},
-    {8.26990032, 3.67601943, -1.17589259},
-    {7.9669919, 3.7531426, -0.933349252},
-    {7.61602879, 3.62884736, -0.817214429},
-    {7.18107414, 3.3484962, -0.730167568},
-    {7.01952696, 3.24139786, -0.574363708},
-    {7.00113773, 3.13705873, -0.353568047},
-    {6.93865061, 2.86645532, -0.19976373},
-    {7.0231905, 2.77822495, -0.334763914},
-    {7.15213346, 2.85495448, -0.58054769},
-    {7.37515926, 2.87978339, -0.907442451},
-    {8.03498363, 3.0636797, -1.37570453},
-    {8.78124428, 3.30642939, -1.75522745},
-    {9.13720322, 3.37419939, -1.73908854},
-    {9.57243729, 3.41559935, -1.68614197},
-    {10.1182175, 3.32657313, -1.62301695},
-    {10.6047945, 3.143049, -1.51030147},
-    {10.7991695, 2.82368994, -1.20329762},
-    {10.7404509, 2.53747153, -0.807843328},
-    {10.7027292, 2.19965935, 0.179965615},
-    {11.408783, 2.16591215, 0.53799063},
-    {10.8938694, 2.123981, 0.586380243},
-    {10.0123682, 1.87059915, 1.31237221},
-    {10.2441711, 1.7758193, 1.7548852},
-    {10.1235952, 1.56277514, 2.49413371},
-    {9.65887642, 1.4578805, 2.7948792},
-    {9.961339, 1.62335753, 2.55308032},
-    {9.91596127, 1.89750946, 2.66635013},
-    {9.35341358, 2.15251136, 2.6536684},
-    {9.39792252, 2.61367321, 2.88734031},
-    {9.43095112, 4.02943611, 3.58266068},
-    {9.12364197, 3.54816699, 3.29714227},
-    {9.57898331, 3.73966408, 3.08134508},
-    {9.71216774, 5.03456736, 2.86868572},
-    {9.50504303, 5.6614418, 2.43709445},
-    {8.62904644, 4.8789835, 2.179811},
-    {8.49809551, 4.61389875, 1.95614958},
-    {8.54677486, 4.55267239, 1.44354522},
-    {8.32338715, 4.0021081, 1.15556777},
-    {8.36630726, 3.11834002, 0.901731133},
-    {8.67576313, 2.63284111, 0.385079712},
-    {8.65403175, 1.50928903, -0.223634467},
-    {9.27974033, 0.763817012, -1.28068483},
-    {9.24268627, 0.0456920899, -1.12566352},
-    {9.18011379, -0.507475615, -0.996479273},
-    {9.23516083, -1.1782186, -0.897913277},
-    {9.49224758, -1.71598089, -1.0411464},
-    {9.56826973, -1.82724726, -1.01494157},
-    {8.72200108, -1.6856674, 0.103188545},
-    {7.90629196, -1.39431179, 1.63472116},
-    {8.47268391, -1.34803784, 2.02779317},
-    {9.83372784, -1.5986836, 0.7725299},
-    {10.7421274, -1.96317291, -0.86197114},
-    {10.8630705, -1.88639975, -1.6764642},
-    {10.8180685, -1.6156739, -1.63109303},
-    {10.4063272, -1.2691958, -0.673188865},
-    {9.77477169, -0.735998392, 0.478732079},
-    {9.48157024, -0.322535187, 1.20508969},
-    {9.8011055, -0.0709459782, 1.07727373},
-    {10.6381216, 0.139606461, 0.147449791},
-    {11.1039391, 0.200106606, -0.833145797},
-    {11.0973692, 0.285914987, -1.22740889},
-    {10.9182673, 0.444802701, -1.15311229},
-    {10.8122292, 0.640529633, -0.862078488},
-    {10.7622023, 0.691894829, -0.670557082},
-    {11.0761185, 0.769466758, -0.966552019},
-    {11.6844654, 0.925658941, -1.80778575},
-    {12.133173, 0.851531208, -2.69904685},
-    {12.1045046, 0.645902514, -3.08527851},
-    {11.8608408, 0.363825053, -3.03438735},
-    {11.4465017, 0.125597805, -2.6592164},
-    {11.0518694, -0.145972222, -2.2370379},
-    {10.8721466, -0.516161203, -2.08397818},
-    {10.8324986, -0.844554603, -2.10069704},
-    {10.7105894, -1.10204852, -2.24730206},
-    {10.4814596, -1.32512569, -2.20770645},
-    {10.2507086, -1.49779105, -1.81374168},
-    {10.0047808, -1.52519596, -1.33937454},
-    {9.94750118, -1.45780659, -1.07464683},
-    {10.138382, -1.30490923, -1.23872447},
-    {10.2206545, -1.1662339, -1.50620508},
-    {10.3707714, -0.98309046, -1.93464112},
-    {10.5377865, -0.783494413, -2.21489167},
-    {10.5083904, -0.486959159, -2.21753311},
-    {10.3886251, -0.277904481, -2.13728094},
-    {10.3365011, -0.0383496732, -2.13093305},
-    {10.5509386, 0.254317135, -2.25282025},
-    {10.7160816, 0.447048992, -2.25341582},
-    {10.8142233, 0.580705762, -2.15956187},
-    {10.8411522, 0.701519907, -1.91364276},
-    {10.8430977, 0.839323997, -1.55723608},
-    {10.8992233, 0.828768849, -1.16457689},
-    {10.8538485, 0.827870309, -0.834783852},
-    {10.6860638, 0.766721308, -0.508112192},
-    {10.5992136, 0.599143386, -0.227872685},
-    {10.4252253, 0.455435127, -0.00203660782},
-    {10.102973, 0.379510462, 0.193159312},
-    {9.86620235, 0.288388312, 0.404358685},
-    {9.64712238, 0.206096679, 0.466225237},
-    {9.64444637, 0.106511094, 0.445827186},
-    {9.92667389, 0.0349291638, 0.285024971},
-    {10.0555153, -0.0430919193, 0.117671601},
-    {10.0143032, -0.169184029, -0.0170747247},
-    {10.0535803, -0.29108271, -0.0867556036},
-    {10.2211018, -0.407440454, -0.132316247},
-    {10.3640566, -0.553281724, -0.143266544},
-    {10.3831387, -0.712540329, -0.221021578},
-    {10.497529, -0.829743624, -0.34389019},
-    {10.5774221, -0.907615244, -0.469405353},
-    {10.6238852, -1.01869524, -0.587809741},
-    {10.6983767, -1.03550398, -0.691699505},
-    {10.6770811, -1.04551351, -0.779237688},
-    {10.5692072, -0.984279633, -0.841339409},
-    {10.4215031, -0.876166999, -0.906549156},
-    {10.3804407, -0.732703984, -1.06214011},
-    {10.2962332, -0.582801223, -1.27014053},
-    {10.3947248, -0.496094286, -1.37555504},
-    {10.6108952, -0.453115046, -1.51327968},
-    {10.7446461, -0.222495928, -1.66261685},
-    {10.9593287, -0.141779259, -1.7781564},
-    {11.2461672, -0.0893656462, -1.92868519},
-    {11.6402798, -0.0126920976, -2.08576465},
-    {11.9785967, -0.00325767882, -2.12566781},
-    {12.0869036, 0.0407696664, -2.05956054},
-    {12.0710344, 0.0791290775, -1.95378029},
-    {11.9592543, 0.0864442661, -1.85587776},
-    {11.8691359, 0.135350555, -1.67342865},
-    {11.4929914, 0.209690779, -1.45565856},
-    {11.3479338, 0.224666074, -1.27832961},
-    {11.3104563, 0.28533411, -1.19781101},
-    {10.9553595, 0.305547059, -1.02422583},
-    {10.5714712, 0.309426159, -0.75125581},
-    {10.426527, 0.389017493, -0.578858376},
-    {10.2757883, 0.469405621, -0.538399458},
-    {10.2976942, 0.408331066, -0.50248158},
-    {10.4817572, 0.427131861, -0.514668167},
-    {10.5725117, 0.408562511, -0.560973346},
-    {10.7285776, 0.357197285, -0.762869596},
-    {10.755024, 0.247723475, -0.882776082},
-    {10.6399174, 0.192391917, -0.918637991},
-    {10.4941044, 0.0410690829, -1.01107025},
-    {10.4007025, -0.111683421, -1.14785576},
-    {10.3952684, -0.32422635, -1.2819699},
-    {10.2870092, -0.504330814, -1.36855757},
-    {10.1257362, -0.663518071, -1.40875793},
-    {10.0491199, -0.833981991, -1.46736681},
-    {9.99935436, -0.982442915, -1.54693866},
-    {9.83315086, -1.0655998, -1.55731523},
-    {9.73397732, -1.14676547, -1.56077099},
-    {9.65560341, -1.11292613, -1.58444929},
-    {9.45059013, -1.02906454, -1.59859431},
-    {9.28363609, -0.959592938, -1.62546241},
-    {9.18710709, -0.850109875, -1.65145051},
-    {9.24575806, -0.717023432, -1.71615565},
-    {9.41895962, -0.625453651, -1.77835917},
-    {9.74382687, -0.4910025, -1.92883396},
-    {10.0136309, -0.286231697, -1.92519271},
-    {9.95865536, -0.175826177, -1.79453945},
-    {10.1339188, -0.0797814727, -1.79096103},
-    {10.4672117, 0.0474722721, -1.75121641},
-    {10.6113405, 0.101719007, -1.64817512},
-    {10.6805239, 0.149490148, -1.63045669},
-    {10.83778, 0.286214471, -1.71145356},
-    {10.9647293, 0.352385879, -1.6926403},
-    {10.9422197, 0.338627934, -1.47278094},
-    {10.9981146, 0.310891896, -1.29468942},
-    {10.9575443, 0.215081856, -1.12407851},
-    {10.7848921, 0.12437515, -0.940769911},
-    {10.8496628, 0.0117493523, -0.78647542},
-    {10.9481716, -0.152411729, -0.544148564},
-    {10.8593502, -0.268020749, -0.393917412},
-    {10.7760887, -0.369003981, -0.391598433},
-    {10.7805309, -0.392485172, -0.385996521},
-    {10.7659893, -0.42113623, -0.432602048},
-    {10.7990971, -0.583699822, -0.591644883},
-    {10.8255777, -0.749026895, -0.715671003},
-    {10.7836256, -0.793503523, -0.880195141},
-    {10.7041769, -0.800691664, -1.01032627},
-    {10.2948933, -0.765949011, -1.1828903},
-    {9.90539742, -0.651987016, -1.34503245},
-    {9.76078892, -0.490703076, -1.46816528},
-    {9.6376009, -0.368804336, -1.63105214},
-    {9.48674202, -0.215008348, -1.81255031},
-    {9.40828228, -0.0631815642, -1.95854497},
-    {9.28827477, 0.126577988, -2.01772189},
-    {9.17609596, 0.294151366, -2.06134725},
-    {9.16820145, 0.347593784, -2.11529803},
-    {9.05603313, 0.468763143, -2.10288715},
-    {9.06481171, 0.57224232, -2.07430053},
-    {9.33788109, 0.594206035, -2.08068943},
-    {9.55859375, 0.613013744, -2.08440614},
-    {9.74888611, 0.519978583, -2.04467106},
-    {10.1167822, 0.421690822, -1.99420667},
-    {10.3285198, 0.329043746, -1.8794024},
-    {10.3481569, 0.159224063, -1.70981574},
-    {10.4680748, -0.0456106067, -1.5489409},
-    {10.5430117, -0.191129938, -1.40799904},
-    {10.3764238, -0.335110068, -1.21445513},
-    {10.2646933, -0.501635134, -1.04189074},
-    {10.3636303, -0.677295327, -0.961340964},
-    {10.3753815, -0.787663221, -0.889128745},
-    {10.3474121, -0.896233916, -0.807834566},
-    {10.193428, -0.987583101, -0.677703798},
-    {10.0022335, -0.973097801, -0.587376535},
-    {9.78803349, -0.857385039, -0.514884293},
-    {9.67258263, -0.699513257, -0.466097981},
-    {9.68238163, -0.483664662, -0.468958557},
-    {9.83651447, -0.239268288, -0.549955487},
-    {9.91611576, -0.00887577515, -0.643372297},
-    {9.94755554, 0.272264808, -0.746626616},
-    {10.1392612, 0.513771117, -0.923402607},
-    {10.3588629, 0.755394638, -1.13673866},
-    {10.4075193, 0.950817525, -1.27564943},
-    {10.458251, 1.14145279, -1.46935678},
-    {10.5510283, 1.39913201, -1.64625287},
-    {10.6501732, 1.48768139, -1.86853302},
-    {10.5274305, 1.50085974, -2.033355},
-    {10.4391937, 1.48239172, -2.21396971},
-    {10.5531712, 1.43302143, -2.50280881},
-    {10.5315542, 1.34714496, -2.6836164},
-    {10.3074255, 1.21125221, -2.80246377},
-    {9.9957056, 0.970285296, -2.79746437},
-    {9.89647198, 0.751646221, -2.89320064},
-    {9.87102985, 0.563406885, -2.93012524},
-    {9.85481453, 0.233800933, -3.08765149},
-    {9.71066856, -0.0999210477, -3.14851665},
-    {9.50161552, -0.383431822, -3.11953378},
-    {9.52658272, -0.767763972, -3.11704206},
-    {9.5420208, -1.05485392, -3.13841033},
-    {9.45035076, -1.30873287, -3.11367798},
-    {9.40997314, -1.51740849, -3.05787396},
-    {9.29301167, -1.629179, -3.0005281},
-    {9.22191906, -1.77932632, -2.85940266},
-    {9.29288769, -1.86198986, -2.76321912},
-    {9.25853062, -1.8567301, -2.65690589},
-    {9.29259682, -1.80745566, -2.51351953},
-    {9.41339588, -1.78127337, -2.28617263},
-    {9.49998283, -1.74353528, -2.01876378},
-    {9.39342308, -1.58851814, -1.71367776},
-    {9.41008377, -1.41604972, -1.45149434},
-    {9.57020569, -1.28229642, -1.22532427},
-    {9.56611252, -1.08491349, -0.950056791},
-    {9.40312958, -0.916150987, -0.679043829},
-    {9.30703545, -0.744848251, -0.495518684},
-    {9.28574562, -0.566777527, -0.376497179},
-    {9.18799877, -0.376441747, -0.236688823},
-    {9.21686268, -0.210515708, -0.1087915},
-    {9.49888229, -0.0732013062, -0.0621256158},
-    {9.78107166, 0.0757891536, -0.0563503951},
-    {9.96403027, 0.302455395, -0.100525796},
-    {10.0901785, 0.561460137, -0.171921313},
-    {10.1881943, 0.752490222, -0.239278466},
-    {10.2864141, 0.827720582, -0.354759246},
-    {10.2592001, 0.850608706, -0.539475441},
-    {10.2527905, 0.915026486, -0.743960083},
-    {10.2428226, 0.959203541, -0.854437172},
-    {10.1885204, 0.760930836, -1.02893722},
-    {10.1317863, 0.522615135, -1.26234841},
-    {9.97078419, 0.229281113, -1.32558632},
-    {9.74742699, -0.0532054305, -1.29427063},
-    {9.63298988, -0.376591533, -1.35337067},
-    {9.55500317, -0.872609317, -1.38333845},
-    {9.41469097, -1.26301205, -1.36726964},
-    {9.30917263, -1.60942972, -1.47285342},
-    {9.32285309, -1.91844666, -1.61118257},
-    {9.47479057, -2.28598547, -1.70920181},
-    {9.56181812, -2.48143959, -1.87630439},
-    {9.59640884, -2.60545802, -1.9864099},
-    {9.62584877, -2.51431298, -2.02635813},
-    {9.77507019, -2.38567543, -2.06908894},
-    {9.85778999, -2.20492339, -2.17897058},
-    {9.9235487, -1.91545177, -2.22989154},
-    {9.92310333, -1.47847271, -2.17599273},
-    {9.95315456, -1.03610277, -2.09678316},
-    {9.98722553, -0.656928718, -1.98719943},
-    {9.91700268, -0.295724958, -1.80525458},
-    {9.92072105, 0.045112554, -1.58772516},
-    {9.75481415, 0.349083424, -1.26292622},
-    {9.58448792, 0.520128369, -1.00734806},
-    {9.55859184, 0.675774693, -0.773397446},
-    {9.539855, 0.773255944, -0.554024994},
-    {9.42276955, 0.897655189, -0.414017648},
-    {9.33160591, 0.95634383, -0.277734578},
-    {9.29200363, 0.934008777, -0.106449813},
-    {9.38182735, 0.849835634, -0.0378186703},
-    {9.42025757, 0.754668415, 0.0562655032},
-    {9.39426517, 0.591681182, 0.208552673},
-    {9.60219288, 0.522524416, 0.25107789},
-    {9.80891418, 0.413413584, 0.302720457},
-    {9.84068108, 0.288460761, 0.269093692},
-    {9.75766373, -0.0394979157, 0.117224872},
-    {9.58597755, -0.329868615, 0.0347393528},
-    {9.34733868, -0.355326474, 0.0858090073},
-    {9.27488518, -0.523948252, 0.10397362},
-    {9.4007473, -0.930826783, -0.0669531599},
-    {9.53048229, -1.09795094, -0.320663095},
-    {9.51367092, -1.30715573, -0.602960467},
-    {9.52735901, -1.55784178, -0.782969534},
-    {9.40238667, -1.50722516, -0.859201849},
-    {9.04606724, -1.45915449, -1.1047225},
-    {8.72857952, -1.46439588, -1.4477675},
-    {8.75029945, -1.28005028, -1.51193929},
-    {8.63142586, -1.18136299, -1.63834786},
-    {8.74955654, -0.972807407, -1.92115057},
-    {8.92368793, -0.652173042, -2.04834843},
-    {8.88333511, -0.492320299, -2.14251256},
-    {8.77068233, -0.216505826, -2.12015915},
-    {8.80322361, -0.0168580022, -2.10176873},
-    {9.06607914, 0.185135782, -2.05065823},
-    {9.25819683, 0.288388252, -1.9239496},
-    {9.40387344, 0.423687547, -1.74569821},
-    {9.63046074, 0.401673883, -1.51893735},
-    {9.78801346, 0.452889323, -1.19584394},
-    {10.011775, 0.421441257, -1.07688022},
-    {10.2274342, 0.301743329, -0.743017197},
-    {10.3020506, 0.180952728, -0.550233722},
-    {10.2364264, 0.0245963186, -0.23311539},
-    {10.0742607, -0.13339299, 0.006599057},
-    {10.0356817, -0.345231384, 0.193115577},
-    {10.1022682, -0.546950459, 0.261500269},
-    {10.1566811, -0.640755415, 0.346665859},
-    {9.96890926, -0.666839778, 0.276732206},
-    {9.87127018, -0.63215667, -0.0321318768},
-    {9.87585545, -0.525690794, -0.426971406},
-    {9.84209251, -0.309540927, -0.861770988},
-    {9.57952785, 0.0448583551, -1.31302559},
-    {9.30672836, 0.315440387, -1.56630385},
-    {9.49426651, 0.566615283, -1.82860339},
-    {9.73430634, 0.704024792, -2.36865807},
-    {9.62183189, 0.918171346, -2.72182727},
-    {9.59341431, 1.09667659, -2.89096737},
-    {9.59103489, 1.13681042, -3.0772295},
-    {9.5557251, 1.07254386, -3.20381355},
-    {9.61510849, 0.979067624, -3.30304408},
-    {9.41726303, 0.866656363, -3.22865152},
-    {9.452075, 0.649664521, -3.31843281},
-    {9.54536057, 0.36738047, -3.26453424},
-    {9.43612766, 0.0773863271, -3.06853008},
-    {9.37114334, -0.271465033, -2.86208248},
-    {8.98313236, -0.668310165, -2.6411283},
-    {8.92570591, -0.92962867, -2.32294798},
-    {9.09977436, -1.16444087, -2.18045974},
-    {9.11181164, -1.33540857, -1.9946394},
-    {9.06964397, -1.56351244, -1.79295635},
-    {9.20585155, -1.72077322, -1.60723019},
-    {9.38577652, -1.87967408, -1.33598161},
-    {9.5443182, -2.00605202, -1.18125272},
-    {9.57957745, -2.09365749, -0.988736868},
-    {9.57719803, -2.12540483, -0.819894314},
-    {9.61246014, -2.0749383, -0.70807755},
-    {9.67013073, -2.05494881, -0.578714013},
-    {9.76673889, -1.94630086, -0.462109506},
-    {9.70909786, -1.83079791, -0.373485833},
-    {9.64935398, -1.62717736, -0.313962996},
-    {9.52917957, -1.50095367, -0.314788669},
-    {9.53202343, -1.33442974, -0.293565094},
-    {9.51857948, -1.14182842, -0.26363796},
-    {9.51084328, -0.950294733, -0.233562082},
-    {9.56611252, -0.818589568, -0.224551842},
-    {9.74979305, -0.625818789, -0.241923988},
-    {10.0381069, -0.398006052, -0.364585966},
-    {10.2909155, -0.162073091, -0.459023625},
-    {10.5643282, -0.0511785075, -0.508265972},
-    {10.7901697, 0.0943811536, -0.634227335},
-    {10.9373913, 0.288542897, -0.814587116},
-    {11.0729904, 0.439116627, -1.07220149},
-    {11.3360729, 0.544533253, -1.3139385},
-    {11.5414286, 0.617004812, -1.53941214},
-    {11.532052, 0.676978528, -1.79236424},
-    {11.4143972, 0.638829231, -1.97190166},
-    {11.1783276, 0.345666319, -2.02680397},
-    {10.9558439, 0.142006978, -2.16356301},
-    {10.7032862, -0.0943075716, -2.15350962},
-    {10.4625378, -0.432589531, -2.05658698},
-    {10.2810564, -0.85939455, -2.02114606},
-    {10.1193399, -1.21535707, -1.87270224},
-    {9.990201, -1.72601449, -1.68584394},
-    {9.86880016, -1.96486986, -1.62152338},
-    {9.75200939, -2.16449046, -1.46920788},
-    {9.6042757, -2.33550787, -1.28994274},
-    {9.53913403, -2.39300871, -1.11825836},
-    {9.63781452, -2.37267852, -0.974601328},
-    {9.82439518, -2.27242184, -0.937726974},
-    {9.83776855, -2.06119299, -0.973157465},
-    {9.88094902, -1.87439024, -1.05557942},
-    {9.87022877, -1.58822799, -1.11681437},
-    {9.84097862, -1.26252925, -1.26865149},
-    {9.83675766, -0.929533482, -1.39734292},
-    {9.81966972, -0.624582231, -1.49529767},
-    {9.88025379, -0.289884686, -1.64832389},
-    {9.87623692, -0.0186821446, -1.77994323},
-    {9.86254978, 0.177943185, -1.97201252},
-    {9.79798222, 0.345816076, -2.18105507},
-    {9.54129982, 0.467143089, -2.32801032},
-    {9.41711426, 0.465169072, -2.31580114},
-    {9.31535149, 0.357197285, -2.26592302},
-    {9.26446915, 0.29894346, -2.26696539},
-    {9.2975111, 0.15791975, -2.29081655},
-    {9.27681828, -0.114673942, -2.2574358},
-    {9.33110046, -0.378442943, -2.20803142},
-    {9.28292179, -0.661991477, -2.11376119},
-    {9.28559589, -0.872123778, -1.97379923},
-    {9.34361935, -1.01169312, -1.87151122},
-    {9.36399174, -1.12513793, -1.78615594},
-    {9.38781548, -1.12512362, -1.66605151},
-    {9.62050152, -1.07489347, -1.63239229},
-    {9.80319023, -0.988182127, -1.54841805},
-    {9.88129711, -0.821207702, -1.45223415},
-    {10.0540257, -0.572468221, -1.44210923},
-    {10.3003979, -0.294826567, -1.39788866},
-    {10.4273911, 0.0362907462, -1.42939532},
-    {10.424757, 0.341719598, -1.40984356},
-    {10.5104713, 0.693841636, -1.38076675},
-    {10.6616287, 0.974478483, -1.35366833},
-    {10.7230721, 1.15118682, -1.2644825},
-    {10.7168236, 1.35649788, -1.27952063},
-    {10.723815, 1.47989428, -1.28770936},
-    {10.7250071, 1.49412072, -1.31614769},
-    {10.6912584, 1.33247817, -1.31403625},
-    {10.6509752, 1.24649715, -1.30717587},
-    {10.55478, 1.00864947, -1.2145592},
-    {10.2533655, 0.661862075, -0.981191456},
-    {10.1743851, 0.491375804, -0.859052479},
-    {10.3165941, 0.162482291, -0.893893242},
-    {10.391757, -0.151472241, -0.955110371},
-    {10.2161932, -0.413730174, -0.910122514},
-    {10.0529509, -0.66276443, -0.820120275},
-    {9.94675922, -0.802039385, -0.728029072},
-    {9.84841824, -0.935020149, -0.558293104},
-    {9.77645493, -0.985876858, -0.473316967},
-    {9.76039028, -1.00547624, -0.517650843},
-    {9.72537899, -1.08387423, -0.587922513},
-    {9.76257229, -1.07788408, -0.667430401},
-    {9.77328491, -0.98803252, -0.689763844},
-    {9.86979675, -0.883645475, -0.670105994},
-    {9.95635128, -0.815029383, -0.5383991},
-    {9.86240196, -0.592684865, -0.524346173},
-    {9.86157322, -0.223934457, -0.699703455},
-    {10.0176687, -0.0223760642, -0.853466928},
-    {10.1309929, 0.0958287269, -0.994424284},
-    {10.1296034, 0.236646324, -1.0767312},
-    {9.98246861, 0.389743567, -1.05242133},
-    {9.80646133, 0.450237274, -0.920175076},
-    {9.64776897, 0.442456573, -0.835275412},
-    {9.69205379, 0.43851307, -0.852501631},
-    {9.70633602, 0.441358358, -0.91846019},
-    {9.66869545, 0.414852113, -1.01762176},
-    {9.70504189, 0.333981067, -1.0766772},
-    {9.54553986, 0.221453637, -1.01070058},
-    {9.33543491, 0.148441866, -0.940347135},
-    {9.31996441, -0.0206291676, -0.911462367},
-    {9.30835915, -0.198984668, -0.922182679},
-    {9.35966396, -0.341122836, -1.03957176},
-    {9.41545773, -0.506480396, -1.23770642},
-    {9.28559685, -0.630572498, -1.36662197},
-    {9.14513874, -0.681361318, -1.42015493},
-    {9.10349274, -0.773137033, -1.45818985},
-    {9.05701351, -0.840380967, -1.50252116},
-    {8.97420692, -0.898629963, -1.61869466},
-    {9.00101471, -0.938972354, -1.76016808},
-    {9.04353619, -0.972158432, -1.96799242},
-    {9.0168829, -1.02043784, -2.13483143},
-    {8.95665169, -1.05976367, -2.15187263},
-    {8.9359951, -1.01336002, -2.09301305},
-    {8.94073296, -1.06710184, -1.96799219},
-    {8.97554684, -1.02097797, -1.94402087},
-    {9.08223629, -1.0003984, -1.93833113},
-    {9.20966816, -0.910097778, -1.9470036},
-    {9.29824257, -0.856249928, -1.93598044},
-    {9.42559528, -0.777180493, -1.80153239},
-    {9.56438065, -0.653189719, -1.62936056},
-    {9.68340302, -0.539921939, -1.36225891},
-    {9.70521545, -0.472033948, -1.12417781},
-    {9.84871387, -0.368205369, -1.0222373},
-    {10.0218897, -0.231181636, -0.963425457},
-    {10.0397444, -0.0504298322, -0.870666265},
-    {10.0782747, 0.0603872985, -0.730560064},
-    {10.0154915, 0.182885021, -0.578840375},
-    {9.94423866, 0.346033901, -0.447761834},
-    {9.92855358, 0.473733962, -0.388240367},
-    {9.89648438, 0.566179633, -0.315943718},
-    {9.79054451, 0.595154524, -0.313814193},
-    {9.71247387, 0.588898718, -0.368721336},
-    {9.78409958, 0.555288494, -0.464798689},
-    {9.77075481, 0.567300498, -0.559186637},
-    {9.64286232, 0.455671102, -0.609755397},
-    {9.51789474, 0.271229506, -0.669346631},
-    {9.50786972, 0.0496050753, -0.760933816},
-    {9.5301857, -0.208718687, -0.870815337},
-    {9.36846542, -0.522151232, -0.924267054},
-    {9.28217411, -0.82674855, -1.04084861},
-    {9.30404377, -1.07713509, -1.18586838},
-    {9.24587345, -1.32991779, -1.30885172},
-    {9.12623978, -1.51257086, -1.38593709},
-    {9.041008, -1.56637776, -1.44598079},
-    {8.94013882, -1.55709302, -1.4720366},
-    {8.93645573, -1.48313928, -1.58705258},
-    {9.02597332, -1.39785123, -1.72869349},
-    {9.07928085, -1.24461675, -1.82835209},
-    {9.09367371, -1.00869823, -1.90903175},
-    {9.06868172, -0.792006016, -1.98183894},
-    {9.07704353, -0.491420001, -2.04589367},
-    {9.06882954, -0.249900699, -2.03290868},
-    {9.14989853, -0.0701518506, -2.04069614},
-    {9.3586359, 0.130713046, -2.04321599},
-    {9.55964279, 0.257911205, -1.99479258},
-    {9.75943089, 0.341967881, -1.93991971},
-    {9.90852165, 0.353153974, -1.72932017},
-    {9.97969341, 0.384848416, -1.49268436},
-    {10.02561, 0.31526649, -1.21594429},
-    {10.1023779, 0.198758781, -0.982930064},
-    {10.1507301, 0.108158402, -0.767187059},
-    {10.152813, 0.0199540462, -0.583307028},
-    {10.0795612, -0.0547592677, -0.401560456},
-    {10.0922604, -0.137735859, -0.237731025},
-    {10.0410824, -0.238219991, -0.0861601606},
-    {9.91864014, -0.255441457, 0.0271460433},
-    {9.92164516, -0.316496998, 0.103733607},
-    {9.88858604, -0.411184371, 0.152512133},
-    {9.88479996, -0.468185633, 0.170180559},
-    {9.98169231, -0.513282001, 0.182578489},
-    {10.029213, -0.607011378, 0.105065644},
-    {9.98930836, -0.690024257, 0.014490149},
-    {9.93024254, -0.785716236, -0.0562330857},
-    {9.83294582, -0.829743743, -0.183832511},
-    {9.6981535, -0.862539589, -0.360714912},
-    {9.56648636, -0.910460472, -0.543404162},
-    {9.34927177, -0.938164771, -0.731751204},
-    {9.20501041, -0.926774263, -0.941682756},
-    {9.22425556, -0.927411199, -1.09953547},
-    {9.23307896, -0.995370388, -1.28666723},
-    {9.23084545, -1.01603591, -1.49630618},
-    {9.19058228, -1.0565964, -1.64134383},
-    {9.04380512, -1.04644084, -1.71784616},
-    {8.8413105, -1.09188354, -1.80752385},
-    {8.77643108, -1.11414826, -1.89382565},
-    {8.84596252, -1.11966503, -2.00476837},
-    {8.90969372, -1.13690007, -2.06827259},
-    {8.93716145, -1.17791879, -2.05017996},
-    {8.76092052, -1.14877522, -1.98696387},
-    {8.54267502, -1.12049067, -1.86311018},
-    {8.59042931, -1.04730272, -1.83481157},
-    {8.73327637, -0.992645621, -1.89474773},
-    {8.81620693, -0.952091873, -1.88446462},
-    {8.89669609, -0.887548208, -1.83830833},
-    {9.0673418, -0.801889658, -1.83428848},
-    {9.1336956, -0.662020504, -1.8094238},
-    {9.16791344, -0.581303656, -1.7212801},
-    {9.23501682, -0.42752552, -1.72797132},
-    {9.27232552, -0.277542233, -1.72522378},
-    {9.48113823, -0.166865125, -1.78399026},
-    {9.77462292, -0.0760376304, -1.88044453},
-    {9.98975468, 0.0627833381, -1.98913491},
-    {9.95927143, 0.229491994, -1.97282398},
-    {9.79275799, 0.339063615, -1.93558812},
-    {9.71972561, 0.378012925, -1.96992791},
-    {9.67911148, 0.311372906, -1.98660374},
-    {9.73653793, 0.206396192, -2.0787673},
-    {9.70028114, 0.0895845369, -2.11692834},
-    {9.62109566, -0.0448939651, -2.13635445},
-    {9.66051292, -0.177270681, -2.13207006},
-    {9.5507164, -0.259185314, -2.02784657},
-    {9.48361778, -0.318187982, -1.950423},
-    {9.64012909, -0.407290846, -1.93776751},
-    {9.79545307, -0.47647664, -1.89712024},
-    {9.95449352, -0.518706977, -1.85438871},
-    {10.0162363, -0.51451385, -1.78426123},
-    {9.9984827, -0.438126117, -1.62806094},
-    {10.0719948, -0.369210005, -1.46671021},
-    {10.209794, -0.281348646, -1.28860295},
-    {10.4079657, -0.188352317, -1.09832048},
-    {10.51929, -0.0718944222, -0.902700603},
-    {10.3738956, 0.000186722187, -0.639736533},
-    {10.1925497, 0.0555855483, -0.405915082},
-    {10.2115803, 0.0590394959, -0.162094578},
-    {10.4704494, 0.121037133, 0.0429285243},
-    {10.5266495, 0.136053294, 0.208874121},
-    {10.2968283, 0.0644305944, 0.423046887},
-    {10.0644131, -0.0309438501, 0.566501021},
-    {9.99397755, -0.152947873, 0.713437021},
-    {10.0022516, -0.30830425, 0.773089409},
-    {10.0577774, -0.459182531, 0.757370174},
-    {10.0248461, -0.604640961, 0.643352568},
-    {9.94660854, -0.716979742, 0.496598989},
-    {9.73386002, -0.791556776, 0.297382921},
-    {9.53394032, -0.848213196, 0.0343196653},
-    {9.25097847, -0.816729784, -0.298022211},
-    {9.05752182, -0.707395792, -0.70182395},
-    {8.9346323, -0.569023848, -1.14075434},
-    {8.93638325, -0.460489303, -1.54215539},
-    {8.86113834, -0.292879671, -1.98690164},
-    {8.85045433, -0.0989980772, -2.47371197},
-    {8.87869453, 0.101569287, -2.83185768},
-    {8.87913895, 0.161170796, -3.10537004},
-    {8.84188652, 0.246706977, -3.30733395},
-    {8.82250404, 0.400306791, -3.53804255},
-    {9.01861572, 0.56588918, -3.75433135},
-    {9.34094048, 0.645471454, -3.95687723},
-    {9.41711521, 0.583773255, -3.91920733},
-    {9.38869762, 0.492124587, -3.71314216},
-    {9.62852669, 0.450193793, -3.44692588},
-    {9.99198532, 0.360192329, -3.07082748},
-    {10.305459, -0.0180834029, -2.49521494},
-    {10.7462826, -0.328071654, -1.988837},
-    {10.863369, -0.622549236, -1.59268796},
-    {10.7291431, -0.956318438, -1.32592654},
-    {10.999053, -1.25608969, -1.02729952},
-    {11.1115274, -1.37858737, -0.727135539},
-    {10.9168921, -1.49282181, -0.436211526},
-    {10.5580616, -1.41775036, -0.144635886},
-    {10.454236, -1.52864027, -0.010225689},
-    {10.4426298, -1.58285058, 0.180801407},
-    {10.2094965, -1.52789128, 0.334307939},
-    {10.1036558, -1.54408276, 0.444500715},
-    {10.0012112, -1.59782577, 0.513125896},
-    {9.82258797, -1.57805347, 0.601240456},
-    {9.59252357, -1.59827507, 0.589655817},
-    {9.38750744, -1.55816865, 0.510770679},
-    {9.35937595, -1.48527086, 0.382417709},
-    {9.43526936, -1.46257949, 0.240367323},
-    {9.40759182, -1.39940298, 0.0956358314},
-    {9.3138628, -1.31883633, -0.174005717},
-    {9.33275795, -1.28619003, -0.36667037},
-    {9.40986919, -1.22330308, -0.572505534},
-    {9.42636204, -1.14382851, -0.871300161},
-    {9.42142963, -1.07638645, -1.13822329},
-    {9.59252262, -1.00076115, -1.40071785},
-    {9.63391781, -0.943474054, -1.58676863},
-    {9.64075565, -0.897113025, -1.76779664},
-    {9.65322208, -0.826598942, -1.97662818},
-    {9.56529713, -0.760558069, -2.14889455},
-    {9.42184353, -0.745982051, -2.31891465},
-    {9.31431198, -0.756215036, -2.36955142},
-    {9.25481892, -0.68765229, -2.40024662},
-    {9.21641445, -0.650040388, -2.3680625},
-    {9.26313019, -0.748278141, -2.39843631},
-    {9.47955036, -0.758470535, -2.32454491},
-    {9.57764339, -0.761606097, -2.23822927},
-    {9.78943825, -0.787077725, -2.06856155},
-    {9.99332619, -0.770591378, -1.88654912},
-    {10.0983601, -0.761006951, -1.69209802},
-    {10.1644173, -0.774035633, -1.46995234},
-    {10.3355093, -0.750224888, -1.22294211},
-    {10.46315, -0.695845306, -0.953833818},
-    {10.4008236, -0.567226827, -0.726093292},
-    {10.295043, -0.403846323, -0.539979517},
-    {10.3551493, -0.277455121, -0.387812853},
-    {10.379549, -0.149117053, -0.23311539},
-    {10.3139973, -0.0252803005, -0.152218089},
-    {10.2820988, 0.0563439764, -0.0261570308},
-    {10.3393803, 0.118191831, 0.0302726608},
-    {10.3813696, 0.220568314, -0.012603553},
-    {10.2390633, 0.216589391, -0.0543869138},
-    {10.2895384, 0.152335435, -0.049979616},
-    {10.4807711, 0.196753025, -0.130272448},
-    {10.4850311, 0.131669536, -0.223735228},
-    {10.3448982, -0.130842462, -0.221021697},
-    {10.1671314, -0.364647627, -0.173586115},
-    {10.0882425, -0.552251697, -0.204826072},
-    {10.0690527, -0.837530613, -0.261404634},
-    {9.96371841, -1.16848457, -0.31366533},
-    {9.84050751, -1.40816128, -0.319697648},
-    {9.87941074, -1.66199255, -0.381785303},
-    {9.81107616, -1.91844666, -0.394513041},
-    {9.72895145, -2.1363368, -0.394811004},
-    {9.76361561, -2.31364441, -0.50067234},
-    {9.78711987, -2.39106679, -0.598344982},
-    {9.66080952, -2.34569097, -0.681128204},
-    {9.56971931, -2.29092264, -0.792828023},
-    {9.68114376, -2.15542293, -0.959981501},
-    {9.8314209, -1.93703425, -1.2060405},
-    {9.79009533, -1.63466501, -1.3782351},
-    {9.76780033, -1.31173897, -1.50302851},
-    {9.84915066, -1.00283813, -1.63477457},
-    {9.96760941, -0.704595685, -1.75049412},
-    {9.96446419, -0.365659535, -1.85870671},
-    {10.0201035, -0.12261086, -1.82490802},
-    {10.0372133, 0.117592789, -1.7470386},
-    {9.92652416, 0.341023982, -1.62152338},
-    {9.95017815, 0.577333927, -1.54439819},
-    {10.0748005, 0.700648546, -1.43459284},
-    {9.97933865, 0.752844214, -1.1964395},
-    {9.96848202, 0.779345632, -1.01915395},
-    {10.0382557, 0.846289873, -0.908931494},
-    {10.0623569, 0.876539946, -0.71924448},
-    {10.0501308, 0.813916087, -0.488765389},
-    {10.0943432, 0.713908494, -0.326469868},
-    {10.0738134, 0.561609924, -0.181896955},
-    {10.1126919, 0.500940681, -0.136182651},
-    {10.1837244, 0.376529008, -0.0320945159},
-    {10.2005377, 0.186981395, 0.0935897902},
-    {10.2420769, -0.019580869, 0.160105556},
-    {10.2289858, -0.258436561, 0.20879288},
-    {10.173624, -0.381202042, 0.216959327},
-    {10.1822786, -0.556476593, 0.222878844},
-    {10.2105389, -0.811623573, 0.206857264},
-    {10.2765961, -1.05317473, 0.146258757},
-    {10.4015675, -1.26594925, 0.0547051579},
-    {10.2005682, -1.41018546, -0.0173724461},
-    {10.0392962, -1.53747535, -0.185768113},
-    {9.93128681, -1.63077152, -0.358928114},
-    {9.69294643, -1.62987268, -0.570204496},
-    {9.46948528, -1.52849019, -0.78579849},
-    {9.3721838, -1.39850473, -1.0124104},
-    {9.38557339, -1.33216393, -1.29247415},
-    {9.33499622, -1.15389049, -1.55616021},
-    {9.19384861, -0.958173335, -1.7252233},
-    {9.16107082, -0.812522113, -1.82297242},
-    {9.20049667, -0.658276558, -1.93434262},
-    {9.20774937, -0.512621343, -2.04574943},
-    {9.275033, -0.339452803, -2.07296038},
-    {9.32838249, -0.260074168, -2.0515151},
-    {9.38418961, -0.16599381, -2.02683592},
-    {9.58627415, -0.127402946, -1.99449468},
-    {9.67866421, -0.0773853734, -1.85647297},
-    {9.5632143, -0.100597188, -1.68569505},
-    {9.58746338, -0.123958662, -1.46950531},
-    {9.75454044, -0.176671669, -1.25435805},
-    {9.9296484, -0.232679114, -1.05409992},
-    {10.0171299, -0.291382164, -0.836570323},
-    {10.0221882, -0.372548223, -0.649712384},
-    {10.0389996, -0.486210674, -0.49754557},
-    {10.0608692, -0.608109653, -0.30681628},
-    {9.99793625, -0.640306473, -0.197828233},
-    {9.98665428, -0.677730978, -0.103851028},
-    {10.0904751, -0.779426575, -0.0461085141},
-    {10.1602983, -0.810237169, -0.0439663976},
-    {10.1419525, -0.877364755, -0.0191591363},
-    {10.15802, -0.884553134, -0.0465552174},
-    {10.1656904, -0.898457468, -0.15380615},
-    {10.1364946, -0.932821751, -0.249147549},
-    {10.1184454, -0.921392381, -0.35803476},
-    {10.2376785, -0.890035033, -0.493963182},
-    {10.2747126, -0.877789974, -0.660125017},
-    {10.2254152, -0.819751322, -0.830799699},
-    {10.1659069, -0.722670436, -1.01568627},
-    {10.1831646, -0.636712432, -1.18303931},
-    {10.0886898, -0.589989483, -1.40726924},
-    {9.91812515, -0.503327668, -1.58546937},
-    {9.93654156, -0.481437832, -1.74243736},
-    {9.92206097, -0.417773485, -1.87969959},
-    {9.77169418, -0.365083247, -1.9931953},
-    {9.77021885, -0.344476759, -2.08502054},
-    {9.65991688, -0.328071594, -2.14427876},
-    {9.57169342, -0.331515938, -2.18269229},
-    {9.4987402, -0.365228266, -2.18738556},
-    {9.39933395, -0.398426414, -2.17400932},
-    {9.33715916, -0.47922194, -2.16298556},
-    {9.3567934, -0.526576281, -2.11929393},
-    {9.40481949, -0.565915465, -2.06625152},
-    {9.43404388, -0.594902277, -1.98266053},
-    {9.50104904, -0.675262451, -1.88159072},
-    {9.4174118, -0.719975173, -1.77651858},
-    {9.30749512, -0.78797698, -1.65467799},
-    {9.43266296, -0.750047863, -1.52122021},
-    {9.50995064, -0.730457544, -1.40339792},
-    {9.50494289, -0.711275697, -1.25715077},
-    {9.49531841, -0.666010618, -1.15670955},
-    {9.4901638, -0.525295973, -1.10561633},
-    {9.54894447, -0.500132978, -0.99380368},
-    {9.52765656, -0.389320463, -0.878111124},
-    {9.50221539, -0.348437965, -0.816767633},
-    {9.51218224, -0.228336245, -0.78579849},
-    {9.61695004, -0.165932894, -0.742197692},
-    {9.66928959, -0.0979017019, -0.734580159},
-    {9.83935547, -0.0714587942, -0.752690554},
-    {9.90524864, -0.0508791208, -0.829125941},
-    {9.98031044, 0.000553781749, -0.778315544},
-    {10.0296459, -0.00233649556, -0.772037506},
-    {10.1023769, -0.0353049599, -0.773887217},
-    {10.1156178, -0.140131891, -0.860690653},
-    {10.2215204, -0.237729773, -0.928688407},
-    {10.2888947, -0.465484828, -1.02507591},
-    {10.26581, -0.711130559, -1.18279576},
-    {10.2398472, -0.769842267, -1.19078183},
-    {10.3230124, -0.626079619, -1.08655798},
-    {10.5543613, -0.471384943, -1.06809568},
-    {10.5576353, -0.73015821, -1.20924413},
-    {10.3106651, -0.944005191, -1.37034404},
-    {10.1066904, -1.03610313, -1.37138593},
-    {10.0915165, -1.04299176, -1.38642442},
-    {10.0770864, -0.86209029, -1.39744246},
-    {10.1696234, -0.749476194, -1.32954764},
-    {10.1929541, -0.736833334, -1.24617827},
-    {10.1471615, -0.718177795, -1.32448542},
-    {9.99377155, -0.67804414, -1.30066276},
-    {9.8256588, -0.614070535, -1.20189583},
-    {9.85808659, -0.575762689, -1.19107962},
-    {9.91893673, -0.560338259, -1.16904354},
-    {9.95116043, -0.548634887, -1.10237658},
-    {9.95742607, -0.494422883, -1.01961482},
-    {10.0370655, -0.47512871, -0.966254175},
-    {10.1431427, -0.476177037, -0.989778996},
-    {10.0400314, -0.430284649, -0.903566837},
-    {9.81151962, -0.365210205, -0.766740561},
-    {9.76750755, -0.329941154, -0.69262886},
-    {9.6998806, -0.266566813, -0.654899478},
-    {9.76554871, -0.242562726, -0.503054619},
-    {9.84856415, -0.195839956, -0.381261736},
-    {9.92548275, -0.161097273, -0.36235258},
-    {9.81851387, -0.0673519149, -0.280016005},
-    {9.72374249, 0.0207028389, -0.190085918},
-    {9.77745056, 0.138108939, -0.176387966},
-    {9.84194946, 0.222891688, -0.238123462},
-    {9.83072567, 0.357023358, -0.296024203},
-    {9.90355682, 0.447393864, -0.334857404},
-    {9.94869328, 0.576585174, -0.458982885},
-    {9.96282578, 0.732777357, -0.61368072},
-    {9.91872501, 0.81783694, -0.78830564},
-    {9.74817753, 0.908305824, -0.875845909},
-    {9.65841675, 0.990506887, -1.02852905},
-    {9.6434412, 1.08053076, -1.23072958},
-    {9.65545368, 1.16451478, -1.5335288},
-    {9.58508205, 1.17604578, -1.75537622},
-    {9.55529308, 1.11000931, -1.97500372},
-    {9.61528301, 1.09922254, -2.31118584},
-    {9.62555122, 1.13201833, -2.60956335},
-    {9.59560299, 1.04692996, -2.80815005},
-    {9.54922771, 0.9180215, -2.94397235},
-    {9.61271095, 0.814351678, -3.11444306},
-    {9.68436909, 0.679175436, -3.25463128},
-    {9.69116211, 0.450493306, -3.33942652},
-    {9.60338211, 0.198010013, -3.33436441},
-    {9.54506207, -0.0746899471, -3.23416042},
-    {9.56544399, -0.371350199, -3.11698365},
-    {9.5979948, -0.666404426, -2.99273133},
-    {9.57917118, -0.966984689, -2.85364366},
-    {9.61141109, -1.21299279, -2.64174652},
-    {9.74096584, -1.42297363, -2.43326283},
-    {9.79662323, -1.61095393, -2.20238638},
-    {9.85183716, -1.74458373, -1.9928571},
-    {9.94481468, -1.84540391, -1.76753116},
-    {10.0733671, -1.89298856, -1.52638209},
-    {10.1493902, -1.89688206, -1.31823206},
-    {10.2412844, -1.83915925, -1.07942033},
-    {10.3048162, -1.76649129, -0.869763374},
-    {10.2981663, -1.69666314, -0.699590564},
-    {10.2364254, -1.59303343, -0.544744134},
-    {10.1656075, -1.49584413, -0.415953308},
-    {10.0747061, -1.34174812, -0.293416113},
-    {10.1484985, -1.20607233, -0.175047979},
-    {10.3053398, -1.08084726, -0.110781319},
-    {10.2700491, -0.984887838, -0.00129224302},
-    {10.0961065, -0.825076997, 0.0576252975},
-    {9.95880795, -0.681787729, 0.0782156661},
-    {9.8241663, -0.521402419, 0.0274437051},
-    {9.62852573, -0.39306432, -0.014543551},
-    {9.39876175, -0.276211888, -0.109337538},
-    {9.35115337, -0.148422718, -0.211846575},
-    {9.33529091, -0.0332999863, -0.27834937},
-    {9.33052731, 0.195014983, -0.437393814},
-    {9.34494877, 0.340806156, -0.662742496},
-    {9.36697674, 0.487332493, -0.793094218},
-    {9.40071583, 0.636819601, -0.853471816},
-    {9.36444759, 0.69593811, -1.05871534},
-    {9.25777435, 0.79657203, -1.26865149},
-    {9.36563873, 0.936291456, -1.51551294},
-    {9.57346821, 1.02012134, -1.7119453},
-    {9.50970173, 1.09940863, -1.73244691},
-    {9.33355236, 1.03092527, -1.89983988},
-    {9.25866699, 1.02299821, -1.95488977},
-    {9.14484882, 1.00487375, -1.94453967},
-    {9.03889179, 0.940885425, -2.04244733},
-    {9.05569077, 0.830615819, -1.95536804},
-    {9.22057152, 0.726168931, -1.95530283},
-    {9.31926727, 0.687869668, -1.88288987},
-    {9.48702717, 0.553035319, -1.84741008},
-    {9.62757111, 0.382628053, -1.67715001},
-    {9.58433914, 0.324700922, -1.44553411},
-    {9.60323429, 0.228409827, -1.30319428},
-    {9.80541992, 0.257911175, -1.22517538},
-    {10.0058212, 0.261355519, -1.03980625},
-    {10.119935, 0.261205763, -0.855926394},
-    {10.2526417, 0.362438619, -0.666834712},
-    {10.8041573, 0.582425535, -0.914589047},
-    {11.4552002, 0.786239088, -1.15489912},
-    {10.5281754, 1.32699656, -0.333319008},
-    {9.02380848, 1.43325758, 0.433239102},
-    {9.43749714, 1.24268579, 0.505383551},
-    {10.240159, 1.05264938, 0.0706892833},
-    {10.0012236, 0.434469759, -0.284469277},
-    {10.8129339, 0.097076647, -0.639140964},
-    {11.6324749, -0.0255709179, -0.932777643},
-    {10.7098675, 0.0259803608, -0.622893751},
-    {9.70663834, -0.0145954862, -0.327838749},
-    {9.34249592, 0.00245556026, -0.579868853},
-    {9.23209095, 0.0237412285, -0.84363544},
-    {8.76636696, 0.0172582883, -1.20492601},
-    {9.06059647, 0.015524934, -1.95825529},
-    {9.5715456, 0.070570454, -2.42225838},
-    {9.29184341, 0.258360445, -2.18924451},
-    {9.11465359, 0.358844578, -2.32220387},
-    {9.32368469, 0.459478468, -2.78138351},
-    {9.31728363, 0.483289152, -2.93354988},
-    {8.89252853, 0.374418855, -2.98655486},
-    {8.91633224, 0.283518881, -3.2588768},
-    {9.1531868, 0.132717818, -3.25649405},
-    {8.98060513, -0.0382999554, -2.77781034},
-    {9.29824162, -0.167686448, -2.68907142},
-    {9.89572906, -0.363413215, -2.84451294},
-    {9.88322926, -0.644948483, -2.68966651},
-    {9.47677326, -0.961076915, -2.21128011},
-    {9.4099741, -1.11442375, -1.66872203},
-    {9.52066803, -1.28153431, -1.13630569},
-    {9.52036858, -1.34669006, -0.665494621},
-    {9.89384651, -1.35452557, -0.503357351},
-    {10.5667086, -1.26792026, -0.501565516},
-    {10.8495188, -1.16478133, -0.366332024},
-    {10.7414637, -1.04657662, -0.0152022177},
-    {10.642066, -0.961110771, 0.261269748},
-    {10.612236, -0.884403408, 0.552284181},
-    {10.6399069, -0.703951359, 0.929722667},
-    {10.7816916, -0.515262365, 0.948036075},
-    {11.0703163, -0.319835216, 0.687774897},
-    {11.2948751, -0.128237933, 0.453740954},
-    {11.4056435, 0.0089013679, 0.269569129},
-    {11.1924591, 0.07551229, 0.121542849},
-    {10.8644123, 0.14874135, 0.0350371338},
-    {10.6663542, 0.277035534, -0.0413263366},
-    {10.6218367, 0.394535661, -0.262119472},
-    {10.7156343, 0.347613096, -0.625591993},
-    {10.864089, 0.210548401, -1.08274102},
-    {10.8361864, 0.054967124, -1.43996727},
-    {10.573967, -0.142323747, -1.55760372},
-    {10.1314278, -0.446192712, -1.64637864},
-    {9.79117012, -0.731024802, -1.6232965},
-    {9.56734562, -1.0435034, -1.54340327},
-    {9.52211094, -1.43822098, -1.69072187},
-    {9.45311832, -1.82410216, -1.92034757},
-    {9.44984627, -2.01518679, -2.06417608},
-    {9.29615879, -2.05966353, -2.06313372},
-    {9.12714958, -2.01982903, -2.05226493},
-    {9.13562965, -1.94824791, -2.12373185},
-    {9.16836071, -1.75656426, -2.20145321},
-    {9.12223911, -1.46529412, -2.2629447},
-    {9.01035881, -1.06201029, -2.32428813},
-    {8.98045635, -0.762804151, -2.32250166},
-    {9.11859226, -0.489968002, -2.34345913},
-    {9.28827381, -0.232978672, -2.28170562},
-    {9.37158871, 0.0190555602, -2.13311195},
-    {9.49373436, 0.203850433, -1.91424298},
-    {9.67152214, 0.331889063, -1.7196424},
-    {9.83747959, 0.456687599, -1.31663513},
-    {9.81836414, 0.514178157, -0.916763127},
-    {9.8960247, 0.484636933, -0.594324768},
-    {10.2010355, 0.384661049, -0.344097704},
-    {10.5988474, 0.288760275, -0.112513795},
-    {10.6224985, 0.257761419, 0.195690483},
-    {10.18822, 0.155630037, 0.460418493},
-    {9.75171185, 0.0482573025, 0.63983202},
-    {9.64040947, -0.0919341967, 0.75404948},
-    {9.61945152, -0.352181911, 0.897264421},
-    {9.73428154, -0.535387576, 0.973333299},
-    {9.90807724, -0.710989773, 0.934338152},
-    {10.0068512, -0.818879783, 0.832880378},
-    {9.87341976, -0.936531901, 0.740025997},
-    {9.73415565, -1.07893205, 0.701026201},
-    {9.68104458, -1.28109848, 0.553326428},
-    {9.75827503, -1.50385809, 0.272833973},
-    {9.85345745, -1.61546278, -0.0501141809},
-    {10.0883923, -1.7028029, -0.431884885},
-    {10.0377235, -1.68131077, -0.821126223},
-    {9.7119894, -1.58809173, -1.15802574},
-    {9.37754059, -1.45960367, -1.4924351},
-    {9.15806484, -1.35220706, -1.80114818},
-    {9.04443073, -1.23767042, -2.09961176},
-    {9.07373905, -1.10154486, -2.34855723},
-    {9.13907814, -0.916173756, -2.59568977},
-    {9.08541203, -0.704595566, -2.6618154},
-    {9.02445507, -0.569241226, -2.68073845},
-    {9.13681984, -0.449371368, -2.68862462},
-    {9.26387024, -0.33778283, -2.67553115},
-    {9.51129055, -0.243311584, -2.71736097},
-    {9.83272362, -0.16067709, -2.71747041},
-    {9.94556618, -0.0547726303, -2.52127099},
-    {10.0584898, -0.000861665874, -2.19579554},
-    {9.98127556, 0.0269924514, -1.9185605},
-    {10.0671196, 0.0239973683, -1.62405419},
-    {10.4784842, 0.0659280866, -1.27758479},
-    {10.55198, 0.0633822605, -0.95493871},
-    {10.4615831, 0.0333863646, -0.720349729},
-    {10.4282579, 0.0333863348, -0.44689554},
-    {10.3055553, 0.130810961, -0.237185106},
-    {10.3520823, 0.172647431, 0.0406726263},
-    {10.5130634, 0.0300792772, 0.263882548},
-    {10.390604, -0.116911195, 0.4059515},
-    {10.4055843, -0.114374496, 0.505234659},
-    {10.46418, -0.0800265819, 0.481028616},
-    {10.4024878, -0.0917327031, 0.498726696},
-    {10.3642244, -0.137586072, 0.517294824},
-    {10.3692827, -0.291831434, 0.498683453},
-    {10.5098772, -0.433048308, 0.411135614},
-    {10.6580563, -0.565879107, 0.207304001},
-    {10.6626701, -0.467790931, 0.0683886707},
-    {10.5569429, -0.601928771, -0.0453774929},
-    {10.5549564, -0.837830544, -0.350143522},
-    {10.6303854, -0.941608906, -0.591049314},
-    {10.6340828, -1.03500152, -0.806595147},
-    {10.5739985, -1.2267381, -1.02819276},
-    {10.1612167, -1.42108572, -1.37814069},
-    {9.96955872, -1.60649705, -1.55354738},
-    {9.69279861, -1.45720768, -1.44181192},
-    {9.58047104, -1.7682445, -1.7275337},
-    {9.64935398, -1.80169392, -1.87639308},
-    {9.65595818, -1.73572874, -1.89843619},
-    {9.64776707, -1.71805, -1.84737289},
-    {9.51426601, -1.53133535, -1.70758224},
-    {9.57407665, -1.55439758, -1.90426707},
-    {9.45014381, -1.21730375, -1.77904999},
-    {9.48510647, -1.1073854, -1.71964216},
-    {9.63810158, -0.846035123, -1.60308313},
-    {9.77974033, -0.614688873, -1.40384936},
-    {9.96535492, -0.380485207, -1.33758807},
-    {10.1236544, -0.135789096, -1.16457689},
-    {10.2510042, -0.0290151983, -1.09415126},
-    {10.3234596, 0.21283558, -0.898657739},
-    {10.3106642, 0.376215905, -0.754829288},
-    {10.3679447, 0.497066408, -0.748724937},
-    {10.5342951, 0.608437121, -0.680789948},
-    {10.6334667, 0.738844752, -0.627542019},
-    {10.6779947, 0.907239377, -0.567375541},
-    {10.7397366, 1.06927192, -0.678596973},
-    {10.8647079, 1.25256932, -0.652987897},
-    {10.8552895, 1.15705895, -0.479092121},
-    {10.7560329, 1.04132271, -0.385390103},
-    {10.7129555, 0.931050181, -0.416399956},
-    {10.7480354, 0.863748193, -0.46385783},
-    {10.8603916, 0.601444125, -0.410593301},
-    {10.7843676, 0.232602924, -0.450496078},
-    {10.6428804, -0.102993108, -0.426524639},
-    {10.5527248, -0.478573292, -0.336147904},
-    {10.7330399, -0.623234391, -0.576606631},
-    {11.1543751, -0.421217889, -0.55069977},
-    {10.8861322, -0.451767415, -0.487569749},
-    {10.2840347, -0.478573173, -0.310091943},
-    {10.433404, -0.705448806, -0.47848773},
-    {10.3603563, -0.963772416, -0.523303628},
-    {10.0305099, -1.16463625, -0.400549918},
-    {10.1339493, -1.26076865, -0.450360864},
-    {10.3361835, -1.23860872, -0.525755644},
-    {10.190156, -1.18271077, -0.61427629},
-    {10.0618162, -1.19585729, -0.608889043},
-    {10.1489372, -1.18216503, -0.806595027},
-    {10.0450811, -1.14299941, -1.00650883},
-    {9.90644073, -0.938232183, -0.927552342},
-    {10.0349827, -0.862734735, -0.880899251},
-    {10.1795921, -0.590588272, -1.00124359},
-    {10.3027792, -0.318337649, -1.03429735},
-    {10.5260935, -0.228785545, -1.15326107},
-    {10.6513624, -0.157203764, -1.24080896},
-    {10.5193987, -0.027667366, -1.32016778},
-    {10.4722376, 0.104115054, -1.10636079},
-    {10.6146536, 0.221439555, -0.880321503},
-    {10.5709629, 0.306474566, -0.7717067},
-    {10.4649467, 0.379959732, -0.649116695},
-    {10.699482, 0.263116241, -0.71053201},
-    {10.7802687, 0.133875027, -0.841194987},
-    {10.5873995, 0.045831345, -0.876741111},
-    {10.4683695, -0.0327590443, -0.715968966},
-    {10.535449, -0.0636171326, -0.72655803},
-    {10.504817, -0.143726081, -0.688275218},
-    {10.6055393, -0.197037965, -0.766442478},
-    {10.8372555, -0.33908987, -1.05819654},
-    {10.9235716, -0.405691743, -1.39493513},
-    {10.8779488, -0.548058629, -1.78575003},
-    {10.7691927, -0.701555312, -1.97901046},
-    {10.681159, -0.742641985, -1.99824882},
-    {10.6631079, -0.75381422, -2.22488213},
-    {10.7040291, -0.810275912, -2.4748168},
-    {10.811595, -0.848313034, -2.77051497},
-    {10.7580538, -0.855183601, -3.00471449},
-    {10.7417498, -0.84298557, -3.15819049},
-    {10.7010231, -0.850130022, -3.04888105},
-    {10.5455828, -0.851308107, -2.98402405},
-    {10.5824823, -0.796348751, -2.88545847},
-    {10.6068783, -0.795749724, -2.78123474},
-    {10.5994396, -0.808029354, -2.65661311},
-    {10.5436487, -0.892939508, -2.46618152},
-    {10.4773092, -0.821057856, -2.11635041},
-    {10.482501, -0.767881334, -1.80913985},
-    {10.4035864, -0.672503352, -1.47444129},
-    {10.2914524, -0.628446996, -1.26660073},
-    {10.2777853, -0.548208177, -1.12750304},
-    {10.1405869, -0.371472597, -0.964927852},
-    {10.0178165, -0.207815692, -0.829355717},
-    {9.98216629, -0.0501303263, -0.706737459},
-    {10.1067028, 0.132104337, -0.647061229},
-    {10.1770649, 0.312421232, -0.615913987},
-    {10.1830149, 0.410958558, -0.624103129},
-    {10.1923885, 0.454087347, -0.687232852},
-    {10.2472868, 0.481042862, -0.739344418},
-    {10.2243748, 0.519828856, -0.84818387},
-    {10.1368942, 0.480743378, -0.976825356},
-    {9.99646187, 0.374205589, -1.10179889},
-    {9.89349556, 0.179290891, -1.39580452},
-    {9.76539898, -0.0827765912, -1.62598991},
-    {9.64259624, -0.478037119, -1.76672077},
-    {9.5086937, -0.895407975, -1.83596718},
-    {9.25619984, -1.25791109, -1.8623178},
-    {9.02925396, -1.55903983, -1.86823499},
-    {8.89982033, -1.86348736, -1.97037435},
-    {8.73339653, -2.04158926, -2.10956478},
-    {8.61372185, -2.15610433, -2.28944755},
-    {8.51627541, -2.17122912, -2.40632749},
-    {8.5040741, -2.15415716, -2.45188785},
-    {8.60494423, -2.0965023, -2.51859069},
-    {8.73006535, -1.97250748, -2.56876707},
-    {8.84722519, -1.77148926, -2.56233811},
-    {8.99942207, -1.54790986, -2.51290441},
-    {9.37099361, -1.28139782, -2.60256553},
-    {9.82595158, -0.987882674, -2.66718459},
-    {10.2700472, -0.786615074, -2.58261395},
-    {10.7007561, -0.551352918, -2.31609941},
-    {11.1379089, -0.318033606, -2.01355314},
-    {11.3229399, -0.191347376, -1.67229509},
-    {11.3683147, -0.119316302, -1.17648828},
-    {11.3602819, 0.0370258503, -0.831210613},
-    {11.2407036, 0.201976106, -0.702237189},
-    {11.0149727, 0.145446822, -0.19172363},
-    {10.9610376, -0.0322508216, 0.176100001},
-    {10.576952, -0.289290398, 0.358096838},
-    {10.4561005, -0.501585364, 0.69110018},
-    {10.7630863, -0.640813529, 0.703600585},
-    {11.0604391, -0.766892791, 0.594077408},
-    {10.8032637, -0.956733882, 0.355301499},
-    {10.4619722, -0.993723035, 0.168294519},
-    {10.2523451, -1.24860215, -0.124573983},
-    {10.2492189, -1.29277897, -0.432033867},
-    {10.4813471, -1.23724401, -0.776657701},
-    {10.4442625, -1.05973482, -1.21357656},
-    {10.2596359, -0.704100728, -1.50375068},
-    {10.2733221, -0.42571035, -1.94938087},
-    {10.1871853, -0.00814508647, -2.31573844},
-    {10.3891287, 0.482390642, -2.60804081},
-    {10.1897812, 0.840780914, -2.75522876},
-    {9.97631741, 1.21295249, -2.74790239},
-    {10.3611012, 1.78539014, -2.36389351},
-    {10.373724, 2.14568138, -2.20240116},
-    {10.1691799, 2.67027926, -1.87642443},
-    {10.3333807, 3.05527997, -1.60057771},
-    {10.6130638, 3.1997962, -1.07884288},
-    {11.0517826, 3.06997395, -0.729445457},
-    {11.2147474, 2.8059361, -0.280193686},
-    {11.3321629, 2.48937798, 0.073004283},
-    {11.1286373, 2.30413413, 0.296936274},
-    {11.2635775, 1.8734448, 0.285918325},
-    {10.9716768, 1.57244146, 0.545881867},
-    {10.6607342, 1.56031156, 0.489601135},
-    {10.1597748, 1.68752885, 0.409560978},
-    {10.0813608, 1.69664454, -0.175835639},
-    {9.84990406, 1.65765095, -0.817214429},
-    {9.49715233, 1.84958863, -1.42881763},
-    {8.97018909, 1.95236433, -1.90828729},
-    {8.9703989, 2.07692027, -2.97429347},
-    {8.90969276, 2.55475163, -3.68733931},
-    {8.75308704, 2.72663522, -4.11224222},
-    {8.67710114, 2.62250829, -4.8511157},
-    {8.49578762, 2.17646718, -5.37671852},
-    {8.4620285, 2.12636805, -5.51257944},
-    {8.38598537, 1.79877818, -5.75019884},
-    {8.31631851, 1.26410031, -5.67790651},
-    {8.10020542, 0.6682657, -5.0645709},
-    {8.15682983, 0.147543356, -4.43273163},
-    {8.25904083, -0.566178679, -4.36960268},
-    {8.06473923, -1.01199269, -3.62514782},
-    {8.28343868, -1.59767616, -3.17951822},
-    {8.99875546, -2.08557057, -3.22597146},
-    {9.20342255, -2.26536465, -2.54602289},
-    {9.37199688, -2.2469368, -1.85263586},
-    {9.91715145, -2.38657355, -1.59189403},
-    {10.4533405, -2.29432631, -1.05543983},
-    {10.7834425, -1.89651918, -0.413544148},
-    {11.1444063, -1.56353247, -0.130231708},
-    {11.4987116, -1.07905793, 0.313832998},
-    {11.6710777, -0.548208416, 0.591591418},
-    {11.7213621, -0.153160289, 1.11330521},
-    {11.7793245, 0.482971519, 1.26356316},
-    {11.5904379, 0.73262763, 1.5656358},
-    {11.3294973, 1.14849114, 1.59462464},
-    {11.0465832, 1.52119219, 1.57950187},
-    {10.9161844, 1.95640755, 1.50920618},
-    {10.7773838, 2.10661888, 1.3523562},
-    {10.7214632, 2.4080379, 1.02067089},
-    {10.5844154, 2.27972388, 0.75775367},
-    {10.3245001, 2.16067052, 0.543648481},
-    {10.2550211, 2.17519641, 0.276538193},
-    {10.3076897, 2.08399653, -0.176387966},
-    {10.0876493, 1.97632492, -0.568120241},
-    {9.82699299, 1.33029103, -0.930073738},
-    {9.73404026, 0.869823754, -1.10151017},
-    {9.77730179, 0.2454817, -1.53739989},
-    {9.58101273, -0.260538012, -1.80207026},
-    {9.18889141, -0.751722276, -1.83994591},
-    {8.92912769, -1.34639096, -1.88788903},
-    {8.98387814, -1.93162489, -2.13236785},
-    {8.85503769, -2.11956453, -2.22616935},
-    {8.58581257, -2.08762217, -2.2067318},
-    {8.53769875, -2.22364283, -2.11852145},
-    {8.6117878, -2.25838542, -2.24671626},
-    {8.49676991, -1.92880392, -2.32862616},
-    {8.48367119, -1.69321799, -2.33075333},
-    {8.69004536, -1.37649107, -2.49625778},
-    {8.93284607, -0.833337545, -2.57278752},
-    {9.09278202, -0.498490214, -2.60584116},
-    {9.21092319, -0.194746375, -2.55714011},
-    {9.45707798, 0.00364552881, -2.57714868},
-    {9.71481609, 0.0711694881, -2.42225862},
-    {9.88784409, -0.0170349553, -2.32726622},
-    {10.0364256, -0.0540331416, -2.13309836},
-    {10.2903767, -0.160213307, -1.7468946},
-    {10.4981213, -0.422266126, -1.35947502},
-    {10.5232658, -0.672054172, -1.02670407},
-    {10.6168451, -0.890093982, -0.88272649},
-    {10.6295109, -1.10045111, -0.634299815},
-    {10.6113424, -1.32228053, -0.681128085},
-    {10.6256361, -1.35097027, -0.656590223},
-    {10.6497269, -1.42006886, -0.671450496},
-    {10.3927679, -1.22199595, -0.735076427},
-    {10.1870422, -0.998801112, -0.922624588},
-    {10.1743183, -0.679691136, -1.20279217},
-    {10.2171936, -0.28289175, -1.61044669},
-    {10.0736656, 0.132268578, -1.98243487},
-    {9.88278484, 0.642775953, -2.07549167},
-    {9.70807076, 1.09679472, -2.12602425},
-    {9.73750687, 1.42906034, -2.32570481},
-    {9.80185032, 1.63878202, -2.36910415},
-    {9.90614223, 1.78119695, -2.42493892},
-    {9.92577171, 1.79760158, -2.50242114},
-    {9.77451897, 1.7986697, -2.32555127},
-    {9.70752621, 1.744807, -2.21678877},
-    {9.69978905, 1.5022074, -2.31877947},
-    {9.69566345, 1.10057032, -2.39269257},
-    {9.75275421, 0.762727857, -2.33158326},
-    {9.80200863, 0.468478113, -2.33354378},
-    {9.64905643, 0.106361248, -2.23495388},
-    {9.61483955, -0.361616135, -2.15336132},
-    {9.52744865, -0.732186556, -2.05701113},
-    {9.4596653, -1.04074538, -2.1118207},
-    {9.39111519, -1.3902998, -2.19676995},
-    {9.32933521, -1.70340168, -2.1432364},
-    {9.14291859, -1.85285497, -1.97230995},
-    {9.18770695, -1.95987523, -1.95391977},
-    {9.30469799, -2.06627512, -2.00229144},
-    {9.36984634, -2.06344581, -1.9248718},
-    {9.43124866, -2.0392971, -1.89712048},
-    {9.50816631, -1.98583579, -1.90441597},
-    {9.64697456, -1.87157428, -1.84962392},
-    {9.72166061, -1.6658138, -1.70773101},
-    {9.76289177, -1.46581161, -1.49292207},
-    {9.94839382, -1.21460819, -1.33416367},
-    {10.1949158, -0.935768604, -1.25435793},
-    {10.3901711, -0.651882768, -1.10973966},
-    {10.4958324, -0.373955816, -0.877852857},
-    {10.5838175, -0.112277836, -0.714033186},
-    {10.7117424, 0.222746536, -0.545362115},
-    {10.830965, 0.594772875, -0.331988454},
-    {10.9529333, 0.955609679, -0.188448086},
-    {11.1638794, 1.36602318, -0.172142282},
-    {11.4407692, 1.69628716, -0.136187464},
-    {11.4547558, 1.71605444, -0.0255614091},
-    {11.2661057, 1.69688606, 0.105909348},
-    {11.2047062, 1.61956835, 0.16714859},
-    {11.1428747, 1.34079301, 0.196103558},
-    {11.0706148, 0.986159086, 0.131071866},
-    {10.894166, 0.493023098, -0.0617420152},
-    {10.7705317, -0.153609574, -0.418186933},
-    {11.0154171, -0.919595182, -1.19926846},
-    {11.0594559, -1.4885062, -1.8657043},
-    {10.3903151, -1.54640591, -1.58229244},
-    {9.94790554, -1.50277174, -1.30056715},
-    {9.43122005, -1.34499311, -0.970847428},
-    {9.05648136, -1.27525806, -0.866199493},
-    {9.25524521, -1.54960537, -1.45268106},
-    {9.46291447, -1.82878816, -2.08256125},
-    {9.46656609, -1.86791217, -2.48148537},
-    {9.33826351, -1.46754062, -2.49729919},
-    {9.13845634, -0.916300952, -2.28289628},
-    {8.92847061, -0.291454643, -1.98173857},
-    {8.90377808, 0.175987303, -1.9500258},
-    {9.15660763, 0.365433723, -2.24299407},
-    {9.40929222, 0.367670923, -2.5735991},
-    {9.56068516, 0.395683765, -2.65318871},
-    {9.69972897, 0.426276803, -2.62018251},
-    {9.72299957, 0.406765461, -2.36240387},
-    {9.74442291, 0.323802412, -1.94759452},
-    {9.76183033, 0.144248769, -1.58385408},
-    {9.80314541, -0.129690066, -1.26104915},
-    {9.85466576, -0.51720953, -1.03355289},
-    {9.86113358, -0.891857326, -0.770784497},
-    {9.89706326, -1.14096606, -0.544640362},
-    {9.85084438, -1.34416854, -0.244383156},
-    {9.67152214, -1.44717431, 0.0524575338},
-    {9.51277733, -1.52968836, 0.32879898},
-    {9.5842905, -1.60362113, 0.437137365},
-    {9.77522087, -1.68947506, 0.489452213},
-    {9.77962875, -1.68450558, 0.449698359},
-    {9.74412632, -1.67195344, 0.41024226},
-    {9.73028946, -1.55672133, 0.327204376},
-    {9.82104111, -1.37559235, 0.199114978},
-    {9.95538902, -1.18915033, -0.119362772},
-    {10.0751514, -0.964221895, -0.407317758},
-    {10.1929827, -0.819260836, -0.657901287},
-    {10.2120266, -0.685531855, -0.926053524},
-    {10.163229, -0.541619003, -1.14730537},
-    {10.0001707, -0.341699123, -1.2738626},
-    {9.9279356, -0.187921226, -1.46996593},
-    {10.0222359, -0.041338373, -1.74428129},
-    {10.0297756, 0.0696718767, -1.91126478},
-    {10.0611687, 0.135413393, -2.0211463},
-    {10.0394535, 0.197479114, -2.08429861},
-    {9.91194534, 0.226762608, -2.06804729},
-    {9.81383324, 0.301218718, -2.07979512},
-    {9.76420975, 0.217627645, -2.0595603},
-    {9.81642818, 0.033581391, -2.05315781},
-    {9.84556007, -0.134772599, -2.07173777},
-    {9.73735237, -0.33551091, -1.98788595},
-    {9.55731297, -0.593942046, -1.84780586},
-    {9.47141933, -0.7442348, -1.76594782},
-    {9.50295734, -0.836332738, -1.73378718},
-    {9.49879456, -0.925285876, -1.66485071},
-    {9.38096333, -1.01498771, -1.61065423},
-    {9.4763279, -1.03190994, -1.57626033},
-    {9.63908863, -0.975003898, -1.49630618},
-    {9.69011879, -0.869128823, -1.40101564},
-    {9.77400208, -0.776767612, -1.30277491},
-    {9.82907677, -0.61784339, -1.21177518},
-    {9.8331852, -0.433362186, -1.06387866},
-    {9.89141273, -0.297671944, -0.929627001},
-    {9.95746994, -0.165739745, -0.76048696},
-    {9.9898262, -0.0604224913, -0.597194493},
-    {10.0084133, 0.00550045166, -0.460783869},
-    {9.97309017, 0.0957289338, -0.22358638},
-    {10.0080042, 0.167855293, -0.0186673608},
-    {10.1090059, 0.181107312, 0.127863482},
-    {10.1284676, 0.238865361, 0.278031737},
-    {10.1635246, 0.24638021, 0.415751219},
-    {10.1635237, 0.194715455, 0.599333763},
-    {10.0968733, 0.135862648, 0.778598368},
-    {10.1071157, 0.0754986852, 0.871718287},
-    {10.1652145, 0.14879936, 0.851915121},
-    {10.2347898, 0.148591623, 0.660081208},
-    {10.1353941, 0.102363445, 0.515390813},
-    {9.81890202, 0.456884354, 0.615226626},
-    {9.68833542, 0.780848026, 0.394906491},
-    {9.59802723, 1.09473002, 0.0712177679},
-    {9.40193653, 1.48582542, -0.100674711},
-    {9.31548023, 1.87039626, -0.290337533},
-    {9.33946609, 2.32298899, -0.677324712},
-    {9.34512234, 2.71596885, -1.03667486},
-    {9.18219662, 2.91093183, -1.38195765},
-    {9.2109108, 3.02204847, -1.86302412},
-    {9.27252579, 3.08507657, -2.41146207},
-    {9.35641384, 3.0440619, -3.01603532},
-    {9.45538902, 2.90007782, -3.57877135},
-    {9.38304424, 2.57713294, -3.86396933},
-    {9.23660374, 2.2018795, -4.06185865},
-    {9.23920059, 1.75694168, -4.28145838},
-    {9.16881561, 1.1832726, -4.32111216},
-    {9.09545898, 0.587966383, -4.26999521},
-    {9.05216503, -0.108084761, -4.04382896},
-    {8.82587242, -0.731750906, -3.58714032},
-    {8.59423256, -1.26148081, -2.98521543},
-    {8.59825039, -2.07194328, -2.54717851},
-    {8.80868244, -2.77406669, -2.2686851},
-    {8.78957653, -3.08052802, -1.86138642},
-    {8.65850449, -3.18909907, -1.35143495},
-    {8.65996361, -3.41488528, -0.899668455},
-    {8.74540901, -3.58856726, -0.596956909},
-    {8.97259426, -3.61455631, -0.432601929},
-    {9.15468788, -3.40554023, -0.303708881},
-    {9.18048286, -3.07145214, -0.159581438},
-    {9.27137089, -2.76054764, -0.0430675372},
-    {9.48066235, -2.36203408, -0.0230998639},
-    {9.69999313, -1.91292858, -0.0179455318},
-    {10.0416765, -1.41392934, -0.0809489563},
-    {10.1892614, -0.891591668, -0.1430365},
-    {10.2655859, -0.395011008, -0.0577219352},
-    {10.3646688, 0.0987239853, -0.0522130057},
-    {10.3923445, 0.425784081, -0.0199035592},
-    {10.2880507, 0.798219383, -0.0709732398},
-    {10.3987408, 1.16571259, -0.202443883},
-    {10.4061794, 1.47719872, -0.28522709},
-    {10.2474327, 1.64626944, -0.252024531},
-    {10.1171074, 1.76801884, -0.252620161},
-    {9.98838425, 1.85975373, -0.343375802},
-    {9.90048695, 1.87044954, -0.457345068},
-    {9.90444279, 1.76466143, -0.582509577},
-    {9.84305954, 1.52901304, -0.757360399},
-    {9.59995937, 1.23070538, -0.845950484},
-    {9.38462353, 0.862417758, -0.89750278},
-    {9.20905113, 0.446218103, -0.978578568},
-    {9.00024414, 0.00318147754, -1.07747579},
-    {8.86232758, -0.455661118, -1.16159904},
-    {8.98774147, -0.953493774, -1.35994887},
-    {9.05841446, -1.30431008, -1.54543984},
-    {8.97216225, -1.55889452, -1.6058265},
-    {8.91633701, -1.69491875, -1.60672557},
-    {8.98000908, -1.72960889, -1.67289078},
-    {8.93686581, -1.67000675, -1.76058769},
-    {8.90681171, -1.52145171, -1.92898273},
-    {8.90458107, -1.30071604, -2.13221908},
-    {9.05722427, -1.02532089, -2.42642784},
-    {9.11837101, -0.688676417, -2.71423411},
-    {9.15263939, -0.292475849, -2.93801212},
-    {9.28921795, -0.104408562, -3.13152194},
-    {9.40712833, 0.0544425845, -3.26243162},
-    {9.55666637, 0.16027233, -3.36935353},
-    {9.81345558, 0.130771026, -3.44424605},
-    {10.0977936, -0.0315997973, -3.34069896},
-    {10.1853104, -0.273016959, -3.10650253},
-    {10.3095751, -0.521784067, -2.81921601},
-    {10.4573593, -0.817463934, -2.3982873},
-    {10.4540873, -1.08896565, -1.8817848},
-    {10.3409758, -1.29591036, -1.39965296},
-    {10.4079142, -1.53072309, -1.00160027},
-    {10.3172092, -1.69831026, -0.639438808},
-    {10.2757015, -1.81706417, -0.370094895},
-    {10.3501196, -1.95121825, -0.108825184},
-    {10.3215256, -1.98718321, 0.117820643},
-    {10.1414518, -1.89012992, 0.360183358},
-    {9.82811546, -1.7847321, 0.549599349},
-    {9.79679298, -1.71672976, 0.624794066},
-    {9.84707737, -1.55439758, 0.611244977},
-    {9.70499802, -1.34339571, 0.534566164},
-    {9.6753912, -1.16998219, 0.411582261},
-    {9.74745655, -0.985586464, 0.219702557},
-    {9.66286945, -0.718414605, 0.0488647334},
-    {9.52661419, -0.445178181, -0.0336016901},
-    {9.644454, -0.184414729, -0.264697671},
-    {9.85359478, -0.0268486906, -0.478110552},
-    {9.83339024, 0.0880915746, -0.651052356},
-    {9.78366756, 0.179908127, -0.846970081},
-    {9.89587784, 0.291306078, -1.06928635},
-    {9.88620567, 0.333236843, -1.23708665},
-    {9.78354931, 0.240240335, -1.37749076},
-    {9.68848324, 0.162368879, -1.4288584},
-    {9.60011005, 0.0621843003, -1.48409677},
-    {9.53613663, -0.0400970168, -1.59636104},
-    {9.5651474, -0.167985946, -1.66648829},
-    {9.75915241, -0.322381049, -1.69701135},
-    {9.93083954, -0.51316607, -1.77205205},
-    {10.1488113, -0.691381097, -1.72320712},
-    {10.3152771, -0.878113866, -1.58608735},
-    {10.4011087, -1.03716576, -1.38263953},
-    {10.5010986, -1.16533947, -1.18184805},
-    {10.6126814, -1.39835501, -0.983823478},
-    {10.7839231, -1.56592846, -0.867837548},
-    {10.8836021, -1.65802681, -0.678745985},
-    {10.8897715, -1.74970746, -0.539009631},
-    {10.8407564, -1.77109003, -0.359821528},
-    {10.8135281, -1.71238673, -0.18874605},
-    {10.84519, -1.67085516, -0.17979452},
-    {10.8117428, -1.65113783, -0.299222946},
-    {10.8547688, -1.51050043, -0.41175577},
-    {10.7674074, -1.33201432, -0.52598387},
-    {10.7037306, -1.15126276, -0.684106171},
-    {10.545433, -0.921392381, -0.812003374},
-    {10.3803596, -0.661466897, -1.0456357},
-    {10.4058809, -0.485461682, -1.40369582},
-    {10.2506027, -0.289135903, -1.60011685},
-    {10.0692015, -0.0454879329, -1.73319149},
-    {10.0284901, 0.127049908, -1.92620361},
-    {9.90352154, 0.269219935, -2.0973165},
-    {9.82625008, 0.326947212, -2.18716002},
-    {9.75840759, 0.326497942, -2.27887678},
-    {9.65930748, 0.287076682, -2.27964354},
-    {9.58101082, 0.230883136, -2.25654292},
-    {9.59525394, 0.159287557, -2.17670107},
-    {9.62939072, 0.0507934056, -2.09547186},
-    {9.63536072, -0.0718945414, -1.98323333},
-    {9.59852028, -0.190356985, -1.85186696},
-    {9.65310478, -0.311499, -1.74847293},
-    {9.6741991, -0.446376324, -1.53412426},
-    {9.67702675, -0.531885207, -1.35381711},
-    {9.73787689, -0.559888959, -1.20939279},
-    {9.87861824, -0.686130881, -1.05365324},
-    {9.93173122, -0.663368225, -0.892255425},
-    {9.93615913, -0.698206186, -0.762797236},
-    {10.0828857, -0.763552964, -0.716415286},
-    {10.0429678, -0.765408099, -0.588657379},
-    {10.0217419, -0.782421768, -0.535066307},
-    {10.1164923, -0.800873339, -0.595461905},
-    {10.1455545, -0.774837315, -0.603565633},
-    {10.1745319, -0.805783033, -0.584647},
-    {10.187624, -0.84082526, -0.683659315},
-    {10.0850449, -0.861282647, -0.74749279},
-    {10.0271492, -0.888765514, -0.800447345},
-    {10.087945, -0.855500937, -0.981441021},
-    {10.059083, -0.861790717, -1.07420039},
-    {10.0142078, -0.86070174, -1.14049268},
-    {9.96401596, -0.873321652, -1.22949314},
-    {9.96802235, -0.84378165, -1.3356092},
-    {9.99501896, -0.789836884, -1.4075942},
-    {9.99972343, -0.735249639, -1.44166291},
-    {9.98692703, -0.699009418, -1.40205801},
-    {10.0177231, -0.619939864, -1.40176022},
-    {10.1394234, -0.599573672, -1.42454052},
-    {10.1523657, -0.597926199, -1.34145904},
-    {10.1281157, -0.578907609, -1.26016462},
-    {10.2197628, -0.584148943, -1.25167799},
-    {10.2791233, -0.58654511, -1.20001292},
-    {10.2901354, -0.598974645, -1.15966332},
-    {10.3439922, -0.587743163, -1.14879429},
-    {10.3474665, -0.584938645, -1.11811376},
-    {10.3496428, -0.596428633, -1.10025609},
-    {10.3997221, -0.532295763, -1.16854417},
-    {10.3648176, -0.466742694, -1.194206},
-    {10.319479, -0.43072027, -1.2136929},
-    {10.348752, -0.372548103, -1.22636652},
-    {10.2881975, -0.340650886, -1.22145319},
-    {10.253521, -0.295937657, -1.16254997},
-    {10.1942549, -0.223353639, -1.1319741},
-    {10.1840553, -0.201380774, -1.06794667},
-    {10.1694736, -0.173826337, -1.00049925},
-    {10.1975727, -0.147551522, -0.929121733},
-    {10.2624283, -0.16299583, -0.858850956},
-    {10.3231611, -0.147320136, -0.722817898},
-    {10.3332777, -0.129948705, -0.581073403},
-    {10.2910566, -0.0900464952, -0.438521415},
-    {10.3054276, -0.0815302506, -0.319692999},
-    {10.3475618, -0.113775484, -0.255151212},
-    {10.3453302, -0.130248278, -0.190383703},
-    {10.2303257, -0.140281677, -0.182045817},
-    {10.1364021, -0.0733466148, -0.259202898},
-    {10.0170145, 0.0345622227, -0.35304448},
-    {9.85796547, 0.224924728, -0.517064035},
-    {9.70464325, 0.4208664, -0.772167742},
-    {9.64271832, 0.613084018, -1.17384398},
-    {9.73192501, 0.788934588, -1.69596863},
-    {9.63016319, 0.96055156, -2.14963937},
-    {9.46997929, 1.04461098, -2.54717803},
-    {9.46988487, 1.08154714, -3.0595789},
-    {9.57883549, 1.08334875, -3.54846978},
-    {9.47974968, 0.974029183, -3.80694389},
-    {9.27086735, 0.870100617, -3.95479298},
-    {9.20912457, 0.635288239, -4.13182402},
-    {9.1856184, 0.277379006, -4.21996689},
-    {8.99899483, -0.0824952796, -4.08452654},
-    {8.85890579, -0.499838233, -3.81602645},
-    {8.86693954, -0.977399707, -3.51928592},
-    {8.8047514, -1.46020293, -3.1223433},
-    {8.74286079, -1.86872888, -2.75309396},
-    {8.74883461, -2.19101477, -2.36338329},
-    {8.72273636, -2.43998551, -2.06246853},
-    {8.79820633, -2.61944008, -1.87567997},
-    {8.93494034, -2.62709522, -1.7219075},
-    {9.09769154, -2.57765818, -1.58310914},
-    {9.30196571, -2.42888117, -1.3578949},
-    {9.47767639, -2.16008401, -1.16662514},
-    {9.83398628, -1.87157404, -1.09340727},
-    {10.1392879, -1.56194401, -1.00838566},
-    {10.3988905, -1.22898483, -0.894042194},
-    {10.6511288, -0.924783349, -0.734205544},
-    {10.9545679, -0.677894235, -0.671152532},
-    {11.227356, -0.350997388, -0.546517313},
-    {11.3219442, -0.142281517, -0.329529405},
-    {11.4366035, 0.0515518896, -0.0982202217},
-    {11.558898, 0.252220631, 0.0100235147},
-    {11.5586004, 0.417847186, 0.120053977},
-    {11.4858503, 0.471907943, 0.233210966},
-    {11.3564129, 0.507249594, 0.348601431},
-    {11.1908579, 0.555869341, 0.331596255},
-    {11.0542479, 0.536750913, 0.326416701},
-    {10.9830046, 0.548707008, 0.281403601},
-    {10.916482, 0.529413044, 0.197774962},
-    {10.7968655, 0.468014359, 0.0890846625},
-    {10.7266417, 0.363486916, -0.0635287017},
-    {10.7075596, 0.263406605, -0.208525836},
-    {10.5765638, 0.127049938, -0.369219631},
-    {10.4325886, -0.014131763, -0.545315742},
-    {10.309474, -0.152711242, -0.692741632},
-    {10.2196474, -0.285069823, -0.940960765},
-    {10.1248426, -0.51181829, -1.13747847},
-    {9.98614597, -0.659363627, -1.28842521},
-    {9.74739742, -0.729858637, -1.46176314},
-    {9.55190563, -0.777180374, -1.64445305},
-    {9.37129211, -0.778078973, -1.89384484},
-    {9.1420269, -0.65453279, -2.11539364},
-    {8.98923397, -0.523498893, -2.32503271},
-    {8.91514206, -0.352331519, -2.64217067},
-    {8.81433105, -0.187195152, -2.85109639},
-    {8.82558537, -0.0293463189, -3.01511049},
-    {8.86032391, 0.137839377, -3.11780715},
-    {8.92354202, 0.206337258, -3.14028716},
-    {9.03474522, 0.236602798, -3.18254852},
-    {9.25521278, 0.116013601, -3.13393426},
-    {9.45505238, -0.170381933, -2.875036},
-    {9.43872261, -0.426944762, -2.58746028},
-    {9.46241093, -0.545672476, -2.52176714},
-    {9.58226967, -0.714034557, -2.41203904},
-    {9.50281143, -0.912856221, -1.87687159},
-    {9.59445667, -1.16459084, -1.55184221},
-    {9.95761776, -1.43639231, -1.310341},
-    {10.1248436, -1.60411561, -0.967147827},
-    {10.1610718, -1.69409001, -0.65379113},
-    {10.1300507, -1.77079034, -0.331383407},
-    {10.2175303, -1.86962724, -0.0662086755},
-    {10.4780483, -1.95431006, 0.0671545118},
-    {10.5737019, -1.97295702, 0.229637638},
-    {10.5156822, -1.94719923, 0.373033077},
-    {10.4439554, -2.03948593, 0.416654199},
-    {10.3185501, -2.0749383, 0.464736342},
-    {10.1889658, -1.97460413, 0.286513895},
-    {10.0357037, -1.76756883, 0.109541327},
-    {9.90597916, -1.53260601, 0.0256570466},
-    {9.94438267, -1.32379138, -0.190622821},
-    {9.90413666, -1.18402016, -0.472157449},
-    {9.82892895, -1.05272567, -0.671897173},
-    {9.74769592, -0.937266111, -0.826594591},
-    {9.79001713, -0.820477366, -0.909197569},
-    {9.97532463, -0.727013111, -0.944813907},
-    {9.96550083, -0.598525107, -1.05171776},
-    {9.80675793, -0.484862804, -1.1373297},
-    {9.80199814, -0.432449192, -1.15698338},
-    {9.97086048, -0.36041823, -1.29232514},
-    {9.8463335, -0.273711354, -1.2400645},
-    {9.58463669, -0.180565178, -1.0944494},
-    {9.4693346, -0.200332537, -0.994543612},
-    {9.33097172, -0.228635877, -0.92218256},
-    {9.22935867, -0.230732352, -0.811407804},
-    {9.08876514, -0.274909377, -0.656412303},
-    {9.02910614, -0.283145785, -0.490249842},
-    {8.98283577, -0.374345154, -0.387812912},
-    {8.9548502, -0.478931755, -0.303671628},
-    {8.96349525, -0.616345942, -0.228499681},
-    {8.96260357, -0.787213624, -0.197679326},
-    {9.06161976, -0.975641787, -0.299251705},
-    {9.23069668, -1.13958228, -0.42042014},
-    {9.39674282, -1.23506546, -0.533523202},
-    {9.55131054, -1.32737219, -0.654327989},
-    {9.52051449, -1.29307878, -0.707779706},
-    {9.41577625, -1.21370995, -0.757211447},
-    {9.42425632, -1.14706981, -0.916673481},
-    {9.48689079, -1.04433918, -1.08834469},
-    {9.39970779, -0.93681705, -1.23589563},
-    {9.37039757, -0.716830134, -1.34533036},
-    {9.3974762, -0.420319229, -1.47828984},
-    {9.32532692, -0.140000299, -1.46924376},
-    {9.34740162, 0.122257851, -1.44354451},
-    {9.39083958, 0.264190853, -1.4035368},
-    {9.54997349, 0.317363024, -1.39729333},
-    {9.78640938, 0.250482529, -1.3457998},
-    {9.85345745, 0.171368495, -1.13657558},
-    {9.84397125, 0.0837759152, -0.929121971},
-    {9.96602535, -0.0632894114, -0.698855996},
-    {9.83416176, -0.200990543, -0.449927509},
-    {9.64566898, -0.317424685, -0.192588389},
-    {9.60578632, -0.469347626, -0.0410461687},
-    {9.6517334, -0.811473966, -0.0343461148},
-    {9.7966423, -1.03220928, 0.0216369946},
-    {9.73728085, -1.32482612, 0.0406950749},
-    {9.47424698, -1.42186594, 0.116182812},
-    {9.3394537, -1.37124979, 0.187948197},
-    {9.17758465, -1.39326346, 0.215195209},
-    {9.10081673, -1.2802, 0.0938490778},
-    {9.29422379, -1.33800447, -0.199019372},
-    {9.47695541, -1.33047128, -0.560955167},
-    {9.49700832, -1.35097039, -0.996407032},
-    {9.31267262, -1.25893509, -1.32597482},
-    {9.11873627, -1.18133569, -1.5841701},
-    {9.0259819, -0.949246287, -1.58891606},
-    {9.06659794, -0.837680578, -1.74867618},
-    {9.20019817, -0.84082526, -1.97097027},
-    {9.34727192, -0.784112632, -2.1626358},
-    {9.40759373, -0.863138497, -2.37371993},
-    {9.58890724, -0.910800695, -2.41160655},
-    {9.52600574, -0.928371608, -2.19041681},
-    {9.41100502, -0.942251444, -1.62393939},
-    {9.27786064, -1.00660157, -1.11737847},
-    {9.43645573, -1.19289434, -0.877664149},
-    {9.86662388, -1.39785123, -0.853611529},
-    {9.87311554, -1.61834192, -0.781927466},
-    {9.73504925, -1.64637959, -0.557918549},
-    {9.77343273, -1.58419824, -0.154649913},
-    {9.76703548, -1.54331541, 0.287109494},
-    {9.59698582, -1.2018795, 0.70281291},
-    {9.56499958, -1.07908189, 0.947440684},
-    {9.91596127, -0.974255264, 0.905900002},
-    {10.085865, -0.957931995, 0.688817143},
-    {10.0907736, -0.853554547, 0.589655817},
-    {10.0709867, -0.681038976, 0.510445833},
-    {9.96312428, -0.527841926, 0.4522295},
-    {9.71303177, -0.29198128, 0.60037595},
-    {9.62699127, -0.121267468, 0.528529346},
-    {9.63551712, 0.00932148658, 0.325523317},
-    {9.75928688, 0.0450036339, 0.112573199},
-    {9.81043053, 0.0487064421, -0.0542280264},
-    {9.67402458, -0.0233926289, -0.376438618},
-    {9.65173244, -0.109282844, -0.457940698},
-    {9.8216362, -0.144474685, -0.61680764},
-    {9.73489952, -0.175473586, -0.719691098},
-    {9.62317085, -0.241065264, -0.818852365},
-    {9.55443573, -0.414479107, -0.892850935},
-    {9.56769753, -0.394126028, -1.00333273},
-    {9.54774094, -0.670706213, -1.24721134},
-    {9.44300175, -0.852655828, -1.33773708},
-    {9.39871788, -0.985998809, -1.46163833},
-    {9.37843323, -1.11367476, -1.60633647},
-    {9.2385807, -1.11008084, -1.6113987},
-    {9.24021721, -1.15021467, -1.63269019},
-    {9.28380966, -1.04643595, -1.64221907},
-    {9.23328495, -0.98123008, -1.74818468},
-    {9.46189594, -0.884702861, -1.83339489},
-    {9.75706863, -0.840975225, -2.02099729},
-    {9.97877598, -0.827396095, -2.10776734},
-    {10.0641241, -0.695447206, -2.07173729},
-    {10.1557875, -0.538324416, -1.89131355},
-    {10.3264036, -0.487499416, -1.76911938},
-    {10.8086958, -0.526576221, -1.76533723},
-    {11.151103, -0.516460657, -1.71562266},
-    {11.3230886, -0.654682636, -1.52265966},
-    {11.4809408, -0.760258496, -1.36453724},
-    {11.5187302, -0.981892347, -1.25808036},
-    {11.7687941, -1.1200552, -1.03509617},
-    {12.1026764, -1.34055054, -0.880642116},
-    {12.3447332, -1.44747388, -0.811854601},
-    {12.3950214, -1.51201749, -0.549657404},
-    {12.7630987, -1.62783003, -0.450486362},
-    {13.0773087, -1.86273861, -0.4839966},
-    {12.9952164, -1.88432109, -0.485877931},
-    {12.621501, -1.80343664, -0.317387551},
-    {12.3545542, -1.66147077, -0.426375717},
-    {12.3706236, -1.61489773, -0.591495931},
-    {12.1943855, -1.34528363, -0.658844352},
-    {12.0773821, -1.20813489, -1.02314985},
-    {12.2992668, -1.21546137, -1.57723963},
-    {11.6151361, -0.773137033, -1.22502649},
-    {11.3869143, -0.597177386, -1.53591084},
-    {11.3224316, -0.559816301, -1.82658219},
-    {11.0065022, -0.511581659, -1.75165892},
-    {11.1487236, -0.369253665, -1.91722071},
-    {11.2257872, -0.308603734, -2.11152267},
-    {10.9321041, -0.339902014, -1.7174089},
-    {10.6784391, -0.17891787, -1.56315827},
-    {10.6768303, -0.10965047, -1.67960417},
-    {10.711791, -0.0611249357, -1.53710198},
-    {10.843729, 0.0722176731, -1.10070276},
-    {11.0255337, -0.279701442, -0.747831285},
-    {10.9028978, -0.742206454, -0.767706096},
-    {9.98906231, -0.664773941, -0.554229856},
-    {9.56380939, -0.737795413, -0.476403207},
-    {9.83747959, -1.11076164, -0.886963069},
-    {10.1639719, -1.18241155, -1.49987936},
-    {9.82372093, -1.12610459, -1.38076663},
-    {9.42298412, -1.14011824, -1.17761195},
-    {9.25752258, -1.02668226, -1.21773541},
-    {9.41384125, -0.923638701, -1.46980333},
-    {9.52735806, -0.874669552, -1.71294236},
-    {9.22289753, -0.622984707, -1.7148329},
-    {9.05563164, -0.35947147, -1.76533723},
-    {9.07775593, -0.145223483, -1.85230374},
-    {9.22607327, -0.0270229895, -1.93039048},
-    {9.28574657, 0.156079292, -1.79036558},
-    {9.29674625, 0.372945487, -1.71415722},
-    {9.41027164, 0.509346128, -1.54112232},
-    {9.68892956, 0.52147609, -1.39148664},
-    {9.98499489, 0.301489234, -1.27148068},
-    {10.3057737, 0.11427103, -1.17225599},
-    {10.536458, 0.0630102232, -0.856932521},
-    {10.5197964, 0.0592491366, -0.519243956},
-    {10.6111927, -0.0823273584, -0.300562888},
-    {10.5989265, -0.181967437, -0.0741089955},
-    {10.6417599, -0.214626655, 0.111418307},
-    {10.7163591, -0.320357114, 0.207285941},
-    {10.717165, -0.489939839, 0.180887848},
-    {10.6512938, -0.512330949, 0.174078792},
-    {10.4467955, -0.442782193, 0.249440148},
-    {10.0915155, -0.330916852, 0.0770243034},
-    {9.76882267, -0.209018245, -0.181003615},
-    {9.59668827, -0.0860710889, -0.510648072},
-    {9.57199097, 0.0764108077, -0.936774015},
-    {9.49537182, 0.276630312, -1.50643063},
-    {9.18697453, 0.492410481, -1.79438567},
-    {8.79931259, 0.654133022, -2.04505992},
-    {8.92451668, 0.790282369, -2.69845176},
-    {8.86113834, 0.892863035, -3.0544486},
-    {8.58917427, 0.865308523, -3.09241676},
-    {8.45496082, 0.864741266, -3.20771194},
-    {8.32048512, 0.806156158, -3.3934741},
-    {8.24326897, 0.687851489, -3.37694693},
-    {8.15192223, 0.386548847, -3.22478056},
-    {7.98469687, 0.166711673, -2.99608421},
-    {7.87617111, -0.0200059395, -2.71747112},
-    {8.0006609, -0.264884919, -2.50155377},
-    {8.01251888, -0.597477078, -2.2023468},
-    {8.004632, -0.794252217, -1.87761581},
-    {8.06354713, -0.890393376, -1.6591928},
-    {8.24907112, -0.997766137, -1.45461607},
-    {8.29905987, -1.0247215, -1.16547},
-    {8.44203472, -1.02591991, -0.961043119},
-    {8.67857647, -1.01753354, -0.903277993},
-    {8.79885292, -0.924937963, -0.798757076},
-    {8.910532, -0.837381124, -0.735324562},
-    {9.0654068, -0.67130506, -0.749915957},
-    {9.02717209, -0.369403392, -0.617105246},
-    {8.94876766, -0.135190085, -0.481316388},
-    {9.00426102, 0.0653291345, -0.344932437},
-    {9.09903049, 0.304933548, -0.267211288},
-    {9.15927601, 0.510852754, -0.292843163},
-    {9.40117645, 0.713956833, -0.349816918},
-    {9.71600628, 0.86183697, -0.357380539},
-    {9.94652271, 1.03116238, -0.260367274},
-    {10.1362982, 1.27712882, -0.134549692},
-    {10.2763405, 1.37400973, -0.0465326793},
-    {10.3422728, 1.35150146, -0.0128922015},
-    {10.5450048, 1.24139595, -0.0757810399},
-    {10.8157606, 1.09233391, -0.252769023},
-    {10.9334421, 0.953213394, -0.365926057},
-    {10.8715935, 0.864450812, -0.398961663},
-    {10.8176041, 0.755539775, -0.457095325},
-    {10.6854315, 0.637384772, -0.472531855},
-    {10.6715965, 0.481492132, -0.580478072},
-    {10.6741257, 0.193667158, -0.80247438},
-    {10.5888758, -0.0102961743, -1.02700186},
-    {10.4157057, -0.109069534, -1.04693532},
-    {10.2816248, -0.0540142916, -1.26229715},
-    {10.150878, -0.0582169704, -1.46295452},
-    {9.96758556, -0.030362973, -1.56985855},
-    {9.77971745, 0.0316524096, -1.82493436},
-    {9.41702557, 0.224895671, -2.01514125},
-    {9.2134409, 0.268843144, -2.27351642},
-    {9.12234211, 0.352713794, -2.60334206},
-    {8.82052135, 0.448846012, -2.66614199},
-    {8.64898205, 0.471758187, -2.81547976},
-    {8.5745945, 0.404219657, -2.92059612},
-    {8.41703987, 0.349110633, -2.84049368},
-    {8.35663605, 0.256713122, -2.81294823},
-    {8.35657024, 0.0635910705, -2.75739431},
-    {8.2241745, -0.138726115, -2.57284474},
-    {8.25130367, -0.439936876, -2.4807725},
-    {8.46762466, -0.774484873, -2.48851442},
-    {8.55436134, -0.96362257, -2.23971796},
-    {8.57412529, -1.0465765, -1.92273784},
-    {8.72498322, -1.20349765, -1.72799003},
-    {8.90963745, -1.35253072, -1.5088129},
-    {8.90621662, -1.27750468, -0.980547726},
-    {8.87839603, -1.11936545, -0.414315611},
-    {9.1764431, -1.02290642, -0.235813394},
-    {10.2274361, -1.46740937, -1.29945385},
-    {10.5864964, -1.83593261, -2.04854226},
-    {9.6591835, -1.40383792, -1.09507847},
-    {9.51634884, -1.14197826, -0.501714408},
-    {9.36860847, -0.722457111, 0.357584536},
-    {8.87702274, -0.0193875432, 1.70783627},
-    {9.14306831, -0.284643263, 1.29242086},
-    {9.29467201, -0.415527165, 1.00714588},
-    {9.54164124, -0.547609389, 0.399224341},
-    {9.75736618, -0.551952124, 0.208346233},
-    {9.73177624, -0.209916577, 0.530843914},
-    {10.0802832, -0.261545032, 0.0204593316},
-    {10.2998047, -0.393214166, -0.88763988},
-    {10.1124554, -0.269386679, -1.01632679},
-    {10.388711, -0.301595271, -1.38320851},
-    {10.5933399, 0.105762333, -0.627527297},
-    {10.9258356, 0.212000564, -1.02224624},
-    {10.6254807, 0.134423077, -1.29242146},
-    {10.3576765, 0.220023692, -0.959851742},
-    {10.6762543, 0.413558811, -0.787486136},
-    {17.2064457, 6.49391842, -5.0113225},
-    {19.2668648, 15.244194, -7.92000771},
-    {15.2994633, 4.27336979, 1.49716854},
-    {12.3615913, 2.9153204, 0.74105525},
-    {11.7887564, 7.27457952, -1.34741497},
-    {10.846014, 9.7843008, -2.26084661},
-    {10.6492786, 15.1538239, -12.4514008},
-    {15.9478006, 6.36707783, -7.33476543},
-    {29.5983219, 0.416050553, -14.1776447},
-    {28.2569561, -27.2762432, -19.5987587},
-    {28.2421684, -9.72577953, -26.36092},
-    {18.3552437, 3.83267951, -13.089653},
-    {18.9566479, 2.20933986, -27.2006855},
-    {18.8807697, -4.08534241, -34.6256027},
-    {11.407443, -8.7137804, -29.729599},
-    {12.3524351, -10.6185646, -8.70415211},
-    {11.951149, -16.4419651, -0.842783093},
-    {8.31647205, -14.9316006, -0.748345017},
-    {7.84692907, -13.6797342, 0.0983157754},
-    {6.77202082, -13.8104696, -0.579733491},
-    {5.93336868, -13.05826, -0.880492985},
-    {5.207057, -12.5641499, -1.59095526},
-    {4.71164131, -11.7963982, -2.38850546},
-    {3.55488276, -11.7808676, -4.3460784},
-    {3.37963343, -14.5149965, -4.52029896},
-    {2.4802711, -14.362606, -4.21773434},
-    {1.67554021, -13.3414421, -5.14234686},
-    {1.42172801, -13.3637552, -5.65557337},
-    {2.13273001, -10.9519873, -8.49894428},
-    {0.472616494, -5.25417757, -16.8535557},
-    {1.82483482, -7.16717672, -12.2222042},
-    {1.61766636, -7.80582952, -8.89022923},
-    {1.05960655, -4.16279221, -8.67284966},
-    {1.80110729, -6.28089571, -8.63741207},
-    {1.00827873, -2.35332918, -11.7288351},
-    {1.78199208, -2.45487046, -10.4920702},
-    {2.32420492, -2.26168036, -6.99693155},
-    {1.79768586, -3.09550381, -9.49160004},
-    {2.63693285, -4.01513624, -8.01043224},
-    {5.58897066, -5.20752048, -7.57788467},
-    {4.71593285, -3.54700804, -6.30965042},
-    {4.76429796, -3.76107764, -7.39138508},
-    {4.96499348, -3.96590662, -7.29831457},
-    {4.88764715, -5.05000496, -7.30605745},
-    {4.78511381, -5.48795462, -6.78014612},
-    {4.68945074, -5.62243319, -6.53120089},
-    {4.44307756, -5.77413273, -5.92089748},
-    {4.19268608, -5.67843962, -5.7813859},
-    {4.03289986, -5.5533967, -5.89424467},
-    {4.0148983, -5.6651125, -5.79895592},
-    {5.25911522, -6.04847908, -6.20632076},
-    {6.17096519, -5.96851158, -6.17341566},
-    {6.2146244, -5.13103533, -6.29727983},
-    {5.96645927, -5.68193722, -6.77959871},
-    {5.06644964, -6.26891661, -6.14319134},
-    {4.13510942, -6.34124613, -6.48415089},
-    {4.05521679, -7.01618195, -6.0621953},
-    {3.90019155, -6.75860834, -6.16091013},
-    {4.03675604, -6.79330826, -5.92117214},
-    {5.14425945, -6.36685514, -6.43561363},
-    {6.35663748, -5.9584775, -7.48990965},
-    {6.33504057, -5.83002949, -8.20357418},
-    {5.40181828, -5.16516066, -8.25722694},
-    {5.07403755, -4.96067524, -7.6495204},
-    {4.85131931, -5.1212101, -6.58524895},
-    {4.73646355, -5.16389036, -5.99013186},
-    {4.7702136, -5.35422993, -5.71990824},
-    {4.71816397, -5.35841846, -5.81042147},
-    {4.71420479, -5.13332033, -6.47298002},
-    {4.76666498, -5.08347273, -6.5955224},
-    {4.65210724, -4.97295475, -6.44097281},
-    {4.53000689, -4.96127939, -6.25685453},
-    {4.48138428, -5.17753172, -6.32343626},
-    {4.52460623, -5.28129625, -6.3264761},
-    {4.57593393, -5.49439383, -6.36548471},
-    {4.67948198, -5.7089901, -6.3678689},
-    {4.80858898, -5.72510958, -6.23880768},
-    {4.9373126, -5.88464975, -6.06323719},
-    {4.97138166, -6.03784752, -5.99206734},
-    {5.08906317, -6.22698498, -5.78242731},
-    {5.42706585, -6.35418034, -5.90947771},
-    {5.71705246, -6.35700369, -6.03310823},
-    {5.81494379, -6.51001835, -5.86193657},
-    {5.81538963, -6.71502924, -5.66793203},
-    {5.87921476, -6.86283588, -5.75860643},
-    {5.84871578, -6.92543364, -5.71245003},
-    {5.79530382, -7.0796771, -5.59720802},
-    {5.81509113, -7.14736509, -5.66495371},
-    {5.77075672, -6.97140646, -5.75116062},
-    {5.69987631, -6.88305283, -5.69579649},
-    {5.64901924, -6.73109674, -5.67761421},
-    {5.55875063, -6.81012297, -5.67627001},
-    {5.48599863, -6.607656, -5.71304464},
-    {5.36604071, -6.48748684, -5.80523491},
-    {5.2690835, -6.55868721, -5.73791122},
-    {5.28980637, -6.4047699, -5.75200176},
-    {5.23069763, -6.47347879, -5.80267811},
-    {5.20705605, -6.50709009, -5.76712084},
-    {5.17618322, -6.55472136, -5.80061626},
-    {5.15829468, -6.54568911, -5.80419588},
-    {5.09900045, -6.49634552, -5.84118652},
-    {5.00961685, -6.46449232, -5.78064203},
-    {4.94665289, -6.60975647, -5.83844233},
-    {4.90339041, -6.58160114, -5.84451628},
-    {4.8273654, -6.5992713, -5.8287344},
-    {4.79590654, -6.6451478, -5.85958862},
-    {4.72158527, -6.65243387, -5.86506367},
-    {4.67040682, -6.78661156, -5.89126825},
-    {4.62407017, -6.87884092, -5.95871115},
-    {4.56323957, -6.75412941, -5.91122866},
-    {4.52668905, -6.61394691, -5.90868855},
-    {4.51047277, -6.54775524, -5.89513874},
-    {4.47648382, -6.51144695, -5.91323185},
-    {4.47997332, -6.48635578, -5.92715073},
-    {4.43546581, -6.37493658, -5.92828894},
-    {4.44560623, -6.31129551, -5.9597578},
-    {4.39680767, -6.30530643, -6.09912014},
-    {4.36273813, -6.24076319, -6.13440704},
-    {4.32063437, -6.2079668, -6.10567188},
-    {4.31548071, -6.07217121, -6.13225555},
-    {4.31944323, -5.9779458, -6.10760689},
-    {4.33149433, -6.03395271, -6.14885092},
-    {4.29162216, -6.00550127, -6.19694233},
-    {4.3096242, -5.94320297, -6.2109375},
-    {4.29073, -5.8425703, -6.22374201},
-    {4.31855059, -5.85290194, -6.21048927},
-    {4.34274721, -5.88673306, -6.20574427},
-    {4.3856492, -5.88165474, -6.17862701},
-    {4.41550064, -5.88444233, -6.14715004},
-    {4.47640324, -5.90097332, -6.22731447},
-    {4.58099222, -6.00714827, -6.20914936},
-    {4.64455509, -5.8938489, -6.10915422},
-    {4.75474787, -5.98492193, -6.06077433},
-    {4.79656982, -6.08441973, -6.02035666},
-    {4.83063889, -6.18520451, -5.99653482},
-    {4.85504341, -6.23699093, -5.99061966},
-    {4.92511225, -6.31024837, -6.00427675},
-    {4.97492933, -6.29072142, -5.94643879},
-    {5.02626038, -6.27461624, -5.89186382},
-    {5.10650206, -6.31860161, -5.89114237},
-    {5.17460966, -6.28239393, -5.88888645},
-    {5.25375986, -6.26606989, -5.90005207},
-    {5.26789188, -6.22443914, -5.90630579},
-    {5.29987907, -6.21949768, -5.83528519},
-    {5.33945417, -6.16184282, -5.80267763},
-    {5.36892557, -6.17251539, -5.8481164},
-    {5.38302612, -6.19376373, -5.86573601},
-    {5.40104723, -6.25184488, -5.86506271},
-    {5.40398264, -6.30335426, -5.79599667},
-    {5.42143011, -6.32447338, -5.79017162},
-    {5.4736352, -6.31217575, -5.79718876},
-    {5.46702671, -6.30800152, -5.80307102},
-    {5.48024035, -6.26858187, -5.8002615},
-    {5.4782629, -6.22788429, -5.77945089},
-    {5.43958044, -6.21230984, -5.79865789},
-    {5.42143917, -6.33297825, -5.78487873},
-    {5.37456512, -6.27370787, -5.83677387},
-    {5.33646536, -6.28476763, -5.75845623},
-    {5.32487345, -6.28823376, -5.77394199},
-    {5.26446104, -6.2933054, -5.80864382},
-    {5.17272043, -6.3024826, -5.82111788},
-    {5.16196346, -6.27235985, -5.84466505},
-    {5.07299566, -6.2534914, -5.85568333},
-    {5.02880907, -6.23911476, -5.89335299},
-    {4.99459124, -6.2343235, -5.9332552},
-    {4.9437089, -6.21740103, -6.00234032},
-    {4.87170172, -6.29347563, -5.94620848},
-    {4.77829218, -6.35664845, -5.90370321},
-    {4.79022551, -6.36133242, -5.94673204},
-    {4.7340827, -6.34049702, -5.97717857},
-    {4.70746088, -6.30743837, -6.0101347},
-    {4.66681671, -6.35208893, -6.01065969},
-    {4.62577391, -6.33315897, -6.01916599},
-    {4.60762358, -6.32702017, -6.04179716},
-    {4.54703093, -6.32455587, -6.0372529},
-    {4.50795317, -6.30197287, -6.03095579},
-    {4.49783564, -6.30843735, -6.04129505},
-    {4.46940517, -6.30923843, -6.08889914},
-    {4.46093035, -6.28658581, -6.07231855},
-    {4.4578743, -6.29115629, -6.05761147},
-    {4.42522335, -6.30305862, -6.01708078},
-    {4.46896505, -6.29467297, -6.06844854},
-    {4.43638182, -6.33016443, -6.09599352},
-    {4.43681049, -6.33965921, -6.10900879},
-    {4.43474531, -6.36850214, -6.10820103},
-    {4.48230505, -6.3907032, -6.06538439},
-    {4.50526571, -6.35532379, -6.09584522},
-    {4.53457403, -6.35023212, -6.07425547},
-    {4.55614758, -6.33226109, -6.05981302},
-    {4.59765577, -6.30455732, -6.0349474},
-    {4.62349319, -6.25978994, -6.04216194},
-    {4.63327026, -6.31418467, -6.00867081},
-    {4.64571047, -6.30901766, -5.93777704},
-    {4.70789814, -6.2492981, -5.97747612},
-    {4.73973751, -6.25573874, -6.04239178},
-    {4.79255247, -6.24240923, -6.03718185},
-    {4.79270124, -6.26337481, -5.96645784},
-    {4.82111788, -6.26711845, -5.95484447},
-    {4.84611225, -6.31459236, -5.95707798},
-    {4.86798239, -6.31429005, -5.93191528},
-    {4.90293932, -6.32382965, -5.96174288},
-    {4.90417862, -6.3112464, -5.89647484},
-    {4.904284, -6.34034729, -5.90585899},
-    {4.92890882, -6.31961775, -5.92795849},
-    {4.9743619, -6.37447214, -5.90323782},
-    {4.98715162, -6.39111471, -5.87876081},
-    {5.00247574, -6.3822794, -5.85687399},
-    {5.00363922, -6.34241676, -5.96823978},
-    {5.05498838, -6.28450346, -5.98346519},
-    {5.08067703, -6.33428431, -5.89893961},
-    {5.01782417, -6.39054966, -5.7698307},
-    {4.99518538, -6.43184614, -5.69443512},
-    {4.99578142, -6.42825317, -5.67239904},
-    {4.97204399, -6.39585781, -5.7271266},
-    {4.9887886, -6.41552401, -5.82605362},
-    {4.97958374, -6.44295263, -5.85036612},
-    {4.93151045, -6.43334436, -5.85017395},
-    {4.98748159, -6.45249033, -5.90745687},
-    {5.01794863, -6.35891771, -5.79136181},
-    {4.87482548, -6.43678904, -5.88054705},
-    {4.63128376, -6.57679415, -5.73521233},
-    {4.7486062, -6.68982267, -5.64241838},
-    {4.94772577, -6.73794222, -5.59586859},
-    {4.89832258, -6.70022631, -5.63674641},
-    {4.83936882, -6.64406538, -5.75015736},
-    {4.78198957, -6.64090157, -5.8388586},
-    {4.69554949, -6.65303183, -5.89558554},
-    {4.67254353, -6.65158033, -5.89258385},
-    {4.64463472, -6.70095301, -5.78627634},
-    {4.6058383, -6.72476339, -5.70515442},
-    {4.60107756, -6.78781033, -5.67269516},
-    {4.59824514, -6.75148678, -5.72510576},
-    {4.57995129, -6.72236776, -5.83662415},
-    {4.5406642, -6.68734932, -5.83053923},
-    {4.51009941, -6.68323565, -5.81202269},
-    {4.48919725, -6.69241714, -5.83692217},
-    {4.45185423, -6.71188498, -5.86446762},
-    {4.45349073, -6.69121981, -5.84779263},
-    {4.41599989, -6.71592808, -5.8196516},
-    {4.40751982, -6.72745895, -5.84168816},
-    {4.42165232, -6.70020437, -5.85568333},
-    {4.42076063, -6.71113634, -5.83870983},
-    {4.4296875, -6.70065355, -5.83424187},
-    {4.41719055, -6.69361544, -5.84511232},
-    {4.42626524, -6.70364809, -5.85985088},
-    {4.42641449, -6.71847391, -5.84585571},
-    {4.42166233, -6.71547365, -5.8458066},
-    {4.4445262, -6.70698214, -5.83484316},
-    {4.44084501, -6.67429733, -5.83766699},
-    {4.46970797, -6.66516256, -5.82113981},
-    {4.48643875, -6.66348791, -5.81086683},
-    {4.50972843, -6.65303278, -5.8196516},
-    {4.54742193, -6.64746714, -5.80733156},
-    {4.55212927, -6.63730764, -5.80774021},
-    {4.59661341, -6.57171583, -5.95424891},
-    {4.59463882, -6.59349346, -5.85129261},
-    {4.62666655, -6.63284683, -5.75672483},
-    {4.6057806, -6.67529202, -5.64672232},
-    {4.61402082, -6.70828962, -5.62266922},
-    {4.6720438, -6.69720793, -5.65334034},
-    {4.69245386, -6.67844439, -5.75528193},
-    {4.72986937, -6.62783527, -5.72141647},
-    {4.71384954, -6.55075169, -5.75994587},
-    {4.62592268, -6.56452894, -5.83424234},
-    {4.71771812, -6.71428061, -5.75026894},
-    {4.85836124, -6.80332899, -5.57062006},
-    {4.89373493, -6.78736401, -5.4589076},
-    {4.86874819, -6.79345512, -5.4764843},
-    {4.88620996, -6.73063326, -5.6513319},
-    {4.87307549, -6.68149519, -5.68208027},
-    {4.81664038, -6.72537708, -5.6073761},
-    {4.84075546, -6.73988962, -5.60450459},
-    {4.86634541, -6.74198532, -5.65572262},
-    {4.89428425, -6.7375474, -5.61653233},
-    {4.86589956, -6.73958921, -5.59423018},
-    {4.88206291, -6.73171616, -5.61859655},
-    {4.8652854, -6.71402168, -5.61277866},
-    {4.8420949, -6.72805929, -5.61835146},
-    {4.82915211, -6.69750786, -5.62624264},
-    {4.81868792, -6.69093227, -5.66013575},
-    {4.79314804, -6.68387985, -5.65497875},
-    {4.78079939, -6.66905451, -5.65602016},
-    {4.75282955, -6.66950417, -5.65036249},
-    {4.77678204, -6.66875601, -5.64708757},
-    {4.75684595, -6.66591072, -5.65051126},
-    {4.72357321, -6.67482948, -5.67100525},
-    {4.70150137, -6.63820648, -5.68460751},
-    {4.69599676, -6.66006947, -5.67716265},
-    {4.69533777, -6.64286757, -5.68828821},
-    {4.6692071, -6.63556337, -5.6725421},
-    {4.64282513, -6.61382389, -5.70070601},
-    {4.61476469, -6.6373086, -5.70113325},
-    {4.62220383, -6.6509347, -5.69890118},
-    {4.59435081, -6.65187025, -5.71586561},
-    {4.6055603, -6.65015697, -5.7152586},
-    {4.61613464, -6.63473606, -5.70417118},
-    {4.59542418, -6.63446331, -5.71661854},
-    {4.60717726, -6.62248135, -5.70411253},
-    {4.60345793, -6.65752459, -5.69845581},
-    {4.61030197, -6.65393019, -5.72287273},
-    {4.60167217, -6.66650963, -5.71468449},
-    {4.59438229, -6.65138483, -5.71289682},
-    {4.60911083, -6.67145061, -5.70277119},
-    {4.60473824, -6.66799021, -5.70778036},
-    {4.61000443, -6.68253279, -5.70187855},
-    {4.59257317, -6.66926241, -5.68591452},
-    {4.6162529, -6.68403101, -5.6968174},
-    {4.61104536, -6.68642664, -5.68296957},
-    {4.64169312, -6.6868763, -5.69205284},
-    {4.62443495, -6.66950417, -5.69413662},
-    {4.64989424, -6.67641068, -5.70113945},
-    {4.62964201, -6.70409775, -5.66272068},
-    {4.64794207, -6.71652651, -5.67388678},
-    {4.64989424, -6.71358681, -5.67616129},
-    {4.66921711, -6.73374796, -5.67433405},
-    {4.67366123, -6.73217916, -5.64641428},
-    {4.6782918, -6.73539686, -5.64976788},
-    {4.71325397, -6.73629475, -5.64574718},
-    {4.72396612, -6.7253623, -5.64798117},
-    {4.71742058, -6.73030424, -5.63547421},
-    {4.74940729, -6.7464776, -5.63413286},
-    {4.75149059, -6.75246763, -5.61060858},
-    {4.75867224, -6.74451685, -5.62577343},
-    {4.75506067, -6.75022078, -5.60123014},
-    {4.78899574, -6.77654505, -5.59308243},
-    {4.7879405, -6.75411558, -5.59676266},
-    {4.78422022, -6.77328396, -5.59631395},
-    {4.80281925, -6.76310587, -5.60195017},
-    {4.7980566, -6.75156975, -5.57859707},
-    {4.8275156, -6.7687912, -5.58008575},
-    {4.80358553, -6.76773357, -5.58539772},
-    {4.83210373, -6.78619385, -5.58679152},
-    {4.8373723, -6.75984907, -5.55973196},
-    {4.81858873, -6.77118635, -5.57517242},
-    {4.81233883, -6.77537918, -5.57100344},
-    {4.81681156, -6.7697854, -5.57567406},
-    {4.81291628, -6.79185867, -5.58087111},
-    {4.81189394, -6.77882528, -5.5857439},
-    {4.79790831, -6.7768774, -5.58068037},
-    {4.78607845, -6.77283478, -5.59677124},
-    {4.77574062, -6.77942419, -5.59363461},
-    {4.75751829, -6.76600933, -5.57899427},
-    {4.7550559, -6.76154804, -5.59139204},
-    {4.72351885, -6.76834106, -5.5972085},
-    {4.73348761, -6.79185343, -5.60941839},
-    {4.72218132, -6.79275084, -5.60956621},
-    {4.70819616, -6.76789284, -5.62028694},
-    {4.70774603, -6.75686073, -5.6285162},
-    {4.67212486, -6.78350115, -5.62428284},
-    {4.6513629, -6.77073717, -5.62147808},
-    {4.65076828, -6.7800231, -5.62847614},
-    {4.62825346, -6.77602863, -5.62230873},
-    {4.62904692, -6.77088833, -5.62951756},
-    {4.61131001, -6.76835108, -5.6245904},
-    {4.59983301, -6.76078129, -5.64266491},
-    {4.59482908, -6.75546408, -5.65095806},
-    {4.58441448, -6.77028799, -5.65021324},
-    {4.58099174, -6.77852488, -5.64664078},
-    {4.57682657, -6.76340055, -5.6363678},
-    {4.5887289, -6.77178621, -5.65274477},
-    {4.56150341, -6.77313328, -5.65870047},
-    {4.59274578, -6.76055384, -5.65944529},
-    {4.57965326, -6.76190233, -5.65363932},
-    {4.57876062, -6.79230261, -5.67522764},
-    {4.56909037, -6.7668438, -5.65840197},
-    {4.54688692, -6.77326965, -5.65999079},
-    {4.56864405, -6.78331661, -5.65334034},
-    {4.56849527, -6.77358341, -5.65676451},
-    {4.57598734, -6.78844643, -5.67115974},
-    {4.56298971, -6.76998806, -5.65765905},
-    {4.57846355, -6.75890684, -5.66301823},
-    {4.58612776, -6.7586031, -5.65508223},
-    {4.57936573, -6.76943302, -5.66040134},
-    {4.60459375, -6.76470232, -5.66605425},
-    {4.61893034, -6.75651169, -5.6584034},
-    {4.61178923, -6.75321722, -5.66450739},
-    {4.64437056, -6.75306749, -5.65319204},
-    {4.6512146, -6.7708869, -5.64276981},
-    {4.64347792, -6.7571106, -5.65289354},
-    {4.64942932, -6.75366592, -5.65125561},
-    {4.68552828, -6.76121664, -5.62663937},
-    {4.70959711, -6.75289297, -5.62966251},
-    {4.71340227, -6.76579666, -5.6243062},
-    {4.70615816, -6.7620883, -5.61379004},
-    {4.72203684, -6.76665068, -5.62966204},
-    {4.73717642, -6.76528311, -5.62692833},
-    {4.74753141, -6.75181103, -5.62428236},
-    {4.76819324, -6.75308514, -5.61725521},
-    {4.77409983, -6.76448631, -5.62044096},
-    {4.77353096, -6.75889349, -5.62967157},
-    {4.76696253, -6.75411606, -5.61194897},
-    {4.76845074, -6.7665453, -5.62043524},
-    {4.78469563, -6.75011063, -5.61644459},
-    {4.78218842, -6.7394352, -5.609025},
-    {4.76904583, -6.73509741, -5.63279343},
-    {4.77380657, -6.73914003, -5.62147808},
-    {4.76428509, -6.74542999, -5.63160324},
-    {4.76845121, -6.73374891, -5.63204956},
-    {4.78752565, -6.71881533, -5.62779427},
-    {4.76227427, -6.73403358, -5.63842297},
-    {4.74613333, -6.72086954, -5.64008856},
-    {4.73443413, -6.72534943, -5.65638113},
-    {4.71920633, -6.7250638, -5.65676546},
-    {4.70626211, -6.70799112, -5.65676546},
-    {4.71890783, -6.72386503, -5.66614389},
-    {4.714818, -6.72151184, -5.67715359},
-    {4.68498707, -6.70784187, -5.66793203},
-    {4.70009995, -6.72084618, -5.68568993},
-    {4.67040682, -6.71997118, -5.68758583},
-    {4.65968561, -6.718575, -5.68576097},
-    {4.63777494, -6.70951986, -5.68294716},
-    {4.62041807, -6.70349836, -5.68282127},
-    {4.60142088, -6.71402216, -5.69983864},
-    {4.6323204, -6.68972111, -5.6965189},
-    {4.59073019, -6.70327139, -5.70850706},
-    {4.60390377, -6.69795942, -5.71185446},
-    {4.58039713, -6.70724344, -5.73046589},
-    {4.56685877, -6.70364857, -5.72346783},
-    {4.57355356, -6.68028688, -5.72421312},
-    {4.55793238, -6.67803955, -5.731359},
-    {4.5643301, -6.6775918, -5.73359251},
-    {4.56180048, -6.69166851, -5.72614813},
-    {4.53680515, -6.68493128, -5.74446154},
-    {4.55183268, -6.66830635, -5.76143503},
-    {4.53457355, -6.65842295, -5.73776102},
-    {4.52192831, -6.68425369, -5.7409873},
-    {4.53933477, -6.66680861, -5.74788618},
-    {4.52371359, -6.68283272, -5.75086308},
-    {4.56047583, -6.67281914, -5.75108004},
-    {4.55094004, -6.69885731, -5.76411438},
-    {4.55583143, -6.68076706, -5.7484951},
-    {4.54588127, -6.66021967, -5.73835802},
-    {4.57444572, -6.67968893, -5.7542882},
-    {4.57771969, -6.68702745, -5.74743938},
-    {4.58009958, -6.68193388, -5.74565268},
-    {4.59081173, -6.68582869, -5.7487793},
-    {4.60719061, -6.66639233, -5.74373055},
-    {4.60360575, -6.67863894, -5.73389006},
-    {4.61130905, -6.68178368, -5.73601818},
-    {4.64704895, -6.68358135, -5.71319437},
-    {4.62443447, -6.6757946, -5.7185545},
-    {4.64853668, -6.66860676, -5.70798302},
-    {4.66073704, -6.67444658, -5.71096134},
-    {4.67561483, -6.66186666, -5.69547701},
-    {4.68930149, -6.67264938, -5.7078352},
-    {4.69923306, -6.68352699, -5.69868374},
-    {4.7126689, -6.68101168, -5.70389605},
-    {4.72433615, -6.65550089, -5.69449711},
-    {4.71935463, -6.66890526, -5.67984343},
-    {4.74453354, -6.6598568, -5.69810629},
-    {4.74505329, -6.65191412, -5.69032526},
-    {4.73818588, -6.66769838, -5.68684578},
-    {4.77112818, -6.65842295, -5.67388678},
-    {4.76249838, -6.66366386, -5.67358971},
-    {4.78079987, -6.67324829, -5.6855011},
-    {4.76830149, -6.68912268, -5.66822958},
-    {4.77454138, -6.66421413, -5.65277195},
-    {4.76428509, -6.66755772, -5.66450834},
-    {4.78109741, -6.68432951, -5.66108274},
-    {4.79867125, -6.68070221, -5.65748024},
-    {4.7840724, -6.66710949, -5.66227293},
-    {4.7653079, -6.66392183, -5.66663122},
-    {4.78331375, -6.6793108, -5.66762447},
-    {4.79433823, -6.670403, -5.65542459},
-    {4.77871656, -6.67294884, -5.64857578},
-    {4.77872515, -6.65898561, -5.64569712},
-    {4.78254652, -6.66385221, -5.65271521},
-    {4.77050161, -6.65942097, -5.64757538},
-    {4.76595974, -6.68394804, -5.65947819},
-    {4.74410105, -6.66392231, -5.65479326},
-    {4.76328945, -6.67888021, -5.66172361},
-    {4.72848701, -6.6768384, -5.63919115},
-    {4.74271154, -6.66995478, -5.63666534},
-    {4.74985313, -6.67474651, -5.65780735},
-    {4.73348808, -6.66441298, -5.65334082},
-    {4.7364645, -6.66980362, -5.67731237},
-    {4.73847437, -6.66624689, -5.65825653},
-    {4.71451235, -6.69523382, -5.6485672},
-    {4.71801567, -6.68013763, -5.65750885},
-    {4.69703817, -6.67190027, -5.66391182},
-    {4.6995225, -6.6858511, -5.65984631},
-    {4.68778896, -6.68472195, -5.66285992},
-    {4.67918539, -6.68447971, -5.66718769},
-    {4.67658329, -6.68439817, -5.6620121},
-    {4.68230915, -6.68777466, -5.65631866},
-    {4.66267109, -6.67893887, -5.66495419},
-    {4.66936064, -6.69755125, -5.66347456},
-    {4.66400909, -6.71323299, -5.67031384},
-    {4.66296864, -6.69870663, -5.65929604},
-    {4.66071367, -6.72592974, -5.66576576},
-    {4.67095709, -6.70952082, -5.67543983},
-    {4.63419199, -6.71579313, -5.66286039},
-    {4.64838791, -6.72057152, -5.67284441},
-    {4.64657593, -6.72331619, -5.65421629},
-    {4.64273453, -6.7231164, -5.65959406},
-    {4.65584612, -6.74840975, -5.64856625},
-    {4.63291502, -6.73195171, -5.65334082},
-    {4.65344667, -6.74617815, -5.63592005},
-    {4.65880251, -6.76549625, -5.64738512},
-    {4.66807222, -6.76717091, -5.63342524},
-    {4.6928854, -6.76136208, -5.63212538},
-    {4.69093847, -6.76692438, -5.61822176},
-    {4.68558121, -6.7598052, -5.63443136},
-    {4.69201994, -6.76296091, -5.61884308},
-    {4.67872858, -6.78643799, -5.62566566},
-    {4.70255184, -6.77530289, -5.61090088},
-    {4.70299435, -6.76386786, -5.6284337},
-    {4.69173193, -6.7702198, -5.61494446},
-    {4.7042222, -6.78612804, -5.61183357},
-    {4.72289371, -6.78445244, -5.60974693},
-    {4.71325493, -6.78646183, -5.59944248},
-    {4.71875858, -6.78391695, -5.60792875},
-    {4.73482656, -6.77717686, -5.60703468},
-    {4.72590113, -6.77552891, -5.59810162},
-    {4.74107599, -6.77777672, -5.60465288},
-    {4.72560358, -6.78766012, -5.58827496},
-    {4.73631525, -6.80293369, -5.59646463},
-    {4.72679329, -6.79499817, -5.58351135},
-    {4.72441292, -6.78930759, -5.6086731},
-    {4.72779846, -6.80187702, -5.59545279},
-    {4.744349, -6.7960453, -5.59006166},
-    {4.72019434, -6.79478407, -5.61429214},
-    {4.74525547, -6.79447126, -5.59516573},
-    {4.7174201, -6.822402, -5.59035969},
-    {4.72664452, -6.78983831, -5.59508181},
-    {4.72808695, -6.79795647, -5.60483742},
-    {4.71051884, -6.77700758, -5.6064539},
-    {4.70615768, -6.78285408, -5.60931444},
-    {4.71174717, -6.78303623, -5.59292936},
-    {4.71741152, -6.78067636, -5.6188426},
-    {4.69822836, -6.77283525, -5.63547516},
-    {4.68320131, -6.78855801, -5.62222242},
-    {4.67546558, -6.77822638, -5.62251997},
-    {4.68543339, -6.76474857, -5.61581993},
-    {4.67754841, -6.77867413, -5.61730909},
-    {4.69659138, -6.78316784, -5.61626673},
-    {4.66638947, -6.77987194, -5.63055992},
-    {4.66832447, -6.78017139, -5.62475348},
-    {4.66951418, -6.76894093, -5.62654114},
-    {4.67784548, -6.77508116, -5.6572113},
-    {4.66981173, -6.76998997, -5.63145304},
-    {4.64184141, -6.75007153, -5.6391964},
-    {4.65106535, -6.75546217, -5.65244675},
-    {4.64169264, -6.74752617, -5.65438271},
-    {4.64526463, -6.73764229, -5.65631866},
-    {4.66605186, -6.75439215, -5.67442846},
-    {4.64744186, -6.74161291, -5.65869188},
-    {4.62635946, -6.72367859, -5.65302277},
-    {4.62850952, -6.73233318, -5.65563583},
-    {4.6304183, -6.72041178, -5.68179274},
-    {4.63647604, -6.71939516, -5.65537119},
-    {4.62267399, -6.71934843, -5.66670179},
-    {4.64645386, -6.71997166, -5.64768314},
-    {4.62458372, -6.72461414, -5.65676498},
-    {4.61565733, -6.71877289, -5.67269564},
-    {4.63083267, -6.69391584, -5.66465569},
-    {4.64167023, -6.71271515, -5.67688227},
-    {4.62282753, -6.71285534, -5.67192793},
-    {4.63217115, -6.70484638, -5.68818092},
-    {4.63603926, -6.70005369, -5.67433405},
-    {4.64220953, -6.70814133, -5.67816114},
-    {4.64555073, -6.68961191, -5.68508434},
-    {4.65448761, -6.69571114, -5.67433357},
-    {4.66864872, -6.68483353, -5.66504431},
-    {4.65299988, -6.68163443, -5.67224932},
-    {4.67903614, -6.67878962, -5.66778278},
-    {4.63634253, -6.69755173, -5.67868996},
-    {4.6742754, -6.71213436, -5.67746067},
-    {4.69480562, -6.69121933, -5.68237448},
-    {4.66728306, -6.69945621, -5.68803263},
-    {4.69346762, -6.6972084, -5.69934845},
-    {4.6760602, -6.7160759, -5.67478085},
-    {4.71563482, -6.70200109, -5.65408468},
-    {4.7025423, -6.70858955, -5.66763449},
-    {4.70197439, -6.70371199, -5.66850948},
-    {4.69331837, -6.70605421, -5.68837261},
-    {4.72590065, -6.72206736, -5.68029022},
-    {4.72887659, -6.70739174, -5.66748476},
-    {4.72887516, -6.70394802, -5.67403603},
-    {4.70774508, -6.69412756, -5.65205002},
-    {4.72274971, -6.7083602, -5.66316795},
-    {4.68260574, -6.69616079, -5.67076063},
-    {4.71405077, -6.67822838, -5.6799202},
-    {4.68290424, -6.69046974, -5.67433405},
-    {4.71207333, -6.69572544, -5.67211914},
-    {4.69744492, -6.66660976, -5.68254375},
-    {4.69837666, -6.68403196, -5.69905043},
-    {4.71163988, -6.68541527, -5.68742418},
-    {4.6800766, -6.67789125, -5.68847942},
-    {4.66624117, -6.67489529, -5.67775822},
-    {4.69153357, -6.66935539, -5.6933918},
-    {4.68408537, -6.66464901, -5.69926167},
-    {4.68587923, -6.66291475, -5.71319437},
-    {4.65419006, -6.67579365, -5.69190311},
-    {4.66797829, -6.65627861, -5.70097637},
-    {4.66043806, -6.67729092, -5.71274805},
-    {4.66489697, -6.69877434, -5.71182299},
-    {4.65830326, -6.6722002, -5.69190788},
-    {4.68111849, -6.6600709, -5.69711447},
-    {4.67293596, -6.68552828, -5.69785881},
-    {4.66143465, -6.66377735, -5.69059992},
-    {4.69669724, -6.67575502, -5.70743227},
-    {4.65091753, -6.67908907, -5.68639421},
-    {4.64484453, -6.67612123, -5.70518208},
-    {4.66341448, -6.65917206, -5.7070899},
-    {4.68230915, -6.68043661, -5.69458246},
-    {4.65876436, -6.66787243, -5.70420361},
-    {4.65710735, -6.66653681, -5.6845355},
-    {4.64987612, -6.67624331, -5.69905043},
-    {4.66326618, -6.678339, -5.69726372},
-    {4.67268753, -6.67626667, -5.69622946},
-    {4.65599966, -6.69013214, -5.6945219},
-    {4.66386032, -6.67264891, -5.6993475},
-    {4.66460943, -6.67829895, -5.67832708},
-    {4.68691969, -6.67594385, -5.68922377},
-    {4.65983868, -6.6896677, -5.70097733},
-    {4.6620121, -6.69165945, -5.6822257},
-    {4.67366123, -6.67158175, -5.67822933},
-    {4.66534853, -6.7039485, -5.69190359},
-    {4.6785903, -6.68807411, -5.68669224},
-    {4.66475344, -6.70469618, -5.68058729},
-    {4.69605923, -6.69296551, -5.67471838},
-    {4.67695332, -6.6855278, -5.68103409},
-    {4.67239952, -6.70138836, -5.6833806},
-    {4.67427492, -6.6897707, -5.68365479},
-    {4.68495131, -6.69238567, -5.67962742},
-    {4.67665529, -6.70978832, -5.67269659},
-    {4.67978001, -6.70379829, -5.68192768},
-    {4.70031071, -6.70933962, -5.67269564},
-    {4.71971941, -6.7134409, -5.65580368},
-    {4.70314741, -6.68425798, -5.65486813},
-    {4.68736696, -6.70724249, -5.66376209},
-    {4.6864748, -6.71817493, -5.66525221},
-    {4.69554996, -6.70739126, -5.66271973},
-    {4.6924262, -6.72536135, -5.66286945},
-    {4.69721317, -6.72752714, -5.66129017},
-    {4.70001268, -6.71143484, -5.65482903},
-    {4.69004631, -6.72386503, -5.65631866},
-    {4.68558168, -6.72296619, -5.65334129},
-    {4.69270468, -6.71826601, -5.66408968},
-    {4.69331837, -6.71922302, -5.65602064},
-    {4.68148851, -6.70922995, -5.64858389},
-    {4.7060647, -6.72305775, -5.65287018},
-    {4.6820116, -6.71577883, -5.65870142},
-    {4.7096839, -6.71458054, -5.64976645},
-    {4.70774603, -6.72520351, -5.64829588},
-    {4.67725039, -6.72266674, -5.65750933},
-    {4.72158575, -6.72416401, -5.65974236},
-    {4.68930149, -6.71233463, -5.65617037},
-    {4.69629431, -6.72446489, -5.65616894},
-    {4.69049215, -6.73524523, -5.65631866},
-    {4.65954685, -6.73270082, -5.64693832},
-    {4.68336344, -6.72128248, -5.65176153},
-    {4.67964983, -6.72475815, -5.65763426},
-    {4.69837666, -6.73749256, -5.66971922},
-    {4.69063997, -6.72655964, -5.65095854},
-    {4.68052292, -6.73360014, -5.6497674},
-    {4.65686893, -6.72506332, -5.65066099},
-    {4.68216038, -6.71967316, -5.67046356},
-    {4.65805769, -6.7213192, -5.66182756},
-    {4.67990208, -6.73391628, -5.66461086},
-    {4.67995691, -6.73743486, -5.65609694},
-    {4.67918062, -6.72868919, -5.65609312},
-    {4.67918968, -6.72475863, -5.65440607},
-    {4.64065123, -6.72551203, -5.66569853},
-    {4.66475344, -6.72258949, -5.64815187},
-    {4.66951513, -6.71765375, -5.65912485},
-    {4.65790939, -6.72161913, -5.65393591},
-    {4.68333578, -6.70713663, -5.66347504},
-    {4.67115068, -6.71982145, -5.65185165},
-    {4.6611824, -6.72775745, -5.66808033},
-    {4.65350008, -6.72796345, -5.66533327},
-    {4.65415668, -6.72537661, -5.65932465},
-    {4.67769718, -6.71068573, -5.66004181},
-    {4.67367983, -6.72656012, -5.65200043},
-    {4.66683626, -6.71832323, -5.65363789},
-    {4.6672821, -6.72940588, -5.65542507},
-    {4.68394566, -6.72566271, -5.63428211},
-    {4.6781435, -6.73659468, -5.64410973},
-    {4.68610573, -6.72331524, -5.65638208},
-    {4.66533089, -6.72070265, -5.64540768},
-    {4.68697071, -6.72635174, -5.6558609},
-    {4.66564608, -6.73240089, -5.65229797},
-    {4.68134451, -6.73711109, -5.65984631},
-    {4.66905451, -6.72954988, -5.66270638},
-    {4.67975855, -6.73435211, -5.6533494},
-    {4.70343542, -6.72596169, -5.65006495},
-    {4.67397785, -6.72476339, -5.64366293},
-    {4.67873812, -6.72925711, -5.65438175},
-    {4.70009947, -6.73275471, -5.64093256},
-    {4.69347143, -6.73820877, -5.65594435},
-    {4.70700645, -6.73509693, -5.64366245},
-    {4.68751621, -6.72521257, -5.63383579},
-    {4.68751621, -6.71532965, -5.65423441},
-    {4.70904255, -6.74509907, -5.64093304},
-    {4.67857409, -6.71146393, -5.65317631},
-    {4.7056675, -6.71847439, -5.63249588},
-    {4.68293095, -6.71808815, -5.63255882},
-    {4.71027851, -6.71143532, -5.6388979},
-    {4.68871164, -6.71424627, -5.64103556},
-    {4.7305131, -6.72341585, -5.64857531},
-    {4.73154926, -6.74088717, -5.64627409},
-    {4.71986437, -6.69819307, -5.65638161},
-    {4.71973276, -6.70280695, -5.63872957},
-    {4.69865561, -6.72505856, -5.64179897},
-    {4.71973324, -6.70172596, -5.65394545},
-    {4.72843027, -6.69601107, -5.63577127},
-    {4.7235198, -6.71128607, -5.62996483},
-    {4.71019697, -6.72723579, -5.64959526},
-    {4.70191813, -6.70759916, -5.64072752},
-    {4.7052207, -6.71038723, -5.64559793},
-    {4.72337151, -6.70679283, -5.64246941},
-    {4.70384979, -6.71039152, -5.62404013},
-    {4.70269632, -6.71460295, -5.64151096},
-    {4.70966387, -6.70318937, -5.64792109},
-    {4.70120382, -6.71038675, -5.64946985},
-    {4.70566654, -6.70364761, -5.63234663},
-    {4.7034359, -6.70499516, -5.65944433},
-    {4.7052207, -6.7060442, -5.63979149},
-    {4.71861029, -6.72221804, -5.62683821},
-    {4.69735813, -6.70124292, -5.64266586},
-    {4.70069075, -6.71285582, -5.64072847},
-    {4.70009899, -6.69732237, -5.63458061},
-    {4.68349838, -6.69091988, -5.63428259},
-    {4.69629383, -6.71173477, -5.63785601},
-    {4.6943593, -6.71113634, -5.6499157},
-    {4.70298481, -6.71736193, -5.64035511},
-    {4.68067312, -6.70319986, -5.65601969},
-    {4.69147491, -6.71579409, -5.63873053},
-    {4.70923853, -6.71203375, -5.66123152},
-    {4.70774984, -6.71098614, -5.63964319},
-    {4.70700645, -6.71053696, -5.646492},
-    {4.69435978, -6.71682787, -5.6518507},
-    {4.69049168, -6.72251749, -5.64723587},
-    {4.69748449, -6.72371531, -5.64544964},
-    {4.69274092, -6.73348093, -5.64945126},
-    {4.70789909, -6.71817398, -5.63785553},
-    {4.69750214, -6.71765232, -5.63587999},
-    {4.70585489, -6.71772575, -5.65157366},
-    {4.69187593, -6.72665548, -5.65551519},
-    {4.68594694, -6.73156023, -5.64626074},
-    {4.69078922, -6.73374844, -5.64291906},
-    {4.68528509, -6.71997213, -5.63934422},
-    {4.70659161, -6.73391628, -5.63024807},
-    {4.67665529, -6.72686052, -5.6418767},
-    {4.72145081, -6.74132252, -5.63385773},
-    {4.70806122, -6.71934986, -5.61091137},
-    {4.71756935, -6.73914051, -5.62921953},
-    {4.70998144, -6.74123716, -5.64128017},
-    {4.72000742, -6.7356596, -5.63674593},
-    {4.70360804, -6.73511505, -5.63073778},
-    {4.71308327, -6.7555542, -5.63790131},
-    {4.71312952, -6.7485652, -5.62720394},
-    {4.70745325, -6.74542904, -5.6391964},
-    {4.68513584, -6.74123573, -5.62073278},
-    {4.68495035, -6.73987055, -5.64295435},
-    {4.70358419, -6.74093676, -5.63383532},
-    {4.68602848, -6.73359919, -5.64887333},
-    {4.67561483, -6.72536278, -5.6330905},
-    {4.69900084, -6.74315453, -5.6391902},
-    {4.6979351, -6.75076199, -5.6348691},
-    {4.69688892, -6.75651169, -5.63636684},
-    {4.70403004, -6.74602747, -5.62549686},
-    {4.69435978, -6.7481246, -5.63919592},
-    {4.69242573, -6.74018717, -5.64306736},
-    {4.69153357, -6.75291729, -5.64351273},
-    {4.69108725, -6.7446804, -5.6278801},
-    {4.68052387, -6.74587965, -5.63725996},
-    {4.67977953, -6.7346468, -5.63547373},
-    {4.6930213, -6.74063778, -5.6406846},
-    {4.66648436, -6.72752857, -5.63342571},
-    {4.69132185, -6.7476368, -5.63919067},
-    {4.6800766, -6.74932241, -5.63458109},
-    {4.67412615, -6.74348211, -5.64663982},
-    {4.68177652, -6.75468206, -5.65493679},
-    {4.68763638, -6.72537661, -5.64687586},
-    {4.68812466, -6.74277544, -5.65075064},
-    {4.66260386, -6.73588943, -5.64318705},
-    {4.67963076, -6.73689365, -5.65631819},
-    {4.68509483, -6.73362684, -5.6487298},
-    {4.67695332, -6.73734331, -5.64827871},
-    {4.69004583, -6.7386899, -5.63443089},
-    {4.66281986, -6.74842453, -5.64038706},
-    {4.68321943, -6.74887371, -5.64569616},
-    {4.68871164, -6.74933767, -5.64349413},
-    {4.66311646, -6.73060369, -5.64649105},
-    {4.68141651, -6.72416449, -5.65572357},
-    {4.6904912, -6.73929071, -5.66138077},
-    {4.66728306, -6.74183512, -5.66301823},
-    {4.68870592, -6.72790766, -5.67314291},
-    {4.65719271, -6.7349205, -5.66134501},
-    {4.64491653, -6.72139931, -5.65490866},
-    {4.67340946, -6.71779823, -5.66143465},
-    {4.66147995, -6.71652699, -5.65214968},
-    {4.65880251, -6.70858955, -5.68952131},
-    {4.63511419, -6.71842146, -5.68176413},
-    {4.64195871, -6.72622013, -5.67558384},
-    {4.65880251, -6.711586, -5.64247179},
-    {4.64809084, -6.73479652, -5.6826725},
-    {4.6598444, -6.73734426, -5.66316843},
-    {4.65133667, -6.71707153, -5.67601728},
-    {4.68241453, -6.7256856, -5.66823864},
-    {4.67010975, -6.73374844, -5.66852856},
-    {4.6556778, -6.71847486, -5.67478037},
-    {4.65627241, -6.7235651, -5.68847799},
-    {4.68677235, -6.72131872, -5.67224979},
-    {4.6512146, -6.71458006, -5.68579865},
-    {4.65270233, -6.70933867, -5.67522812},
-    {4.66906834, -6.74078655, -5.65721178},
-    {4.64239168, -6.71620131, -5.68670034},
-    {4.6673646, -6.71811152, -5.68560648},
-    {4.65552902, -6.73090315, -5.68892527},
-    {4.63960981, -6.72221851, -5.67210054},
-    {4.65422249, -6.72534943, -5.69622946},
-    {4.66981173, -6.71038723, -5.68609524},
-    {4.67535019, -6.70713663, -5.68068838},
-    {4.66743088, -6.71083641, -5.69607162},
-    {4.65359449, -6.70694351, -5.68207645},
-    {4.6500392, -6.69615984, -5.68366957},
-    {4.64199066, -6.69810772, -5.71736383},
-    {4.66056967, -6.69761324, -5.69262123},
-    {4.64048815, -6.69322443, -5.70082283},
-    {4.65523243, -6.71218538, -5.68401146},
-    {4.64946079, -6.69267607, -5.69579697},
-    {4.64755297, -6.68193817, -5.69943857},
-    {4.62964201, -6.696311, -5.70634604},
-    {4.64571047, -6.69750834, -5.69473219},
-    {4.64383411, -6.68236542, -5.70922375},
-    {4.6377244, -6.67467356, -5.71434736},
-    {4.64719725, -6.69166803, -5.69100952},
-    {4.6513629, -6.6834321, -5.69473219},
-    {4.64340162, -6.67292643, -5.70908022},
-    {4.63053417, -6.68987131, -5.70173025},
-    {4.65799665, -6.68580341, -5.70389605},
-    {4.6534462, -6.68088627, -5.70292091},
-    {4.65939713, -6.67025232, -5.69443369},
-    {4.66720629, -6.67975187, -5.69146633},
-    {4.68087864, -6.69306898, -5.69728804},
-    {4.64138174, -6.6785903, -5.68973303},
-    {4.66817474, -6.67115068, -5.72406435},
-    {4.6598444, -6.65947056, -5.69979477},
-    {4.66311741, -6.65737438, -5.69503021},
-    {4.63529539, -6.66171789, -5.69324255},
-    {4.67858934, -6.66561079, -5.70158148},
-    {4.66415787, -6.69436312, -5.70634556},
-    {4.66638994, -6.67070198, -5.67135715},
-    {4.66879272, -6.67495966, -5.68583441},
-    {4.67888308, -6.69214058, -5.69375229},
-    {4.6651988, -6.69301605, -5.70024157},
-    {4.67948198, -6.68957186, -5.68118286},
-    {4.65624237, -6.68221998, -5.68496799},
-    {4.66832399, -6.69870663, -5.68118286},
-    {4.68133926, -6.70883608, -5.68529987},
-    {4.68290472, -6.72251701, -5.67046356},
-    {4.67457342, -6.70155144, -5.68699026},
-    {4.69389534, -6.70095253, -5.66663218},
-    {4.68974829, -6.70948839, -5.67865229},
-    {4.68717527, -6.71471119, -5.67146587},
-    {4.7074523, -6.71278286, -5.67775869},
-    {4.70082045, -6.71315145, -5.66258955},
-    {4.68899059, -6.70647097, -5.65782452},
-    {4.68441105, -6.64916754, -5.6484127},
-    {4.69138479, -6.681036, -5.65810537},
-    {4.67665529, -6.73584461, -5.68698978},
-    {4.67650652, -6.76864195, -5.67924738},
-    {4.71380424, -6.74335527, -5.66157818},
-    {4.70499039, -6.70991898, -5.61690521},
-    {4.7090888, -6.72042084, -5.64023876},
-    {4.73304176, -6.7141304, -5.65483046},
-    {4.71279478, -6.72622061, -5.65349483},
-    {4.70453024, -6.73928976, -5.67776728},
-    {4.72039509, -6.74617863, -5.64827824},
-    {4.71741962, -6.74213552, -5.61730957},
-    {4.73328066, -6.72781801, -5.66085815},
-    {4.72902441, -6.70424747, -5.66361523},
-    {4.73708773, -6.73140669, -5.64533854},
-    {4.72709036, -6.71517944, -5.6438117},
-    {4.70328665, -6.69136906, -5.65557337},
-    {4.71668863, -6.71852398, -5.64569712},
-    {4.70120382, -6.72027159, -5.6415782},
-    {4.67586231, -6.72593069, -5.65089512},
-    {4.69837666, -6.74033737, -5.64887381},
-    {4.71340322, -6.73509693, -5.65051174},
-    {4.67627192, -6.72862434, -5.64410877},
-    {4.69750166, -6.73072243, -5.64815235},
-    {4.66966724, -6.72568655, -5.65117931},
-    {4.68201113, -6.72461319, -5.63681364},
-    {4.69733524, -6.73165131, -5.64574766},
-    {4.68677282, -6.72910643, -5.64619398},
-    {4.69525194, -6.73180199, -5.64842749},
-    {4.68711424, -6.72476768, -5.65854645},
-    {4.70849371, -6.73314953, -5.65572262},
-    {4.70923805, -6.7271595, -5.65587091},
-    {4.70558167, -6.73958015, -5.65378284},
-    {4.70760059, -6.72603178, -5.65617943},
-    {4.70168591, -6.72142744, -5.65450335},
-    {4.69584751, -6.71607733, -5.66793251},
-    {4.70893955, -6.74168491, -5.65348864},
-    {4.6781435, -6.70724154, -5.6607852},
-    {4.67531681, -6.70319939, -5.64783192},
-    {4.6907897, -6.71458054, -5.66361332},
-    {4.6927228, -6.71502924, -5.66956902},
-    {4.67873812, -6.71937323, -5.66167784},
-    {4.66807175, -6.71257019, -5.67486191},
-    {4.67591095, -6.71562862, -5.6712079},
-    {4.65415621, -6.70203495, -5.67285109},
-    {4.66862202, -6.69301558, -5.65914679},
-    {4.6808219, -6.68867302, -5.67046261},
-    {4.65865326, -6.70619392, -5.68326664},
-    {4.66222429, -6.69960499, -5.67150497},
-    {4.67643929, -6.69107771, -5.67991543},
-    {4.68809748, -6.70667219, -5.68545294},
-    {4.66864872, -6.70719767, -5.68597984},
-    {4.66534853, -6.69586182, -5.6852026},
-    {4.66088486, -6.69526243, -5.6768651},
-    {4.67657852, -6.69523287, -5.69713306},
-    {4.68567181, -6.69557905, -5.68727875},
-    {4.67620897, -6.69226742, -5.69919872},
-    {4.68528461, -6.67878962, -5.66435862},
-    {4.68513536, -6.66590977, -5.67061138},
-    {4.67799425, -6.65452862, -5.66986752},
-    {4.6943593, -6.65767384, -5.68550062},
-    {4.7107749, -6.66392326, -5.67962742},
-    {4.69941854, -6.66875648, -5.64604521},
-    {4.70882988, -6.66864538, -5.65963173},
-    {4.72634649, -6.65692472, -5.66242266},
-    {4.71786642, -6.66606045, -5.6709094},
-    {4.71726751, -6.6663909, -5.67471743},
-    {4.72277498, -6.69121933, -5.6662941},
-    {4.70938587, -6.68313074, -5.67254782},
-    {4.71666241, -6.69214153, -5.65302277},
-    {4.73111582, -6.69557905, -5.66345644},
-    {4.76089144, -6.69523335, -5.65179396},
-    {4.75372171, -6.69466352, -5.65036249},
-    {4.75982141, -6.71817446, -5.63368797},
-    {4.76862669, -6.71286058, -5.65031672},
-    {4.74972725, -6.70603466, -5.65031815},
-    {4.75744152, -6.71892405, -5.65706301},
-    {4.73274374, -6.70245075, -5.65140438},
-    {4.75567007, -6.70435238, -5.67115974},
-    {4.74390221, -6.72775841, -5.66376257},
-    {4.71206427, -6.70784235, -5.66942072},
-    {4.70715475, -6.71338224, -5.67046356},
-    {4.68379784, -6.67594433, -5.69860315},
-    {4.66222382, -6.67908955, -5.67597103},
-    {4.69569874, -6.68283272, -5.6874361},
-    {4.6952529, -6.68178463, -5.70857906},
-    {4.69389677, -6.68163872, -5.68121481},
-    {4.66214275, -6.68935966, -5.70251274},
-    {4.69450855, -6.68313217, -5.69354105},
-    {4.67665577, -6.69750738, -5.6889267},
-    {4.65970325, -6.70313168, -5.6845355},
-    {4.67546558, -6.70873928, -5.69607306},
-    {4.68763638, -6.69585133, -5.69421339},
-    {4.6891346, -6.72607374, -5.69608593},
-    {4.67829227, -6.71562767, -5.68430948},
-    {4.66177797, -6.7118845, -5.66956949},
-    {4.67754841, -6.71922159, -5.70247507},
-    {4.66772938, -6.72251701, -5.67463255},
-    {4.68454123, -6.74797583, -5.69249964},
-    {4.65552902, -6.75141954, -5.71453381},
-    {4.66401005, -6.73180294, -5.69756079},
-    {4.64094877, -6.75261784, -5.69830561},
-    {4.63856888, -6.73030472, -5.70083666},
-    {4.64808989, -6.72656107, -5.72034168},
-    {4.62919569, -6.72925663, -5.71200323},
-    {4.62681198, -6.72767305, -5.70951128},
-    {4.63172483, -6.7151804, -5.71111012},
-    {4.62175226, -6.71934891, -5.70650864},
-    {4.62071609, -6.70334864, -5.70381498},
-    {4.60613585, -6.69900608, -5.70872784},
-    {4.60848856, -6.6947093, -5.7067709},
-    {4.60040569, -6.6955409, -5.71834373},
-    {4.60792065, -6.6775918, -5.7097702},
-    {4.63517809, -6.68076754, -5.68771124},
-    {4.62175703, -6.69211674, -5.71944857},
-    {4.6259222, -6.68717623, -5.72063923},
-    {4.61937666, -6.68882275, -5.70247507},
-    {4.63514757, -6.68373108, -5.73180628},
-    {4.64199114, -6.64793968, -5.71140766},
-    {4.6309948, -6.65245056, -5.71066904},
-    {4.61192369, -6.65256834, -5.71803665},
-    {4.63142776, -6.66231728, -5.73895311},
-    {4.6224823, -6.70777845, -5.71817541},
-    {4.62098455, -6.71873045, -5.71465492},
-    {4.63514662, -6.70334911, -5.70500612},
-    {4.64065218, -6.72356415, -5.70917416},
-    {4.6488843, -6.72346163, -5.69218731},
-    {4.64432764, -6.73913574, -5.70235872},
-    {4.64426804, -6.74350166, -5.70965672},
-    {4.67489052, -6.73140574, -5.69083261},
-    {4.64764404, -6.73150206, -5.67373943},
-    {4.69019365, -6.71517897, -5.69711351},
-    {4.72462463, -6.71852398, -5.68251371},
-    {4.71206474, -6.7271595, -5.68014145},
-    {4.72634602, -6.72176933, -5.6689744},
-    {4.73021507, -6.74078655, -5.67388725},
-    {4.73809958, -6.71562862, -5.66495466},
-    {4.7465539, -6.73783827, -5.66432285},
-    {4.76319599, -6.7150197, -5.65701818},
-    {4.72515631, -6.70050335, -5.65229893},
-    {4.73991728, -6.73827267, -5.67052937},
-    {4.74777031, -6.7250638, -5.65110683},
-    {4.73438025, -6.70993853, -5.62892199},
-    {4.75357342, -6.66635895, -5.65423393},
-    {4.72311163, -6.72012138, -5.67546225},
-    {4.70358467, -6.71787548, -5.67433453},
-    {4.67600632, -6.72549391, -5.69623041},
-    {4.65419006, -6.72641134, -5.66197538},
-    {4.65907145, -6.70914602, -5.67838335},
-    {4.6533556, -6.71881485, -5.68684578},
-    {4.68751621, -6.71413088, -5.67954493},
-    {4.67457247, -6.71997166, -5.68252277},
-    {4.70976496, -6.71910381, -5.69709778},
-    {4.67713213, -6.72235823, -5.68174934},
-    {4.71380472, -6.73594999, -5.66432238},
-    {4.6986742, -6.74707747, -5.66882563},
-    {4.70655966, -6.73809195, -5.65244675},
-    {4.75833368, -6.74033737, -5.67582321},
-    {4.76651669, -6.7702899, -5.65408516},
-    {4.77752638, -6.79829121, -5.67224979},
-    {4.75565481, -6.81296825, -5.67180252},
-    {4.74836588, -6.80053854, -5.64708662},
-    {4.74405146, -6.76834297, -5.63070822},
-    {4.74777031, -6.77418184, -5.66703749},
-    {4.75405502, -6.79606915, -5.7253952},
-    {4.73378563, -6.80937386, -5.63666534},
-    {4.75520945, -6.77358246, -5.63696241},
-    {4.75060272, -6.76618671, -5.64856672},
-    {4.77633619, -6.68822241, -5.68833017},
-    {4.76755857, -6.74602795, -5.6878829},
-    {4.73501205, -6.7135849, -5.66966438},
-    {4.72940874, -6.70636368, -5.65102577},
-    {4.72203207, -6.69331646, -5.69890118},
-    {4.72563553, -6.69267559, -5.72553921},
-    {4.70893955, -6.68777418, -5.69949675},
-    {4.71459341, -6.68957233, -5.7204895},
-    {4.71625757, -6.65564537, -5.72178555},
-    {4.72802639, -6.61345863, -5.7390914},
-    {4.71310616, -6.62787342, -5.70723867},
-    {4.70298862, -6.56902027, -5.71527958},
-    {4.76339197, -6.43723679, -5.94233799},
-    {4.67368031, -6.50672388, -5.90764523},
-    {4.63782454, -6.52244711, -5.72391415},
-    {4.62785721, -6.52439451, -5.76054096},
-    {4.65508747, -6.54005527, -5.70792627},
-    {4.68640757, -6.58006859, -5.75261736},
-    {4.70024347, -6.60351276, -5.72452879},
-    {4.72441244, -6.56497717, -5.7376132},
-    {4.72069263, -6.49219704, -5.77200747},
-    {4.71620083, -6.45099211, -5.79657412},
-    {4.69389486, -6.49315166, -5.81158876},
-    {4.72710466, -6.47247791, -5.83484316},
-    {4.72318268, -6.51696444, -5.81057787},
-    {4.72947121, -6.50357914, -5.79612637},
-    {4.77574062, -6.44906902, -5.71334362},
-    {4.84883928, -6.35810041, -5.55199575},
-    {4.68989706, -6.39755392, -5.77900362},
-    {4.75877953, -6.4191184, -5.982687},
-    {4.91615629, -6.46629477, -5.86727285},
-    {4.97331619, -6.47467613, -5.71408844},
-    {4.93179369, -6.46831894, -5.57596207},
-    {4.93474054, -6.46536684, -5.50855064},
-    {4.97257185, -6.5335288, -5.41615582},
-    {4.9454937, -6.55838823, -5.36240721},
-    {4.92689705, -6.56108284, -5.3500495},
-    {4.96394205, -6.56857109, -5.37238407},
-    {5.03552246, -6.48124218, -5.58231449},
-    {5.02857399, -6.43630505, -5.61629057},
-    {5.01979733, -6.50084639, -5.50998163},
-    {4.95703983, -6.56720972, -5.53178167},
-    {4.97928572, -6.5492034, -5.61456919},
-    {4.93344307, -6.58249664, -5.59840059},
-    {4.89716959, -6.57171059, -5.56383467},
-    {4.89044762, -6.61065197, -5.60822678},
-    {4.89223194, -6.63386297, -5.57844687},
-    {4.85374498, -6.6258769, -5.59935188},
-    {4.89050913, -6.61191225, -5.63396549},
-    {4.90949106, -6.61259794, -5.65765905},
-    {4.93017054, -6.60421324, -5.58336115},
-    {4.88245392, -6.59944677, -5.50969172},
-    {4.88835907, -6.63262701, -5.49379683},
-    {4.90562201, -6.61843872, -5.54762697},
-    {4.90337372, -6.59552622, -5.62057638},
-    {4.87884331, -6.58953667, -5.58202219},
-    {4.87929821, -6.57403898, -5.54881954},
-    {4.87973595, -6.56482792, -5.5750246},
-    {4.86411381, -6.54041767, -5.588871},
-    {4.88330555, -6.6265254, -5.57010984},
-    {4.87048006, -6.58812141, -5.63919973},
-    {4.91306067, -6.60031843, -5.63681316},
-    {4.88613272, -6.64524412, -5.60003901},
-    {4.88628149, -6.68807364, -5.52246428},
-    {4.85489845, -6.69194937, -5.47504091},
-    {4.8690238, -6.62697411, -5.43640661},
-    {4.76473045, -6.65906143, -5.64165068},
-    {4.68587923, -6.75755882, -5.63085794},
-    {4.82081985, -6.83573055, -5.50891495},
-    {4.92883205, -6.85804319, -5.39322853},
-    {4.86889219, -6.88624668, -5.33571529},
-    {4.83412457, -6.9125309, -5.30842876},
-    {4.87756348, -6.89822674, -5.34934473},
-    {4.85935354, -6.85444975, -5.40290642},
-    {4.79892302, -6.81305838, -5.47042036},
-    {4.78208494, -6.79246664, -5.50040579},
-    {4.76400995, -6.835567, -5.44515419},
-    {4.79406404, -6.87207651, -5.38667202},
-    {4.78593874, -6.91311216, -5.32041168},
-    {4.79252863, -6.95941591, -5.27293825},
-    {4.79704714, -6.9829607, -5.27218866},
-    {4.81650543, -6.9612236, -5.33917952},
-    {4.82959843, -6.96526623, -5.39337683},
-    {4.8337636, -6.99342012, -5.34707165},
-    {4.85236073, -7.01558447, -5.30702019},
-    {4.85935211, -7.0143857, -5.33084297},
-    {4.84700489, -6.98428535, -5.31803751},
-    {4.85697317, -6.98533344, -5.30448961},
-    {4.81308413, -7.00435114, -5.28900433},
-    {4.87780142, -7.01064205, -5.35496283},
-    {4.86038113, -7.02913857, -5.31449175},
-    {4.86099052, -7.07862997, -5.30538273},
-    {4.86025524, -7.02696896, -5.30029535},
-    {4.86571836, -6.94651127, -5.29947662},
-    {4.86813116, -6.96107388, -5.27560472},
-    {4.87423086, -7.00146341, -5.29261255},
-    {4.85764027, -6.96393585, -5.32012224},
-    {4.8545723, -6.90515709, -5.29998922},
-    {4.8462429, -6.92966652, -5.29860973},
-    {4.84658766, -6.88598824, -5.33042002},
-    {4.85533667, -6.8983264, -5.33530998},
-    {4.81551409, -6.87956715, -5.24259043},
-    {4.83986282, -6.83153772, -5.30270195},
-    {4.85712194, -6.86044025, -5.34037256},
-    {4.82915163, -6.99761343, -5.29778862},
-    {4.84655809, -7.04463482, -5.31803751},
-    {4.87869406, -6.88425016, -5.30999756},
-    {4.83614397, -6.83737755, -5.28349543},
-    {4.85726929, -6.82509708, -5.30314875},
-    {4.86039448, -6.7897563, -5.31282663},
-    {4.86500692, -6.81551456, -5.29496002},
-    {4.84596348, -6.80712795, -5.30463696},
-    {4.82721758, -6.82794285, -5.29927778},
-    {4.80787754, -6.86029053, -5.33694792},
-    {4.78154278, -6.84531355, -5.32577944},
-    {4.79493237, -6.84561348, -5.32086706},
-    {4.78954554, -6.88465023, -5.32488585},
-    {4.8001399, -6.87885857, -5.31610346},
-    {4.82124758, -6.9111867, -5.35147715},
-    {4.81189299, -6.95059109, -5.32012272},
-    {4.8140707, -6.97250557, -5.29485655},
-    {4.81233931, -6.95086718, -5.3053956},
-    {4.83721924, -6.9728651, -5.32842255},
-    {4.82751513, -6.98937654, -5.33411837},
-    {4.84149981, -6.99626541, -5.30210686},
-    {4.83019209, -6.97829485, -5.30240536},
-    {4.83316851, -6.97155523, -5.28051805},
-    {4.8059926, -6.97003651, -5.28518248},
-    {4.82431936, -6.97673035, -5.30121756},
-    {4.79582548, -6.99177265, -5.31163502},
-    {4.79612303, -6.99761248, -5.32831097},
-    {4.78979683, -6.98129082, -5.30709076},
-    {4.77028608, -6.96691465, -5.33536959},
-    {4.75788736, -6.95867777, -5.34230757},
-    {4.73472309, -6.97613382, -5.35347366},
-    {4.74000645, -6.98074913, -5.35547161},
-    {4.7127943, -7.01911879, -5.3647356},
-    {4.7241869, -6.99373388, -5.37391567},
-    {4.71568108, -6.9958849, -5.34726477},
-    {4.72142315, -6.96467209, -5.35055351},
-    {4.73227072, -6.97439241, -5.3576622},
-    {4.71370125, -6.94549942, -5.34096813},
-    {4.71608114, -6.94519901, -5.34617853},
-    {4.72203207, -6.94924259, -5.34290266},
-    {4.72277594, -6.95118999, -5.34811401},
-    {4.75246859, -6.9658246, -5.33095121},
-    {4.75198412, -6.9643631, -5.34010267},
-    {4.77767467, -6.96137285, -5.32310009},
-    {4.77529526, -6.93456697, -5.32637596},
-    {4.7654748, -6.89518213, -5.31357098},
-    {4.76112366, -6.88363266, -5.31362486},
-    {4.77261591, -6.90791082, -5.33337355},
-    {4.76636744, -6.90237045, -5.31059361},
-    {4.77618742, -6.88754511, -5.32101631},
-    {4.77574015, -6.88170385, -5.33754253},
-    {4.77439737, -6.87492037, -5.32069969},
-    {4.78345728, -6.86675882, -5.30837011},
-    {4.78794003, -6.90536547, -5.33754253},
-    {4.79069901, -6.89568615, -5.33788157},
-    {4.79478407, -6.9207902, -5.31952763},
-    {4.80504942, -6.91854429, -5.32414198},
-    {4.82201004, -6.91090584, -5.32458973},
-    {4.82424259, -6.90686178, -5.32116461},
-    {4.84465551, -6.90033293, -5.3111701},
-    {4.84774876, -6.89353466, -5.32295084},
-    {4.85411263, -6.89526367, -5.32780695},
-    {4.86753511, -6.88170576, -5.30508471},
-    {4.83325911, -6.88218069, -5.32142162},
-    {4.83307266, -6.86651134, -5.33349514},
-    {4.83465624, -6.90491629, -5.34781599},
-    {4.8215642, -6.89473295, -5.34751892},
-    {4.82575607, -6.88581133, -5.34625578},
-    {4.84612751, -6.88181686, -5.33303308},
-    {4.8276639, -6.87646341, -5.35079384},
-    {4.82806492, -6.89612246, -5.34899759},
-    {4.80118227, -6.8909893, -5.33858442},
-    {4.81219101, -6.90281868, -5.33218288},
-    {4.8347621, -6.9093318, -5.33380079},
-    {4.82364702, -6.90057325, -5.34677362},
-    {4.82602692, -6.88889265, -5.35287809},
-    {4.81580162, -6.89205503, -5.34914255},
-    {4.81839848, -6.86519098, -5.34336662},
-    {4.81633282, -6.89418173, -5.35685492},
-    {4.80400801, -6.86283493, -5.36672449},
-    {4.80238533, -6.88639259, -5.34639835},
-    {4.78749514, -6.86493206, -5.36255646},
-    {4.7773242, -6.88629818, -5.35301304},
-    {4.79195786, -6.87930775, -5.36062002},
-    {4.78124571, -6.86972475, -5.35436726},
-    {4.73557091, -6.87212133, -5.35645199},
-    {4.7400341, -6.8894906, -5.35496283},
-    {4.7257514, -6.90236998, -5.37029886},
-    {4.70462608, -6.90521622, -5.36136484},
-    {4.69144249, -6.93097162, -5.36401415},
-    {4.68639278, -6.92559958, -5.35795021},
-    {4.66935587, -6.91452074, -5.36475039},
-    {4.69101, -6.91151476, -5.37570858},
-    {4.7154336, -6.87377739, -5.49825382},
-    {4.71553516, -6.85284758, -5.53871298},
-    {4.68959856, -6.92063999, -5.380126},
-    {4.66821575, -6.9974823, -5.21472597},
-    {4.65661383, -7.0022378, -5.14060831},
-};
-
-const float GYRO_DATA[IMU_DATA_SIZE][MOTION_SENSOR_AXIS_NUM] = {
-    {0.0134358415, 0.00595300971, 0.000731654873},
-    {0.0463735685, 0.0217599906, 0.0077480115},
-    {0.187150612, -0.00544426497, 0.0192549434},
-    {0.138911277, -0.00840414315, 0.021566309},
-    {0.118940406, -0.0400315821, 0.0142830163},
-    {0.0420168974, -0.0521038882, 0.0181907173},
-    {-0.114458971, -0.025989553, 0.0108046355},
-    {0.0317549482, 0.0247343481, -0.0115206884},
-    {-0.0828869566, 0.0332039446, -0.0186711792},
-    {-0.141902566, 0.00386180496, -0.0237592775},
-    {-0.158656061, 0.00145656988, -0.0318943784},
-    {-0.104235962, -0.00570477918, -0.0297004152},
-    {-0.185461238, 0.000292573124, 0.034536548},
-    {-0.304729015, 0.0536744148, -2.01906078e-05},
-    {-0.944312692, 0.0363321193, -0.0400524363},
-    {-0.454091966, 0.0101457238, -0.0501786992},
-    {-0.396595657, -0.0260738228, -0.0647147745},
-    {-0.291883796, -0.0107155051, 0.0370973423},
-    {-0.0755134672, 0.0145764705, 0.0838899985},
-    {-0.25969097, 0.0311551001, 0.0659644529},
-    {-0.149460495, 0.00859020837, 0.0503835306},
-    {-0.0215040408, 0.0110013373, 0.0412212163},
-    {0.0155216185, 0.00924274884, 0.0334435999},
-    {0.0306907296, 0.00880530104, 0.025967503},
-    {0.0406699888, 0.00794169307, 0.0202360265},
-    {0.058912985, 0.00116430921, 0.0154485237},
-    {0.0742928386, -0.00260078884, 0.00927783456},
-    {0.0958144441, -0.00835962035, 0.00547258649},
-    {0.126862153, -0.0166856479, -6.33625314e-05},
-    {0.146294326, -0.019811308, 0.000231918413},
-    {0.158898741, -0.0224718694, -0.00457372237},
-    {0.158117205, -0.0246169511, -0.00558806211},
-    {0.14817889, -0.025425192, -0.0111248549},
-    {0.133800417, -0.0238080528, -0.0169619694},
-    {0.118369147, -0.0227781534, -0.0229868572},
-    {0.102207586, -0.0222970173, -0.0281685796},
-    {0.0908881128, -0.0224386137, -0.0354196243},
-    {0.0752573013, -0.0241513476, -0.0448313653},
-    {0.06326814, -0.0260636285, -0.0477746129},
-    {0.0564338192, -0.0285745375, -0.051532656},
-    {0.0551700592, -0.0295722447, -0.0529959723},
-    {0.057316646, -0.0330843888, -0.0481147394},
-    {0.0595106296, -0.0352570564, -0.0462281629},
-    {0.0457583144, -0.0360906273, -0.0438170284},
-    {0.0348500051, -0.0342614911, -0.0439833105},
-    {0.035322655, -0.0358578265, -0.0379562303},
-    {0.0425490066, -0.0390338711, -0.0273381639},
-    {0.0404575691, -0.0406125076, -0.0192277394},
-    {0.0216968488, -0.0418773443, -0.0148501471},
-    {0.0307095051, -0.0437064841, -0.00540514803},
-    {0.0531081259, -0.0506602302, 0.00930504315},
-    {0.0625365004, -0.0555127375, 0.0171763804},
-    {0.0653628409, -0.0608671196, 0.0282675978},
-    {0.0556141958, -0.0634761974, 0.0348760933},
-    {0.0302272737, -0.0627627671, 0.0384941399},
-    {-0.000667502172, -0.0634631738, 0.0436182469},
-    {-0.0334545858, -0.0660680979, 0.0484192222},
-    {-0.0727531388, -0.0690151006, 0.0449626297},
-    {-0.122389279, -0.0686658844, 0.0449792594},
-    {-0.1727238, -0.0688488111, 0.0475899428},
-    {-0.2277309, -0.0632283688, 0.0480887964},
-    {-0.290071249, -0.0624301955, 0.0488703325},
-    {-0.356635183, -0.0573252439, 0.0489202216},
-    {-0.448980391, -0.046113085, 0.0488426238},
-    {-0.53529197, -0.0298050437, 0.044413887},
-    {-0.608959973, -0.0147278085, 0.0403517112},
-    {-0.682903409, -0.000655252486, 0.0292486828},
-    {-0.772264957, 0.0165220052, 0.0184068885},
-    {-0.85406059, 0.0323357284, 0.0179911759},
-    {-0.93208164, 0.0473679081, 0.00325830979},
-    {-1.01052046, 0.0659046769, -0.00114371208},
-    {-1.08039141, 0.0775819421, -0.00344298268},
-    {-1.13518226, 0.0820051208, -0.0100943903},
-    {-1.19593167, 0.0786836967, -0.0139237763},
-    {-1.26511216, 0.0829967707, -0.0128824394},
-    {-1.33553934, 0.106848121, 3.23774293e-05},
-    {-1.38853455, 0.124939933, 0.0194544885},
-    {-1.40509641, 0.141601726, 0.0506994724},
-    {-1.39348018, 0.146866396, 0.0902829021},
-    {-1.37384629, 0.148630768, 0.131188467},
-    {-1.36510503, 0.137328193, 0.171971262},
-    {-1.3488425, 0.113482893, 0.200855017},
-    {-1.36003804, 0.0856412053, 0.224294662},
-    {-1.39023864, 0.0524900332, 0.242657483},
-    {-1.4331156, 0.0174365714, 0.255712479},
-    {-1.48283505, -0.0224884991, 0.26016888},
-    {-1.5331862, -0.0564605631, 0.25790742},
-    {-1.58349264, -0.0953254327, 0.247110978},
-    {-1.63034666, -0.127630621, 0.231617719},
-    {-1.66556406, -0.155360028, 0.20606184},
-    {-1.70505846, -0.179494977, 0.177475289},
-    {-1.7432394, -0.20487614, 0.143977895},
-    {-1.78176117, -0.219210908, 0.097603485},
-    {-1.82429147, -0.23192355, 0.0527979955},
-    {-1.85435426, -0.235803157, 0.0110948775},
-    {-1.88406444, -0.230178684, -0.0341724902},
-    {-1.91632342, -0.218222797, -0.0685103685},
-    {-1.959777, -0.197087944, -0.105437778},
-    {-2.01325679, -0.177571416, -0.132859513},
-    {-2.05673504, -0.156065375, -0.159751058},
-    {-2.10397649, -0.127514213, -0.178108945},
-    {-2.15286946, -0.0841833204, -0.186738089},
-    {-2.19252753, -0.0389131829, -0.199201956},
-    {-2.26018524, 0.000791428145, -0.207175598},
-    {-2.33265162, 0.0539361723, -0.206360802},
-    {-2.3934164, 0.094993487, -0.195800185},
-    {-2.45084715, 0.119136587, -0.178075686},
-    {-2.4974792, 0.145214945, -0.153028309},
-    {-2.53420615, 0.155153975, -0.120590888},
-    {-2.56669807, 0.1498162, -0.091058664},
-    {-2.59960246, 0.128661707, -0.0539357364},
-    {-2.64167643, 0.0999971628, -0.0182922501},
-    {-2.69660783, 0.0576166287, 0.0157387685},
-    {-2.76293159, 0.0109680817, 0.0394087136},
-    {-2.84052014, -0.0404971838, 0.061358355},
-    {-2.91149735, -0.0944760293, 0.0704933181},
-    {-2.97819233, -0.145537525, 0.0752708912},
-    {-3.03381419, -0.186291203, 0.0843797401},
-    {-3.08780289, -0.218206167, 0.0827592462},
-    {-3.12939095, -0.237861067, 0.0750269815},
-    {-3.1663394, -0.251230389, 0.0613749847},
-    {-3.20518327, -0.252095073, 0.0469081774},
-    {-3.23887897, -0.234029457, 0.0228819735},
-    {-3.2844348, -0.207198083, -0.00412475271},
-    {-3.34135461, -0.166358441, -0.0122394692},
-    {-3.40620375, -0.113159269, -0.0201062709},
-    {-3.47314858, -0.0568939969, -0.0114102606},
-    {-3.53321457, -0.00847065728, -0.000183794182},
-    {-3.58404279, 0.0377349593, 0.0160773825},
-    {-3.62488842, 0.0649860948, 0.0371761918},
-    {-3.66208506, 0.101244301, 0.0656485111},
-    {-3.70584822, 0.112182349, 0.0921211243},
-    {-3.73476839, 0.124324679, 0.110030025},
-    {-3.75528789, 0.106681831, 0.117479593},
-    {-3.77873445, 0.0949254707, 0.128670618},
-    {-3.80454683, 0.0688716173, 0.117469013},
-    {-3.82942581, 0.030570427, 0.090078488},
-    {-3.85371256, -0.0115469322, 0.0680762753},
-    {-3.8816483, -0.0456187613, 0.0320256501},
-    {-3.90524459, -0.0610832945, 0.0081304675},
-    {-3.93143463, -0.0830661729, -0.0424036011},
-    {-3.9633112, -0.0922950059, -0.0908092186},
-    {-3.9930439, -0.101420537, -0.124626055},
-    {-4.02625561, -0.107435562, -0.155088112},
-    {-4.05752563, -0.100098319, -0.177337497},
-    {-4.09412718, -0.0976494029, -0.199875668},
-    {-4.12139797, -0.0995284244, -0.213660702},
-    {-4.15315628, -0.0845890269, -0.227575555},
-    {-4.17133427, -0.0871502459, -0.219164744},
-    {-4.18395472, -0.0686991438, -0.212530002},
-    {-4.20475721, -0.0719749704, -0.184411138},
-    {-4.22354889, -0.0751998201, -0.162314549},
-    {-4.2297368, -0.112804517, -0.122626625},
-    {-4.24444962, -0.113945343, -0.0820293501},
-    {-4.24500656, -0.138990924, -0.031716004},
-    {-4.2417717, -0.175869972, 0.0151809566},
-    {-4.23664665, -0.196298346, 0.0734456852},
-    {-4.26279068, -0.229197606, 0.105324149},
-    {-4.26423693, -0.251546383, 0.11802835},
-    {-4.28197956, -0.230627671, 0.10359478},
-    {-4.30613565, -0.22191985, 0.086590372},
-    {-4.33288002, -0.207530648, 0.0623893291},
-    {-4.35498142, -0.184523225, 0.0394419655},
-    {-4.3799057, -0.154905915, 0.0298800673},
-    {-4.40355778, -0.126934916, 0.020766532},
-    {-4.43499565, -0.0896012038, 0.0243931524},
-    {-4.45636272, -0.0493768081, 0.0274860617},
-    {-4.48694086, -0.0140573345, 0.0273323748},
-    {-4.51040554, 0.0182513706, 0.0537923798},
-    {-4.5388236, 0.0280622002, 0.0713687241},
-    {-4.56535435, 0.0396699198, 0.0704979897},
-    {-4.58944988, 0.0292550121, 0.0670408607},
-    {-4.60674667, 0.0340262912, 0.0581626594},
-    {-4.62018728, 0.0101033971, 0.040622592},
-    {-4.6308794, -0.00664151879, 0.0278518889},
-    {-4.65299511, -0.0129104704, -0.0077996552},
-    {-4.67564392, -0.0228709523, -0.032925345},
-    {-4.69039297, -0.0384019874, -0.0769576654},
-    {-4.70169973, -0.0361072533, -0.102199756},
-    {-4.69819117, -0.0572254732, -0.119643062},
-    {-4.69719458, -0.0857600123, -0.120125286},
-    {-4.69895649, -0.0837812126, -0.140179291},
-    {-4.69835138, -0.103307113, -0.143379018},
-    {-4.7045269, -0.127314702, -0.128206745},
-    {-4.70046949, -0.143244788, -0.103962362},
-    {-4.69192839, -0.179064751, -0.0935690105},
-    {-4.68774891, -0.194277734, -0.109316759},
-    {-4.68774939, -0.191970259, -0.115590587},
-    {-4.67416334, -0.178155005, -0.121685155},
-    {-4.66745138, -0.177708745, -0.104091108},
-    {-4.65376616, -0.132299185, -0.0897485241},
-    {-4.64025831, -0.106196456, -0.0642534792},
-    {-4.60519886, -0.0562071018, -0.0133178039},
-    {-4.5895915, -0.0351025723, 0.0509939566},
-    {-4.5550704, -0.0489777252, 0.112358026},
-    {-4.49086714, -0.0426422618, 0.126143053},
-    {-4.47708225, -0.0422764346, 0.151651204},
-    {-4.42902613, -0.0398653001, 0.109664202},
-    {-4.38377619, -0.0563522242, 0.0805275142},
-    {-4.39759779, -0.0655729771, 0.00398996565},
-    {-4.40168667, -0.0961238667, -0.0516007841},
-    {-4.43260098, -0.0813035667, -0.101717517},
-    {-4.45309496, -0.0466290712, -0.135397315},
-    {-4.49046803, -0.0202769041, -0.205313206},
-    {-4.47621679, -0.0115179662, -0.202806562},
-    {-4.38727188, -0.0220228992, -0.228792667},
-    {-4.28625393, 0.0171372611, -0.225832775},
-    {-4.26285791, -0.00260078791, -0.158159629},
-    {-4.23534107, -0.0422088429, -0.155688852},
-    {-4.1856184, -0.0777450651, -0.0697575063},
-    {-4.17480898, -0.0814366043, -0.0606617182},
-    {-4.1129508, -0.102637932, -0.0484231189},
-    {-4.09732294, -0.135738492, 0.0304273572},
-    {-4.01592159, -0.192955196, 0.0526915714},
-    {-4.02919292, -0.231625363, 0.0388100818},
-    {-3.98296547, -0.257565796, 0.0536260977},
-    {-3.93559146, -0.305705428, 0.0704375207},
-    {-3.98470306, -0.257388771, 0.0639035106},
-    {-3.95836449, -0.273925036, 0.0377746746},
-    {-3.92619634, -0.280180603, 0.0475733131},
-    {-3.95740795, -0.214431465, 0.0353014544},
-    {-3.95835924, -0.164387196, 0.00778932869},
-    {-3.88339424, -0.0781607777, 0.0176752321},
-    {-3.84245372, -0.0489031672, 0.0153939109},
-    {-3.87032437, 0.0128803588, 0.0171763767},
-    {-3.84918022, 0.0684362277, 0.0357978046},
-    {-3.83415699, 0.118671, 0.0471077114},
-    {-3.80620146, 0.127311915, 0.0593017787},
-    {-3.74457955, 0.142532945, 0.0997702256},
-    {-3.78229475, 0.104458638, 0.089170292},
-    {-3.7450788, 0.100346871, 0.0956846625},
-    {-3.73888659, 0.0560202859, 0.0831993595},
-    {-3.72155356, 0.038879808, 0.0558407083},
-    {-3.72575593, -0.0192625653, 0.0102422861},
-    {-3.71054077, -0.0302787088, -0.0188807994},
-    {-3.72292948, -0.0256146584, -0.0814972445},
-    {-3.75136399, -0.0437397398, -0.0958310291},
-    {-3.70959282, -0.0692312568, -0.130401701},
-    {-3.72998953, -0.0766073614, -0.136996269},
-    {-3.72026825, -0.133384079, -0.133128792},
-    {-3.70104313, -0.0927293599, -0.164308771},
-    {-3.74734282, -0.106886268, -0.155242577},
-    {-3.75486183, -0.0834975541, -0.161477491},
-    {-3.67758656, -0.0731234401, -0.146336257},
-    {-3.66223073, -0.099630706, -0.112693854},
-    {-3.66782641, -0.0907621756, -0.073752895},
-    {-3.66893101, -0.0941418931, -0.0379981548},
-    {-3.65430832, -0.121809669, 0.00651358627},
-    {-3.65709019, -0.142915443, 0.055044882},
-    {-3.57025218, -0.13920781, 0.0323013589},
-    {-3.53423357, -0.189589977, 0.0790117905},
-    {-3.50632596, -0.186279416, 0.0381615683},
-    {-3.48439264, -0.190928325, 0.0414575413},
-    {-3.50753212, -0.211729616, 0.062631771},
-    {-3.52629685, -0.178148031, 0.0685585141},
-    {-3.49844408, -0.160239145, 0.0284172539},
-    {-3.52927327, -0.172693923, 0.0358003229},
-    {-3.57106113, -0.119432747, -0.0018133868},
-    {-3.55043912, -0.108886257, 0.0123364739},
-    {-3.47739244, -0.10509897, -0.0267395359},
-    {-3.4568274, -0.078770116, -0.0321014374},
-    {-3.45392942, -0.0542157106, -0.0155152883},
-    {-3.4274714, -0.0305523518, -0.0248028077},
-    {-3.36037731, -0.024443157, -0.0177858844},
-    {-3.35649776, -0.0311031453, -0.0258705635},
-    {-3.33473635, -0.0292230435, -0.0205537286},
-    {-3.31075788, -0.00943511166, 0.017043354},
-    {-3.25464463, -0.0116780046, 0.0165298209},
-    {-3.26294875, -0.0195683148, 0.0352708921},
-    {-3.27996469, -0.0082847178, 0.0253812969},
-    {-3.25631261, -0.0196638666, 0.0160822235},
-    {-3.23175192, -0.015250558, 0.0193990599},
-    {-3.24321294, 0.00918883085, -0.0092463363},
-    {-3.25171018, -0.0272276253, 0.0197870564},
-    {-3.2351644, -0.0432741456, 0.0131190214},
-    {-3.24539089, -0.0481463037, -0.0151494592},
-    {-3.25337315, -0.0577575862, -0.03741505},
-    {-3.20861721, -0.0928564817, -0.0632401109},
-    {-3.21480846, -0.0827546865, -0.0676190779},
-    {-3.24247479, -0.0973087624, -0.0919414535},
-    {-3.25262499, -0.103319727, -0.090559788},
-    {-3.29248357, -0.107244045, -0.0865190625},
-    {-3.25386882, -0.0895668715, -0.10161937},
-    {-3.236444, -0.0926487595, -0.11828912},
-    {-3.16826677, -0.072882548, -0.101825342},
-    {-3.13015556, -0.0655896217, -0.0829106718},
-    {-3.12761188, -0.0470488146, -0.0823951811},
-    {-3.10438347, -0.0293596033, -0.0773164332},
-    {-3.03888178, -0.0394163281, -0.0552907065},
-    {-3.00439453, -0.029956216, -0.0374241173},
-    {-2.99912286, -0.0304202978, -0.0112417573},
-    {-3.01031613, -0.0349652469, -0.000140344258},
-    {-3.0353899, -0.0473647602, 0.0232790485},
-    {-3.07726002, -0.0437231138, 0.0276523437},
-    {-3.10617709, -0.0446210578, 0.0484380051},
-    {-3.12624788, -0.0813534558, 0.0570681915},
-    {-3.10323453, -0.0749680921, 0.0598451644},
-    {-3.0832262, -0.0888030231, 0.0512110442},
-    {-3.06214476, -0.0867632702, 0.0457208902},
-    {-3.05376863, -0.109015226, 0.0379907563},
-    {-3.02138662, -0.0934633091, 0.0336573943},
-    {-2.98399115, -0.0565437004, 0.0263054352},
-    {-2.99574518, -0.0753557906, 0.0162418559},
-    {-3.01466751, -0.0660598055, 0.00957026612},
-    {-3.00135136, -0.0393830724, -0.00572109036},
-    {-2.99294639, -0.0384377614, -0.00377202593},
-    {-3.01763058, -0.0102499072, -0.020686755},
-    {-3.03146505, -0.011862875, -0.0242951456},
-    {-3.04406977, -0.00477912463, -0.0429856032},
-    {-3.03971338, 0.0137782991, -0.0268226806},
-    {-3.01841187, 0.00810797699, -0.0421042889},
-    {-2.95665383, 0.0136452764, -0.0295164976},
-    {-2.95929766, 0.0265490022, -0.0179430507},
-    {-2.93196058, 0.029924592, -0.00683520082},
-    {-2.9277699, 0.0417308435, -0.00369241112},
-    {-2.92315888, 0.0405406468, 0.0164160002},
-    {-2.91741037, 0.0323856138, 0.0352349505},
-    {-2.87805986, 0.0189497713, 0.0506506637},
-    {-2.88611507, 5.97736798e-05, 0.0454614908},
-    {-2.89564371, -0.0279093906, 0.047556676},
-    {-2.84554219, -0.053899765, 0.0425182357},
-    {-2.85649991, -0.0979986042, 0.033239536},
-    {-2.83601952, -0.119916432, 0.0098108938},
-    {-2.81184125, -0.116573803, -0.0289987214},
-    {-2.81514001, -0.146762997, -0.049211219},
-    {-2.80989075, -0.136476994, -0.086718604},
-    {-2.80230761, -0.114992946, -0.112858638},
-    {-2.78401613, -0.0976327583, -0.140179291},
-    {-2.83546519, -0.0833655, -0.155095071},
-    {-2.83712769, -0.054431878, -0.160831913},
-    {-2.85187697, -0.0375040472, -0.1643904},
-    {-2.88844347, -0.012843959, -0.166951209},
-    {-2.86607671, -5.42518683e-05, -0.164539576},
-    {-2.83180451, 0.0156286508, -0.133696452},
-    {-2.85099649, 0.0148258973, -0.0897283703},
-    {-2.83735991, 0.0174985547, -0.0502270609},
-    {-2.8626287, 0.0260388833, -0.00791605562},
-    {-2.83854866, 0.00785365701, 0.0194094907},
-    {-2.83032107, -0.0192736518, 0.0559019744},
-    {-2.83914948, -0.0379701518, 0.0830429494},
-    {-2.82527781, -0.0645404086, 0.0978198722},
-    {-2.78896976, -0.0984052345, 0.108390845},
-    {-2.76268673, -0.126510456, 0.119436212},
-    {-2.7521894, -0.153206408, 0.125094339},
-    {-2.72663116, -0.17793186, 0.121753141},
-    {-2.71898913, -0.187429309, 0.112712257},
-    {-2.71304631, -0.187526554, 0.105141252},
-    {-2.70055747, -0.190342158, 0.0952451304},
-    {-2.71414328, -0.190220371, 0.0833911449},
-    {-2.72661567, -0.187880799, 0.07132034},
-    {-2.7166214, -0.181091279, 0.0540251806},
-    {-2.72175956, -0.160056233, 0.0324081033},
-    {-2.73425388, -0.147757992, 0.00915849954},
-    {-2.73010683, -0.131779984, -0.00468790485},
-    {-2.73000717, -0.119998135, -0.0255921669},
-    {-2.74301434, -0.0944708362, -0.053935729},
-    {-2.74894571, -0.0570736751, -0.0689201877},
-    {-2.73434687, -0.0293727033, -0.076924406},
-    {-2.71610594, 0.00361827621, -0.0827111304},
-    {-2.71910214, 0.0331233107, -0.08549162},
-    {-2.72870731, 0.0556998737, -0.0822401717},
-    {-2.72721362, 0.0794609487, -0.0808487236},
-    {-2.70283651, 0.0936450809, -0.0705390573},
-    {-2.67521071, 0.100088887, -0.0560319349},
-    {-2.64723015, 0.0980682671, -0.0363508239},
-    {-2.63581133, 0.0975307673, -0.0290632453},
-    {-2.61453366, 0.0972670764, -0.0152527587},
-    {-2.61546898, 0.0880760327, 0.00366142485},
-    {-2.59367108, 0.071955055, 0.0149819478},
-    {-2.60178494, 0.0553163365, 0.0177583769},
-    {-2.59606409, 0.0380892009, 0.0177750085},
-    {-2.56666517, 0.0150088165, 0.0190221462},
-    {-2.56238675, -0.0166856498, 0.0169964861},
-    {-2.55489588, -0.0494009517, 0.00638232566},
-    {-2.53176165, -0.0740867853, -0.0067354301},
-    {-2.50291133, -0.101906292, -0.0238461755},
-    {-2.49406505, -0.126050904, -0.0406077206},
-    {-2.48881054, -0.136925966, -0.0654673576},
-    {-2.48345661, -0.152213112, -0.0898613855},
-    {-2.48330116, -0.158089235, -0.11480201},
-    {-2.49712515, -0.15322192, -0.138965413},
-    {-2.49790621, -0.157212734, -0.148443654},
-    {-2.47292161, -0.153257057, -0.166546404},
-    {-2.48506904, -0.149126858, -0.170902103},
-    {-2.47578287, -0.137645811, -0.173677698},
-    {-2.48119426, -0.125734985, -0.171806723},
-    {-2.4787333, -0.10398487, -0.170759112},
-    {-2.47106171, -0.0784737766, -0.160522819},
-    {-2.45690036, -0.0582896993, -0.150838166},
-    {-2.42907715, -0.0482337289, -0.133254319},
-    {-2.40028, -0.0424427167, -0.106539793},
-    {-2.38212132, -0.0384186134, -0.0866520926},
-    {-2.36190724, -0.0442043953, -0.0513060316},
-    {-2.33960056, -0.046885401, -0.0343381912},
-    {-2.33665943, -0.0645752773, -0.0095123928},
-    {-2.31555796, -0.0695139468, 0.00663389917},
-    {-2.29477215, -0.0766974539, 0.0152641013},
-    {-2.2695477, -0.08797355, 0.0245428085},
-    {-2.25152469, -0.0979198813, 0.030945899},
-    {-2.2442801, -0.103887595, 0.0355559215},
-    {-2.24481153, -0.109443828, 0.0336573869},
-    {-2.25435805, -0.119851001, 0.0335887223},
-    {-2.24626327, -0.118351407, 0.0311700311},
-    {-2.23401475, -0.124514662, 0.0368328989},
-    {-2.22903681, -0.123038448, 0.0391501561},
-    {-2.22792935, -0.119044751, 0.035765551},
-    {-2.25231957, -0.113246977, 0.0233123004},
-    {-2.2563982, -0.101067357, 0.00693160389},
-    {-2.25930834, -0.0877952278, -0.00985100958},
-    {-2.24056339, -0.0671526939, -0.0218174979},
-    {-2.2417438, -0.0593372993, -0.0301650148},
-    {-2.24232864, -0.0407113358, -0.0406167954},
-    {-2.24819827, -0.0173145104, -0.0474536344},
-    {-2.25426912, 0.00449690642, -0.0587585568},
-    {-2.24199295, 0.0193322226, -0.0671135783},
-    {-2.24018073, 0.0348300077, -0.0762592554},
-    {-2.22057557, 0.0488811024, -0.0813475922},
-    {-2.22973752, 0.0602716431, -0.0837587267},
-    {-2.23353434, 0.0815330669, -0.0885740146},
-    {-2.22835803, 0.0899535343, -0.0882816836},
-    {-2.24257064, 0.0974444523, -0.0937957913},
-    {-2.22078085, 0.109855205, -0.0916122049},
-    {-2.23153329, 0.119487733, -0.0896422789},
-    {-2.22538066, 0.123123676, -0.082789436},
-    {-2.2157867, 0.118770771, -0.071736306},
-    {-2.18324828, 0.124372557, -0.0691573694},
-    {-2.17970753, 0.121665254, -0.0614111125},
-    {-2.16750693, 0.105590194, -0.0492017344},
-    {-2.15618896, 0.0833697245, -0.0403062627},
-    {-2.15888405, 0.0561976582, -0.0311460905},
-    {-2.14361906, 0.0251522064, -0.0234304592},
-    {-2.13887978, -0.00906928256, -0.0150164301},
-    {-2.14472032, -0.036202129, -0.0082916636},
-    {-2.14047265, -0.0686537027, -0.0156316869},
-    {-2.11859298, -0.0925610662, -0.0188243613},
-    {-2.11107445, -0.117496796, -0.0212833676},
-    {-2.11362123, -0.13586174, -0.022898348},
-    {-2.09135699, -0.144666269, -0.0284624621},
-    {-2.08575153, -0.161918625, -0.0364672169},
-    {-2.08189392, -0.16615887, -0.0437671393},
-    {-2.08006477, -0.166192144, -0.0496370047},
-    {-2.07826877, -0.166059151, -0.0511335731},
-    {-2.07122207, -0.162804678, -0.0640007183},
-    {-2.05095387, -0.150705457, -0.0682044178},
-    {-2.03839374, -0.136610016, -0.0682443231},
-    {-2.01539636, -0.121677607, -0.069824025},
-    {-2.00694156, -0.114900731, -0.0757362321},
-    {-2.00164461, -0.102654591, -0.0701233372},
-    {-1.99193776, -0.0939610824, -0.0666029304},
-    {-1.98518252, -0.0860759616, -0.0561720133},
-    {-1.97370875, -0.075367175, -0.0498032868},
-    {-1.96873677, -0.060551174, -0.0428525731},
-    {-1.96435666, -0.0489348955, -0.0321674943},
-    {-1.96231163, -0.0370250419, -0.0164470207},
-    {-1.9459585, -0.0178466216, 0.000162382144},
-    {-1.94070089, -0.00391444191, 0.022963101},
-    {-1.93850374, 0.00398195861, 0.0437846854},
-    {-1.9218123, 0.0139729511, 0.0608829781},
-    {-1.90774453, 0.0211314298, 0.0801308453},
-    {-1.89048934, 0.0268669594, 0.0963457599},
-    {-1.89231193, 0.0341149755, 0.113921106},
-    {-1.88429701, 0.0329010971, 0.130815685},
-    {-1.87827218, 0.0255925953, 0.145195037},
-    {-1.8818953, 0.019659251, 0.159796149},
-    {-1.86598182, 0.0170616284, 0.170890912},
-    {-1.86020231, 0.00727655133, 0.178855449},
-    {-1.84590185, -0.00166959269, 0.18635495},
-    {-1.83593857, -0.0174999423, 0.196039587},
-    {-1.83326423, -0.0339621753, 0.202168658},
-    {-1.82496667, -0.0429748334, 0.204729468},
-    {-1.81335974, -0.0510729142, 0.203415796},
-    {-1.81404054, -0.0613134019, 0.19753091},
-    {-1.8198638, -0.0664784834, 0.19394812},
-    {-1.81329334, -0.0718751922, 0.181632429},
-    {-1.82076919, -0.0783925056, 0.165775806},
-    {-1.81390882, -0.0812702999, 0.144633979},
-    {-1.83624077, -0.0848121867, 0.126791582},
-    {-1.84836483, -0.0803518146, 0.109039187},
-    {-1.84461832, -0.0704274029, 0.0848134235},
-    {-1.84695327, -0.0583355539, 0.0588560179},
-    {-1.85406911, -0.049160637, 0.0362149626},
-    {-1.85920501, -0.0385183878, 0.0197205413},
-    {-1.86445343, -0.0272501204, -0.00035692635},
-    {-1.85642099, -0.0190533698, -0.0232099984},
-    {-1.87877655, -0.0237023793, -0.0414890349},
-    {-1.88939464, -0.0189503785, -0.0574025214},
-    {-1.88626492, -0.0110581536, -0.0732691586},
-    {-1.88771605, -0.00720436964, -0.0899097621},
-    {-1.89320517, -0.00255787675, -0.107884564},
-    {-1.89332652, -0.00516158063, -0.123750314},
-    {-1.90242243, -0.000256168656, -0.137568623},
-    {-1.90448403, -0.000671880785, -0.152068675},
-    {-1.90864575, 0.00827527232, -0.16398631},
-    {-1.91399193, 0.0146242119, -0.171188802},
-    {-1.91387904, 0.019066168, -0.173270062},
-    {-1.91371298, 0.0188998822, -0.175997123},
-    {-1.91569173, 0.021893017, -0.176080272},
-    {-1.9187721, 0.0271410812, -0.174177065},
-    {-1.92340744, 0.0262829456, -0.17085889},
-    {-1.92886174, 0.0238718092, -0.164822742},
-    {-1.93380034, 0.0174735859, -0.152959645},
-    {-1.9379077, 0.00967105664, -0.142806575},
-    {-1.94653964, -0.00422842801, -0.12895602},
-    {-1.95647526, -0.0196026452, -0.11081975},
-    {-1.96751225, -0.0357205048, -0.0897755697},
-    {-1.98393214, -0.0549010038, -0.0701732337},
-    {-1.99747097, -0.0731389672, -0.0520980284},
-    {-1.99563837, -0.0901171789, -0.0323609859},
-    {-1.99997115, -0.106766112, -0.0124819232},
-    {-2.00794697, -0.121810637, 0.00621818565},
-    {-2.01641059, -0.141132995, 0.0193879735},
-    {-2.02367926, -0.160823673, 0.0294769499},
-    {-2.02771783, -0.178370073, 0.0351537615},
-    {-2.02558064, -0.195106253, 0.0412768349},
-    {-2.02489138, -0.20935978, 0.0410216674},
-    {-2.02258229, -0.221968219, 0.0388776064},
-    {-2.01845789, -0.232550666, 0.0417420641},
-    {-2.01784301, -0.239625648, 0.0339799896},
-    {-2.01789188, -0.24645029, 0.0286400784},
-    {-2.01345611, -0.251669824, 0.0198505465},
-    {-2.00778079, -0.252444834, 0.0130251534},
-    {-2.00940871, -0.255862206, 0.00616074167},
-    {-2.01163387, -0.255378455, -0.00182094681},
-    {-2.00513792, -0.250488043, -0.00949522853},
-    {-2.00040007, -0.243141443, -0.0147820227},
-    {-1.99887919, -0.235174298, -0.0210092515},
-    {-1.9977535, -0.222579449, -0.0276541021},
-    {-1.99429512, -0.21105586, -0.0298989546},
-    {-1.99268222, -0.195092514, -0.0386954397},
-    {-1.99348009, -0.180010468, -0.0400090963},
-    {-1.98920465, -0.160323784, -0.0460024178},
-    {-1.9882648, -0.13949962, -0.0498499572},
-    {-1.98649597, -0.11396198, -0.0517155677},
-    {-1.97875571, -0.0916651487, -0.0521781519},
-    {-1.97528827, -0.0685827509, -0.0517488271},
-    {-1.96587694, -0.0443716235, -0.0471759811},
-    {-1.96255088, -0.0237688925, -0.0399425775},
-    {-1.95756817, -0.0146539472, -0.0306356512},
-    {-1.95192742, -0.00417939015, -0.0232408941},
-    {-1.94658661, 0.00745291496, -0.0175102055},
-    {-1.93907177, 0.0169044603, -0.0108094169},
-    {-1.93445265, 0.0247858465, -0.00388229778},
-    {-1.93203163, 0.0345844924, -0.000356925884},
-    {-1.92645383, 0.0384834521, 0.00897422899},
-    {-1.92405605, 0.0452061966, 0.015147699},
-    {-1.92273891, 0.0466035008, 0.0221886169},
-    {-1.91799128, 0.0463964865, 0.0313229561},
-    {-1.91545057, 0.0477483459, 0.0357171744},
-    {-1.91002727, 0.047546532, 0.0422741771},
-    {-1.9117012, 0.045256082, 0.0456942916},
-    {-1.90661252, 0.0410158187, 0.0507493615},
-    {-1.90012741, 0.035628181, 0.0544575155},
-    {-1.89564455, 0.0291694645, 0.0553740487},
-    {-1.88945746, 0.0212201159, 0.0573032126},
-    {-1.88213563, 0.0115999654, 0.0509322658},
-    {-1.87162638, 0.000425601378, 0.0412045941},
-    {-1.86414373, -0.0107986489, 0.0326741561},
-    {-1.85317743, -0.022329269, 0.0285417195},
-    {-1.84837973, -0.0327815488, 0.023844419},
-    {-1.84756482, -0.0400149524, 0.014998043},
-    {-1.84471464, -0.0441656485, 0.0050777914},
-    {-1.84202731, -0.0470987, -0.00459035113},
-    {-1.83905303, -0.0465157256, -0.0168993678},
-    {-1.83616602, -0.0468605421, -0.0315521546},
-    {-1.834656, -0.0443201326, -0.043636255},
-    {-1.82924855, -0.0429526567, -0.0534197465},
-    {-1.83343041, -0.0426089987, -0.066631332},
-    {-1.83305895, -0.041570209, -0.0810815319},
-    {-1.83294713, -0.0386602804, -0.095324412},
-    {-1.82911921, -0.0349225961, -0.110565394},
-    {-1.82502604, -0.0272067059, -0.124311395},
-    {-1.82064295, -0.0212413576, -0.132513523},
-    {-1.81563807, -0.0126444139, -0.141476333},
-    {-1.81262803, -0.00309964479, -0.147412688},
-    {-1.81038296, 0.00566358445, -0.152783751},
-    {-1.80720723, 0.0156406946, -0.156974122},
-    {-1.80088842, 0.0283448827, -0.160116881},
-    {-1.79734457, 0.0382936299, -0.160147205},
-    {-1.7943511, 0.0494575649, -0.158610344},
-    {-1.79132307, 0.0625507459, -0.157987937},
-    {-1.78748572, 0.0728594437, -0.152733818},
-    {-1.78181577, 0.0839506611, -0.147179917},
-    {-1.77832055, 0.0948530659, -0.141407654},
-    {-1.76919985, 0.101491727, -0.134252474},
-    {-1.76431382, 0.107434951, -0.12630254},
-    {-1.7612505, 0.114117302, -0.117128126},
-    {-1.75775421, 0.118454821, -0.103845984},
-    {-1.75329769, 0.119419269, -0.0905597731},
-    {-1.74569058, 0.118857935, -0.0771874413},
-    {-1.73966241, 0.117324069, -0.0627901554},
-    {-1.73390877, 0.113682441, -0.0466438755},
-    {-1.72847378, 0.109014109, -0.0296640117},
-    {-1.72418118, 0.105933547, -0.0135032348},
-    {-1.72542191, 0.0974605754, -0.0012082106},
-    {-1.72378743, 0.0889311731, 0.0108108753},
-    {-1.72599375, 0.0778978691, 0.0198702011},
-    {-1.72722423, 0.0660583675, 0.0308782812},
-    {-1.72956276, 0.0524102673, 0.0398958251},
-    {-1.72427225, 0.0408905484, 0.0441245511},
-    {-1.7188592, 0.0259156059, 0.0463755578},
-    {-1.71264756, 0.0113628749, 0.0503416955},
-    {-1.70774937, -0.00197999086, 0.0499229729},
-    {-1.70162725, -0.0160444584, 0.0510388985},
-    {-1.69579911, -0.0297293533, 0.0487631038},
-    {-1.68633449, -0.0421101451, 0.0423852056},
-    {-1.67532277, -0.0576099418, 0.0356204286},
-    {-1.66574872, -0.070228979, 0.0294981133},
-    {-1.65395892, -0.0853110403, 0.024409784},
-    {-1.64945865, -0.0946643129, 0.0155613981},
-    {-1.63901007, -0.104088388, 0.00906005409},
-    {-1.63179314, -0.111367926, 0.00483801775},
-    {-1.62480915, -0.119249836, -0.00227898639},
-    {-1.61938632, -0.124462634, -0.0122535788},
-    {-1.61523676, -0.129835784, -0.0192620661},
-    {-1.61318576, -0.131954029, -0.0271386188},
-    {-1.61501682, -0.131734833, -0.035569787},
-    {-1.61062491, -0.131804377, -0.0405245721},
-    {-1.60732365, -0.130076095, -0.0454385728},
-    {-1.60256028, -0.126250446, -0.0505848303},
-    {-1.60019886, -0.118617952, -0.0566043481},
-    {-1.60093069, -0.113080651, -0.0596141145},
-    {-1.59794033, -0.104726098, -0.0639652535},
-    {-1.59296691, -0.0953918397, -0.0657911301},
-    {-1.58767891, -0.0882531777, -0.0649939999},
-    {-1.5855161, -0.0757829025, -0.0650017634},
-    {-1.58323467, -0.0653175041, -0.0640458688},
-    {-1.58012855, -0.0562776551, -0.0627569035},
-    {-1.57901847, -0.0483023934, -0.0586898923},
-    {-1.57671952, -0.0402144976, -0.0551410466},
-    {-1.57500672, -0.0312683508, -0.0523308292},
-    {-1.57628727, -0.0225383863, -0.0470263213},
-    {-1.57813931, -0.0116547644, -0.0395041928},
-    {-1.57791078, -0.000754045788, -0.0314229131},
-    {-1.57515657, 0.00784880109, -0.0224482305},
-    {-1.57287824, 0.015075326, -0.0154155176},
-    {-1.56865823, 0.0238677803, -0.00325603783},
-    {-1.56192243, 0.0285792891, 0.00789283961},
-    {-1.55022526, 0.0338489264, 0.021475343},
-    {-1.54338944, 0.0363143794, 0.0355752781},
-    {-1.53392577, 0.0371705964, 0.0472946614},
-    {-1.52542973, 0.0387752578, 0.0598510578},
-    {-1.5145601, 0.0368642248, 0.0705947429},
-    {-1.50362754, 0.0352517664, 0.0836073235},
-    {-1.49321103, 0.0332138203, 0.0945928767},
-    {-1.48318446, 0.0304567013, 0.107286319},
-    {-1.47486985, 0.0241544973, 0.117928565},
-    {-1.46770275, 0.0191326849, 0.126508877},
-    {-1.46406114, 0.0127639659, 0.13447395},
-    {-1.45933914, 0.0033854791, 0.145249233},
-    {-1.45739341, -0.00639209151, 0.151235476},
-    {-1.45571411, -0.0170343425, 0.159034297},
-    {-1.45581818, -0.0267957896, 0.164875403},
-    {-1.45602739, -0.0387280062, 0.169309676},
-    {-1.45449114, -0.0497282222, 0.17301999},
-    {-1.45327032, -0.0590772778, 0.174630836},
-    {-1.45351875, -0.0707777143, 0.174299255},
-    {-1.4507277, -0.0812762156, 0.174718708},
-    {-1.44878769, -0.0924713761, 0.172131479},
-    {-1.44755232, -0.103676416, 0.17003271},
-    {-1.44228959, -0.113723628, 0.166246027},
-    {-1.43805993, -0.124291524, 0.163544372},
-    {-1.43363118, -0.134398416, 0.158801466},
-    {-1.43001878, -0.142086834, 0.153781682},
-    {-1.42430258, -0.150611252, 0.148292243},
-    {-1.42112648, -0.156514362, 0.140177533},
-    {-1.41635394, -0.163282171, 0.133127064},
-    {-1.41460836, -0.167838365, 0.12577723},
-    {-1.40812147, -0.173852339, 0.11605005},
-    {-1.40273488, -0.177176654, 0.107809842},
-    {-1.40009165, -0.181590199, 0.100036271},
-    {-1.39739764, -0.183036864, 0.0916056409},
-    {-1.39348972, -0.186179668, 0.0836239457},
-    {-1.38965285, -0.186210915, 0.0755786672},
-    {-1.38590193, -0.188662827, 0.0675020292},
-    {-1.38271451, -0.18942219, 0.058215566},
-    {-1.37947226, -0.187543198, 0.0495687351},
-    {-1.3751986, -0.18772608, 0.040506199},
-    {-1.37056732, -0.185800701, 0.0309604127},
-    {-1.36744952, -0.183568969, 0.0208845381},
-    {-1.36443973, -0.181759655, 0.0125960261},
-    {-1.36141348, -0.178414091, 0.00578584522},
-    {-1.35882854, -0.175674424, 0.000549372751},
-    {-1.3547678, -0.170497969, -0.00779085141},
-    {-1.35282207, -0.167644382, -0.0127937524},
-    {-1.35047174, -0.163199008, -0.0170118529},
-    {-1.34676373, -0.158409998, -0.0224992614},
-    {-1.34229076, -0.152257457, -0.0265399944},
-    {-1.33947861, -0.147214487, -0.0309097674},
-    {-1.33542323, -0.141631842, -0.0349041373},
-    {-1.33103716, -0.136392757, -0.0384867862},
-    {-1.32674289, -0.130673632, -0.0415888056},
-    {-1.32263577, -0.125452295, -0.0433846712},
-    {-1.31963611, -0.120843798, -0.0474444181},
-    {-1.31665993, -0.116041668, -0.0478978902},
-    {-1.31275833, -0.110120796, -0.0497035235},
-    {-1.30861807, -0.10691148, -0.051582545},
-    {-1.30580771, -0.103452742, -0.0528629348},
-    {-1.30312169, -0.0986784101, -0.0515962392},
-    {-1.30095875, -0.0944966227, -0.0534116849},
-    {-1.29652321, -0.0912620276, -0.0546774641},
-    {-1.29251885, -0.0876615569, -0.0571622178},
-    {-1.29123414, -0.0844090655, -0.0555159375},
-    {-1.28796065, -0.0804424137, -0.0557900667},
-    {-1.28464019, -0.0784439817, -0.0538322255},
-    {-1.28197908, -0.0743860975, -0.0573858991},
-    {-1.27870309, -0.0713763386, -0.0554237291},
-    {-1.27564347, -0.0704451427, -0.0568537787},
-    {-1.27313268, -0.0673522428, -0.0558726937},
-    {-1.27035594, -0.0683998317, -0.0539936796},
-    {-1.26924145, -0.0678178445, -0.0553738475},
-    {-1.26641476, -0.0660884827, -0.0599965677},
-    {-1.2628547, -0.0660915077, -0.0570639074},
-    {-1.26051641, -0.0663978681, -0.0596922189},
-    {-1.25825763, -0.0657934546, -0.0594623163},
-    {-1.25502419, -0.0671859533, -0.0591485202},
-    {-1.25031841, -0.0665374473, -0.0605286881},
-    {-1.24681091, -0.0647853985, -0.0622560382},
-    {-1.24321783, -0.0675018951, -0.0630229637},
-    {-1.241238, -0.0663833469, -0.0649230555},
-    {-1.23692644, -0.0685101822, -0.066045329},
-    {-1.23390615, -0.0698631406, -0.0679616332},
-    {-1.23008144, -0.0699296594, -0.0710379109},
-    {-1.22526836, -0.0723317191, -0.0741882548},
-    {-1.21932757, -0.0728482455, -0.0772966668},
-    {-1.213449, -0.0737668127, -0.0799286216},
-    {-1.21017694, -0.0774124861, -0.0836423263},
-    {-1.20497763, -0.0764700323, -0.0869433433},
-    {-1.19993639, -0.0773303658, -0.0899903774},
-    {-1.19358194, -0.0806218013, -0.0929044187},
-    {-1.18736637, -0.0803321376, -0.096796006},
-    {-1.18275654, -0.0813035667, -0.100936003},
-    {-1.1782335, -0.0825340673, -0.103031173},
-    {-1.17234731, -0.0822142065, -0.109518245},
-    {-1.16567814, -0.0823112577, -0.113469444},
-    {-1.1590445, -0.0820352361, -0.117680907},
-    {-1.15286839, -0.0826031044, -0.120578781},
-    {-1.14954925, -0.0846458972, -0.125862151},
-    {-1.14346361, -0.082068488, -0.128389671},
-    {-1.13877261, -0.0832158402, -0.132996842},
-    {-1.13493311, -0.0823511556, -0.13607204},
-    {-1.12979472, -0.0809377432, -0.139547393},
-    {-1.12537599, -0.0809745193, -0.142008439},
-    {-1.12174976, -0.0801170766, -0.145717591},
-    {-1.11800075, -0.0778060406, -0.149280638},
-    {-1.11496222, -0.0773293525, -0.151619703},
-    {-1.11136389, -0.0751374066, -0.15577887},
-    {-1.10864341, -0.0736211911, -0.159335345},
-    {-1.10546732, -0.0734382719, -0.163941428},
-    {-1.10241723, -0.0709257647, -0.166416958},
-    {-1.09823394, -0.0706280619, -0.173818782},
-    {-1.09477508, -0.0673522353, -0.174666822},
-    {-1.0923475, -0.0662713945, -0.181151941},
-    {-1.08795106, -0.0636082962, -0.182787597},
-    {-1.08609354, -0.0615537167, -0.186242446},
-    {-1.08411324, -0.0574325621, -0.19047904},
-    {-1.08158863, -0.0555459894, -0.192110181},
-    {-1.07876396, -0.0532115661, -0.197519794},
-    {-1.07816327, -0.0493171401, -0.199711308},
-    {-1.07727623, -0.0467306525, -0.203059465},
-    {-1.07748604, -0.0428881608, -0.204459071},
-    {-1.07603467, -0.0376537032, -0.20675987},
-    {-1.07455122, -0.0348581001, -0.214407966},
-    {-1.07263613, -0.0302620605, -0.214804843},
-    {-1.07202721, -0.0259139705, -0.219879791},
-    {-1.07179451, -0.0210251883, -0.221326485},
-    {-1.06906748, -0.0158703458, -0.225184292},
-    {-1.06826913, -0.01088179, -0.226930231},
-    {-1.06492329, -0.00386846904, -0.230746016},
-    {-1.06271505, 0.00118407561, -0.230630904},
-    {-1.06153488, 0.00730980793, -0.231602862},
-    {-1.05919039, 0.0143270418, -0.235094845},
-    {-1.05711925, 0.0186064709, -0.236467004},
-    {-1.05399263, 0.024754636, -0.239014149},
-    {-1.05041027, 0.0293425936, -0.240000248},
-    {-1.0484165, 0.0358400531, -0.240569398},
-    {-1.04545486, 0.0432107821, -0.241463602},
-    {-1.04261148, 0.0493300818, -0.240382746},
-    {-1.03809845, 0.0556342304, -0.242092565},
-    {-1.03669405, 0.0605255067, -0.241389319},
-    {-1.0312407, 0.0671301484, -0.240062267},
-    {-1.02823055, 0.0735685602, -0.240140289},
-    {-1.0244199, 0.080271706, -0.239626899},
-    {-1.02025974, 0.0856250897, -0.237917721},
-    {-1.01758814, 0.0930850729, -0.237960339},
-    {-1.0130626, 0.100313112, -0.234097168},
-    {-1.00993669, 0.106365882, -0.233797863},
-    {-1.00727606, 0.109674968, -0.231004283},
-    {-1.00289357, 0.116761744, -0.230564877},
-    {-0.996629775, 0.122110933, -0.225138143},
-    {-0.992892027, 0.126586184, -0.223488182},
-    {-0.991146028, 0.131824151, -0.221259937},
-    {-0.986922503, 0.136679679, -0.217551798},
-    {-0.98333782, 0.141758204, -0.215111315},
-    {-0.977257073, 0.148891687, -0.212442398},
-    {-0.974235058, 0.153640777, -0.211099893},
-    {-0.967317283, 0.159859836, -0.206261009},
-    {-0.962062895, 0.165646553, -0.20591183},
-    {-0.956212878, 0.171617746, -0.204813823},
-    {-0.953599155, 0.177502677, -0.202652603},
-    {-0.947553813, 0.184001401, -0.199170217},
-    {-0.942864656, 0.187026381, -0.197046593},
-    {-0.937282205, 0.192595854, -0.194655314},
-    {-0.93102622, 0.198045969, -0.189898551},
-    {-0.928519487, 0.2022883, -0.1860708},
-    {-0.924549103, 0.207683429, -0.182548761},
-    {-0.920325339, 0.21242258, -0.179455861},
-    {-0.915153682, 0.217244849, -0.176346302},
-    {-0.909467161, 0.224764451, -0.172064722},
-    {-0.902806461, 0.229099885, -0.168305084},
-    {-0.896147549, 0.234172687, -0.166768298},
-    {-0.891142249, 0.239261016, -0.163159877},
-    {-0.886844397, 0.242324203, -0.158116922},
-    {-0.882017136, 0.248337239, -0.15521735},
-    {-0.877281666, 0.253721535, -0.150136903},
-    {-0.873067319, 0.258217514, -0.146780834},
-    {-0.869736493, 0.262173563, -0.140750721},
-    {-0.866210818, 0.266570956, -0.136515647},
-    {-0.863862634, 0.270185113, -0.131773084},
-    {-0.859766245, 0.274080008, -0.125619367},
-    {-0.85620755, 0.278507888, -0.121159293},
-    {-0.854830325, 0.283478409, -0.115007997},
-    {-0.849387228, 0.288247108, -0.108469218},
-    {-0.844533741, 0.292729795, -0.104373559},
-    {-0.839553654, 0.294618458, -0.0999028832},
-    {-0.836334586, 0.298475146, -0.0956813693},
-    {-0.832992196, 0.302831829, -0.0893126428},
-    {-0.827392936, 0.306645334, -0.0843951404},
-    {-0.822491825, 0.309809417, -0.0824804828},
-    {-0.817045689, 0.313174754, -0.0771073177},
-    {-0.813832283, 0.316852212, -0.0713341981},
-    {-0.809928536, 0.319360644, -0.0674627721},
-    {-0.802906454, 0.32297489, -0.0621572137},
-    {-0.799785256, 0.327724695, -0.0569036677},
-    {-0.796304882, 0.330203354, -0.0512429252},
-    {-0.791637301, 0.334509194, -0.0453801081},
-    {-0.789641917, 0.337202996, -0.0405079573},
-    {-0.786848247, 0.339880168, -0.0350371674},
-    {-0.783614695, 0.342200041, -0.0283459537},
-    {-0.782840729, 0.345666915, -0.0239858553},
-    {-0.779196441, 0.348569363, -0.0177359506},
-    {-0.777003407, 0.350649416, -0.0125760688},
-    {-0.776781321, 0.353356689, -0.00856832135},
-    {-0.776036024, 0.357421756, 0.00111373514},
-    {-0.776043296, 0.358059973, 0.00397923775},
-    {-0.774326921, 0.361517429, 0.0100467773},
-    {-0.771184087, 0.363559216, 0.0178248882},
-    {-0.765916228, 0.3641707, 0.023324104},
-    {-0.763485253, 0.367400318, 0.0271036047},
-    {-0.764034033, 0.368680745, 0.0349522606},
-    {-0.765996218, 0.372206062, 0.0416535586},
-    {-0.765896201, 0.374883235, 0.0451455414},
-    {-0.765397489, 0.37737748, 0.0529775769},
-    {-0.764136314, 0.378803015, 0.0554375947},
-    {-0.765744627, 0.382090867, 0.0617048666},
-    {-0.76536423, 0.384012282, 0.0696393549},
-    {-0.768606782, 0.387421161, 0.0750935003},
-    {-0.773927808, 0.389266878, 0.0816617757},
-    {-0.777325988, 0.390590101, 0.0887671858},
-    {-0.781389415, 0.392121941, 0.0952331573},
-    {-0.783838451, 0.396084517, 0.10286314},
-    {-0.785827458, 0.396663845, 0.107929997},
-    {-0.788078845, 0.397298425, 0.115550697},
-    {-0.793000877, 0.401405722, 0.122052431},
-    {-0.795278847, 0.401954502, 0.1310651},
-    {-0.799419224, 0.4026362, 0.13808234},
-    {-0.802728355, 0.406078249, 0.143569767},
-    {-0.805139482, 0.406942993, 0.151617959},
-    {-0.806753457, 0.408617377, 0.158199802},
-    {-0.809097171, 0.4099527, 0.164172441},
-    {-0.812090278, 0.411116719, 0.169859439},
-    {-0.817067683, 0.41120252, 0.176606849},
-    {-0.821749449, 0.410616845, 0.185692281},
-    {-0.826714277, 0.41097939, 0.193497136},
-    {-0.832510054, 0.410301894, 0.202185303},
-    {-0.83829689, 0.41051808, 0.209219158},
-    {-0.845275342, 0.410020262, 0.218393043},
-    {-0.849088788, 0.409287572, 0.227543771},
-    {-0.852081776, 0.408522725, 0.236423388},
-    {-0.857490838, 0.406894118, 0.245146394},
-    {-0.861544967, 0.404731423, 0.252931982},
-    {-0.862325013, 0.403517604, 0.263710797},
-    {-0.867543459, 0.400168121, 0.272620112},
-    {-0.869180441, 0.399530411, 0.28007701},
-    {-0.870922148, 0.396699786, 0.288952887},
-    {-0.872901082, 0.394355237, 0.298929989},
-    {-0.876376271, 0.391794443, 0.306878448},
-    {-0.879784822, 0.388335735, 0.314294726},
-    {-0.88157177, 0.385801047, 0.325589478},
-    {-0.882362187, 0.381833851, 0.333018452},
-    {-0.885106027, 0.378109187, 0.342180818},
-    {-0.887966156, 0.37295422, 0.35220775},
-    {-0.889108717, 0.368942469, 0.361061096},
-    {-0.891657829, 0.363875151, 0.370698601},
-    {-0.893278301, 0.358937413, 0.379961759},
-    {-0.892129838, 0.353408307, 0.387735367},
-    {-0.897860289, 0.351902574, 0.379312247},
-    {-0.884973049, 0.338633031, 0.404504448},
-    {-0.887521803, 0.338733286, 0.413726658},
-    {-0.883753181, 0.326373488, 0.423232466},
-    {-0.882297456, 0.327462196, 0.431496143},
-    {-0.876342773, 0.315303177, 0.444745421},
-    {-0.868876755, 0.310347915, 0.449334919},
-    {-0.858884394, 0.304920048, 0.456860065},
-    {-0.852341533, 0.293193758, 0.468702316},
-    {-0.845530391, 0.28312704, 0.478867173},
-    {-0.84055835, 0.275727361, 0.485601723},
-    {-0.832476795, 0.267479599, 0.488810986},
-    {-0.819124162, 0.227488026, 0.473030478},
-    {-0.652489364, 0.250338137, 0.512086868},
-    {-0.624030948, 0.26454547, 0.551763415},
-    {-0.602371514, 0.209662244, 0.5206213},
-    {-0.584362686, 0.197357148, 0.499885619},
-    {-0.589522541, 0.220426947, 0.496413827},
-    {-0.575162292, 0.216106042, 0.507306278},
-    {-0.557015359, 0.210365206, 0.502347708},
-    {-0.527376771, 0.207766563, 0.502280176},
-    {-0.495832562, 0.224677816, 0.501066208},
-    {-0.502966166, 0.233008668, 0.498621821},
-    {-0.524182498, 0.2290999, 0.4991014},
-    {-0.516220093, 0.22007218, 0.495333493},
-    {-0.540496647, 0.21014449, 0.494298458},
-    {-0.581353009, 0.203127235, 0.502911925},
-    {-0.552806795, 0.192386195, 0.501202762},
-    {-0.534618795, 0.191817716, 0.495754242},
-    {-0.497495383, 0.188810095, 0.491820782},
-    {-0.46157378, 0.181356996, 0.49172157},
-    {-0.482745856, 0.179863945, 0.487863272},
-    {-0.518089056, 0.174824417, 0.484459728},
-    {-0.441174567, 0.170468807, 0.455969691},
-    {-0.0152184619, 0.166976854, 0.223735809},
-    {0.982991457, 0.256388366, -0.196865886},
-    {1.81009543, 0.280555665, -0.506892622},
-    {2.80153418, 0.171875715, -0.904042125},
-    {3.67549992, -0.0459857024, -1.30320251},
-    {4.29208279, -0.296426684, -1.58769178},
-    {4.77235031, -0.671522796, -1.76872492},
-    {4.6038208, -0.900832653, -1.67068207},
-    {4.3812151, -1.04550111, -1.58540404},
-    {4.18820524, -1.18279338, -1.4748174},
-    {4.06399012, -1.27607918, -1.35327959},
-    {3.98839641, -1.33358085, -1.22284555},
-    {3.88603139, -1.37254143, -1.08474565},
-    {3.8690536, -1.38195288, -0.930898488},
-    {3.87264585, -1.353585, -0.755484283},
-    {3.94019055, -1.36296332, -0.602751434},
-    {4.02742386, -1.33173478, -0.469324201},
-    {4.2204361, -1.29709399, -0.331166476},
-    {4.4072485, -1.26038623, -0.194481626},
-    {4.5380187, -1.20118427, -0.103978992},
-    {4.61321354, -1.13352287, -0.0206701253},
-    {4.64590502, -1.0617044, 0.0913395807},
-    {4.63125992, -1.01225209, 0.199140236},
-    {4.61100101, -0.930505455, 0.281370252},
-    {4.30801344, -1.10390759, 0.46222207},
-    {3.1621089, -2.21828413, 1.09006488},
-    {2.60079861, -2.4544065, 1.41000259},
-    {1.65233696, -2.9119792, 1.79988337},
-    {0.922015667, -3.17419362, 2.0817709},
-    {-0.0648213401, -3.45601201, 2.34069633},
-    {-1.15538609, -3.75050282, 2.52287793},
-    {-2.36828709, -4.22802401, 2.66671467},
-    {-3.30951071, -4.69792938, 2.65761876},
-    {-3.90268326, -5.13765335, 2.53132534},
-    {-4.29519987, -5.51384068, 2.289397},
-    {-4.51909351, -5.73813772, 1.94176066},
-    {-4.48143482, -6.00635004, 1.53926146},
-    {-4.21184111, -6.29870653, 1.11382699},
-    {-3.72618818, -6.55698061, 0.649741769},
-    {-3.18907046, -6.77667665, 0.209767863},
-    {-2.67667961, -7.01396561, -0.201605037},
-    {-2.20336509, -7.27978897, -0.578706563},
-    {-1.79776239, -7.48802805, -0.91726321},
-    {-1.58113861, -7.60607862, -1.19742954},
-    {-1.56367278, -7.6176033, -1.42426229},
-    {-1.67324269, -7.49185181, -1.62952113},
-    {-1.81196356, -7.23257732, -1.76014578},
-    {-1.74199009, -6.82085848, -1.82193792},
-    {-1.48314917, -6.40829325, -1.86381173},
-    {-1.15523911, -5.99487495, -1.82720888},
-    {-0.566562653, -5.29956627, -1.58066905},
-    {-0.0104460977, -4.66794682, -1.27783585},
-    {0.419866711, -4.04944992, -0.95930022},
-    {0.674905956, -3.42054582, -0.612734735},
-    {0.667818427, -2.74897981, -0.280271918},
-    {0.361866444, -2.13294721, -0.0164464824},
-    {-0.101121388, -1.55372572, 0.192773551},
-    {-0.59252733, -1.07570565, 0.317237973},
-    {-1.21972179, -0.480338126, 0.449600935},
-    {-1.79682159, 0.0824001655, 0.574972868},
-    {-2.30576396, 0.527683735, 0.690541744},
-    {-2.87188125, 0.926534295, 0.797519505},
-    {-3.362257, 1.28097117, 0.914367914},
-    {-3.74464226, 1.59437859, 1.06141114},
-    {-3.92030096, 1.79884863, 1.23685491},
-    {-3.91187882, 1.94403338, 1.43153179},
-    {-3.80646539, 2.0350759, 1.61594629},
-    {-3.47092319, 2.10651064, 1.80243075},
-    {-2.83893967, 2.19933748, 2.01191926},
-    {-1.78523803, 2.35885477, 2.2841506},
-    {-0.583265305, 2.55203843, 2.55869555},
-    {0.355597496, 2.74097133, 2.77152467},
-    {1.09790313, 2.95338893, 2.91996121},
-    {1.66549516, 3.19732738, 2.99881196},
-    {1.99194336, 3.42121124, 3.01027656},
-    {2.15964222, 3.59241867, 2.94555855},
-    {2.30592322, 3.65938139, 2.77006102},
-    {2.66610312, 3.55054832, 2.38973475},
-    {3.40425014, 3.14751387, 1.64403605},
-    {4.31163836, 2.31371856, 0.545148492},
-    {4.54947615, 1.68996608, -0.133428112},
-    {4.22693205, 1.20241797, -0.428235114},
-    {3.83065605, 0.360066116, -0.772755265},
-    {3.12668991, -0.911781609, -1.20538557},
-    {1.92496753, -2.64645076, -1.67473435},
-    {1.03616047, -3.58417344, -1.78400457},
-    {0.891285181, -3.65468836, -1.61690807},
-    {0.853824794, -3.61608911, -1.36875367},
-    {0.865163445, -3.41820621, -1.10509777},
-    {0.795854092, -3.08451438, -0.871119082},
-    {0.602447867, -2.73764324, -0.68990165},
-    {0.293905646, -2.36346793, -0.531614602},
-    {0.0430312417, -1.93503404, -0.355568469},
-    {-0.0292861909, -1.50074708, -0.125346646},
-    {0.0023639265, -1.02723181, 0.152943179},
-    {0.0646150559, -0.519548178, 0.464782834},
-    {0.319261104, 0.00238977512, 0.801588356},
-    {0.512835681, 0.437917531, 1.06913304},
-    {0.602497816, 0.807607174, 1.29130328},
-    {0.706784308, 1.18500197, 1.52376211},
-    {0.901759028, 1.5427829, 1.73962772},
-    {1.07393265, 1.89456356, 1.92200661},
-    {1.17623651, 2.22797441, 2.07362771},
-    {1.24214709, 2.51201344, 2.18159437},
-    {1.36387289, 2.72985744, 2.23948741},
-    {1.48781264, 2.94874525, 2.28010368},
-    {1.53457403, 3.15570474, 2.28063607},
-    {1.51892376, 3.25747275, 2.24161506},
-    {1.49391925, 3.24370193, 2.15390801},
-    {1.63055599, 3.18640018, 2.0093894},
-    {1.68290246, 3.13343763, 1.84839201},
-    {1.60378373, 3.08356905, 1.71147251},
-    {1.49357009, 3.02197671, 1.5865761},
-    {1.52743089, 2.8536427, 1.42433763},
-    {1.51949048, 2.51333904, 1.24539793},
-    {1.37738669, 2.09793019, 1.10433221},
-    {0.990819514, 1.56093121, 1.02146387},
-    {0.662576675, 0.986895859, 0.979119539},
-    {0.267635286, 0.317756742, 0.95091635},
-    {-0.0716722906, -0.125119716, 0.926589966},
-    {-0.226716593, -0.421123952, 0.864964843},
-    {-0.291085571, -0.708265185, 0.773025632},
-    {-0.289206505, -0.914043307, 0.669230461},
-    {-0.262451291, -1.07284546, 0.549987435},
-    {-0.22568661, -1.21298766, 0.417806238},
-    {-0.21660845, -1.31441164, 0.284084707},
-    {-0.20835869, -1.38506258, 0.136170059},
-    {-0.242180005, -1.43811166, -0.0133401668},
-    {-0.331709087, -1.45831108, -0.149607658},
-    {-0.445298404, -1.44539058, -0.293793589},
-    {-0.555146456, -1.39545548, -0.434736907},
-    {-0.623239219, -1.29333663, -0.563022435},
-    {-0.748120308, -1.15623736, -0.674204171},
-    {-0.808193326, -0.991428852, -0.729941368},
-    {-0.750963807, -0.815319657, -0.748051465},
-    {-0.588453293, -0.613349736, -0.739005446},
-    {-0.328233689, -0.404229373, -0.707627475},
-    {-0.060481295, -0.180974916, -0.651057243},
-    {0.205469683, 0.0537305884, -0.574809551},
-    {0.452857733, 0.279984266, -0.498806566},
-    {0.684509516, 0.510156095, -0.419488519},
-    {0.955122113, 0.736619949, -0.374042779},
-    {1.19934738, 0.930836082, -0.359196186},
-    {1.42472816, 1.10409379, -0.339089692},
-    {1.65325129, 1.27592874, -0.332843333},
-    {1.85226679, 1.43177724, -0.347369581},
-    {2.05244875, 1.56109273, -0.38465178},
-    {2.20266008, 1.66691923, -0.440689921},
-    {2.32479668, 1.75445151, -0.493003249},
-    {2.42579794, 1.81341636, -0.559334397},
-    {2.52879524, 1.81790614, -0.637721241},
-    {2.5515101, 1.78571332, -0.716523647},
-    {2.52523637, 1.71436059, -0.792416334},
-    {2.47508502, 1.61058176, -0.85828191},
-    {2.36723256, 1.48756373, -0.91328907},
-    {2.3413372, 1.36014771, -0.964638472},
-    {2.34795499, 1.24177873, -1.00365329},
-    {2.315202, 1.10507488, -1.01472294},
-    {2.2110405, 0.942447722, -1.00195229},
-    {2.00978589, 0.765004814, -0.964504898},
-    {1.73104215, 0.579829574, -0.894748151},
-    {1.43226063, 0.413561136, -0.805137098},
-    {1.16283715, 0.263995677, -0.697566152},
-    {0.956718385, 0.117739804, -0.587686002},
-    {0.780385911, -0.0129254889, -0.485152394},
-    {0.570063651, -0.150278151, -0.374719024},
-    {0.305894852, -0.302080423, -0.247948706},
-    {0.0653965995, -0.43640554, -0.124964193},
-    {-0.127693757, -0.566457212, -0.00971193612},
-    {-0.307744831, -0.684809506, 0.0973616168},
-    {-0.415367186, -0.776924431, 0.190079689},
-    {-0.47665298, -0.842454672, 0.270962447},
-    {-0.454128176, -0.915390015, 0.324537933},
-    {-0.370187402, -0.992995501, 0.352390647},
-    {-0.229669392, -1.08897305, 0.367545813},
-    {-0.0203062538, -1.17476749, 0.371239901},
-    {0.117078029, -1.22918689, 0.403207451},
-    {0.0551700629, -1.24847591, 0.490972757},
-    {-0.0177293699, -1.24533319, 0.589081049},
-    {-0.0409629345, -1.22309792, 0.680960238},
-    {0.0927172378, -1.21648252, 0.716688275},
-    {0.236587211, -1.21762979, 0.74449116},
-    {0.329889804, -1.19918919, 0.785846174},
-    {0.391402751, -1.1698544, 0.824017704},
-    {0.406838804, -1.16856587, 0.852758348},
-    {0.448235035, -1.21081221, 0.857016265},
-    {0.40288344, -1.23754525, 0.850816786},
-    {0.336823881, -1.30341649, 0.818986952},
-    {0.211212099, -1.38122153, 0.797951818},
-    {0.0715824217, -1.43503141, 0.755432725},
-    {-0.117982708, -1.50149536, 0.689284444},
-    {-0.295442283, -1.52475893, 0.625364482},
-    {-0.382869512, -1.48402631, 0.550141037},
-    {-0.424231172, -1.44072068, 0.468461961},
-    {-0.393650264, -1.35543025, 0.408728123},
-    {-0.305851728, -1.22406518, 0.352307528},
-    {-0.0881919563, -1.05799758, 0.294872075},
-    {0.171652824, -0.893224359, 0.233380407},
-    {0.400423139, -0.707795978, 0.171285734},
-    {0.622934282, -0.484295756, 0.141408041},
-    {0.959215224, -0.279323518, 0.101054154},
-    {1.2117002, -0.0882709026, 0.0586645305},
-    {1.40287161, 0.118643634, 0.0248861127},
-    {1.65276754, 0.317674547, -0.0302325338},
-    {1.84489715, 0.517988205, -0.0932536051},
-    {1.91140652, 0.674786627, -0.166146979},
-    {1.93859911, 0.805827856, -0.260852486},
-    {1.84070694, 0.915243506, -0.345790952},
-    {1.73904657, 1.00114381, -0.449672431},
-    {1.71000683, 1.06335354, -0.566850483},
-    {1.62703049, 1.13409138, -0.683399796},
-    {1.48652256, 1.15293002, -0.799893022},
-    {1.3300066, 1.0788151, -0.938014507},
-    {1.09115994, 0.944143832, -1.05004191},
-    {0.918339789, 0.820411086, -1.13414884},
-    {0.740275145, 0.687976539, -1.20584643},
-    {0.56063062, 0.594631016, -1.24373949},
-    {0.404976398, 0.503846228, -1.27714646},
-    {0.199821532, 0.396716446, -1.29348361},
-    {0.0482193381, 0.301252097, -1.29271853},
-    {-0.0299014486, 0.211325124, -1.29369974},
-    {-0.0321266428, 0.136530519, -1.28363156},
-    {-0.0570558123, 0.0818887353, -1.2512635},
-    {-0.060015697, 0.0184675436, -1.22836614},
-    {-0.0900301561, -0.0405953415, -1.17533672},
-    {-0.0896270499, -0.0948900729, -1.11598408},
-    {-0.0394961014, -0.134664491, -1.05188775},
-    {0.0479699001, -0.178613633, -0.989663839},
-    {0.174130455, -0.231176406, -0.922600985},
-    {0.317890555, -0.276856452, -0.839688599},
-    {0.462751597, -0.328220397, -0.754636347},
-    {0.60492599, -0.378177881, -0.668817103},
-    {0.7762326, -0.407422096, -0.575530529},
-    {0.84362793, -0.432531118, -0.460644096},
-    {0.891411126, -0.500263095, -0.370736212},
-    {0.931746125, -0.557534218, -0.290296197},
-    {0.994066119, -0.602125466, -0.208971441},
-    {1.07374978, -0.639556289, -0.128955036},
-    {1.07241023, -0.667185247, -0.032570608},
-    {0.98789686, -0.707633257, 0.0581823066},
-    {0.892033517, -0.737281978, 0.138431549},
-    {0.903338075, -0.767770171, 0.183936298},
-    {0.816754341, -0.775816858, 0.246401504},
-    {0.742554426, -0.764663458, 0.318989903},
-    {0.684260249, -0.779585004, 0.37071532},
-    {0.644381881, -0.796794891, 0.399778932},
-    {0.650072038, -0.770721912, 0.437595189},
-    {0.634175122, -0.772284985, 0.449817151},
-    {0.586704254, -0.779074013, 0.448394656},
-    {0.584276557, -0.783939481, 0.438200265},
-    {0.599038959, -0.794533849, 0.42681998},
-    {0.578996599, -0.776510179, 0.436285108},
-    {0.599903703, -0.760379016, 0.435533285},
-    {0.670066893, -0.737319648, 0.419971138},
-    {0.704812944, -0.717427552, 0.409193695},
-    {0.741096318, -0.693665326, 0.401494712},
-    {0.856747866, -0.652426779, 0.382837474},
-    {0.978784382, -0.599265337, 0.37578702},
-    {1.03203404, -0.529142439, 0.385411888},
-    {1.21000373, -0.46272856, 0.367589146},
-    {1.4150337, -0.402067602, 0.355899274},
-    {1.52077127, -0.301946342, 0.349518418},
-    {1.65056312, -0.250210524, 0.31642428},
-    {1.8072896, -0.20982638, 0.28076309},
-    {1.85818374, -0.145955235, 0.258206755},
-    {1.88182962, -0.118900627, 0.219113111},
-    {1.89208925, -0.0872233212, 0.188300461},
-    {1.85128272, -0.0827668831, 0.163457438},
-    {1.84005857, -0.11550843, 0.132694691},
-    {1.94997299, -0.236663818, 0.0841560513},
-    {1.94779456, -0.355707347, 0.0163449515},
-    {1.76927114, -0.509604335, -0.0458457023},
-    {1.44283664, -0.700882196, -0.0906263068},
-    {1.1515919, -0.924517274, -0.139347866},
-    {0.940884829, -1.15567088, -0.167656258},
-    {0.670824349, -1.37232506, -0.196849287},
-    {0.375701338, -1.58784747, -0.255514711},
-    {0.0287599228, -1.77963889, -0.313429326},
-    {-0.244943574, -1.92604184, -0.402142823},
-    {-0.453076035, -2.05188751, -0.513777792},
-    {-0.653091073, -2.11482167, -0.631723702},
-    {-0.724208593, -2.19206142, -0.785332561},
-    {-0.753542244, -2.20303965, -0.966025054},
-    {-0.753059089, -2.14568448, -1.12658298},
-    {-0.682637155, -2.07715797, -1.24436283},
-    {-0.513026297, -1.95510483, -1.3037765},
-    {-0.233426467, -1.79981101, -1.31563926},
-    {0.099934034, -1.63961101, -1.29979968},
-    {0.439953983, -1.46068919, -1.22686958},
-    {0.742975473, -1.30892062, -1.11647284},
-    {1.09124315, -1.1786195, -0.976593733},
-    {1.50205076, -1.12470984, -0.824725509},
-    {1.93785071, -1.18237746, -0.611880541},
-    {2.3054924, -1.27637362, -0.352338046},
-    {2.5724895, -1.27876973, -0.108073369},
-    {2.78349066, -1.10696828, 0.105359428},
-    {2.81725025, -0.874999464, 0.293193161},
-    {2.59833503, -0.688460648, 0.48352322},
-    {2.2610321, -0.574905038, 0.683830202},
-    {1.74071121, -0.469013572, 0.849510729},
-    {1.06405544, -0.36395511, 0.973798394},
-    {0.375102669, -0.309978902, 1.08316433},
-    {-0.440482736, -0.221823126, 1.09560478},
-    {-1.48913169, -0.11770644, 1.04561853},
-    {-2.50943971, -0.0928470865, 1.03956521},
-    {-3.43469, -0.148316488, 1.05685782},
-    {-4.03028965, -0.229613304, 1.06492269},
-    {-4.29124165, -0.263286084, 1.01530313},
-    {-4.21287155, -0.271716684, 0.951882064},
-    {-3.85228276, -0.254273385, 0.901913285},
-    {-3.28179097, -0.235350162, 0.868972361},
-    {-2.55515814, -0.215761751, 0.850148976},
-    {-1.75784814, -0.107531764, 0.816213548},
-    {-0.895271003, 0.0236186292, 0.798526168},
-    {-0.00818459224, 0.107496634, 0.787575543},
-    {0.816041052, 0.178134575, 0.783917367},
-    {1.46673739, 0.287328005, 0.7628088},
-    {1.84466457, 0.413195282, 0.740982652},
-    {1.98835027, 0.528438985, 0.714710057},
-    {1.8126713, 0.658266366, 0.665721714},
-    {1.3446449, 0.74212414, 0.61824733},
-    {0.750417411, 0.76282692, 0.608625054},
-    {0.020283429, 0.838685811, 0.555125594},
-    {-0.798513949, 0.965545714, 0.461584628},
-    {-1.46911144, 1.0072031, 0.428845376},
-    {-1.87247431, 1.00984323, 0.441536188},
-    {-2.29175043, 1.15747714, 0.388443291},
-    {-2.43678403, 1.26596427, 0.391065389},
-    {-2.26951337, 1.33087325, 0.432423681},
-    {-1.90814257, 1.38132441, 0.473828733},
-    {-1.60110104, 1.60946643, 0.43375349},
-    {-1.26517534, 1.78817272, 0.397708207},
-    {-0.815582335, 1.90136456, 0.402442485},
-    {-0.33094418, 1.9856379, 0.399299681},
-    {0.132650882, 2.19461298, 0.34211728},
-    {0.558681667, 2.36308885, 0.280439079},
-    {0.902205408, 2.45252395, 0.219862491},
-    {1.13703775, 2.45259094, 0.164375558},
-    {1.25288463, 2.47784209, 0.0742009431},
-    {1.29244626, 2.5076561, -0.0327479765},
-    {1.29464674, 2.5354991, -0.118715629},
-    {1.24247646, 2.53771234, -0.209538355},
-    {1.1364727, 2.52283883, -0.31336537},
-    {0.970686376, 2.46289325, -0.436216831},
-    {0.805665016, 2.36076045, -0.54234004},
-    {0.704995811, 2.23022652, -0.650924325},
-    {0.689498127, 2.04909229, -0.768970072},
-    {0.750591278, 1.83599794, -0.89087373},
-    {0.769930303, 1.5959655, -0.98687011},
-    {0.727697968, 1.33228433, -1.07048035},
-    {0.642912149, 1.03561091, -1.13141167},
-    {0.51982075, 0.696960926, -1.17264402},
-    {0.24257344, 0.361580402, -1.18248785},
-    {-0.136114329, 0.0183047801, -1.15292573},
-    {-0.592926383, -0.311758161, -1.10613},
-    {-1.09354305, -0.619928539, -1.05235016},
-    {-1.64629328, -0.894355059, -0.986820281},
-    {-2.17719197, -1.1417706, -0.919724226},
-    {-2.74633598, -1.35644841, -0.850185752},
-    {-3.27548909, -1.51657772, -0.790038228},
-    {-3.73148298, -1.62905443, -0.735949039},
-    {-4.13651323, -1.6979115, -0.686409354},
-    {-4.51641607, -1.74021435, -0.637824416},
-    {-4.89608765, -1.76583624, -0.594658852},
-    {-5.21672821, -1.7849288, -0.551117241},
-    {-5.49513006, -1.78695703, -0.515152454},
-    {-5.76973438, -1.77890921, -0.482261211},
-    {-5.95562363, -1.75937068, -0.464418799},
-    {-6.08877659, -1.73490942, -0.455664605},
-    {-6.24075365, -1.69182634, -0.462511897},
-    {-6.35525751, -1.63982809, -0.482244581},
-    {-6.41531849, -1.56162381, -0.51092875},
-    {-6.38393927, -1.45948446, -0.528241575},
-    {-6.23349285, -1.38361323, -0.525163889},
-    {-5.91877508, -1.30433118, -0.470089078},
-    {-5.34485865, -1.23073351, -0.373527288},
-    {-4.53941107, -1.20041037, -0.247269958},
-    {-3.6322875, -1.16761148, -0.0853384361},
-    {-2.77812576, -1.13939059, 0.0986437798},
-    {-1.88444686, -1.12298036, 0.295072168},
-    {-0.926245153, -1.10144651, 0.49704212},
-    {0.0282600727, -1.06551182, 0.696085036},
-    {0.986234128, -0.994042873, 0.902412176},
-    {1.91580868, -0.888656974, 1.10665023},
-    {2.7470777, -0.741439104, 1.29427981},
-    {3.40486836, -0.569467008, 1.46046543},
-    {3.83933902, -0.346644849, 1.58842158},
-    {4.09994078, -0.113296829, 1.65009701},
-    {4.14822912, 0.11793986, 1.6467824},
-    {3.93950844, 0.37346977, 1.57373893},
-    {3.51443338, 0.598885894, 1.44037807},
-    {3.0659616, 0.754748702, 1.25662529},
-    {2.51761293, 0.870501399, 1.07113981},
-    {1.88786459, 0.921912611, 0.898884356},
-    {1.15069008, 0.896902263, 0.753270924},
-    {0.423874229, 0.794121444, 0.656226993},
-    {-0.339365274, 0.663402498, 0.587985516},
-    {-1.06322885, 0.570537627, 0.521465003},
-    {-1.6261394, 0.514196932, 0.453259289},
-    {-2.15406251, 0.457297623, 0.392813087},
-    {-2.51430225, 0.381700933, 0.349597096},
-    {-2.77551651, 0.334578365, 0.341836393},
-    {-2.89900398, 0.323834151, 0.36831978},
-    {-2.84296465, 0.32070753, 0.419170827},
-    {-2.70350122, 0.307704002, 0.501049519},
-    {-2.49887061, 0.307038784, 0.585821748},
-    {-2.18286133, 0.254369259, 0.677493334},
-    {-1.67422915, 0.13267222, 0.763281345},
-    {-1.2889657, 0.0715087727, 0.847343147},
-    {-1.033283, -0.00374815869, 0.935369909},
-    {-0.82376343, -0.146038398, 1.02162182},
-    {-0.654668152, -0.250182837, 1.08923364},
-    {-0.598197699, -0.33929503, 1.12377107},
-    {-0.520315826, -0.437151313, 1.08434975},
-    {-0.419304907, -0.512853861, 0.980354309},
-    {-0.203128278, -0.586078346, 0.811617851},
-    {-0.0197913069, -0.671798885, 0.652202845},
-    {0.0607572347, -0.691204488, 0.500434339},
-    {0.180832312, -0.695917785, 0.323504269},
-    {0.154128909, -0.630856454, 0.126208559},
-    {0.00471913163, -0.532119334, -0.0965460613},
-    {-0.29281497, -0.322666466, -0.337376922},
-    {-0.589733839, -0.0609502681, -0.564223051},
-    {-0.690635622, 0.133320719, -0.728479743},
-    {-0.687127054, 0.340478837, -0.879533112},
-    {-0.746463537, 0.517700553, -0.998290539},
-    {-0.887517154, 0.763424993, -1.09784901},
-    {-0.774859071, 0.922185063, -1.24748099},
-    {-0.436186045, 0.92902863, -1.4561435},
-    {0.180598974, 0.787902355, -1.71047688},
-    {0.779458046, 0.52573055, -1.95757663},
-    {1.07933688, 0.219789028, -2.07718539},
-    {1.36810791, 0.0498123057, -2.14644337},
-    {1.49302173, 0.0626688302, -2.1898005},
-    {1.56909657, 0.0322203413, -2.19243193},
-    {1.67965603, -0.033094272, -2.18813562},
-    {1.70480227, -0.0675185248, -2.15781713},
-    {1.71552753, -0.0764812976, -2.09238386},
-    {1.69515908, -0.163580984, -1.98026383},
-    {1.65059304, -0.220068574, -1.8498069},
-    {1.63564324, -0.217824146, -1.68902111},
-    {1.60025859, -0.177383155, -1.49374056},
-    {1.55414605, -0.125887856, -1.309515},
-    {1.5198431, -0.0609835275, -1.13965285},
-    {1.54864371, 0.0323357284, -0.958069742},
-    {1.62932539, 0.147072494, -0.763116896},
-    {1.63689101, 0.237947389, -0.566617668},
-    {1.63203573, 0.315818697, -0.346323073},
-    {1.59576905, 0.413694143, -0.140944198},
-    {1.4296999, 0.553706288, 0.056253396},
-    {1.18300879, 0.747766614, 0.24511157},
-    {0.961184025, 0.945924222, 0.426013142},
-    {0.749111474, 1.12215233, 0.567048192},
-    {0.495010942, 1.30445063, 0.678741992},
-    {0.269500554, 1.44970405, 0.813746393},
-    {0.085600242, 1.5629077, 0.939144611},
-    {-0.0997111872, 1.68665934, 1.01003242},
-    {-0.346202075, 1.80504203, 1.06841862},
-    {-0.711770356, 1.89975154, 1.18567884},
-    {-1.11323285, 1.99774325, 1.28796101},
-    {-1.55763018, 2.05205202, 1.38424015},
-    {-1.89335978, 2.07958889, 1.45361447},
-    {-2.19135976, 2.03510761, 1.50910378},
-    {-2.44710636, 1.99488318, 1.51334393},
-    {-2.56387162, 1.90380907, 1.49806213},
-    {-2.50484014, 1.79426026, 1.4410764},
-    {-2.3798275, 1.70162296, 1.33097911},
-    {-2.22814155, 1.53287673, 1.24753714},
-    {-2.052212, 1.3698175, 1.13752306},
-    {-1.72659886, 1.18933952, 0.978846371},
-    {-1.29137409, 1.00666702, 0.78998667},
-    {-0.949031413, 0.863069117, 0.602451324},
-    {-0.584329486, 0.715950608, 0.400796235},
-    {-0.215076625, 0.547121406, 0.194652557},
-    {0.12454021, 0.341426134, 0.010917509},
-    {0.403993428, 0.130075499, -0.148857206},
-    {0.672320843, -0.0987302512, -0.295456409},
-    {0.812368453, -0.327374905, -0.417062253},
-    {0.73122561, -0.527238071, -0.483435869},
-    {0.714669108, -0.688921332, -0.5642156},
-    {0.662077725, -0.833162129, -0.646218419},
-    {0.54446429, -0.979360044, -0.672740877},
-    {0.429594427, -1.11120737, -0.670845151},
-    {0.329097152, -1.23320782, -0.662930548},
-    {0.246316493, -1.2967416, -0.652167141},
-    {0.163870662, -1.31597102, -0.622772157},
-    {0.124282196, -1.27940476, -0.598109484},
-    {0.128256157, -1.25463617, -0.546705842},
-    {0.101896182, -1.19050872, -0.505008996},
-    {0.0517944694, -1.11752629, -0.471336216},
-    {0.0101359934, -1.02890897, -0.422544569},
-    {0.026107695, -0.901175916, -0.367212206},
-    {0.0263573639, -0.72987783, -0.274069101},
-    {0.0253181104, -0.543098509, -0.145218238},
-    {0.0428982116, -0.370589912, 0.00485464837},
-    {0.0115035623, -0.215844885, 0.140593231},
-    {-0.109621584, -0.0642855391, 0.260155797},
-    {-0.285215706, 0.0788124427, 0.358526587},
-    {-0.382503361, 0.219075605, 0.426768422},
-    {-0.413804054, 0.33023563, 0.508931577},
-    {-0.431049824, 0.438222289, 0.636278749},
-    {-0.465395331, 0.519151688, 0.745571494},
-    {-0.556349576, 0.556606531, 0.839155734},
-    {-0.637773454, 0.556017578, 0.914733946},
-    {-0.767377198, 0.539130092, 0.94803226},
-    {-0.860096872, 0.488273084, 0.918309033},
-    {-0.851732612, 0.416487694, 0.843015134},
-    {-0.7395733, 0.260362595, 0.752472878},
-    {-0.562649131, 0.0791814998, 0.643115103},
-    {-0.339358211, -0.105498068, 0.497407973},
-    {-0.0765177384, -0.293077856, 0.333587319},
-    {0.253498346, -0.48010534, 0.16390644},
-    {0.653296888, -0.604566157, -0.0388472453},
-    {1.04299891, -0.723798871, -0.274181962},
-    {1.35690415, -0.851105869, -0.480071574},
-    {1.63703001, -0.977536023, -0.640533447},
-    {1.87491632, -1.10103405, -0.778415024},
-    {2.11435246, -1.20246148, -0.898636997},
-    {2.32535791, -1.28719282, -1.00277305},
-    {2.53248668, -1.36931539, -1.06425941},
-    {2.76031423, -1.45119429, -1.09879661},
-    {2.98740959, -1.53774571, -1.08697367},
-    {3.17033958, -1.60675395, -1.01876366},
-    {3.25622582, -1.60687041, -0.933958173},
-    {3.28803658, -1.52765191, -0.850965261},
-    {3.35466743, -1.40242279, -0.751293898},
-    {3.39414287, -1.23548901, -0.635110557},
-    {3.46617794, -1.04885054, -0.527490735},
-    {3.61950946, -0.817198694, -0.409444928},
-    {3.77354288, -0.563794196, -0.295579374},
-    {3.82223845, -0.305364758, -0.196316168},
-    {3.7938416, -0.0219696835, -0.145484865},
-    {3.67195559, 0.371441066, -0.169661641},
-    {3.54809046, 0.801454604, -0.241297305},
-    {3.35676885, 1.19793391, -0.363786489},
-    {3.12120032, 1.57405746, -0.514109612},
-    {2.74353576, 1.92481089, -0.697001934},
-    {2.30878305, 2.2158761, -0.874245226},
-    {1.9097296, 2.44812465, -1.04532599},
-    {1.62538433, 2.69599128, -1.21922064},
-    {1.44693649, 2.95122862, -1.36599672},
-    {1.4311595, 3.13213468, -1.46808445},
-    {1.45933211, 3.25030279, -1.5527885},
-    {1.44844019, 3.32305264, -1.62334347},
-    {1.38764632, 3.34355569, -1.66970348},
-    {1.22704792, 3.27213669, -1.66795778},
-    {0.890387237, 3.14708924, -1.60195911},
-    {0.285691231, 2.9971838, -1.45882082},
-    {-0.491678387, 2.81945801, -1.25223732},
-    {-1.17468166, 2.63869452, -1.02093828},
-    {-1.78039062, 2.39831543, -0.777818501},
-    {-2.25338411, 2.12094402, -0.533776402},
-    {-2.59075975, 1.85033154, -0.317006975},
-    {-2.87967348, 1.62325203, -0.105704628},
-    {-2.91978884, 1.30692029, 0.0522932932},
-    {-2.53361106, 0.93030405, 0.0937174559},
-    {-1.56783974, 0.491000086, -0.0304476973},
-    {-0.0790719688, 0.0420800522, -0.308293641},
-    {1.43285978, -0.333437771, -0.672008634},
-    {2.89518619, -0.704207361, -1.01154494},
-    {4.34802151, -1.12269783, -1.28338993},
-    {5.24700832, -1.57431173, -1.4130255},
-    {5.29946327, -1.97188926, -1.41698456},
-    {4.55399895, -2.33227301, -1.32752204},
-    {3.18338203, -2.66673517, -1.15139389},
-    {1.31054151, -2.93238664, -0.971245766},
-    {-0.908186495, -3.06292963, -0.86904043},
-    {-3.37201762, -3.06515837, -0.939246058},
-    {-5.87698746, -2.94889188, -1.16286635},
-    {-8.41957092, -2.79233432, -1.42390096},
-    {-10.6654921, -2.46840239, -1.77704525},
-    {-12.5844612, -2.03085089, -2.05382037},
-    {-14.4325256, -1.54572713, -2.17353129},
-    {-16.2981033, -1.02416313, -2.14073253},
-    {-17.4023647, -0.617456973, -1.98428845},
-    {-17.4384956, -0.314435422, -1.80893409},
-    {-16.9294758, -0.125059247, -1.68756974},
-    {-15.4587717, 0.00168936839, -1.65610147},
-    {-13.9873638, 0.16667752, -1.63366973},
-    {-12.5905876, 0.357273608, -1.61278427},
-    {-11.3475847, 0.575290024, -1.63207376},
-    {-10.2720728, 0.816436887, -1.67176545},
-    {-9.34973621, 1.06210685, -1.68061244},
-    {-8.56394005, 1.30759346, -1.6293298},
-    {-7.89480734, 1.53129685, -1.55541563},
-    {-7.29528332, 1.66839921, -1.45419776},
-    {-6.86030865, 1.70153809, -1.30317485},
-    {-6.51670361, 1.60758841, -1.12611747},
-    {-6.26217699, 1.39926708, -0.961238623},
-    {-6.0232687, 1.11027944, -0.833023071},
-    {-5.67305613, 0.789166033, -0.787178338},
-    {-5.11486912, 0.451723605, -0.840007126},
-    {-4.41012001, 0.151379332, -0.968928039},
-    {-3.56351614, -0.117448412, -1.15540874},
-    {-2.79071736, -0.33867979, -1.33959436},
-    {-2.19993997, -0.523439229, -1.50553024},
-    {-1.7077024, -0.688826501, -1.6657629},
-    {-1.3395431, -0.839315772, -1.80492473},
-    {-1.17622638, -0.974212706, -1.89885569},
-    {-1.15430522, -1.08046126, -1.95253825},
-    {-1.30569124, -1.16184127, -1.95411777},
-    {-1.64650941, -1.21056271, -1.86967838},
-    {-2.10488272, -1.22533906, -1.74860156},
-    {-2.70118976, -1.20505881, -1.54658616},
-    {-3.40100646, -1.15319121, -1.30439973},
-    {-3.99094748, -1.09547698, -1.08612585},
-    {-4.56685495, -1.03984141, -0.839479089},
-    {-5.24769402, -1.00136757, -0.591609299},
-    {-5.84492731, -0.975967765, -0.405187994},
-    {-6.46041536, -0.988073409, -0.205180153},
-    {-7.20408535, -1.03598762, -0.00701307599},
-    {-7.85890865, -1.11235595, 0.140938163},
-    {-8.32161903, -1.21880889, 0.236130133},
-    {-8.694067, -1.3400656, 0.285981715},
-    {-8.92911816, -1.43473196, 0.245934919},
-    {-9.15819263, -1.49896777, 0.151751012},
-    {-9.36768723, -1.57621086, 0.0510839447},
-    {-9.42681026, -1.65491021, -0.0622247979},
-    {-9.27151775, -1.69885921, -0.202070609},
-    {-8.89008999, -1.66211033, -0.357514054},
-    {-8.44687462, -1.57474411, -0.479268044},
-    {-7.98561668, -1.44233131, -0.559550583},
-    {-7.48500824, -1.24892926, -0.608558357},
-    {-6.95847273, -0.971760631, -0.613975763},
-    {-6.39120436, -0.640904188, -0.550276101},
-    {-5.85547018, -0.297507554, -0.398386925},
-    {-5.41559029, 0.00126106013, -0.167340189},
-    {-5.08239698, 0.211334229, 0.0945756957},
-    {-4.89239645, 0.369745016, 0.373641908},
-    {-4.77280378, 0.473207653, 0.659885228},
-    {-4.65658808, 0.522167027, 0.921152472},
-    {-4.53349638, 0.511479974, 1.14323211},
-    {-4.36470652, 0.447666258, 1.30686748},
-    {-4.11785603, 0.354862541, 1.41152763},
-    {-3.79640365, 0.251998931, 1.46903467},
-    {-3.44569898, 0.154222772, 1.49116147},
-    {-3.09061337, 0.0804002061, 1.47621441},
-    {-2.73385572, 0.0223843157, 1.41517889},
-    {-2.3920989, -0.0188801084, 1.31451666},
-    {-2.12878609, -0.0558120385, 1.17230952},
-    {-2.04469585, -0.0920788348, 1.00537586},
-    {-2.01148915, -0.117803141, 0.826170564},
-    {-1.98225546, -0.123606503, 0.644320905},
-    {-1.99567497, -0.128628343, 0.472831041},
-    {-2.08167791, -0.11929974, 0.292278558},
-    {-2.19154167, -0.0890857056, 0.0999032632},
-    {-2.30750966, -0.0409960374, -0.100586779},
-    {-2.45046496, 0.0262164343, -0.30606541},
-    {-2.54660058, 0.118438691, -0.488333106},
-    {-2.51258922, 0.221268982, -0.643241763},
-    {-2.36639047, 0.352893323, -0.768905818},
-    {-2.16192722, 0.49524036, -0.858863771},
-    {-1.91469407, 0.667727947, -0.926508725},
-    {-1.65816617, 0.921271801, -1.07511485},
-    {-1.41857815, 1.20689964, -1.2329421},
-    {-1.14381921, 1.44058287, -1.34672856},
-    {-0.874364078, 1.67165911, -1.47504723},
-    {-0.663032293, 1.88791203, -1.6141479},
-    {-0.479070961, 2.06500554, -1.73744845},
-    {-0.31621024, 2.19917631, -1.82011425},
-    {-0.211420491, 2.30308628, -1.87060201},
-    {-0.19322674, 2.37669086, -1.8849268},
-    {-0.299532861, 2.40414429, -1.84234071},
-    {-0.610968411, 2.32736707, -1.71722305},
-    {-1.1519382, 2.09947538, -1.50903988},
-    {-1.72852123, 1.76722252, -1.23556626},
-    {-2.38696074, 1.35157573, -0.919325113},
-    {-2.99652886, 0.903670013, -0.614324808},
-    {-3.49248719, 0.407295197, -0.343582332},
-    {-3.77171731, -0.119313672, -0.15955098},
-    {-3.94755602, -0.671555042, -0.0602243394},
-    {-4.10526657, -1.17478478, -0.0612818003},
-    {-4.27991676, -1.65481818, -0.132785141},
-    {-4.4823103, -2.09158063, -0.266917557},
-    {-4.37385845, -2.43402481, -0.489881009},
-    {-3.87074184, -2.6790669, -0.760237336},
-    {-3.12782884, -2.83609247, -1.05519426},
-    {-2.31012011, -2.92486382, -1.34263742},
-    {-1.63001394, -2.95827055, -1.59442627},
-    {-1.14003813, -2.9587357, -1.78661871},
-    {-0.748170376, -2.90873408, -1.9176681},
-    {-0.357050925, -2.79961681, -1.97131145},
-    {-0.0213715229, -2.61816835, -1.97428179},
-    {0.2437042, -2.36323547, -1.94061565},
-    {0.567428231, -2.07960248, -1.85605955},
-    {1.07968628, -1.77157581, -1.7208699},
-    {1.56331038, -1.44176579, -1.55939007},
-    {1.83389533, -1.10040557, -1.40982306},
-    {2.14576507, -0.761446536, -1.24608886},
-    {2.48268414, -0.425513923, -1.08526099},
-    {2.89237761, -0.0799067691, -0.916348696},
-    {3.39211464, 0.282716364, -0.749213398},
-    {3.75113583, 0.645091832, -0.611846626},
-    {3.92698431, 0.978219748, -0.494944155},
-    {4.13414621, 1.29247797, -0.407881856},
-    {4.41292238, 1.57787323, -0.353356898},
-    {4.66721725, 1.84993327, -0.34801662},
-    {4.81742144, 2.05790186, -0.380549341},
-    {4.98748779, 2.20869279, -0.453227788},
-    {5.21495533, 2.30719495, -0.532885373},
-    {5.49306679, 2.33278108, -0.606920362},
-    {5.80378199, 2.31524849, -0.686592519},
-    {6.10760069, 2.26727509, -0.779545903},
-    {6.35566616, 2.17955971, -0.875209689},
-    {6.61184359, 2.06174684, -0.956822455},
-    {6.83016014, 1.91980553, -1.01053238},
-    {6.98572826, 1.75869977, -1.02309012},
-    {7.06834745, 1.59573233, -0.980734289},
-    {7.13969707, 1.45429766, -0.90081805},
-    {7.19953012, 1.31128514, -0.808230162},
-    {7.25252581, 1.16861224, -0.698864222},
-    {7.28832579, 1.03799534, -0.578141272},
-    {7.29203224, 0.922976792, -0.443877548},
-    {7.30859709, 0.854000807, -0.305450112},
-    {7.25277472, 0.822622597, -0.16661863},
-    {7.16031933, 0.808538318, -0.00839828141},
-    {7.03224754, 0.808782399, 0.155103892},
-    {6.89572668, 0.832250416, 0.314510912},
-    {6.81186438, 0.879530311, 0.457905531},
-    {6.79595566, 0.962418556, 0.574564338},
-    {6.79678679, 1.08743203, 0.659270048},
-    {6.75945568, 1.23208344, 0.715906799},
-    {6.70963717, 1.39693844, 0.7433604},
-    {6.66089916, 1.57165432, 0.724603355},
-    {6.72686434, 1.73426461, 0.652236104},
-    {6.92073011, 1.87621617, 0.507668853},
-    {7.19781733, 1.96644855, 0.300892144},
-    {7.58665466, 1.9984256, 0.0697552189},
-    {7.98806715, 1.94838989, -0.174031913},
-    {8.23289776, 1.82598686, -0.384497255},
-    {8.24710846, 1.65329313, -0.532691956},
-    {8.14684105, 1.44732285, -0.59731406},
-    {7.91758299, 1.24600124, -0.582514465},
-    {7.57156658, 1.07893503, -0.523138404},
-    {7.12058067, 0.949340522, -0.385715991},
-    {6.63164997, 0.881778657, -0.194996566},
-    {6.1373167, 0.876086295, -0.017687574},
-    {5.73701859, 0.909007728, 0.149023905},
-    {5.42209053, 0.948733211, 0.280804932},
-    {5.13363838, 0.99078089, 0.370480418},
-    {4.94985771, 1.06365299, 0.425423145},
-    {4.81021118, 1.18635488, 0.455038488},
-    {4.79043722, 1.31843746, 0.413843215},
-    {4.73057747, 1.42349422, 0.333018422},
-    {4.68819571, 1.52923048, 0.226906851},
-    {4.66437817, 1.59614861, 0.0950048193},
-    {4.67766523, 1.60637474, -0.055174306},
-    {4.7812438, 1.56097877, -0.219264522},
-    {4.96987677, 1.44660783, -0.3820557},
-    {5.12420988, 1.27875209, -0.505715966},
-    {5.28591967, 1.06896901, -0.577953756},
-    {5.46261597, 0.846110165, -0.60839653},
-    {5.57721758, 0.619239271, -0.589016259},
-    {5.62141705, 0.392293334, -0.52717483},
-    {5.62843895, 0.184114292, -0.435412049},
-    {5.60325766, 0.0115999673, -0.32237798},
-    {5.50569963, -0.128179371, -0.165970117},
-    {5.35255098, -0.230494633, 0.0246758405},
-    {5.1812439, -0.287912905, 0.220210597},
-    {5.17715216, -0.322915971, 0.374041021},
-    {5.20791578, -0.338081151, 0.515034199},
-    {5.20879745, -0.342221707, 0.662845075},
-    {5.30861712, -0.332809895, 0.779976368},
-    {5.48474693, -0.323215246, 0.863251925},
-    {5.61814117, -0.318259954, 0.928302765},
-    {5.68761492, -0.320022553, 0.992256045},
-    {5.65713453, -0.330747962, 1.04899251},
-    {5.57188034, -0.347891927, 1.09613442},
-    {5.37728167, -0.332937866, 1.14380109},
-    {5.26348734, -0.299120516, 1.16035378},
-    {5.04289389, -0.276771784, 1.13579333},
-    {4.74941397, -0.30572471, 1.09304202},
-    {4.44188929, -0.353994608, 1.03726947},
-    {4.18476868, -0.449728489, 0.96528548},
-    {3.9364655, -0.583800793, 0.903709114},
-    {3.75862408, -0.706386209, 0.848652065},
-    {3.67057586, -0.807471097, 0.77478832},
-    {3.63716912, -0.871108413, 0.707259834},
-    {3.59807539, -0.919813156, 0.67771101},
-    {3.58219457, -0.993959665, 0.673902988},
-    {3.58939481, -1.06938684, 0.676646709},
-    {3.64165854, -1.13433778, 0.701722503},
-    {3.72458792, -1.17517531, 0.757664859},
-    {3.77041483, -1.18230236, 0.816084445},
-    {3.84664488, -1.16225123, 0.892897367},
-    {3.93154383, -1.10944486, 0.992289364},
-    {3.93738532, -1.02334583, 1.08022201},
-    {4.05830193, -0.915148199, 1.13344836},
-    {4.24202681, -0.812838912, 1.20757401},
-    {4.36639547, -0.708122134, 1.25681257},
-    {4.58075666, -0.61760205, 1.27370143},
-    {4.94533491, -0.527581394, 1.2704072},
-    {5.27982473, -0.411948591, 1.26338148},
-    {5.62728643, -0.289027005, 1.24557495},
-    {6.09077406, -0.176551729, 1.21607614},
-    {6.42249441, -0.0424593538, 1.16969883},
-    {6.65549564, 0.0943102017, 1.06558776},
-    {6.80427027, 0.223879606, 0.952314377},
-    {6.69763136, 0.347396284, 0.872181535},
-    {6.34673643, 0.429225236, 0.81630981},
-    {5.67126989, 0.530127048, 0.833503902},
-    {4.72902298, 0.629685938, 0.854315877},
-    {3.51978731, 0.703744233, 0.939055502},
-    {2.10242343, 0.757954359, 1.09768093},
-    {0.634416997, 0.756893098, 1.28260231},
-    {-0.803493381, 0.676956832, 1.4745661},
-    {-2.09887171, 0.539305985, 1.62335813},
-    {-3.24517512, 0.365820676, 1.79652762},
-    {-4.10748053, 0.117751077, 1.95963025},
-    {-4.67251778, -0.15546675, 2.0798111},
-    {-4.8751893, -0.434087604, 2.1476078},
-    {-4.57642126, -0.717793524, 2.14156961},
-    {-3.83752775, -0.908299327, 2.01737309},
-    {-2.84887314, -0.987371802, 1.86520088},
-    {-1.80642581, -0.974238336, 1.68461764},
-    {-0.667694807, -0.989725947, 1.50075185},
-    {0.340199441, -0.960237145, 1.39147329},
-    {1.31014693, -0.925395608, 1.31757641},
-    {2.30392742, -0.879339397, 1.24457729},
-    {3.14102364, -0.764253438, 1.2011435},
-    {3.96164083, -0.627484024, 1.11341131},
-    {4.82674026, -0.503484964, 0.960944653},
-    {5.58766174, -0.37910372, 0.78717649},
-    {6.07231569, -0.231542215, 0.651022255},
-    {6.31411123, -0.0689319521, 0.478335053},
-    {6.23648834, 0.0863118991, 0.24418892},
-    {5.94790125, 0.178783089, -0.0296495259},
-    {5.48183632, 0.186432227, -0.287707537},
-    {4.77401114, 0.080126591, -0.443442106},
-    {3.66221118, -0.063128598, -0.524098575},
-    {2.29711032, -0.200413644, -0.531830728},
-    {0.74828738, -0.262554944, -0.445861876},
-    {-0.942574203, -0.262886971, -0.337875754},
-    {-2.63123846, -0.26631096, -0.232161179},
-    {-3.93000412, -0.256900728, -0.185658276},
-    {-4.97435713, -0.231192991, -0.158271104},
-    {-5.57760763, -0.186678484, -0.151619717},
-    {-5.65512943, -0.160604984, -0.131416067},
-    {-5.23434448, -0.198335081, -0.105907902},
-    {-4.40942144, -0.252544045, -0.16465649},
-    {-3.17271948, -0.27906552, -0.316251069},
-    {-1.67057633, -0.271738172, -0.477411002},
-    {-0.0877726898, -0.257426292, -0.645516038},
-    {1.53238118, -0.323902398, -0.790636539},
-    {2.9221096, -0.430951416, -0.922235191},
-    {3.90871215, -0.576384425, -0.978306472},
-    {4.28541517, -0.68551743, -0.966799438},
-    {4.05185127, -0.872821033, -0.898422956},
-    {3.19836116, -1.03560054, -0.775512636},
-    {2.02134061, -1.1379317, -0.658329248},
-    {0.792244792, -1.23291779, -0.566924453},
-    {-0.461926967, -1.31982887, -0.466164798},
-    {-1.61980557, -1.42657423, -0.375073731},
-    {-2.59827137, -1.53495634, -0.286846071},
-    {-3.32120109, -1.57683957, -0.242544457},
-    {-3.62964296, -1.57492709, -0.235311046},
-    {-3.65856004, -1.54662526, -0.268085837},
-    {-3.45135212, -1.53116035, -0.350563318},
-    {-3.18607736, -1.45669806, -0.423828572},
-    {-2.92265892, -1.28680599, -0.463855952},
-    {-2.72934175, -1.07362711, -0.498440683},
-    {-2.56581688, -0.858587086, -0.527025163},
-    {-2.48716331, -0.641573548, -0.489924252},
-    {-2.48634934, -0.396314234, -0.398187369},
-    {-2.51486731, -0.173578247, -0.263410777},
-    {-2.59200644, -0.00303849531, -0.0813819021},
-    {-2.62700987, 0.107346989, 0.0905081555},
-    {-2.64836121, 0.116326369, 0.244504854},
-    {-2.59136295, 0.116423115, 0.378413767},
-    {-2.38688588, 0.0739633366, 0.506859958},
-    {-2.1481452, -0.0134607237, 0.591549039},
-    {-1.91735613, -0.14962694, 0.670458734},
-    {-1.57315707, -0.3063806, 0.741572559},
-    {-1.13980782, -0.488234162, 0.774531305},
-    {-0.705650032, -0.649932861, 0.810541749},
-    {-0.248333633, -0.779634833, 0.83992213},
-    {0.231282711, -0.887520671, 0.88761276},
-    {0.665486634, -0.944406867, 0.940607905},
-    {1.03482258, -0.987873554, 0.957685232},
-    {1.39749861, -1.004722, 0.96836555},
-    {1.67342532, -0.978401005, 0.973969102},
-    {1.89922261, -0.918865323, 0.97346586},
-    {2.11542678, -0.850272775, 0.921052694},
-    {2.31307101, -0.749469101, 0.815407157},
-    {2.41512132, -0.608617067, 0.688241661},
-    {2.50772691, -0.465704918, 0.549239039},
-    {2.59612274, -0.302543014, 0.400988221},
-    {2.66450071, -0.146254539, 0.259387314},
-    {2.69629407, 0.00770889269, 0.118493944},
-    {2.68066287, 0.165709868, -0.0605780408},
-    {2.65878034, 0.303397179, -0.24633573},
-    {2.70898128, 0.41274628, -0.429216206},
-    {2.82954311, 0.497931749, -0.631148934},
-    {3.00375342, 0.541887403, -0.813905537},
-    {3.27656054, 0.559455931, -0.991809428},
-    {3.63134885, 0.535198748, -1.16095424},
-    {3.93977165, 0.46940726, -1.31378508},
-    {4.1669035, 0.371391207, -1.45772302},
-    {4.21443462, 0.282620162, -1.55627775},
-    {3.92297959, 0.228203058, -1.5836513},
-    {3.33155298, 0.201015398, -1.57186186},
-    {2.46357775, 0.218076289, -1.51605618},
-    {1.27901459, 0.307096809, -1.41809487},
-    {-0.34500888, 0.474567115, -1.26394379},
-    {-2.02032161, 0.681128502, -1.09333706},
-    {-3.64015198, 0.907278478, -0.827153265},
-    {-5.14808321, 1.07528996, -0.459002435},
-    {-6.28960562, 1.13271284, -0.0410786644},
-    {-7.16069365, 1.09189832, 0.40680927},
-    {-7.55773163, 0.944928706, 0.802233994},
-    {-7.58125544, 0.788610399, 1.14971912},
-    {-7.09843397, 0.647872508, 1.43841743},
-    {-6.16632032, 0.461586773, 1.65369391},
-    {-4.98205662, 0.169787064, 1.68179071},
-    {-3.74057245, -0.110652909, 1.54947782},
-    {-2.48511934, -0.317428499, 1.36022842},
-    {-1.17070103, -0.429105669, 1.19346094},
-    {0.251586109, -0.479542971, 1.09328282},
-    {1.63605702, -0.490316272, 0.979496241},
-    {3.05229402, -0.523854971, 0.800628901},
-    {4.6068778, -0.58621192, 0.604894876},
-    {6.12737322, -0.648951292, 0.503045022},
-    {7.49439621, -0.667814136, 0.516972661},
-    {8.5962429, -0.666145205, 0.583543599},
-    {9.42120743, -0.661725342, 0.637759626},
-    {9.66730309, -0.610184789, 0.707904398},
-    {9.18096828, -0.536193311, 0.768801987},
-    {7.87727404, -0.472447664, 0.844270766},
-    {5.9260664, -0.481671482, 0.976733983},
-    {3.93801045, -0.513540506, 1.11609447},
-    {2.05022311, -0.621068716, 1.29029369},
-    {0.227175444, -0.798624694, 1.51380968},
-    {-1.42388666, -1.02731669, 1.69885182},
-    {-2.80081153, -1.25494444, 1.83653581},
-    {-3.85286427, -1.54220212, 1.89889288},
-    {-4.38072824, -1.85619891, 1.88417947},
-    {-4.16726589, -2.21846366, 1.78314042},
-    {-3.2953434, -2.59746432, 1.5741545},
-    {-2.10681987, -2.87464523, 1.26887143},
-    {-0.928889036, -2.98524141, 0.990726233},
-    {0.16541715, -3.00536203, 0.749596059},
-    {1.16994596, -2.96003246, 0.553446054},
-    {1.96565366, -2.87058806, 0.427684575},
-    {2.60676622, -2.73629618, 0.352423966},
-    {3.21613503, -2.53893209, 0.246949241},
-    {3.65213466, -2.31158733, 0.152831823},
-    {3.99784184, -2.10670686, 0.0872655809},
-    {4.27051592, -1.90733111, -0.00432429649},
-    {4.51274395, -1.73436093, -0.113645211},
-    {4.81159163, -1.58051395, -0.194537893},
-    {5.09080124, -1.45327258, -0.290617496},
-    {5.34230709, -1.35142338, -0.387461931},
-    {5.59933472, -1.27594602, -0.464235872},
-    {5.95210838, -1.21213293, -0.545220792},
-    {6.32877636, -1.14186215, -0.596175194},
-    {6.69630098, -1.06780708, -0.607457221},
-    {6.99679565, -1.00272298, -0.57544744},
-    {7.24710417, -0.923571408, -0.53507334},
-    {7.48627186, -0.851287186, -0.511942983},
-    {7.68057108, -0.788184404, -0.48454383},
-    {7.84866047, -0.721493483, -0.454839081},
-    {8.00594711, -0.644661129, -0.435052812},
-    {8.14397907, -0.561136186, -0.409677655},
-    {8.25448132, -0.47676006, -0.395607054},
-    {8.28173161, -0.414278597, -0.391728878},
-    {8.26889324, -0.395249933, -0.380494714},
-    {8.18622303, -0.402934879, -0.34875828},
-    {8.04854965, -0.420708239, -0.302689821},
-    {7.89636374, -0.421523064, -0.250010639},
-    {7.7338953, -0.414996684, -0.195391342},
-    {7.53199911, -0.410223216, -0.13428472},
-    {7.27465725, -0.395748824, -0.0455297604},
-    {6.94582748, -0.360712618, 0.0702546015},
-    {6.59044409, -0.296426713, 0.18918179},
-    {6.24920988, -0.206433192, 0.281054348},
-    {5.94111633, -0.112947635, 0.330391109},
-    {5.65502214, -0.0383188464, 0.351476073},
-    {5.34467793, 0.00871063583, 0.358354777},
-    {5.0113163, 0.0476323515, 0.37288776},
-    {4.62952566, 0.0810074136, 0.39427793},
-    {4.21200037, 0.0831192285, 0.412935078},
-    {3.78825593, 0.0523065813, 0.419819295},
-    {3.3433373, -0.0149280634, 0.4187738},
-    {2.89701724, -0.118684478, 0.410274506},
-    {2.37036157, -0.230740026, 0.415274709},
-    {1.85999095, -0.337926149, 0.436003149},
-    {1.42647398, -0.445966989, 0.466379225},
-    {1.03454936, -0.573984981, 0.48912549},
-    {0.706662595, -0.721424878, 0.492218316},
-    {0.411099702, -0.870261848, 0.472358435},
-    {0.113768958, -1.01975012, 0.42623952},
-    {-0.173555225, -1.16832626, 0.37631914},
-    {-0.501336634, -1.30717444, 0.321178973},
-    {-0.775507569, -1.44156623, 0.253667146},
-    {-0.920787036, -1.55744171, 0.180338949},
-    {-0.967899501, -1.64998794, 0.0912896916},
-    {-1.03033972, -1.70183551, -0.0193564743},
-    {-1.11899853, -1.71462178, -0.134524509},
-    {-1.23297465, -1.68010211, -0.244839177},
-    {-1.28163981, -1.59106135, -0.327651232},
-    {-1.31775141, -1.46646845, -0.406107932},
-    {-1.26747882, -1.31675255, -0.464252502},
-    {-1.18317223, -1.13373899, -0.517546833},
-    {-1.0684725, -0.897009552, -0.570278406},
-    {-0.909689486, -0.669415176, -0.592192769},
-    {-0.75076884, -0.443762451, -0.602914691},
-    {-0.650976539, -0.204870075, -0.62202388},
-    {-0.567069113, 0.0239882115, -0.624717772},
-    {-0.528424501, 0.22306484, -0.635725737},
-    {-0.493079841, 0.410275668, -0.654467225},
-    {-0.450866997, 0.599694312, -0.672637582},
-    {-0.485589385, 0.775464177, -0.697600484},
-    {-0.592377603, 0.936145604, -0.728945315},
-    {-0.724921167, 1.07969201, -0.768482327},
-    {-0.873814821, 1.19836879, -0.798360646},
-    {-1.05814254, 1.29839802, -0.835750222},
-    {-1.26662803, 1.38607609, -0.880483925},
-    {-1.42591548, 1.4686904, -0.911908805},
-    {-1.54393339, 1.5413239, -0.940108657},
-    {-1.68892872, 1.59185827, -0.976959527},
-    {-1.843624, 1.63816845, -1.00669134},
-    {-2.02811718, 1.67506754, -1.03727102},
-    {-2.21262693, 1.69864655, -1.05009186},
-    {-2.38002658, 1.70393419, -1.05363369},
-    {-2.58642864, 1.71218038, -1.05261433},
-    {-2.78637743, 1.71344566, -1.0359242},
-    {-3.00778079, 1.70347321, -1.00428879},
-    {-3.1960063, 1.6744051, -0.960965216},
-    {-3.50690246, 1.6376847, -0.910846591},
-    {-3.8656683, 1.58663666, -0.854141235},
-    {-4.34774542, 1.50783384, -0.793597043},
-    {-4.85130644, 1.46110773, -0.725070834},
-    {-5.13308764, 1.37361169, -0.635937989},
-    {-5.25569296, 1.22837305, -0.529008865},
-    {-5.36797142, 1.11215818, -0.438744366},
-    {-5.59742928, 1.01950443, -0.370717078},
-    {-6.08519316, 0.985748231, -0.27578488},
-    {-6.54084778, 0.953173161, -0.170509741},
-    {-6.67132807, 0.844062924, -0.043099992},
-    {-6.68983889, 0.71295768, 0.0901921988},
-    {-6.46585369, 0.621068537, 0.220493257},
-    {-5.977108, 0.574042976, 0.320863008},
-    {-5.01129866, 0.478197306, 0.349251598},
-    {-3.95216918, 0.442710876, 0.395508409},
-    {-2.75794578, 0.405166835, 0.435317576},
-    {-1.38575876, 0.326133162, 0.498981297},
-    {-0.11701826, 0.300354213, 0.590943396},
-    {1.03759944, 0.300121397, 0.697482288},
-    {2.32010102, 0.251805454, 0.734090805},
-    {3.61004782, 0.150697529, 0.718484044},
-    {4.48733473, 0.133852825, 0.734563947},
-    {4.88874769, 0.212056711, 0.796338975},
-    {4.99285889, 0.225775272, 0.808095098},
-    {4.73451853, 0.203542978, 0.786827385},
-    {4.2810421, 0.142516285, 0.760221839},
-    {3.77805686, -0.0383248925, 0.763276219},
-    {3.01790166, -0.235503048, 0.774220645},
-    {1.99831223, -0.367097884, 0.800562382},
-    {0.980015039, -0.477744073, 0.871233582},
-    {0.0774855241, -0.729034364, 0.926240742},
-    {-0.631720841, -0.948397696, 0.900915623},
-    {-1.08197117, -1.06145489, 0.824740529},
-    {-1.15041411, -1.21753025, 0.72713089},
-    {-0.980963945, -1.33276141, 0.544416785},
-    {-0.653537273, -1.32202542, 0.343793154},
-    {-0.35099107, -1.2166158, 0.127998412},
-    {0.220878094, -1.15700197, -0.0923503116},
-    {0.815143287, -1.08180809, -0.304485708},
-    {1.2743386, -0.944512665, -0.522388279},
-    {1.59976578, -0.771237493, -0.735830009},
-    {1.95717299, -0.620017648, -0.966799617},
-    {2.27208614, -0.517728686, -1.203058},
-    {2.50938988, -0.461531311, -1.43199873},
-    {2.5138464, -0.434892327, -1.63541543},
-    {2.35430145, -0.460177302, -1.81324494},
-    {1.79246402, -0.553654969, -1.90759242},
-    {0.60846746, -0.620583057, -1.8842113},
-    {-1.17176521, -0.625953972, -1.72575843},
-    {-3.318856, -0.594758987, -1.4818511},
-    {-5.3324194, -0.491265535, -1.25697792},
-    {-6.89099598, -0.430307806, -1.04227436},
-    {-7.94427729, -0.483763576, -0.836531758},
-    {-8.51806641, -0.601074219, -0.670460761},
-    {-8.46854591, -0.805083036, -0.563086867},
-    {-7.70801926, -0.98589164, -0.559095979},
-    {-6.34009123, -1.16187453, -0.693676293},
-    {-4.42663431, -1.35509396, -0.960026622},
-    {-2.45834303, -1.48689461, -1.2398082},
-    {-0.817121804, -1.56916451, -1.41485405},
-    {0.610579252, -1.68939745, -1.54553843},
-    {1.96954453, -1.86426282, -1.65939403},
-    {3.02495694, -2.05411124, -1.68907583},
-    {3.72050834, -2.18983364, -1.62289393},
-    {4.09089851, -2.24728346, -1.51103115},
-    {4.20847607, -2.26120281, -1.38015139},
-    {4.12017822, -2.25594783, -1.21641028},
-    {3.89163899, -2.18456078, -1.02429938},
-    {3.50971198, -2.03887916, -0.81511426},
-    {3.07686353, -1.82981539, -0.618901432},
-    {2.69599509, -1.44460917, -0.44586131},
-    {2.52228785, -0.850038409, -0.286694735},
-    {2.39955854, -0.291604429, -0.178291827},
-    {2.39033532, 0.277058691, -0.0832357407},
-    {2.23172665, 0.800706267, -0.0528130531},
-    {2.13278127, 1.28187871, -0.0289103165},
-    {1.99990869, 1.7712965, -0.0385457799},
-    {1.84695625, 2.19479036, -0.052887626},
-    {1.70333886, 2.58843827, -0.0639375374},
-    {1.54398465, 2.93551016, -0.065779008},
-    {1.35957766, 3.21150875, -0.035336487},
-    {1.1513716, 3.46610808, 0.0152973589},
-    {0.836635888, 3.63247752, 0.084994033},
-    {0.482831895, 3.7378161, 0.174032092},
-    {0.0670926869, 3.7745173, 0.287838787},
-    {-0.31413272, 3.74917507, 0.420650721},
-    {-0.639976501, 3.6634531, 0.604158521},
-    {-0.79507941, 3.49511242, 0.788140476},
-    {-0.781315446, 3.29396057, 0.931528747},
-    {-0.577578247, 3.05764532, 1.00609088},
-    {-0.267123878, 2.75046682, 1.02533042},
-    {0.263625145, 2.4326458, 0.976891279},
-    {0.95816505, 2.09087968, 0.855868876},
-    {1.70959139, 1.76353097, 0.735811055},
-    {2.55826139, 1.47053671, 0.563718021},
-    {3.21765065, 1.1906445, 0.406204849},
-    {3.71507454, 0.978832424, 0.246337041},
-    {3.61126184, 0.873954952, 0.102031708},
-    {2.97026539, 0.812712133, 0.000248549506},
-    {2.32424808, 0.667312324, -0.00927959383},
-    {1.97932339, 0.361017555, 0.0974422321},
-    {1.63481271, 0.00692734541, 0.266188413},
-    {1.07963908, -0.277728707, 0.427231818},
-    {-0.0813001841, -0.5009076, 0.531014204},
-    {-1.78113401, -0.688826561, 0.550053835},
-    {-3.24499226, -0.898262739, 0.567846417},
-    {-4.57081699, -1.01702344, 0.537016988},
-    {-6.07907391, -0.867433369, 0.399482697},
-    {-7.43577766, -0.444753081, 0.223586187},
-    {-7.86076069, 0.152493894, 0.111777037},
-    {-6.85552692, 0.655090272, 0.135139093},
-    {-4.93928909, 0.811065912, 0.196647987},
-    {-2.59430695, 0.766945541, 0.152387142},
-    {-0.114958845, 0.66553098, 0.0122074801},
-    {2.06923127, 0.44282046, -0.188044727},
-    {3.68261433, 0.159776673, -0.373460799},
-    {4.64795017, -0.0975828916, -0.470039189},
-    {5.0128808, -0.324166119, -0.498830289},
-    {4.78064537, -0.572376966, -0.447574109},
-    {3.97710061, -0.846716821, -0.317589462},
-    {2.79475808, -1.09383488, -0.103747793},
-    {1.49233961, -1.27326894, 0.0760745853},
-    {0.140100464, -1.46300006, 0.272329926},
-    {-1.03620958, -1.65215003, 0.459195644},
-    {-2.03249836, -1.81980813, 0.601198494},
-    {-2.84762096, -1.96242106, 0.678592265},
-    {-3.31469893, -2.10760522, 0.689201355},
-    {-3.41395473, -2.2511754, 0.61711669},
-    {-3.20739508, -2.33975601, 0.482858062},
-    {-2.76749182, -2.35185385, 0.303402096},
-    {-2.19027853, -2.32635307, 0.131281272},
-    {-1.66140842, -2.26434541, -0.00485640671},
-    {-1.26907527, -2.16710186, -0.0847730637},
-    {-0.959004223, -2.04729509, -0.13641265},
-    {-0.708296657, -1.91908491, -0.146974817},
-    {-0.500920832, -1.78486216, -0.132131085},
-    {-0.312968224, -1.6711942, -0.116364025},
-    {-0.107702762, -1.55866742, -0.103067458},
-    {0.0603581518, -1.42083049, -0.0799840465},
-    {0.215851411, -1.28411067, -0.0575854331},
-    {0.383649737, -1.16982293, -0.0314121544},
-    {0.526921093, -1.07086682, -0.00417463854},
-    {0.685124874, -0.996720135, 0.0192882009},
-    {0.893380404, -0.939684331, 0.0313106179},
-    {1.14484668, -0.889789045, 0.0313194245},
-    {1.44412124, -0.851462364, 0.0173947681},
-    {1.76883876, -0.824432135, 0.00405647885},
-    {2.09798336, -0.811677992, -0.00189653086},
-    {2.40534544, -0.844402969, -0.00450720824},
-    {2.65367532, -0.91953069, -0.00592063228},
-    {2.87498188, -1.02402318, -0.00633584103},
-    {3.02809787, -1.13377786, -0.0031957007},
-    {3.0727303, -1.22870469, 0.0182738584},
-    {3.05351353, -1.32071614, 0.0654832348},
-    {2.99477625, -1.39923, 0.130599499},
-    {2.88103747, -1.4529233, 0.221989855},
-    {2.66549873, -1.47996163, 0.321561396},
-    {2.48395967, -1.48670316, 0.429980338},
-    {2.30818439, -1.46027207, 0.529946804},
-    {2.12879634, -1.41096973, 0.61766547},
-    {1.93356085, -1.32019448, 0.673370898},
-    {1.7351824, -1.18399036, 0.702620566},
-    {1.59566915, -1.01707339, 0.700109601},
-    {1.38300681, -0.860166907, 0.67661345},
-    {1.17149603, -0.723282933, 0.643615663},
-    {0.993265033, -0.593443155, 0.597319067},
-    {0.761511207, -0.464289099, 0.524067461},
-    {0.50743252, -0.350103498, 0.425539523},
-    {0.223417416, -0.250282586, 0.316373318},
-    {-0.0780490562, -0.14827092, 0.178477824},
-    {-0.34125182, -0.0672685951, 0.0155291446},
-    {-0.597748756, -0.0050618099, -0.147362828},
-    {-0.838114023, 0.0506271087, -0.290550977},
-    {-1.06175089, 0.100496031, -0.416196108},
-    {-1.25800121, 0.141029298, -0.532514513},
-    {-1.45141447, 0.183509886, -0.642005503},
-    {-1.61358488, 0.21238932, -0.74780196},
-    {-1.78061855, 0.228668645, -0.856352925},
-    {-1.93576252, 0.242187634, -0.945016205},
-    {-2.11701322, 0.24408327, -1.01415765},
-    {-2.29028225, 0.234156042, -1.06938088},
-    {-2.36652398, 0.222931802, -1.10967195},
-    {-2.39342928, 0.20592083, -1.14262962},
-    {-2.42692327, 0.191225246, -1.16474521},
-    {-2.4115684, 0.182737455, -1.1951108},
-    {-2.44456196, 0.169853568, -1.24213469},
-    {-2.55923223, 0.167891428, -1.28999126},
-    {-2.6981554, 0.183340311, -1.33895528},
-    {-2.8426652, 0.20931305, -1.39307165},
-    {-2.98746872, 0.241801962, -1.44786406},
-    {-2.95560622, 0.270821959, -1.50084102},
-    {-2.93046427, 0.317198873, -1.54698527},
-    {-2.99694586, 0.395427495, -1.59299886},
-    {-3.31185555, 0.497003108, -1.66707659},
-    {-3.93992949, 0.634233057, -1.77649689},
-    {-4.43397427, 0.771442711, -1.81675553},
-    {-4.80236912, 0.907245159, -1.78567088},
-    {-5.26155138, 1.03455925, -1.70254958},
-    {-5.89633942, 1.16227078, -1.58381033},
-    {-6.55755997, 1.27385437, -1.41106379},
-    {-7.21676397, 1.38581407, -1.1894387},
-    {-7.84866428, 1.49130559, -0.924729407},
-    {-8.30092621, 1.54265404, -0.624983788},
-    {-8.60075569, 1.51722896, -0.307428956},
-    {-8.74409294, 1.43796134, 0.0151144471},
-    {-8.69825649, 1.34244275, 0.353823751},
-    {-8.41468334, 1.18224764, 0.691379666},
-    {-7.77606964, 0.92415905, 0.954418123},
-    {-6.73779488, 0.608131409, 1.10375011},
-    {-5.28953552, 0.301368535, 1.13037252},
-    {-3.3928535, 0.0874955505, 1.09662092},
-    {-1.39959371, -0.0825464129, 1.04748619},
-    {0.543393433, -0.236625507, 1.02036726},
-    {2.41909671, -0.370423645, 1.01059699},
-    {4.0891819, -0.484694749, 1.02103996},
-    {5.45780849, -0.51322937, 1.08818603},
-    {6.46559811, -0.443738759, 1.22209561},
-    {7.0214386, -0.272248864, 1.36009574},
-    {7.08841801, -0.0356915332, 1.45289934},
-    {6.71223164, 0.219256878, 1.5151397},
-    {6.00457764, 0.441785783, 1.53375924},
-    {5.16519976, 0.602831662, 1.52997518},
-    {4.19869757, 0.711095214, 1.55293632},
-    {3.06483173, 0.795933843, 1.59025085},
-    {1.88431704, 0.848738968, 1.65477431},
-    {0.660626113, 0.884508073, 1.73674393},
-    {-0.343016475, 0.910255134, 1.82878697},
-    {-0.940928102, 0.905432701, 1.86310792},
-    {-1.03659201, 0.838004172, 1.85557568},
-    {-0.649748147, 0.754667819, 1.78436792},
-    {-0.00587324146, 0.690958083, 1.69971645},
-    {0.683953404, 0.693771482, 1.5334084},
-    {1.54066241, 0.712209284, 1.28446913},
-    {2.475317, 0.695555031, 1.00037289},
-    {3.29991412, 0.650164366, 0.716353655},
-    {3.66800618, 0.573136449, 0.456240594},
-    {3.40932536, 0.486360788, 0.283365697},
-    {2.69398284, 0.377477288, 0.224184781},
-    {1.56806576, 0.282860994, 0.247398213},
-    {0.246039256, 0.196643099, 0.300660789},
-    {-1.09011006, 0.129200071, 0.382276922},
-    {-2.3068943, 0.0578438789, 0.458414137},
-    {-3.2748239, -0.0339954309, 0.54471612},
-    {-3.81412506, -0.124269143, 0.638971627},
-    {-3.80381513, -0.205515906, 0.718194425},
-    {-3.21727228, -0.247505635, 0.733632743},
-    {-2.16275835, -0.287114739, 0.696667492},
-    {-0.723453879, -0.359801561, 0.586421549},
-    {0.749177933, -0.396380723, 0.507468283},
-    {1.97975039, -0.369801372, 0.451966524},
-    {3.1618259, -0.425946236, 0.383585751},
-    {3.9334898, -0.503235519, 0.334564924},
-    {4.21351957, -0.498473287, 0.316930592},
-    {4.06753159, -0.49528712, 0.316057384},
-    {3.69553185, -0.650963962, 0.378865272},
-    {3.02718472, -0.770040333, 0.503128171},
-    {2.06156683, -0.784856141, 0.625879943},
-    {0.965182424, -0.827840924, 0.73893714},
-    {-0.306117803, -1.03982127, 0.858596027},
-    {-1.63336277, -1.15842664, 0.900485873},
-    {-2.72338843, -1.22449756, 0.877785444},
-    {-3.33599997, -1.26438916, 0.817190945},
-    {-3.31799173, -1.45598328, 0.740350544},
-    {-2.90568709, -1.61347198, 0.622487724},
-    {-2.39209461, -1.56416583, 0.493672669},
-    {-1.74623072, -1.44371152, 0.36067161},
-    {-0.639386475, -1.55339324, 0.2045798},
-    {0.439599186, -1.63846779, 0.0565018207},
-    {1.30075252, -1.61772192, -0.0693573207},
-    {1.96894634, -1.51519728, -0.176795274},
-    {2.58414197, -1.47752798, -0.308866054},
-    {3.07873416, -1.47872412, -0.422534794},
-    {3.27521586, -1.43506444, -0.4991391},
-    {3.13582969, -1.34624147, -0.554556966},
-    {2.85363293, -1.22986865, -0.5961833},
-    {2.4820857, -1.11747658, -0.607623577},
-    {1.93894827, -0.983916163, -0.597762883},
-    {1.41362321, -0.843250036, -0.574728787},
-    {0.916160345, -0.665896237, -0.563115358},
-    {0.32789439, -0.483763605, -0.54631418},
-    {-0.220081806, -0.323531151, -0.511643767},
-    {-0.6918993, -0.15014565, -0.479583979},
-    {-1.20502222, 0.0288104843, -0.437064886},
-    {-1.71092832, 0.177635729, -0.362485975},
-    {-2.22978401, 0.304097652, -0.286210924},
-    {-2.70426536, 0.392698765, -0.211148709},
-    {-3.06436229, 0.405682713, -0.107517861},
-    {-3.23186493, 0.423000634, -0.00778705534},
-    {-3.28338742, 0.465741426, 0.0555550009},
-    {-3.22458124, 0.451982975, 0.0932562724},
-    {-3.00200844, 0.448380679, 0.0946687981},
-    {-2.64122725, 0.50252372, 0.0950311124},
-    {-2.18800044, 0.587478757, 0.122168854},
-    {-1.55706441, 0.636433065, 0.161628336},
-    {-0.932896554, 0.664651752, 0.229123488},
-    {-0.31697616, 0.612604439, 0.308591098},
-    {0.35502553, 0.434932798, 0.394296557},
-    {0.948321044, 0.191803217, 0.469788015},
-    {1.42264545, -0.0132344579, 0.57383734},
-    {1.6116823, -0.150960416, 0.715690672},
-    {1.5344764, -0.304890633, 0.888128161},
-    {1.21200073, -0.435651779, 1.06311357},
-    {0.822892129, -0.50822413, 1.24447739},
-    {0.559529662, -0.544557393, 1.43223},
-    {0.363827467, -0.589375138, 1.60119224},
-    {0.357444257, -0.652108669, 1.74273443},
-    {0.546822786, -0.680778325, 1.84086597},
-    {0.644518077, -0.715797901, 1.92426789},
-    {0.943349063, -0.795099378, 1.9524864},
-    {1.39075828, -0.764561951, 1.96910787},
-    {1.83498681, -0.653191507, 1.97112703},
-    {2.36102557, -0.596059501, 1.92253983},
-    {2.98704362, -0.55085963, 1.86819649},
-    {3.63132477, -0.435062468, 1.78657365},
-    {4.28011036, -0.264749408, 1.64030242},
-    {4.968647, -0.085859783, 1.39641213},
-    {5.76437187, 0.0738238841, 1.0930413},
-    {6.62291908, 0.193482697, 0.778147221},
-    {7.28094339, 0.24661082, 0.394992888},
-    {7.78061342, 0.213054478, -0.0113581643},
-    {8.11103916, 0.0798101425, -0.377401769},
-    {8.02460575, -0.0952125639, -0.713577926},
-    {7.77989864, -0.382554889, -0.909829617},
-    {7.29145145, -0.740075707, -0.970174968},
-    {6.46724319, -1.10300958, -0.942887902},
-    {5.39864683, -1.41001439, -0.874372721},
-    {4.24336195, -1.64682877, -0.792482972},
-    {3.19492316, -1.78875685, -0.673417151},
-    {2.30413771, -1.8521837, -0.550138712},
-    {1.52679396, -1.87892938, -0.484456122},
-    {0.952578008, -1.86507821, -0.47837016},
-    {0.487993717, -1.81808567, -0.468974978},
-    {-0.0134225851, -1.75917065, -0.523616374},
-    {-0.457570344, -1.66776395, -0.587336898},
-    {-0.738143265, -1.52971387, -0.670412898},
-    {-0.931782365, -1.38863754, -0.743229151},
-    {-1.05365264, -1.21852791, -0.849684775},
-    {-0.972638547, -1.00722921, -0.901083648},
-    {-0.758563161, -0.781530559, -0.86508286},
-    {-0.359511912, -0.530140519, -0.768088758},
-    {0.118364483, -0.278388262, -0.675991535},
-    {0.649556518, -0.0532013662, -0.579321861},
-    {1.14577556, 0.153574258, -0.449020267},
-    {1.70666468, 0.354696184, -0.285412788},
-    {2.27138567, 0.545907438, -0.168680593},
-    {2.71252632, 0.719500244, -0.0604178309},
-    {3.12217879, 0.894755602, 0.0401114002},
-    {3.3535862, 1.03629923, 0.0884960964},
-    {3.3598175, 1.12750149, 0.0413607955},
-    {3.07415104, 1.15598845, -0.102202967},
-    {2.46947956, 1.09623587, -0.289242387},
-    {1.67658353, 0.984900475, -0.480481893},
-    {0.947705865, 0.86791867, -0.588118374},
-    {0.299642473, 0.810816407, -0.58449322},
-    {-0.204289243, 0.804896176, -0.496072978},
-    {-0.667200565, 0.828481793, -0.375159562},
-    {-1.20753324, 0.835825682, -0.268085897},
-    {-1.85275817, 0.832372367, -0.126577154},
-    {-2.6757195, 0.781364024, 0.0922241062},
-    {-3.68865728, 0.611157775, 0.273804337},
-    {-5.12556171, 0.328872055, 0.474926203},
-    {-6.61543941, -0.0624634512, 0.688844979},
-    {-7.67709732, -0.502091467, 0.915144682},
-    {-8.04527569, -1.01841176, 0.999243855},
-    {-7.89895439, -1.51168025, 0.903558493},
-    {-7.36210632, -1.935274, 0.612930357},
-    {-6.54476166, -2.26667953, 0.281484514},
-    {-5.6670537, -2.51743746, -0.0991491675},
-    {-4.96910381, -2.67340732, -0.423745424},
-    {-4.38951635, -2.77024698, -0.659582317},
-    {-4.06442738, -2.80027914, -0.89480263},
-    {-4.10483646, -2.74920011, -1.07877612},
-    {-4.54558706, -2.63567972, -1.17046905},
-    {-5.36245918, -2.44407988, -1.17691624},
-    {-6.4970808, -2.17927361, -1.09242809},
-    {-7.80317974, -1.86045575, -0.943547368},
-    {-9.01698399, -1.58776414, -0.731007159},
-    {-9.87978745, -1.35135663, -0.456985831},
-    {-10.2271566, -1.20582366, -0.182981089},
-    {-9.92973614, -1.15844369, 0.0230494644},
-    {-9.10020924, -1.15766752, 0.212212279},
-    {-7.88234949, -1.29235291, 0.357032567},
-    {-6.46660137, -1.50977623, 0.408777982},
-    {-5.34378386, -1.606534, 0.373454154},
-    {-4.29504251, -1.62247241, 0.337666869},
-    {-3.45133591, -1.67065728, 0.271559447},
-    {-2.73303294, -1.70707369, 0.179703519},
-    {-1.94400704, -1.73297453, 0.121209949},
-    {-1.20516074, -1.76405311, 0.0724152103},
-    {-0.528039455, -1.79449022, 0.0303638075},
-    {0.0616052896, -1.81510937, 0.0129194781},
-    {0.45864445, -1.8269819, 0.0110404557},
-    {0.805548549, -1.82724822, 0.0316764414},
-    {1.09950757, -1.81687152, 0.0586479083},
-    {1.35794795, -1.78863692, 0.106222101},
-    {1.53953147, -1.76118314, 0.141807124},
-    {1.67565274, -1.72037637, 0.196132496},
-    {1.81282079, -1.68134964, 0.252104074},
-    {2.03038859, -1.61992371, 0.326649725},
-    {2.28111315, -1.5380615, 0.405236155},
-    {2.47617149, -1.45833981, 0.443912029},
-    {2.68497062, -1.35855663, 0.47850135},
-    {2.92610431, -1.2629782, 0.512249649},
-    {3.17293406, -1.17379725, 0.532061875},
-    {3.42475629, -1.06125534, 0.542670846},
-    {3.7362144, -0.966152012, 0.520133138},
-    {4.11048412, -0.874055266, 0.489798009},
-    {4.5359745, -0.771486938, 0.462920457},
-    {4.89358711, -0.714351237, 0.415861726},
-    {5.20731163, -0.667024076, 0.345745295},
-    {5.42962456, -0.659842968, 0.265406907},
-    {5.57761431, -0.703255892, 0.172470093},
-    {5.77894783, -0.763341546, 0.122417197},
-    {5.99108601, -0.900524259, 0.0840063915},
-    {6.14197206, -1.00829351, 0.0553388298},
-    {6.44998312, -1.08084381, 0.102430798},
-    {7.03342724, -1.09822059, 0.224085063},
-    {7.74166918, -1.05965912, 0.415163338},
-    {8.35857105, -0.927246094, 0.633113265},
-    {8.84696198, -0.766770959, 0.83724004},
-    {9.20741749, -0.646465659, 0.986928582},
-    {9.5511713, -0.512840331, 1.13151455},
-    {9.79675484, -0.335038096, 1.24246538},
-    {9.88841152, -0.136859417, 1.29851997},
-    {9.87645721, 0.0977539271, 1.27741039},
-    {9.62215519, 0.325333744, 1.22850382},
-    {9.0146904, 0.53750205, 1.15299928},
-    {8.12007999, 0.71503365, 1.10805309},
-    {7.06684923, 0.835742474, 1.09321356},
-    {5.99403286, 0.909528852, 1.10268354},
-    {5.0323925, 0.932957888, 1.13441658},
-    {4.08652163, 0.927897692, 1.16344666},
-    {3.17818832, 0.923125505, 1.2138809},
-    {2.35550761, 0.88902247, 1.26810706},
-    {1.59761477, 0.830221951, 1.34403241},
-    {0.945089996, 0.741558552, 1.43225455},
-    {0.450046927, 0.631102383, 1.51857769},
-    {0.0474544354, 0.485828668, 1.58153749},
-    {-0.294594228, 0.316733301, 1.62914491},
-    {-0.645522475, 0.131973788, 1.68862534},
-    {-0.972622097, -0.0894016474, 1.76990533},
-    {-1.28120458, -0.325472206, 1.85546136},
-    {-1.54326391, -0.602986872, 1.94282603},
-    {-1.58763695, -0.85448885, 2.00164747},
-    {-1.44609475, -1.09697104, 2.0408783},
-    {-1.13697946, -1.3073231, 2.06285357},
-    {-0.773046613, -1.46102166, 2.07633591},
-    {-0.355183542, -1.59683406, 2.10353923},
-    {0.0545714311, -1.71156347, 2.12455845},
-    {0.586384714, -1.81971538, 2.11471438},
-    {1.1689316, -1.87201226, 2.09464383},
-    {1.78308928, -1.88049245, 2.07287741},
-    {2.56306648, -1.87763226, 2.03177118},
-    {3.34844804, -1.80834138, 1.98163617},
-    {4.13652372, -1.68236399, 1.941329},
-    {4.82274866, -1.51245368, 1.90973461},
-    {5.55127764, -1.3316021, 1.85442817},
-    {6.32352257, -1.13228393, 1.78040135},
-    {7.16756964, -0.918100417, 1.67916346},
-    {8.11651993, -0.739259243, 1.55730176},
-    {8.9565649, -0.525401413, 1.44554961},
-    {9.62001133, -0.337066799, 1.30146348},
-    {10.041193, -0.160156041, 1.09763098},
-    {9.94977283, -0.000415901653, 0.838691235},
-    {9.2039299, 0.0659208, 0.550915062},
-    {7.99377155, -0.0436506942, 0.279888213},
-    {6.49260139, -0.277021229, 0.0992214978},
-    {4.70860958, -0.581370056, 0.0168191157},
-    {2.95250678, -0.917352259, 0.016910322},
-    {1.34104359, -1.24040616, 0.0428921133},
-    {-0.289805174, -1.52577317, 0.0468416512},
-    {-1.87072837, -1.81311393, -0.0017967599},
-    {-3.13052177, -2.1072557, -0.0825282186},
-    {-4.08990431, -2.38463545, -0.206329539},
-    {-4.84447289, -2.61131644, -0.419222444},
-    {-5.28236771, -2.76899409, -0.713445842},
-    {-5.53974438, -2.83202624, -1.0390172},
-    {-5.76385021, -2.82415962, -1.36794758},
-    {-6.07123375, -2.71526814, -1.69708169},
-    {-6.45561218, -2.50111985, -1.98976135},
-    {-6.85324907, -2.21681571, -2.21417475},
-    {-7.26658487, -1.86629272, -2.38416982},
-    {-7.67563915, -1.43358016, -2.47223258},
-    {-8.13123512, -0.940336347, -2.45473051},
-    {-8.64234352, -0.459236532, -2.31525588},
-    {-9.1815567, -0.0178990215, -2.0727787},
-    {-9.83922577, 0.327111602, -1.72179937},
-    {-10.6468706, 0.563075125, -1.27911699},
-    {-11.4572353, 0.722751856, -0.774041831},
-    {-12.0406618, 0.72985214, -0.285196602},
-    {-12.2970247, 0.548983693, 0.145764723},
-    {-12.0256815, 0.233308017, 0.433803886},
-    {-11.1595364, -0.141199484, 0.540425897},
-    {-9.74418163, -0.533963561, 0.455715269},
-    {-8.11003017, -0.823135197, 0.238684878},
-    {-6.67250347, -0.995685816, 0.00353294471},
-    {-5.52213526, -1.06574512, -0.241180912},
-    {-4.29094696, -1.1163528, -0.504699647},
-    {-3.27192593, -1.09706187, -0.731366098},
-    {-2.36823654, -1.00603199, -1.02726078},
-    {-1.53105748, -0.835539877, -1.37118852},
-    {-0.769005835, -0.613377333, -1.67784667},
-    {-0.23761414, -0.399170578, -1.88510633},
-    {0.157701507, -0.198318437, -1.99274588},
-    {0.669810414, 0.00409899326, -2.05435658},
-    {1.15975249, 0.195976958, -2.09020567},
-    {1.58055389, 0.361896336, -2.09057117},
-    {1.97393489, 0.475519001, -2.01570988},
-    {2.37331891, 0.594778657, -1.89157808},
-    {2.93095613, 0.673664331, -1.7381134},
-    {3.68544197, 0.648788154, -1.48266602},
-    {4.29253244, 0.601629674, -1.13205385},
-    {4.89526606, 0.536462545, -0.727614939},
-    {5.11035633, 0.558844507, -0.301359504},
-    {5.13777685, 0.647540987, -0.00148081849},
-    {5.07162857, 0.778640211, 0.110013381},
-    {4.95589352, 0.884264648, 0.14090918},
-    {4.75545406, 0.987178504, 0.14626357},
-    {4.52787542, 1.07760441, 0.137383938},
-    {4.21958208, 1.13690233, 0.100151181},
-    {3.90034819, 1.1524992, 0.0580991581},
-    {3.60844421, 1.1469425, 0.0340521932},
-    {3.29719853, 1.11061215, 0.0126201641},
-    {2.89491177, 1.05115163, 0.0171416141},
-    {2.48394346, 1.00219715, 0.0182058383},
-    {2.13509274, 0.950953662, 0.00813314877},
-    {1.85025203, 0.899429739, 1.57491304e-05},
-    {1.52232063, 0.877496779, 0.0392424241},
-    {1.20240462, 0.856295526, 0.106438249},
-    {0.818369031, 0.83143568, 0.17175509},
-    {0.436374307, 0.813248873, 0.232953608},
-    {0.067543827, 0.808656394, 0.282359928},
-    {-0.247252807, 0.809918582, 0.310553312},
-    {-0.527276993, 0.810301006, 0.323473662},
-    {-0.834299207, 0.830468416, 0.386880159},
-    {-1.08339572, 0.851298153, 0.47345078},
-    {-1.28952837, 0.845370531, 0.568910599},
-    {-1.48162103, 0.834844649, 0.652369142},
-    {-1.694067, 0.821425259, 0.744225025},
-    {-1.8975842, 0.805992603, 0.863990784},
-    {-2.14043164, 0.779201388, 0.982002199},
-    {-2.37563133, 0.734834492, 1.0966531},
-    {-2.53369737, 0.668470383, 1.18980062},
-    {-2.60743904, 0.562285066, 1.27471685},
-    {-2.45408988, 0.431170702, 1.30443966},
-    {-2.14790893, 0.284723341, 1.29639184},
-    {-1.79029584, 0.14223358, 1.24652278},
-    {-1.35245061, -0.0090027675, 1.16898382},
-    {-0.88089931, -0.184234098, 1.08860195},
-    {-0.284051776, -0.389596373, 1.01106286},
-    {0.328958601, -0.585496902, 0.927255332},
-    {0.954357207, -0.76240778, 0.840288043},
-    {1.50373018, -0.925300717, 0.75067693},
-    {2.06455803, -1.09248829, 0.679573417},
-    {2.62354422, -1.27943814, 0.652236164},
-    {3.13462186, -1.43892229, 0.685825706},
-    {3.54443145, -1.5585146, 0.745571911},
-    {3.91674423, -1.68337846, 0.815278828},
-    {4.20226431, -1.79806936, 0.935906589},
-    {4.37210655, -1.8644805, 1.05481911},
-    {4.44019365, -1.91670954, 1.17678273},
-    {4.30975103, -1.94515824, 1.41521096},
-    {4.12672901, -1.96621251, 1.67951274},
-    {3.96820354, -1.94955766, 1.89347672},
-    {4.07678223, -1.99087155, 2.02441549},
-    {4.2293601, -2.04295349, 2.11567879},
-    {4.29022408, -2.00504518, 2.27133203},
-    {4.18649292, -1.82768059, 2.4819386},
-    {4.00917578, -1.57996273, 2.67890882},
-    {3.90177965, -1.27857339, 2.85676193},
-    {3.79355359, -0.930710018, 2.98578191},
-    {3.84679651, -0.618864477, 3.06062293},
-    {4.0027132, -0.323331684, 3.0658989},
-    {4.3032403, -0.0815862492, 2.98608208},
-    {4.6711998, 0.202528611, 2.84783578},
-    {5.03833342, 0.521538615, 2.66474843},
-    {5.45320177, 0.757505357, 2.41349554},
-    {6.02018595, 0.908932328, 2.08746314},
-    {6.46870661, 0.994594872, 1.73997402},
-    {6.65393162, 1.02339554, 1.4088006},
-    {6.63401842, 1.03090763, 1.047984},
-    {6.41221857, 0.969918132, 0.692576885},
-    {5.84445572, 0.832915783, 0.34045139},
-    {4.96828032, 0.610191345, 0.0562438294},
-    {3.79421425, 0.360646695, -0.0671417937},
-    {2.38317752, 0.120360136, -0.0795795992},
-    {0.816207528, -0.116356477, -0.0136528937},
-    {-0.945296228, -0.354689986, 0.0880415738},
-    {-2.64448667, -0.558392406, 0.15828599},
-    {-3.88285995, -0.763702154, 0.129266024},
-    {-4.58872652, -1.04595733, 0.0877145603},
-    {-4.75509453, -1.28909922, 0.00507081766},
-    {-4.45641279, -1.46048963, -0.145367369},
-    {-3.7333715, -1.55868101, -0.402693719},
-    {-2.60249949, -1.54163647, -0.712183714},
-    {-1.01098394, -1.58064675, -1.0641098},
-    {0.863160849, -1.61782861, -1.38204038},
-    {2.4762156, -1.59245348, -1.59899914},
-    {3.46039701, -1.64369595, -1.77401507},
-    {3.58614254, -1.71925235, -1.87713087},
-    {2.90876794, -1.82300079, -1.91241562},
-    {1.74372649, -2.02021837, -1.90946054},
-    {0.421463072, -2.25534964, -1.88324726},
-    {-0.780518889, -2.37924933, -1.89923775},
-    {-2.19036436, -2.41747332, -1.93778551},
-    {-3.53323078, -2.39298344, -2.05634999},
-    {-4.70208311, -2.28444982, -2.20783591},
-    {-5.82853127, -2.16249561, -2.35080743},
-    {-6.72399378, -1.94205129, -2.49210024},
-    {-7.50797892, -1.63282716, -2.5826757},
-    {-8.16693497, -1.23661005, -2.58530831},
-    {-8.7030859, -0.798824131, -2.51411629},
-    {-9.27655506, -0.37855491, -2.34803081},
-    {-9.83057499, -0.00181978452, -2.09046721},
-    {-10.331152, 0.295531958, -1.76543438},
-    {-10.8597469, 0.470326304, -1.38703918},
-    {-11.1980839, 0.545912862, -0.994332492},
-    {-11.2091379, 0.512800157, -0.647099614},
-    {-10.7549458, 0.393008232, -0.386996329},
-    {-9.84260654, 0.216863394, -0.267425776},
-    {-8.69691658, 0.0727103055, -0.270848334},
-    {-7.43771553, -0.0277310163, -0.360674471},
-    {-6.0216608, -0.122763835, -0.501047134},
-    {-4.83757067, -0.155405775, -0.668638587},
-    {-3.69710517, -0.177266747, -0.813052297},
-    {-2.62396693, -0.199864909, -0.943486452},
-    {-1.80078876, -0.213367239, -1.04377282},
-    {-1.22728777, -0.20796296, -1.11767018},
-    {-0.57847625, -0.231442481, -1.1764853},
-    {-0.0435035564, -0.258912772, -1.22194755},
-    {0.447120816, -0.302712232, -1.25711679},
-    {0.810287714, -0.338230848, -1.25984406},
-    {1.20135725, -0.388798088, -1.24403024},
-    {1.56730092, -0.443339646, -1.20119524},
-    {1.75811303, -0.48968336, -1.10591364},
-    {1.82359648, -0.545438766, -0.966084421},
-    {1.94202423, -0.619369149, -0.796124339},
-    {2.04106402, -0.681992173, -0.614025652},
-    {2.15533519, -0.74333483, -0.41890654},
-    {2.19471622, -0.779203057, -0.201492205},
-    {2.33061647, -0.81967634, 0.010774401},
-    {2.54602337, -0.86603415, 0.231389508},
-    {2.827595, -0.896077991, 0.446250588},
-    {3.10612059, -0.891843975, 0.671259046},
-    {3.32885981, -0.837868094, 0.901913226},
-    {3.47253036, -0.737082362, 1.07844162},
-    {3.7127459, -0.612185717, 1.22600305},
-    {4.33104372, -0.539419234, 1.36857617},
-    {4.82798672, -0.420824677, 1.49767983},
-    {5.33815002, -0.249251619, 1.58393216},
-    {6.00280809, -0.0942738354, 1.66717446},
-    {6.67578173, 0.0865280703, 1.71554673},
-    {7.50120497, 0.271370709, 1.74443042},
-    {8.08428383, 0.520119131, 1.7321887},
-    {8.65559387, 0.778064728, 1.68541121},
-    {9.37850475, 0.985461295, 1.59707725},
-    {9.98495483, 1.18377757, 1.43221354},
-    {10.4015999, 1.36577511, 1.17777598},
-    {10.7205076, 1.4741919, 0.886170387},
-    {10.7733879, 1.49488509, 0.641632199},
-    {10.3982353, 1.45486426, 0.427351981},
-    {9.49941158, 1.43877137, 0.342455924},
-    {8.25098419, 1.37570381, 0.324537873},
-    {6.7827692, 1.35689712, 0.372926891},
-    {5.3606987, 1.34382725, 0.425206929},
-    {4.02911949, 1.28240132, 0.478551239},
-    {2.82513213, 1.23492694, 0.569309652},
-    {1.6506927, 1.21751678, 0.679307342},
-    {0.337369084, 1.19235468, 0.821889281},
-    {-0.972633243, 1.18180454, 0.94837606},
-    {-2.1361692, 1.14120865, 1.07007742},
-    {-3.04128814, 1.04266989, 1.21404028},
-    {-3.66539454, 0.965611279, 1.35442519},
-    {-4.13209486, 0.845011473, 1.44990087},
-    {-4.47706604, 0.742473185, 1.55099094},
-    {-4.72898769, 0.544225395, 1.6340059},
-    {-4.74927473, 0.383513391, 1.68929017},
-    {-4.57430887, 0.238845304, 1.7487371},
-    {-4.06017065, 0.0928166732, 1.76537287},
-    {-3.15444922, -0.017251052, 1.70335805},
-    {-1.96480012, -0.0546877496, 1.60598159},
-    {-0.476698667, -0.0138638411, 1.49934947},
-    {1.12321854, 0.0582132339, 1.25978577},
-    {2.6283958, 0.159633473, 0.970261276},
-    {3.79500699, 0.267080545, 0.714543104},
-    {4.66062069, 0.34762904, 0.48912698},
-    {5.08470011, 0.347456753, 0.265686572},
-    {4.75927877, 0.360848725, 0.134673506},
-    {3.90805769, 0.389797956, 0.0943010598},
-    {2.71092725, 0.370859116, 0.0703710094},
-    {1.17037821, 0.36897999, 0.0968935043},
-    {-0.432378143, 0.295299083, 0.227710068},
-    {-2.04557729, 0.208365202, 0.451247215},
-    {-3.52624702, 0.109724849, 0.694572389},
-    {-4.52207661, 0.0441525616, 0.929488897},
-    {-4.82492161, -0.0203922335, 1.08636498},
-    {-4.36528063, -0.182124287, 1.20938015},
-    {-3.37383437, -0.358901709, 1.22909105},
-    {-2.14212251, -0.424399704, 1.22753274},
-    {-0.651360452, -0.349594563, 1.18277442},
-    {1.38663065, -0.427476585, 1.01004755},
-    {3.23462582, -0.328702688, 0.912705123},
-    {4.56207561, -0.196109548, 0.804825783},
-    {5.37268829, -0.0982147679, 0.652003288},
-    {5.85538006, -0.242267624, 0.417341679},
-    {5.78246355, -0.29832238, 0.251056463},
-    {5.02047873, -0.378388733, 0.140160918},
-    {3.95513964, -0.480205029, 0.0641852021},
-    {2.42295504, -0.832230866, 0.0856526271},
-    {0.797630429, -0.962507665, 0.138898656},
-    {-0.695058763, -0.969033837, 0.157970056},
-    {-1.82787693, -0.975319147, 0.141524449},
-    {-2.50017405, -1.08887422, 0.0894433856},
-    {-2.93130207, -1.13537967, 0.00372592267},
-    {-3.1275866, -1.07536542, -0.0770735294},
-    {-2.98389125, -1.00995636, -0.171307892},
-    {-2.54616213, -0.998781919, -0.301309615},
-    {-2.07543898, -0.925872445, -0.390085757},
-    {-1.64253533, -0.841775537, -0.462722629},
-    {-1.37150705, -0.796712279, -0.511544049},
-    {-1.11694109, -0.788697422, -0.533709824},
-    {-0.745626032, -0.729732692, -0.53678602},
-    {-0.498360097, -0.635149717, -0.539795876},
-    {-0.374662012, -0.567164242, -0.544591904},
-    {-0.374092489, -0.476756006, -0.546122253},
-    {-0.596933901, -0.395848602, -0.52832216},
-    {-0.935623527, -0.301847547, -0.483475089},
-    {-1.34826005, -0.233554274, -0.413701773},
-    {-1.60455573, -0.162001759, -0.351378113},
-    {-1.77755308, -0.0819258913, -0.305157363},
-    {-1.81813216, -0.0303371549, -0.27802977},
-    {-1.62838411, 0.0436597504, -0.250110447},
-    {-1.30984855, 0.128032863, -0.24548769},
-    {-0.898394942, 0.190719143, -0.265389919},
-    {-0.351546943, 0.290593266, -0.299546987},
-    {0.296460927, 0.404263765, -0.373493493},
-    {0.980117023, 0.538772285, -0.474046707},
-    {1.56974542, 0.649902225, -0.600938916},
-    {2.1496315, 0.723400235, -0.755717158},
-    {2.5939939, 0.75489378, -0.950287461},
-    {2.83096886, 0.755742908, -1.11364603},
-    {2.87057757, 0.731365204, -1.24928486},
-    {2.67148423, 0.67986685, -1.35973144},
-    {2.13957119, 0.596325099, -1.38371003},
-    {1.18341196, 0.477808207, -1.33763313},
-    {0.071165666, 0.352704436, -1.23690736},
-    {-1.17617178, 0.240923867, -1.12859523},
-    {-2.52622485, 0.141452074, -1.00102103},
-    {-3.77830219, 0.0510926992, -0.863835812},
-    {-4.93282032, -0.0275768265, -0.738456726},
-    {-5.85019779, -0.0980182514, -0.620667875},
-    {-6.44245863, -0.16481787, -0.522228539},
-    {-6.65905952, -0.232972294, -0.451265603},
-    {-6.3680234, -0.295028895, -0.427494943},
-    {-5.58941364, -0.336917132, -0.435385376},
-    {-4.55230904, -0.382846713, -0.504377067},
-    {-3.32675838, -0.409046084, -0.63032645},
-    {-1.97719169, -0.382359892, -0.748842597},
-    {-0.654533029, -0.318100661, -0.798824251},
-    {0.587814748, -0.259345144, -0.767856121},
-    {1.70293963, -0.193047196, -0.686858535},
-    {2.55934215, -0.13665989, -0.588118255},
-    {3.08503556, -0.10677845, -0.496112764},
-    {3.40601563, -0.104184404, -0.413685143},
-    {3.46744871, -0.0899075642, -0.335713506},
-    {3.24791217, -0.0624634475, -0.248533905},
-    {2.81581974, -0.0047624968, -0.178641051},
-    {2.21609712, 0.0946710035, -0.114806168},
-    {1.48716831, 0.168573186, -0.0330084898},
-    {0.752458513, 0.188933969, 0.0340693444},
-    {0.0832773, 0.18937093, 0.0972487405},
-    {-0.552659154, 0.186084643, 0.146757066},
-    {-1.13742733, 0.162304223, 0.187352657},
-    {-1.58978152, 0.152703539, 0.20776692},
-    {-1.84024537, 0.126130134, 0.208315179},
-    {-1.84474206, 0.0550979488, 0.177613869},
-    {-1.64732432, 9.88785177e-06, 0.120422855},
-    {-1.32074201, -0.0277310163, 0.0707398504},
-    {-0.837598503, -0.0434903204, -0.00641948916},
-    {-0.22942704, -0.0574083924, -0.0913080722},
-    {0.349012613, -0.0992124751, -0.204864249},
-    {0.812266529, -0.148865238, -0.317189902},
-    {1.11467266, -0.193828702, -0.404190302},
-    {1.22736788, -0.26255393, -0.469096422},
-    {1.10772085, -0.35328871, -0.537299395},
-    {0.819882452, -0.445168793, -0.588134944},
-    {0.376000643, -0.573042154, -0.631701529},
-    {-0.271964312, -0.786975026, -0.681973755},
-    {-1.11300004, -1.02069855, -0.74775207},
-    {-1.97585464, -1.19356298, -0.851949692},
-    {-2.64571738, -1.25748873, -0.998676538},
-    {-3.13037133, -1.25102019, -1.18940556},
-    {-3.32677078, -1.21887708, -1.38814962},
-    {-3.35012221, -1.17296636, -1.58479178},
-    {-3.33910942, -1.14600563, -1.77327216},
-    {-3.40902209, -1.03068519, -1.91986525},
-    {-3.71381664, -0.838865519, -2.01945114},
-    {-4.22178745, -0.566761136, -2.07394838},
-    {-4.8868022, -0.279840082, -2.04434538},
-    {-5.80164337, -0.0351760425, -1.88015425},
-    {-6.77083683, 0.233773604, -1.62771666},
-    {-7.76006699, 0.45706138, -1.27346277},
-    {-8.67495251, 0.598819435, -0.849485517},
-    {-9.2990036, 0.621351123, -0.376437217},
-    {-9.50524616, 0.482619405, 0.0622562915},
-    {-9.28264141, 0.163518116, 0.365992814},
-    {-8.56556797, -0.199313149, 0.508732975},
-    {-7.36539984, -0.543596268, 0.514566958},
-    {-5.74731827, -0.859268785, 0.406183928},
-    {-3.92722702, -1.09052157, 0.249377027},
-    {-2.1320622, -1.25614166, 0.107735284},
-    {-0.34053883, -1.36692083, -0.0015140716},
-    {1.36950636, -1.45332515, -0.0925219506},
-    {2.92114496, -1.53448641, -0.197913498},
-    {4.48123264, -1.57539248, -0.209919274},
-    {5.88923359, -1.59331703, -0.16202274},
-    {7.07122087, -1.55582917, -0.0444544479},
-    {8.01762009, -1.5020107, 0.0753263086},
-    {8.66772842, -1.40396905, 0.26746881},
-    {9.03697968, -1.19257081, 0.50766778},
-    {9.37090015, -0.997256219, 0.632183135},
-    {9.48269176, -0.760886967, 0.695450902},
-    {9.42121506, -0.549230158, 0.684196055},
-    {9.13267899, -0.345048487, 0.601469159},
-    {8.57192421, -0.153696552, 0.448604226},
-    {7.81306028, 0.00600741943, 0.248888329},
-    {7.02105522, 0.127267942, 0.00608516112},
-    {6.13043308, 0.19920291, -0.271910429},
-    {5.26338816, 0.0913004726, -0.518328488},
-    {4.41265869, -0.0562393442, -0.738151908},
-    {3.37369037, -0.238426432, -0.929019451},
-    {2.05148292, -0.475073814, -1.08930624},
-    {0.533223331, -0.730065167, -1.1765182},
-    {-0.81233269, -0.893784583, -1.21785951},
-    {-2.19793749, -1.03348827, -1.23857963},
-    {-3.70364213, -1.21627855, -1.2128849},
-    {-4.97733879, -1.3223449, -1.27395713},
-    {-5.9681282, -1.388538, -1.35796869},
-    {-6.77457809, -1.45425391, -1.44136083},
-    {-7.2441535, -1.42399442, -1.58542001},
-    {-7.55704641, -1.31660128, -1.72008264},
-    {-7.73570633, -1.18746614, -1.85253417},
-    {-7.65071821, -0.99811697, -2.01778841},
-    {-7.38755083, -0.717655241, -2.15819931},
-    {-7.01290083, -0.39778015, -2.26120687},
-    {-6.5892868, -0.0976327658, -2.292974},
-    {-6.28064394, 0.227670908, -2.21440363},
-    {-6.02934122, 0.553948581, -2.07020712},
-    {-5.85011625, 0.835177183, -1.88793647},
-    {-5.7558794, 1.09251273, -1.55888712},
-    {-5.77518749, 1.32995892, -1.1417315},
-    {-5.88332367, 1.45887983, -0.68941927},
-    {-6.05107737, 1.51712096, -0.152763546},
-    {-6.16017103, 1.44720638, 0.272191346},
-    {-5.92632103, 1.2784282, 0.627877951},
-    {-5.27954102, 1.0301466, 0.914584339},
-    {-4.26425362, 0.7236498, 1.07802594},
-    {-2.98752022, 0.427423477, 1.18085766},
-    {-1.64554048, 0.165780589, 1.19080472},
-    {-0.38629663, -0.045453012, 1.12503755},
-    {1.052665, -0.244113401, 1.05862057},
-    {2.32487988, -0.371687353, 1.01643407},
-    {3.41161942, -0.430369467, 1.01300848},
-    {4.44025993, -0.466652781, 0.977756083},
-    {5.4606452, -0.486444265, 0.9719612},
-    {6.39873266, -0.483647197, 0.939061522},
-    {7.16201591, -0.4128097, 0.968610346},
-    {7.74302101, -0.339661866, 0.980539501},
-    {8.05748177, -0.252693713, 0.967907369},
-    {7.95552778, -0.142479867, 0.950036347},
-    {7.43383265, -0.0662043691, 0.930617452},
-    {6.64533091, -0.0544817634, 0.963137984},
-    {5.60663414, -0.00383129949, 1.07478356},
-    {4.28114605, 0.0571812615, 1.22639143},
-    {2.83351302, 0.029209571, 1.38703382},
-    {1.3475219, -0.0257310569, 1.56121743},
-    {-0.177246764, -0.107975714, 1.70219398},
-    {-1.6509583, -0.226321876, 1.82159996},
-    {-2.943115, -0.410087526, 1.96481395},
-    {-3.96768475, -0.613715529, 2.10398912},
-    {-4.77559757, -0.927545547, 2.18230939},
-    {-5.17799091, -1.32265544, 2.1706028},
-    {-4.85059118, -1.70022297, 2.09135151},
-    {-3.93971491, -2.10336494, 1.88263035},
-    {-2.46097875, -2.39013386, 1.71688676},
-    {-0.578972816, -2.33398366, 1.69525623},
-    {1.3079263, -1.99722469, 1.90920508},
-    {3.32787871, -1.51918852, 2.17258143},
-    {5.05315351, -1.16325462, 2.28276229},
-    {6.13141346, -0.934887707, 2.31209469},
-    {6.6169095, -0.712930799, 2.30042076},
-    {6.86237001, -0.583501399, 2.22406387},
-    {6.77488708, -0.464092076, 2.11918759},
-    {6.45267105, -0.265902132, 1.9866308},
-    {6.07525206, -0.103774741, 1.81152165},
-    {5.65038395, -0.095038712, 1.60185742},
-    {5.17367554, -0.225322172, 1.38857305},
-    {4.58482838, -0.238742337, 1.16168404},
-    {4.04759169, -0.144288629, 0.920088232},
-    {3.54825592, -0.227102429, 0.717802465},
-    {2.94018483, -0.375229239, 0.503311157},
-    {2.18278909, -0.387085408, 0.219063252},
-    {1.67123008, -0.380521655, -0.00839979108},
-    {1.19099748, -0.561900914, -0.222340822},
-    {0.764371097, -0.736873269, -0.415119469},
-    {0.303652465, -0.869291246, -0.56442523},
-    {-0.0905279443, -0.899493814, -0.701173007},
-    {-0.550224423, -0.978212714, -0.820668161},
-    {-1.14971578, -1.18024909, -0.952748239},
-    {-1.42352057, -1.32455373, -1.17146909},
-    {-1.45646191, -1.40799332, -1.41064799},
-    {-1.47992432, -1.40551555, -1.62731194},
-    {-1.62580717, -1.38073909, -1.82521331},
-    {-1.89686155, -1.33881295, -1.97608042},
-    {-2.11355472, -1.27504814, -2.09447861},
-    {-2.23866725, -1.16375363, -2.20436049},
-    {-2.42952991, -1.05443776, -2.30098867},
-    {-2.60931706, -0.922257662, -2.36005306},
-    {-2.86750817, -0.713652909, -2.37849402},
-    {-3.2620368, -0.500841081, -2.35701036},
-    {-3.87616038, -0.335686624, -2.26852989},
-    {-4.65489483, -0.197668418, -2.112679},
-    {-5.62046528, -0.0357033424, -1.89391208},
-    {-6.83001709, 0.0616019219, -1.58345139},
-    {-8.14583206, 0.0972035676, -1.21971953},
-    {-9.15592289, 0.146269798, -0.891496956},
-    {-9.76172447, 0.115328662, -0.614807129},
-    {-9.88835239, -0.0382437482, -0.407532632},
-    {-9.40706253, -0.212422475, -0.334697753},
-    {-8.46079731, -0.338561237, -0.372687817},
-    {-7.11944675, -0.444375157, -0.506505609},
-    {-5.37011671, -0.525434673, -0.698864281},
-    {-3.20057774, -0.585180879, -0.93417424},
-    {-1.03280067, -0.551840782, -1.14640415},
-    {1.09664726, -0.482266992, -1.27732074},
-    {3.05558658, -0.424233526, -1.36964214},
-    {4.82527685, -0.394551545, -1.38602102},
-    {6.29548597, -0.370357037, -1.2795819},
-    {7.20290661, -0.323897064, -1.1534214},
-    {7.49626637, -0.292535633, -1.12801301},
-    {7.38660336, -0.39145416, -1.1817565},
-    {6.95587301, -0.557294965, -1.2069819},
-    {6.11761236, -0.721527755, -1.17456412},
-    {4.91161251, -0.897531092, -1.0902164},
-    {3.61493635, -1.05982542, -0.985356867},
-    {2.36286354, -1.18643034, -0.889013886},
-    {1.20341527, -1.31893563, -0.792421699},
-    {0.214038894, -1.44001973, -0.701092362},
-    {-0.735031188, -1.50329542, -0.601269901},
-    {-1.70215976, -1.51701891, -0.481067151},
-    {-2.68938398, -1.52885282, -0.353370011},
-    {-3.62041426, -1.48365271, -0.228509992},
-    {-4.42679739, -1.3920964, -0.111312173},
-    {-5.0906744, -1.29483616, -0.0180927087},
-    {-5.66263533, -1.20569932, 0.0622905642},
-    {-6.28531408, -1.11410666, 0.178031534},
-    {-6.96010303, -1.06601095, 0.342929095},
-    {-7.76810837, -1.06862378, 0.552430868},
-    {-8.57209396, -1.13985407, 0.748713672},
-    {-9.38756752, -1.25725567, 0.920088172},
-    {-10.1073503, -1.45082831, 1.005193},
-    {-10.6446772, -1.72388041, 1.01975453},
-    {-10.9774151, -2.04475451, 0.899404407},
-    {-11.0349741, -2.34562969, 0.624685109},
-    {-10.9581041, -2.58131289, 0.230813697},
-    {-10.7823496, -2.71095443, -0.225367188},
-    {-10.5994701, -2.73573089, -0.733900547},
-    {-10.3505325, -2.6188612, -1.25917077},
-    {-10.1116056, -2.37881637, -1.74724245},
-    {-9.8603735, -2.0335288, -2.16412187},
-    {-9.74456501, -1.57738805, -2.46263433},
-    {-9.71125698, -1.02989256, -2.59759521},
-    {-9.89689732, -0.457629591, -2.50483012},
-    {-10.3309326, 0.0416418016, -2.19603157},
-    {-11.1035986, 0.410900593, -1.73517025},
-    {-12.1150646, 0.615464151, -1.13523686},
-    {-13.0615215, 0.597289681, -0.519076765},
-    {-13.3974648, 0.34538424, -0.0314620286},
-    {-13.0926161, -0.133068144, 0.269497514},
-    {-12.1842108, -0.702285945, 0.323710263},
-    {-10.7393179, -1.22414851, 0.153164446},
-    {-8.93041992, -1.64977121, -0.189108446},
-    {-6.87917137, -1.92314494, -0.621125877},
-    {-4.73125267, -2.13777137, -1.06369615},
-    {-2.49803376, -2.32110405, -1.48501217},
-    {-0.2107853, -2.51033616, -1.84691453},
-    {1.75799668, -2.69829154, -2.08837962},
-    {3.30259061, -2.90342879, -2.18122482},
-    {4.30878496, -3.08982944, -2.1113925},
-    {4.79465055, -3.24235201, -1.86810124},
-    {4.92134047, -3.37769127, -1.50024247},
-    {4.88753319, -3.43825245, -1.08336556},
-    {4.77758551, -3.39298964, -0.648745894},
-    {4.62952662, -3.26007748, -0.21542336},
-    {4.49471855, -3.07373857, 0.185473621},
-    {4.41664791, -2.80917954, 0.54022634},
-    {4.4358201, -2.44360089, 0.829329848},
-    {4.53170061, -2.03101397, 1.03891575},
-    {4.7567668, -1.58255923, 1.15523207},
-    {5.05692768, -1.11883998, 1.17911077},
-    {5.22688675, -0.671571016, 1.10902059},
-    {5.32010794, -0.255138069, 0.929782629},
-    {5.47315598, 0.0657585189, 0.640299976},
-    {5.51640797, 0.303945929, 0.308308542},
-    {5.45501614, 0.431503326, -0.0593813211},
-    {5.41531944, 0.474002779, -0.411660492},
-    {5.56512451, 0.415304989, -0.700812459},
-    {6.08631659, 0.205422014, -0.950686514},
-    {6.74834776, -0.0607340857, -1.19073582},
-    {7.22527599, -0.363864899, -1.34635651},
-    {7.6312232, -0.680029988, -1.43384492},
-    {7.91573286, -0.998610675, -1.42915654},
-    {8.24369335, -1.28985834, -1.32667983},
-    {8.68994522, -1.51888859, -1.12096262},
-    {9.14955616, -1.68778467, -0.82916528},
-    {9.58194733, -1.77847648, -0.529702306},
-    {10.1861448, -1.77719629, -0.231552988},
-    {11.0892735, -1.67085683, 0.0609925315},
-    {11.8169203, -1.5383606, 0.327963412},
-    {12.1408672, -1.37220204, 0.596837938},
-    {12.2643366, -1.15940499, 0.828513443},
-    {12.3775454, -0.926050007, 0.992068589},
-    {12.5011997, -0.693798423, 1.08319736},
-    {12.6093349, -0.494256169, 1.1263485},
-    {12.6674376, -0.323044151, 1.13983369},
-    {12.7347546, -0.175900176, 1.11356771},
-    {12.7816696, -0.0627724305, 1.06787848},
-    {12.750926, -0.00216844748, 1.01916099},
-    {12.5901632, 0.0111177377, 0.973997951},
-    {12.2548046, -0.011735389, 0.985199571},
-    {11.7790623, -0.0431461483, 1.04282892},
-    {11.1439476, -0.0747352988, 1.13356531},
-    {10.0916615, -0.16053845, 1.21221817},
-    {9.02883434, -0.263584822, 1.29354548},
-    {8.07294273, -0.323115498, 1.41275811},
-    {7.23556423, -0.35577035, 1.53853238},
-    {6.14809752, -0.417588532, 1.60642755},
-    {4.71873713, -0.581239998, 1.59324419},
-    {3.06165576, -0.830468237, 1.51261246},
-    {1.44035888, -1.08229029, 1.40271461},
-    {0.32057783, -1.2804693, 1.30407417},
-    {-0.234780893, -1.40224242, 1.21715224},
-    {-0.600051463, -1.47772837, 1.09947896},
-    {-0.80635339, -1.5013957, 0.985654533},
-    {-0.865678251, -1.49916756, 0.867565751},
-    {-0.910831511, -1.49695027, 0.771806121},
-    {-0.919859767, -1.46838808, 0.688236892},
-    {-0.749688506, -1.4147712, 0.641406357},
-    {-0.546200216, -1.38052309, 0.603248477},
-    {-0.185494468, -1.38803935, 0.562608361},
-    {0.148738712, -1.36938202, 0.52614212},
-    {0.458128899, -1.36520803, 0.49812299},
-    {0.628787458, -1.33630776, 0.464150965},
-    {0.80995518, -1.31814933, 0.432290673},
-    {1.04027665, -1.28110111, 0.385813922},
-    {1.31125498, -1.20918274, 0.310520053},
-    {1.47860444, -1.1176095, 0.19453615},
-    {1.68812871, -1.05722368, 0.0126428418},
-    {1.81002772, -0.982785404, -0.203351036},
-    {2.04727697, -0.947606981, -0.409918606},
-    {2.40564418, -0.946302354, -0.635110497},
-    {2.86770082, -0.970762908, -0.863486588},
-    {3.25378227, -1.05299103, -1.07614863},
-    {3.65581703, -1.19081628, -1.26947439},
-    {4.21061707, -1.35327196, -1.41041946},
-    {4.68844366, -1.54637086, -1.48236597},
-    {5.11872053, -1.74086297, -1.52699792},
-    {5.5521369, -1.93375826, -1.50357151},
-    {5.98020983, -2.08698559, -1.39466774},
-    {6.41629934, -2.19462132, -1.22022307},
-    {6.80761194, -2.25912428, -0.991476357},
-    {7.20488453, -2.24069977, -0.717222154},
-    {7.62272549, -2.17809343, -0.410825104},
-    {8.04269791, -2.02336287, -0.121594645},
-    {8.40403271, -1.78574336, 0.142339244},
-    {8.62000084, -1.50273788, 0.324602813},
-    {8.82446957, -1.19834089, 0.453724891},
-    {9.10614777, -0.870871425, 0.573827982},
-    {9.49493027, -0.522981226, 0.697871208},
-    {9.96739674, -0.201827064, 0.799564898},
-    {10.3001842, 0.134168789, 0.800263166},
-    {10.3143358, 0.421017259, 0.675010145},
-    {10.0750198, 0.588825226, 0.445049047},
-    {9.43081951, 0.647519946, 0.196302295},
-    {8.37434959, 0.644182086, -0.0153490016},
-    {6.89396429, 0.627952635, -0.161896124},
-    {5.06277657, 0.58498019, -0.249272034},
-    {2.8439579, 0.55023998, -0.260588944},
-    {0.476054519, 0.524706125, -0.190314248},
-    {-1.67223358, 0.45596385, -0.056354925},
-    {-3.46977711, 0.355278164, 0.125028953},
-    {-4.88662529, 0.251366585, 0.306030333},
-    {-5.98942995, 0.0976525545, 0.468557507},
-    {-6.71912193, -0.030262582, 0.616961479},
-    {-7.14283228, -0.165676653, 0.752373099},
-    {-7.29607105, -0.335196912, 0.844305038},
-    {-7.23941183, -0.536143422, 0.844777763},
-    {-6.93414211, -0.574710429, 0.827323198},
-    {-6.5694108, -0.523581922, 0.895336449},
-    {-6.15107584, -0.507658839, 1.02986979},
-    {-5.96295738, -0.509704113, 1.10828984},
-    {-6.04938459, -0.563068628, 1.18903089},
-    {-6.18934393, -0.71330595, 1.25363684},
-    {-6.32635641, -0.902286828, 1.34694254},
-    {-6.45014572, -1.13691151, 1.39347494},
-    {-6.70601845, -1.43993664, 1.38272691},
-    {-7.08950567, -1.7684164, 1.31644559},
-    {-7.4956398, -2.08384275, 1.16160083},
-    {-7.78810406, -2.38708091, 0.905305624},
-    {-7.80642748, -2.59874511, 0.580683589},
-    {-7.36016846, -2.71679068, 0.265340388},
-    {-6.84343719, -2.75387239, -0.0586662889},
-    {-6.47398329, -2.80151272, -0.334616572},
-    {-6.22172976, -2.67314076, -0.723141909},
-    {-5.82048368, -1.81391215, -0.956223845},
-    {-5.51633072, -1.09354794, -0.999607742},
-    {-5.46082497, -0.442907363, -0.968927979},
-    {-5.2464509, 0.336471349, -0.6523211},
-    {-5.08369112, 1.28151989, -0.16578725},
-    {-5.51001596, 1.6458112, 0.120435953},
-    {-5.64250851, 2.15408468, 0.722774327},
-    {-4.4029398, 3.68647552, 2.35766792},
-    {-4.02708101, 3.95154428, 3.10602331},
-    {-3.41679811, 3.90254903, 3.63392758},
-    {-2.34520411, 3.81932998, 4.27247763},
-    {-1.43031883, 3.56204653, 4.66801453},
-    {-0.820337892, 3.1284492, 4.82248592},
-    {0.0745921358, 2.51733446, 4.71624613},
-    {1.41031098, 1.64924324, 3.92422986},
-    {3.06130695, 0.405496329, 2.26292419},
-    {3.83646083, -0.967586994, 0.857250571},
-    {3.69725513, -1.73935628, 0.493265361},
-    {3.81284928, -1.99960256, 0.629554749},
-    {4.05828619, -2.13906622, 0.821913481},
-    {4.245749, -2.24617529, 1.01751184},
-    {4.38118744, -2.11735797, 1.2343719},
-    {4.45519209, -1.67175472, 1.34725809},
-    {4.32000256, -0.916836739, 1.2335192},
-    {3.88204098, -0.0776951686, 0.863717556},
-    {3.18441319, 0.519619286, 0.339746922},
-    {2.31106806, 0.945907056, -0.27460748},
-    {1.43098938, 1.07840228, -0.870551109},
-    {0.769245803, 0.95778513, -1.44395053},
-    {0.819898546, 1.02388465, -1.94811177},
-    {1.32199705, 1.27827728, -2.16564894},
-    {2.0524714, 0.723466814, -1.9789443},
-    {3.42455649, -0.653125048, -1.51678789},
-    {4.87215233, -2.57662868, -0.659787118},
-    {5.37080908, -3.8605001, 0.456934184},
-    {4.66930103, -2.98341203, 0.955423713},
-    {2.92468762, -0.710260689, 0.662911594},
-    {0.834764898, 1.20542777, 0.0897598565},
-    {-1.54485941, 1.81647599, -0.167882413},
-    {-3.79453325, 1.39409018, 0.0361525416},
-    {-4.90199089, 0.921312988, 0.236988768},
-    {-4.83318186, 1.15564215, 0.199092373},
-    {-4.01060247, 2.09826279, 0.15409559},
-    {-3.1091373, 3.06225085, 0.181665689},
-    {-2.56280518, 3.86141515, 0.247997895},
-    {-2.41075063, 4.34310961, 0.340404779},
-    {-2.31101823, 4.34850025, 0.499370098},
-    {-2.25900149, 3.84527469, 0.619734883},
-    {-1.17861617, 2.88547373, 0.494315058},
-    {2.36372375, 2.10155511, 0.105972655},
-    {1.58530939, 1.6887691, -0.0253427438},
-    {1.02369809, 1.36991704, -0.103729576},
-    {0.927304566, 1.09654224, -0.141234457},
-    {1.69141638, 0.972146332, -0.164490178},
-    {2.90190125, 1.02297759, -0.220795423},
-    {4.57644653, 1.25035834, -0.388659269},
-    {5.69433975, 1.300035, -0.575051308},
-    {5.75268507, 0.940465748, -0.627363801},
-    {5.51592636, 0.441164404, -0.41494894},
-    {5.54251528, 0.177120253, -0.234662518},
-    {5.76791668, 0.26178661, -0.327522248},
-    {5.51919174, 0.484754324, -0.72494632},
-    {4.84664488, 0.843109012, -1.34681106},
-    {4.20394087, 0.981815636, -1.70374262},
-    {3.67488217, 0.838885546, -1.63265562},
-    {3.3056128, 0.620569468, -1.2564683},
-    {2.99314976, 0.473288059, -0.887274981},
-    {2.44595194, 0.43747288, -0.748999178},
-    {1.64779949, 0.459805101, -0.800846815},
-    {0.834184885, 0.528117001, -0.82985276},
-    {0.264518082, 0.549208045, -0.591192126},
-    {0.10425958, 0.509609044, -0.227232262},
-    {-0.000252801226, 0.456279755, 0.0630378351},
-    {-0.29953742, 0.428789377, 0.197608396},
-    {-0.541777194, 0.401455551, 0.260567993},
-    {-0.56309545, 0.375379443, 0.292229742},
-    {-0.424246758, 0.323218435, 0.337225467},
-    {-0.124983296, 0.246760517, 0.435483396},
-    {0.181313977, 0.150497988, 0.517462015},
-    {0.386543125, 0.0548507385, 0.532111645},
-    {0.52708745, -0.0457684174, 0.513038814},
-    {0.679304898, -0.14146556, 0.531579554},
-    {0.762285113, -0.230014458, 0.591404021},
-    {0.774781704, -0.311072916, 0.681943774},
-    {0.708883584, -0.379017264, 0.771930277},
-    {0.518045545, -0.438570321, 0.837433338},
-    {0.28903994, -0.49673593, 0.88455689},
-    {0.122234389, -0.558086157, 0.936696768},
-    {0.0622371733, -0.60806179, 0.99145782},
-    {0.0860184729, -0.641111732, 1.02249599},
-    {0.153454259, -0.666737318, 1.03402901},
-    {0.24845998, -0.688044906, 1.01975954},
-    {0.348862916, -0.701996207, 0.979219377},
-    {0.423159093, -0.701015055, 0.910776258},
-    {0.467258036, -0.690738916, 0.829579234},
-    {0.496723622, -0.676820576, 0.749845445},
-    {0.502646565, -0.651367009, 0.667705774},
-    {0.469785511, -0.615212023, 0.570789576},
-    {0.377547085, -0.566041529, 0.447439313},
-    {0.24096106, -0.504923701, 0.300760716},
-    {0.0851845443, -0.439764559, 0.143935561},
-    {-0.0793879107, -0.361575246, -0.0173973329},
-    {-0.218234986, -0.280972898, -0.168133423},
-    {-0.318755448, -0.202841416, -0.306015551},
-    {-0.375774592, -0.116289973, -0.439359605},
-    {-0.400300205, -0.0204749387, -0.564070463},
-    {-0.378246397, 0.0788381919, -0.670876861},
-    {-0.313017607, 0.18103449, -0.750503361},
-    {-0.220314622, 0.278421164, -0.806001902},
-    {-0.128824487, 0.369595349, -0.847839236},
-    {-0.0491240174, 0.45651263, -0.893218279},
-    {0.0105391107, 0.536745191, -0.947327673},
-    {0.0627990216, 0.608594894, -0.993872285},
-    {0.100311652, 0.665397823, -1.03089392},
-    {0.122864753, 0.709482193, -1.05391657},
-    {0.142569542, 0.735289514, -1.05878866},
-    {0.158965245, 0.743104935, -1.05266929},
-    {0.172600657, 0.722203076, -1.02621317},
-    {0.208185688, 0.661558688, -0.954461098},
-    {0.303151131, 0.573643804, -0.806417465},
-    {0.410381317, 0.488676161, -0.585822701},
-    {0.596137702, 0.403478414, -0.30658564},
-    {0.818036616, 0.315452844, -0.0062199519},
-    {1.0000689, 0.23764801, 0.313213855},
-    {1.12351906, 0.1776191, 0.638251483},
-    {1.17873585, 0.13672401, 0.961254358},
-    {1.14193952, 0.120309159, 1.31198108},
-    {1.03217864, 0.125339046, 1.66700816},
-    {0.885761261, 0.149454668, 2.01375127},
-    {0.744704843, 0.193981588, 2.3662374},
-    {0.68760252, 0.241056904, 2.73266363},
-    {0.794823289, 0.292921275, 3.08573723},
-    {1.06746411, 0.358404368, 3.39740515},
-    {1.64530528, 0.437073886, 3.60524511},
-    {2.49252844, 0.53679508, 3.6500752},
-    {3.69583416, 0.688314021, 3.48201108},
-    {5.43644142, 0.855131328, 3.00281},
-    {6.96603298, 0.916923165, 2.29393673},
-    {7.46219397, 0.90659672, 1.76288819},
-    {7.44086266, 0.914366186, 1.43038428},
-    {7.07173777, 0.842724502, 1.11453533},
-    {6.60302353, 0.641308665, 0.808894455},
-    {6.20406389, 0.354579777, 0.562408924},
-    {6.06970501, -0.00135111995, 0.369416267},
-    {6.2959733, -0.418824434, 0.226728424},
-    {6.26915073, -0.790925443, 0.189223588},
-    {6.05303764, -1.03990281, 0.249420449},
-    {5.77193165, -1.19486332, 0.362982512},
-    {5.3119936, -1.32606447, 0.476921618},
-    {4.90582609, -1.43090725, 0.583959401},
-    {4.58062267, -1.4805603, 0.690681219},
-    {4.38896084, -1.46428096, 0.748365641},
-    {4.2837019, -1.40233958, 0.746619523},
-    {4.14821434, -1.31452429, 0.685442746},
-    {4.123703, -1.11953843, 0.4582645},
-    {4.35808802, -0.750656605, 0.017968636},
-    {4.50925159, -0.528710485, -0.320365936},
-    {4.45074511, -0.519451499, -0.458825022},
-    {4.35091496, -0.542695105, -0.565303862},
-    {4.20686436, -0.582783759, -0.660921216},
-    {4.02000761, -0.632987976, -0.757064044},
-    {3.79134345, -0.695983827, -0.850927591},
-    {3.50527167, -0.771653116, -0.946013927},
-    {3.12121916, -0.852517605, -1.07259023},
-    {2.45866013, -0.967232168, -1.35298395},
-    {1.65387428, -1.17753112, -1.81457579},
-    {0.973164141, -1.33602512, -2.2429719},
-    {0.658219814, -1.34591889, -2.47395873},
-    {0.534121633, -1.33676016, -2.5669744},
-    {0.79415226, -1.24958944, -2.43174028},
-    {1.24018478, -1.0642153, -2.15718508},
-    {1.68641102, -0.858071685, -1.85743964},
-    {2.04644966, -0.707561314, -1.6164602},
-    {2.38060093, -0.619827211, -1.46566236},
-    {2.75886512, -0.496117443, -1.3275907},
-    {2.98365164, -0.351783067, -1.19818532},
-    {2.97478867, -0.237012982, -1.11160076},
-    {2.93774033, -0.0386015251, -0.955342591},
-    {2.76615024, 0.136263967, -0.838776588},
-    {2.41876459, 0.176155806, -0.798618615},
-    {1.99398053, 0.114085063, -0.845090568},
-    {1.6530503, 0.00985235907, -0.991036952},
-    {1.1620307, -0.114626624, -1.12453008},
-    {0.590387344, -0.14849402, -1.15599179},
-    {0.0315409116, -0.114261292, -1.08052194},
-    {-0.113846235, 0.059083961, -0.925326526},
-    {0.115381405, 0.251902223, -0.773351908},
-    {0.477517813, 0.494475454, -0.561047077},
-    {0.84425652, 0.771477103, -0.319699705},
-    {1.12401795, 1.01321876, -0.0904267654},
-    {1.29735363, 1.24578536, 0.131580576},
-    {1.37392807, 1.45650172, 0.329559714},
-    {1.41909087, 1.62822449, 0.477071345},
-    {1.41042733, 1.72753, 0.566732287},
-    {1.26565981, 1.77074742, 0.626212537},
-    {1.00683105, 1.78201604, 0.689909399},
-    {0.638382077, 1.75709558, 0.763281286},
-    {0.259617656, 1.7281785, 0.867509007},
-    {0.00871963054, 1.71075881, 0.976509392},
-    {-0.14869155, 1.65203536, 1.04776299},
-    {-0.270656645, 1.56132102, 1.10747766},
-    {-0.323511183, 1.48191023, 1.1778301},
-    {-0.30626747, 1.39299738, 1.24910009},
-    {-0.253066272, 1.2886188, 1.30932057},
-    {-0.159919858, 1.19067812, 1.36388683},
-    {-0.0692132786, 1.1064266, 1.41463017},
-    {-0.0596482567, 1.03149128, 1.44034004},
-    {-0.182168812, 0.947619319, 1.43590486},
-    {-0.449488878, 0.838436425, 1.38530457},
-    {-0.786904275, 0.697522223, 1.31502843},
-    {-1.12213981, 0.550581753, 1.23710716},
-    {-1.43755543, 0.415939033, 1.11041844},
-    {-1.74857533, 0.27975148, 0.949288011},
-    {-2.13291001, 0.127334461, 0.796305656},
-    {-2.579602, -0.0448538512, 0.564753532},
-    {-2.94344401, -0.170079201, 0.310190529},
-    {-3.27962947, -0.256435096, 0.0860849619},
-    {-3.64169836, -0.310527682, -0.16272755},
-    {-4.07123041, -0.332826495, -0.424377352},
-    {-4.56911325, -0.315268427, -0.639344931},
-    {-5.09119034, -0.236397788, -0.805369854},
-    {-5.5176754, -0.0801683068, -0.93037349},
-    {-5.79779577, 0.118815288, -0.991603374},
-    {-5.93149662, 0.337249815, -0.983488083},
-    {-5.96077871, 0.549998105, -0.901183486},
-    {-5.90149784, 0.724930227, -0.746139109},
-    {-5.80518532, 0.862331629, -0.545798838},
-    {-5.77648449, 0.92289263, -0.320449054},
-    {-5.73719168, 0.890782952, -0.0755941272},
-    {-5.68464565, 0.808139145, 0.178788945},
-    {-5.69628716, 0.678753257, 0.421176374},
-    {-5.85050964, 0.492495686, 0.631786168},
-    {-6.19206429, 0.244166389, 0.80285728},
-    {-6.71325302, -0.057125695, 0.940557837},
-    {-7.35933352, -0.413835108, 1.03337991},
-    {-8.02878952, -0.797808766, 1.04942584},
-    {-8.65394688, -1.1638397, 0.951853752},
-    {-9.18495178, -1.46658838, 0.712358296},
-    {-9.6124506, -1.68504119, 0.368154496},
-    {-9.94693184, -1.80798638, -0.0640619919},
-    {-10.0912848, -1.77367091, -0.513639212},
-    {-9.96449471, -1.5823487, -0.902997971},
-    {-9.49363708, -1.28816032, -1.20750749},
-    {-8.70709419, -0.905136347, -1.4086138},
-    {-7.76112032, -0.481115907, -1.42695725},
-    {-6.75553846, -0.0935421512, -1.28393853},
-    {-5.68840361, 0.211890489, -1.03700519},
-    {-4.67316484, 0.429640889, -0.7370767},
-    {-3.7076807, 0.574159324, -0.464867771},
-    {-2.68489361, 0.679750383, -0.276815832},
-    {-1.49779046, 0.778596878, -0.191736773},
-    {-0.151532069, 0.874604046, -0.180698186},
-    {1.24512351, 0.962884367, -0.192891672},
-    {2.49463391, 1.01666093, -0.168565691},
-    {3.46754122, 1.02096784, -0.104960084},
-    {4.18295336, 1.01012087, -0.0339380726},
-    {4.67510223, 1.00717962, 0.00759583432},
-    {4.86824465, 1.00264335, 0.00473824795},
-    {4.73112679, 0.989888787, -0.0214184131},
-    {4.36832476, 0.976203978, 0.0128862206},
-    {3.96045876, 0.97721982, 0.128804639},
-    {3.56084561, 1.00267136, 0.269846708},
-    {3.2121408, 1.04144716, 0.414787292},
-    {2.86032438, 1.06980765, 0.543707252},
-    {2.45574617, 1.05976212, 0.619411349},
-    {2.03015566, 1.00789773, 0.650689483},
-    {1.6238879, 0.934914947, 0.675582469},
-    {1.27779841, 0.852238119, 0.722940564},
-    {0.98111254, 0.759949684, 0.789304972},
-    {0.721312523, 0.650906205, 0.855493248},
-    {0.485200703, 0.52588141, 0.894924521},
-    {0.278258234, 0.377643526, 0.908298552},
-    {0.106385894, 0.209096879, 0.898454666},
-    {-0.00550489035, 0.0386056863, 0.87868017},
-    {-0.0407432355, -0.107493475, 0.874625742},
-    {-0.0304163918, -0.223127142, 0.881930709},
-    {-0.0423894599, -0.32521069, 0.883172989},
-    {-0.0906454101, -0.42903915, 0.864998043},
-    {-0.140403479, -0.51474297, 0.836191893},
-    {-0.170246124, -0.565210164, 0.811653733},
-    {-0.194646731, -0.57890296, 0.787785769},
-    {-0.255259693, -0.57066524, 0.751133978},
-    {-0.354207456, -0.549911797, 0.698529959},
-    {-0.50927043, -0.52072525, 0.623137176},
-    {-0.729801059, -0.479708344, 0.518995583},
-    {-0.99377346, -0.436605096, 0.397620201},
-    {-1.29054272, -0.388498753, 0.256843179},
-    {-1.58574867, -0.332094908, 0.106937125},
-    {-1.86524105, -0.27361235, -0.0489884987},
-    {-2.10494113, -0.213633314, -0.216121733},
-    {-2.25644326, -0.146254569, -0.374791056},
-    {-2.29183149, -0.0657690018, -0.525484204},
-    {-2.22795892, 0.0225581583, -0.66018635},
-    {-2.09460139, 0.117579408, -0.772098303},
-    {-1.87513471, 0.222632468, -0.848487616},
-    {-1.577052, 0.321239561, -0.890890479},
-    {-1.22209966, 0.406510621, -0.915650249},
-    {-0.815765083, 0.485412985, -0.917994678},
-    {-0.350532532, 0.559093893, -0.883956254},
-    {0.187168241, 0.623332977, -0.804665983},
-    {0.747914135, 0.66865927, -0.7113024},
-    {1.30021346, 0.690758467, -0.616287112},
-    {1.83403921, 0.701001704, -0.520739615},
-    {2.34682894, 0.703213394, -0.425541282},
-    {2.83051991, 0.692171752, -0.330076963},
-    {3.27122498, 0.679883599, -0.240682036},
-    {3.64382029, 0.67257756, -0.169371903},
-    {3.90186119, 0.669002533, -0.114613205},
-    {4.01764679, 0.669257879, -0.0594977215},
-    {3.96862531, 0.672367513, -0.0099447323},
-    {3.76467156, 0.684982538, 0.0394106656},
-    {3.51114845, 0.71294874, 0.0929725021},
-    {3.29871249, 0.757721603, 0.150836423},
-    {3.13384056, 0.822789013, 0.217982367},
-    {3.0152626, 0.91499424, 0.293708652},
-    {2.94401097, 1.01788628, 0.380058527},
-    {2.94066691, 1.12097168, 0.461008161},
-    {3.01161981, 1.21719885, 0.533019245},
-    {3.16711378, 1.3070116, 0.589812577},
-    {3.39166331, 1.38770461, 0.613301218},
-    {3.64978552, 1.45147765, 0.611333966},
-    {3.899544, 1.48260272, 0.583295345},
-    {4.16263008, 1.48092902, 0.538646698},
-    {4.4062047, 1.46965504, 0.483889014},
-    {4.61093521, 1.45106459, 0.41449818},
-    {4.80922699, 1.41097236, 0.329120815},
-    {5.01579618, 1.33891535, 0.237061709},
-    {5.12490606, 1.25093997, 0.137949303},
-    {5.30655575, 1.16616809, 0.0344534144},
-    {5.52930307, 1.06596994, -0.0616271794},
-    {5.80679083, 0.961406887, -0.15289098},
-    {6.17667675, 0.853551686, -0.230222717},
-    {6.57574463, 0.700602591, -0.267803162},
-    {6.96552372, 0.533744574, -0.288113683},
-    {7.35736799, 0.377676815, -0.2999295},
-    {7.73839235, 0.229820848, -0.264892191},
-    {8.07969379, 0.108860172, -0.151070982},
-    {8.36508942, 0.0258672331, -0.0317613482},
-    {8.5878706, -0.0355837047, 0.0602104813},
-    {8.61884117, -0.0553797074, 0.165003911},
-    {8.41396809, -0.0325845294, 0.27981171},
-    {8.01697063, 0.0135122444, 0.364745706},
-    {7.5014534, 0.0789953545, 0.431243092},
-    {6.88447189, 0.172850475, 0.466264963},
-    {6.20868397, 0.303081721, 0.46164912},
-    {5.51841879, 0.43952468, 0.42397055},
-    {4.77843332, 0.546190202, 0.364180297},
-    {3.95670247, 0.627786458, 0.290333003},
-    {3.13871264, 0.693335891, 0.197645679},
-    {2.45341849, 0.74498421, 0.09727595},
-    {1.8273648, 0.747460246, 0.0127557125},
-    {1.10078788, 0.656537056, -0.0306472387},
-    {0.2467971, 0.506531119, -0.0365669951},
-    {-0.587845683, 0.380657375, -0.0373918712},
-    {-1.16842735, 0.343112737, -0.0717873052},
-    {-1.50761139, 0.385957778, -0.128489435},
-    {-1.7443198, 0.451331586, -0.179965794},
-    {-1.96334124, 0.485818505, -0.212401763},
-    {-2.20303273, 0.453502804, -0.21238032},
-    {-2.44287062, 0.355422318, -0.186802596},
-    {-2.6125927, 0.226889402, -0.147263065},
-    {-2.65581059, 0.128864273, -0.112193495},
-    {-2.55697083, 0.0810073987, -0.0856377557},
-    {-2.35484672, 0.0701777041, -0.0617723018},
-    {-2.08490372, 0.061402373, -0.0403582901},
-    {-1.75825477, 0.0297636669, -0.0123961},
-    {-1.37707758, -0.0273772813, 0.0168770701},
-    {-0.945434332, -0.0937915817, 0.0444637761},
-    {-0.487834275, -0.126499891, 0.0776210353},
-    {-0.025677802, -0.10664542, 0.110379234},
-    {0.416782886, -0.0411628224, 0.139575884},
-    {0.807231784, 0.0393073671, 0.155013382},
-    {1.13829517, 0.108038329, 0.157587066},
-    {1.38814545, 0.15909493, 0.149738923},
-    {1.51267636, 0.19669202, 0.126176327},
-    {1.50752616, 0.237613723, 0.088962771},
-    {1.41168821, 0.293439269, 0.0379262567},
-    {1.25051093, 0.355610758, -0.0256087966},
-    {1.03806484, 0.408223391, -0.0949995965},
-    {0.762364209, 0.432101935, -0.163126633},
-    {0.454354256, 0.437073797, -0.223903865},
-    {0.148988172, 0.437323242, -0.273639798},
-    {-0.11186292, 0.448058277, -0.319540471},
-    {-0.286013871, 0.478029966, -0.356217027},
-    {-0.369955748, 0.527220249, -0.387501091},
-    {-0.380995959, 0.582756281, -0.40257737},
-    {-0.333371937, 0.635318935, -0.409544677},
-    {-0.236022532, 0.683623016, -0.406081438},
-    {-0.0784068331, 0.733510494, -0.389424175},
-    {0.136466891, 0.782414794, -0.365695208},
-    {0.379344553, 0.823984623, -0.34029761},
-    {0.64628464, 0.85684979, -0.313719541},
-    {0.916332066, 0.868699312, -0.282537639},
-    {1.1556952, 0.860585511, -0.253585815},
-    {1.36985397, 0.831036627, -0.226348296},
-    {1.53886306, 0.784385622, -0.203523844},
-    {1.6579113, 0.723515272, -0.182594106},
-    {1.7304765, 0.652579427, -0.166818187},
-    {1.77025175, 0.573327899, -0.155444264},
-    {1.78194177, 0.484548301, -0.145012289},
-    {1.76054084, 0.394754291, -0.130501494},
-    {1.71413064, 0.302216589, -0.113823079},
-    {1.646752, 0.220337778, -0.0980426148},
-    {1.57022738, 0.151977912, -0.0815471262},
-    {1.48620367, 0.0927803814, -0.0668974072},
-    {1.38691473, 0.0430112369, -0.0583836064},
-    {1.28099096, -0.00296661654, -0.0546754524},
-    {1.15312994, -0.0464839563, -0.0541292205},
-    {1.00311792, -0.0853614584, -0.0607325211},
-    {0.836577356, -0.119216584, -0.0708383694},
-    {0.660098851, -0.146154791, -0.0878327191},
-    {0.477556586, -0.165661052, -0.110017173},
-    {0.299958497, -0.179511622, -0.139214829},
-    {0.138091639, -0.1908914, -0.166090831},
-    {-0.006939983, -0.199651748, -0.19468759},
-    {-0.129572794, -0.20821245, -0.217618287},
-    {-0.216423556, -0.212535858, -0.236890748},
-    {-0.253255695, -0.210490525, -0.252937257},
-    {-0.253288984, -0.203872398, -0.261567473},
-    {-0.210836381, -0.195524842, -0.269133478},
-    {-0.117733285, -0.18436712, -0.271494716},
-    {0.0244571809, -0.164712191, -0.269399524},
-    {0.191457391, -0.143710405, -0.259888023},
-    {0.37782979, -0.112748101, -0.249245718},
-    {0.574578464, -0.0764147788, -0.239268601},
-    {0.778044999, -0.0401812382, -0.22693029},
-    {0.99073875, -0.0109936558, -0.213988766},
-    {1.19967747, 0.011167625, -0.20113942},
-    {1.39470124, 0.0235156417, -0.190550819},
-    {1.58037102, 0.027846029, -0.173486218},
-    {1.75312459, 0.0205294844, -0.159135818},
-    {1.91780806, 0.00848489068, -0.141637549},
-    {2.07688689, -0.00954400003, -0.119385056},
-    {2.2211678, -0.0398320407, -0.0973941162},
-    {2.35820365, -0.081813015, -0.0718340725},
-    {2.49504137, -0.131466433, -0.0376628637},
-    {2.61824536, -0.181269705, -0.00201444211},
-    {2.72707391, -0.231641978, 0.0377292261},
-    {2.81690145, -0.274410546, 0.0754925907},
-    {2.89493799, -0.307650954, 0.117878698},
-    {2.95210624, -0.321231335, 0.158635184},
-    {2.977633, -0.328536898, 0.197033122},
-    {2.9729588, -0.326125205, 0.229007095},
-    {2.93240166, -0.310395688, 0.255334496},
-    {2.85744429, -0.284766346, 0.272593081},
-    {2.74351931, -0.252444267, 0.273421824},
-    {2.59228277, -0.215462416, 0.269497514},
-    {2.40035343, -0.174690872, 0.258785218},
-    {2.17301011, -0.13156943, 0.237559497},
-    {1.91211617, -0.09000431, 0.212942943},
-    {1.62393868, -0.0509801172, 0.183507159},
-    {1.32620406, -0.0137585234, 0.154162109},
-    {1.02233434, 0.0190994255, 0.128504306},
-    {0.714185476, 0.0501186773, 0.109487332},
-    {0.410155714, 0.0822046623, 0.0916887522},
-    {0.132410064, 0.114129253, 0.0851349831},
-    {-0.115474813, 0.148091882, 0.0784313008},
-    {-0.327917755, 0.188311204, 0.0808636174},
-    {-0.489888608, 0.229634121, 0.0932498351},
-    {-0.614332676, 0.26708591, 0.110470414},
-    {-0.716044009, 0.297993004, 0.133193552},
-    {-0.796998262, 0.32763952, 0.162505075},
-    {-0.866149604, 0.351420373, 0.198211029},
-    {-0.923185349, 0.370809168, 0.236456648},
-    {-0.959917724, 0.389067322, 0.276198804},
-    {-0.981078386, 0.408318877, 0.320706367},
-    {-1.00990307, 0.418150604, 0.36793834},
-    {-1.05733037, 0.415841281, 0.418499589},
-    {-1.12605333, 0.402752519, 0.465963453},
-    {-1.22133589, 0.379653454, 0.507546663},
-    {-1.34421921, 0.343602985, 0.544803798},
-    {-1.50398636, 0.295249224, 0.580982924},
-    {-1.69280303, 0.236051708, 0.606324732},
-    {-1.90414703, 0.171133995, 0.626571655},
-    {-2.11450577, 0.107191794, 0.640516341},
-    {-2.32793427, 0.0433785804, 0.650549114},
-    {-2.55025244, -0.0145068094, 0.649908125},
-    {-2.77668309, -0.0603183694, 0.636821508},
-    {-3.00441098, -0.0951218903, 0.612128258},
-    {-3.21659088, -0.120496988, 0.582612574},
-    {-3.41523457, -0.134930521, 0.549288988},
-    {-3.58433056, -0.138622046, 0.514635086},
-    {-3.72066736, -0.13245289, 0.487031817},
-    {-3.82730651, -0.118152358, 0.459328711},
-    {-3.89543319, -0.0920123234, 0.439291298},
-    {-3.92512751, -0.0562232248, 0.426755428},
-    {-3.91487169, -0.0159867443, 0.426936328},
-    {-3.87198687, 0.0248528924, 0.438426644},
-    {-3.80958343, 0.0623770356, 0.454369634},
-    {-3.73039532, 0.0970705599, 0.481461197},
-    {-3.63667727, 0.126087308, 0.513637424},
-    {-3.52675223, 0.153880611, 0.552398562},
-    {-3.41509891, 0.181518734, 0.596924305},
-    {-3.30849671, 0.204906479, 0.637985528},
-    {-3.2040658, 0.230472594, 0.679202497},
-    {-3.11578846, 0.252347648, 0.715790391},
-    {-3.06335902, 0.268144786, 0.749978542},
-    {-3.05284882, 0.273847818, 0.777062953},
-    {-3.09109378, 0.271703243, 0.794664085},
-    {-3.181005, 0.262507707, 0.809774697},
-    {-3.32294679, 0.246527702, 0.817623198},
-    {-3.51048255, 0.223048195, 0.818454742},
-    {-3.73130965, 0.20005095, 0.808411241},
-    {-3.98752165, 0.17336221, 0.796089411},
-    {-4.27744007, 0.143713519, 0.776484311},
-    {-4.61116552, 0.105684124, 0.75258559},
-    {-4.96921062, 0.0665824339, 0.734432518},
-    {-5.34864092, 0.0239322782, 0.716127932},
-    {-5.73240232, -0.0237023793, 0.70406729},
-    {-6.0936408, -0.0677014366, 0.694788456},
-    {-6.40649843, -0.105736211, 0.687246084},
-    {-6.65304232, -0.142602831, 0.683959305},
-    {-6.82314253, -0.176387042, 0.684276521},
-    {-6.90274811, -0.203795791, 0.684330165},
-    {-6.91334391, -0.227418318, 0.688718975},
-    {-6.86011505, -0.249634057, 0.695586741},
-    {-6.73771238, -0.272841424, 0.706501424},
-    {-6.55087519, -0.291305125, 0.726715326},
-    {-6.3099103, -0.305123359, 0.742362618},
-    {-6.02191782, -0.318083465, 0.757244587},
-    {-5.68245029, -0.320654482, 0.771279693},
-    {-5.29075241, -0.317796886, 0.785947561},
-    {-4.88063955, -0.306273997, 0.797290385},
-    {-4.4555974, -0.296526492, 0.807463467},
-    {-4.00330257, -0.287779927, 0.806831419},
-    {-3.5402317, -0.272897333, 0.806432486},
-    {-3.08539176, -0.250082999, 0.793944478},
-    {-2.66421318, -0.214276761, 0.772741437},
-    {-2.31043315, -0.168697149, 0.741882026},
-    {-2.02092195, -0.114674985, 0.700406373},
-    {-1.79382265, -0.0477416702, 0.642083645},
-    {-1.6435684, 0.0251932219, 0.580689132},
-    {-1.54253113, 0.100595802, 0.510710776},
-    {-1.47752154, 0.184162661, 0.43210876},
-    {-1.44277692, 0.266581684, 0.350711167},
-    {-1.43398023, 0.348909497, 0.266953319},
-    {-1.42859995, 0.426483452, 0.183047891},
-    {-1.41691291, 0.499567538, 0.102420047},
-    {-1.39957595, 0.563284338, 0.028616799},
-    {-1.36633539, 0.615248322, -0.0442660004},
-    {-1.30718124, 0.652308762, -0.111162022},
-    {-1.22808194, 0.673534214, -0.169609591},
-    {-1.11891985, 0.679600894, -0.220212355},
-    {-0.977771282, 0.670432866, -0.263942868},
-    {-0.803293884, 0.64338392, -0.300361842},
-    {-0.605029285, 0.598729372, -0.330324769},
-    {-0.370586544, 0.546472907, -0.355684906},
-    {-0.088151142, 0.478927821, -0.374275625},
-    {0.216283768, 0.403800219, -0.387295723},
-    {0.54750526, 0.319061279, -0.393939525},
-    {0.88534832, 0.229859859, -0.391859442},
-    {1.22090638, 0.14056325, -0.3838965},
-    {1.57189047, 0.0548341125, -0.364431441},
-    {1.95691025, -0.0335681289, -0.336842239},
-    {2.3566401, -0.119033679, -0.300877362},
-    {2.73049235, -0.194238573, -0.260652363},
-    {3.09740734, -0.254023969, -0.217468634},
-    {3.44717169, -0.301332146, -0.162128955},
-    {3.74497175, -0.334073603, -0.11174453},
-    {3.97603536, -0.344966888, -0.0626591519},
-    {4.12372112, -0.336694986, -0.0230732001},
-    {4.17854118, -0.325167418, 0.00409195293},
-    {4.1398654, -0.303177923, 0.0184068903},
-    {4.00133514, -0.27551809, 0.0163676329},
-    {3.76819777, -0.245407179, -0.00335018616},
-    {3.45329094, -0.21110025, -0.039213948},
-    {3.07222867, -0.172421917, -0.0850552171},
-    {2.63701439, -0.127832696, -0.150038481},
-    {2.16348338, -0.0765730143, -0.224949315},
-    {1.68137276, -0.0187495966, -0.309204638},
-    {1.19794846, 0.0452727154, -0.394113392},
-    {0.743889987, 0.112518437, -0.472949237},
-    {0.339002252, 0.184104204, -0.546463907},
-    {0.000877938, 0.262723863, -0.607357502},
-    {-0.264247149, 0.341293573, -0.650059581},
-    {-0.458883971, 0.417319238, -0.672774017},
-    {-0.573338091, 0.485047132, -0.671576738},
-    {-0.628710985, 0.544111669, -0.652320981},
-    {-0.634348154, 0.587379038, -0.615089834},
-    {-0.598181665, 0.615222335, -0.559136271},
-    {-0.541145265, 0.624261022, -0.49576354},
-    {-0.47380355, 0.616237462, -0.425418437},
-    {-0.392931223, 0.590777159, -0.351596355},
-    {-0.300430864, 0.55086273, -0.272874862},
-    {-0.204451546, 0.503875852, -0.196747348},
-    {-0.113894597, 0.448912859, -0.120659418},
-    {-0.0399600863, 0.389969587, -0.0434131101},
-    {0.00692719407, 0.32705909, 0.0268808845},
-    {0.023704607, 0.263893217, 0.0951078236},
-    {0.0162094347, 0.199934557, 0.160115153},
-    {-0.0113742528, 0.133370087, 0.222585455},
-    {-0.0550603941, 0.0709637776, 0.282933354},
-    {-0.129473016, 0.0128969885, 0.333267838},
-    {-0.256598026, -0.0373876467, 0.368004858},
-    {-0.423914224, -0.0839474946, 0.400297403},
-    {-0.624088228, -0.133201167, 0.425273478},
-    {-0.850951135, -0.176402062, 0.430178821},
-    {-1.09608889, -0.207713544, 0.415529132},
-    {-1.34505117, -0.22760129, 0.388291627},
-    {-1.60721612, -0.232889161, 0.348017365},
-    {-1.89818227, -0.230827168, 0.299262553},
-    {-2.22016025, -0.215944707, 0.25173822},
-    {-2.52574229, -0.180808604, 0.201387107},
-    {-2.81802177, -0.131189108, 0.153945953},
-    {-3.10152125, -0.0784767121, 0.116614923},
-    {-3.34244776, -0.010348672, 0.0882189497},
-    {-3.53900671, 0.0731929988, 0.0719330907},
-    {-3.65736604, 0.153272718, 0.0746855512},
-    {-3.75241184, 0.23711592, 0.0939502418},
-    {-3.82033324, 0.320528626, 0.126869664},
-    {-3.85754871, 0.400329351, 0.175146773},
-    {-3.88236237, 0.464345157, 0.236048982},
-    {-3.90582585, 0.517838538, 0.304633588},
-    {-3.92687774, 0.55305779, 0.38026011},
-    {-3.95521355, 0.56762439, 0.462005854},
-    {-3.99721646, 0.563517094, 0.54358542},
-    {-4.08363199, 0.539710581, 0.62649107},
-    {-4.20415354, 0.496512204, 0.699158669},
-    {-4.36307716, 0.435261339, 0.763381124},
-    {-4.58443594, 0.349940449, 0.815128982},
-    {-4.86613226, 0.248352885, 0.849990368},
-    {-5.17069387, 0.141034126, 0.865475774},
-    {-5.48776293, 0.0308724213, 0.857548296},
-    {-5.83836174, -0.0844574422, 0.832563698},
-    {-6.14614058, -0.185364306, 0.789943874},
-    {-6.39279079, -0.265020937, 0.731091619},
-    {-6.54805756, -0.319679856, 0.667163134},
-    {-6.58059406, -0.347014666, 0.606496572},
-    {-6.48552513, -0.356910497, 0.555247843},
-    {-6.30202532, -0.356721729, 0.51405412},
-    {-6.03184795, -0.334855199, 0.483223855},
-    {-5.69019985, -0.291903764, 0.462321788},
-    {-5.28634262, -0.237561747, 0.460409522},
-    {-4.82553291, -0.179411858, 0.471101612},
-    {-4.31866455, -0.119093142, 0.491253912},
-    {-3.79059744, -0.0571079925, 0.511683226},
-    {-3.25816202, 0.00257067988, 0.534456253},
-    {-2.72526765, 0.0618014708, 0.556090057},
-    {-2.23840165, 0.131824151, 0.570822716},
-    {-1.79361272, 0.196336761, 0.581132531},
-    {-1.41131568, 0.254625738, 0.576642871},
-    {-1.11768925, 0.308069795, 0.555109024},
-    {-0.898192763, 0.35047254, 0.517960846},
-    {-0.736530244, 0.389117271, 0.466528744},
-    {-0.621255875, 0.426354498, 0.40908277},
-    {-0.546618223, 0.454377443, 0.347340047},
-    {-0.50832051, 0.477547705, 0.277928174},
-    {-0.495790213, 0.490611136, 0.205057964},
-    {-0.502317667, 0.495938867, 0.12438044},
-    {-0.523419261, 0.491947949, 0.0461765081},
-    {-0.5499084, 0.481804669, -0.0366168767},
-    {-0.578276634, 0.46382913, -0.113690078},
-    {-0.608984947, 0.439254194, -0.188366756},
-    {-0.632186413, 0.411964804, -0.261051953},
-    {-0.636218071, 0.379842252, -0.325535774},
-    {-0.623639107, 0.346830904, -0.379230857},
-    {-0.5895226, 0.310531378, -0.431203574},
-    {-0.525813222, 0.272973448, -0.473669052},
-    {-0.441024959, 0.235586122, -0.506322622},
-    {-0.32983005, 0.192285404, -0.529203475},
-    {-0.18818073, 0.141029283, -0.546655893},
-    {-0.0150022972, 0.0877982825, -0.558978796},
-    {0.196878314, 0.0318368748, -0.562892854},
-    {0.465995222, -0.0296498444, -0.561506569},
-    {0.777512968, -0.0961029455, -0.552250624},
-    {1.11779881, -0.161286727, -0.539662838},
-    {1.47597718, -0.223350272, -0.519516587},
-    {1.87722218, -0.280242592, -0.491090328},
-    {2.31838012, -0.33021909, -0.457791537},
-    {2.78202319, -0.369444072, -0.421690047},
-    {3.27919364, -0.401048303, -0.380072445},
-    {3.76423311, -0.415666044, -0.334804833},
-    {4.19133139, -0.415370524, -0.29652065},
-    {4.55558681, -0.401661068, -0.268393248},
-    {4.84652805, -0.374480963, -0.25278762},
-    {5.04693365, -0.345530242, -0.248602614},
-    {5.15992546, -0.314086229, -0.266938508},
-    {5.20192957, -0.284454167, -0.301991433},
-    {5.16810703, -0.263119757, -0.358678043},
-    {5.06860209, -0.250149578, -0.42845127},
-    {4.92355108, -0.243714303, -0.503562331},
-    {4.74067068, -0.24777168, -0.586887777},
-    {4.52361155, -0.262295932, -0.669977069},
-    {4.29410982, -0.29309392, -0.752744555},
-    {4.07272243, -0.327118516, -0.821959615},
-    {3.86743617, -0.36471951, -0.880226016},
-    {3.69370222, -0.402809471, -0.925672889},
-    {3.56687355, -0.439489365, -0.962106645},
-    {3.49228501, -0.472339809, -0.981299818},
-    {3.47022295, -0.504068553, -0.981972396},
-    {3.50337768, -0.532130003, -0.96539259},
-    {3.58377481, -0.554451466, -0.933592558},
-    {3.70205307, -0.567604601, -0.883174717},
-    {3.84765291, -0.572127581, -0.822231233},
-    {4.02852106, -0.562749147, -0.754370153},
-    {4.23262644, -0.539800763, -0.68411839},
-    {4.42998362, -0.508789539, -0.611813962},
-    {4.58239985, -0.470377594, -0.547112346},
-    {4.68157291, -0.42681095, -0.489311695},
-    {4.72773457, -0.375414312, -0.442257196},
-    {4.71983576, -0.315034032, -0.407782018},
-    {4.65718794, -0.2504282, -0.397809446},
-    {4.54321194, -0.18841967, -0.402915299},
-    {4.37891722, -0.134298652, -0.426356077},
-    {4.17162657, -0.0839973912, -0.461109698},
-    {3.9236629, -0.0414853245, -0.505618751},
-    {3.66247916, -0.0075013754, -0.551031351},
-    {3.41923594, 0.0143381264, -0.595336199},
-    {3.19897413, 0.0321694389, -0.636889756},
-    {3.02557278, 0.0400181003, -0.676548839},
-    {2.91025305, 0.0399515927, -0.700959563},
-    {2.85090661, 0.0331338942, -0.713929653},
-    {2.84956908, 0.0235775281, -0.710062802},
-    {2.90504289, 0.00962921791, -0.687440991},
-    {3.021415, -0.00981756579, -0.653751194},
-    {3.19762778, -0.0333469175, -0.604447484},
-    {3.4093256, -0.0602019764, -0.544102728},
-    {3.64461851, -0.0881212577, -0.478519827},
-    {3.8882432, -0.112648323, -0.405769974},
-    {4.12376928, -0.128312379, -0.32854715},
-    {4.32223129, -0.132944182, -0.254542172},
-    {4.47728109, -0.130694002, -0.186259583},
-    {4.58338594, -0.122656651, -0.127383396},
-    {4.59903193, -0.11486797, -0.0804721788},
-    {4.53273106, -0.110819176, -0.04582908},
-    {4.39135647, -0.101726905, -0.0161234867},
-    {4.16914415, -0.0835867152, -0.00286904722},
-    {3.89778781, -0.0612163208, -0.000848934054},
-    {3.59303021, -0.0456761643, -0.00886012614},
-    {3.25351596, -0.0352591947, -0.024045717},
-    {2.86678624, -0.0342781171, -0.0421708003},
-    {2.44388986, -0.0424044169, -0.0579185188},
-    {2.01876664, -0.0516667217, -0.0709971413},
-    {1.60953736, -0.0599525459, -0.0866188332},
-    {1.20622933, -0.0622971728, -0.102814995},
-    {0.824654698, -0.0639932826, -0.115801871},
-    {0.460222632, -0.0644306615, -0.122110642},
-    {0.0936859697, -0.0714407116, -0.124586031},
-    {-0.262883663, -0.0840140134, -0.116666555},
-    {-0.570527732, -0.0936162248, -0.0956339911},
-    {-0.809285045, -0.0966798961, -0.0632718801},
-    {-0.981620312, -0.0946030617, -0.0244115479},
-    {-1.10313916, -0.0880879983, 0.0167772938},
-    {-1.18898761, -0.0836995766, 0.0650801212},
-    {-1.26627386, -0.0856017619, 0.115740046},
-    {-1.34062362, -0.0925036296, 0.16692324},
-    {-1.40823936, -0.107011259, 0.217749551},
-    {-1.44929504, -0.120496988, 0.264641941},
-    {-1.46640575, -0.129576162, 0.309040099},
-    {-1.46654081, -0.136830211, 0.350356907},
-    {-1.46499205, -0.143996835, 0.382757515},
-    {-1.47086239, -0.156198412, 0.410324484},
-    {-1.48311746, -0.172544241, 0.429796457},
-    {-1.49938047, -0.188557491, 0.438409984},
-    {-1.51560819, -0.202828303, 0.435672343},
-    {-1.51820314, -0.206408501, 0.419799417},
-    {-1.51318204, -0.199582204, 0.397304267},
-    {-1.48719692, -0.189589977, 0.368803471},
-    {-1.45104122, -0.175703645, 0.334049463},
-    {-1.39667559, -0.160955772, 0.296761304},
-    {-1.31402206, -0.144741371, 0.254648238},
-    {-1.19377673, -0.117787033, 0.20908913},
-    {-1.04578769, -0.0806218013, 0.157271653},
-    {-0.873380363, -0.0308753215, 0.107165381},
-    {-0.685347676, 0.0228907261, 0.052212663},
-    {-0.483072609, 0.0710968003, -0.000500807771},
-    {-0.271613598, 0.115943916, -0.0531788766},
-    {-0.0413418598, 0.153906807, -0.108934298},
-    {0.206550002, 0.18833895, -0.162599578},
-    {0.454595625, 0.224156424, -0.214135408},
-    {0.694187462, 0.260462373, -0.261318028},
-    {0.927186251, 0.292705059, -0.309125066},
-    {1.15774155, 0.313385457, -0.352467},
-    {1.38785601, 0.319190294, -0.392407745},
-    {1.60393262, 0.307904661, -0.425535768},
-    {1.80838108, 0.286552519, -0.453360766},
-    {2.01109934, 0.258150995, -0.476441205},
-    {2.20704985, 0.224544793, -0.485985994},
-    {2.39027953, 0.184919015, -0.491972268},
-    {2.56023955, 0.136579916, -0.48683399},
-    {2.71870232, 0.0803845972, -0.47459498},
-    {2.86963153, 0.0180400312, -0.451268882},
-    {3.00726819, -0.0471289344, -0.418287665},
-    {3.13076353, -0.112116203, -0.378133357},
-    {3.22954535, -0.170825601, -0.33071956},
-    {3.30133247, -0.220565408, -0.281131685},
-    {3.34700155, -0.259478122, -0.226797238},
-    {3.35635018, -0.288982213, -0.167969048},
-    {3.31209183, -0.309157699, -0.11311987},
-    {3.207937, -0.319889575, -0.066681236},
-    {3.03717899, -0.319956064, -0.0285187904},
-    {2.79794431, -0.310361415, -0.00159721752},
-    {2.48915267, -0.293067783, 0.00734892674},
-    {2.12931156, -0.2657471, 0.0021441998},
-    {1.73094201, -0.231059968, -0.0143679194},
-    {1.29794502, -0.192282766, -0.0432289839},
-    {0.850013196, -0.150311932, -0.0810316429},
-    {0.405998409, -0.108973421, -0.123268075},
-    {-0.00932070147, -0.0664457232, -0.162434652},
-    {-0.392205626, -0.0161051601, -0.201008424},
-    {-0.712619066, 0.0378998481, -0.236844629},
-    {-0.958737195, 0.0972035751, -0.263246953},
-    {-1.1287806, 0.159593806, -0.279775709},
-    {-1.21302974, 0.220426962, -0.28740418},
-    {-1.21593046, 0.279119551, -0.279276848},
-    {-1.15402973, 0.33341217, -0.259379566},
-    {-1.03099406, 0.382880419, -0.235162467},
-    {-0.862009048, 0.425683349, -0.202818945},
-    {-0.652973056, 0.46495685, -0.167662695},
-    {-0.427422762, 0.492081046, -0.130401701},
-    {-0.207009122, 0.504837215, -0.0941697732},
-    {0.00846054778, 0.500943899, -0.0612270832},
-    {0.210696593, 0.487158954, -0.0351369344},
-    {0.389469773, 0.459938079, -0.0139854625},
-    {0.543632746, 0.422956288, -0.000599506311},
-    {0.674631715, 0.378319204, 0.00975653436},
-    {0.787689507, 0.321755111, 0.0158128422},
-    {0.879246175, 0.263405621, 0.0172595214},
-    {0.959861219, 0.200450033, 0.0145823322},
-    {1.03609169, 0.132392764, 0.0143125188},
-    {1.10798788, 0.0627326593, 0.0133019369},
-    {1.17404354, -0.0123481248, 0.00632199086},
-    {1.23961616, -0.0856532529, 0.00397923589},
-    {1.30079913, -0.157018244, -0.00191769446},
-    {1.35967743, -0.224441856, -0.0092463363},
-    {1.41260564, -0.285784453, -0.021967154},
-    {1.46380532, -0.341506571, -0.0382631049},
-    {1.52531409, -0.390178293, -0.0539271608},
-    {1.59630096, -0.428224325, -0.0716365278},
-    {1.67515373, -0.454713523, -0.0911584049},
-    {1.76760685, -0.471496791, -0.112984098},
-    {1.87391126, -0.475142479, -0.132378891},
-    {1.98527551, -0.472988307, -0.153831318},
-    {2.10393643, -0.458072573, -0.181617543},
-    {2.23670435, -0.436780423, -0.211231425},
-    {2.37605405, -0.410911381, -0.242766514},
-    {2.5242548, -0.385875016, -0.272359908},
-    {2.67043209, -0.355949312, -0.305864811},
-    {2.80981708, -0.323298365, -0.343795508},
-    {2.94588161, -0.284580141, -0.382700711},
-    {3.06541395, -0.245809495, -0.426023543},
-    {3.16601801, -0.214184225, -0.467146456},
-    {3.26087642, -0.190428451, -0.509956241},
-    {3.34994841, -0.174432859, -0.552928448},
-    {3.43339658, -0.159857213, -0.590253174},
-    {3.50696778, -0.145539537, -0.624684274},
-    {3.57715678, -0.137158766, -0.659304917},
-    {3.64144254, -0.129775718, -0.686259747},
-    {3.70376635, -0.128079593, -0.709124088},
-    {3.76218247, -0.132718965, -0.724039793},
-    {3.82036829, -0.139990643, -0.730863631},
-    {3.87721229, -0.148717195, -0.730061412},
-    {3.93511128, -0.157034352, -0.717593193},
-    {3.98917866, -0.158343494, -0.697717011},
-    {4.03638744, -0.151991412, -0.672873974},
-    {4.07340765, -0.140581012, -0.637164891},
-    {4.08665085, -0.1288324, -0.594594479},
-    {4.07203817, -0.112864509, -0.544335485},
-    {4.01994133, -0.0848454311, -0.496594906},
-    {3.92628932, -0.0492936596, -0.451897532},
-    {3.78660369, 0.00151905231, -0.413950175},
-    {3.60882211, 0.056970071, -0.383141249},
-    {3.39078426, 0.116359629, -0.359775513},
-    {3.12547636, 0.180080116, -0.340070724},
-    {2.81813145, 0.241455957, -0.326435357},
-    {2.48270106, 0.302416056, -0.312666953},
-    {2.12374091, 0.364573479, -0.302290738},
-    {1.75483739, 0.425666749, -0.291399062},
-    {1.38307345, 0.483916402, -0.280390948},
-    {1.00978196, 0.537130654, -0.262588322},
-    {0.649263024, 0.582594275, -0.236312509},
-    {0.310135126, 0.620103836, -0.203284502},
-    {-0.0192924477, 0.64787358, -0.161114603},
-    {-0.33526957, 0.666659772, -0.1057925},
-    {-0.638920903, 0.671536028, -0.04386691},
-    {-0.926476717, 0.659167051, 0.0241823494},
-    {-1.20696795, 0.633689523, 0.0969101042},
-    {-1.48152113, 0.594662249, 0.173118621},
-    {-1.74531937, 0.541629493, 0.254431546},
-    {-2.00235963, 0.475968003, 0.334165812},
-    {-2.27024055, 0.3962982, 0.409260243},
-    {-2.54760075, 0.305415154, 0.475070477},
-    {-2.83220601, 0.209246591, 0.529783726},
-    {-3.13206983, 0.104990765, 0.573231459},
-    {-3.43131948, 0.00259159924, 0.596392214},
-    {-3.71742487, -0.0950054452, 0.603863716},
-    {-3.99064851, -0.18576391, 0.595632553},
-    {-4.23333263, -0.268519968, 0.571167529},
-    {-4.41916037, -0.333343059, 0.53580004},
-    {-4.53170633, -0.379369795, 0.490124643},
-    {-4.55934429, -0.40269956, 0.441818893},
-    {-4.50254965, -0.401338518, 0.391474724},
-    {-4.37034321, -0.380700022, 0.342812657},
-    {-4.17473269, -0.339230597, 0.308107346},
-    {-3.90723944, -0.27978158, 0.283781409},
-    {-3.57435346, -0.205252528, 0.271443039},
-    {-3.18961883, -0.120770089, 0.267444164},
-    {-2.76520038, -0.0301590748, 0.274292469},
-    {-2.3097136, 0.0686458647, 0.293388635},
-    {-1.82679582, 0.179897204, 0.324637681},
-    {-1.34845972, 0.295515299, 0.358709484},
-    {-0.886885405, 0.402686059, 0.391334623},
-    {-0.451833516, 0.499846548, 0.420933485},
-    {-0.0515185036, 0.582872689, 0.448420376},
-    {0.273569018, 0.642652154, 0.463435948},
-    {0.497738093, 0.676956773, 0.457233459},
-    {0.646913588, 0.69094342, 0.438445717},
-    {0.731259823, 0.69404608, 0.404557019},
-    {0.769165337, 0.686135828, 0.361519724},
-    {0.768234253, 0.662091136, 0.314244866},
-    {0.738178968, 0.62529999, 0.264074087},
-    {0.695711255, 0.575196087, 0.222059563},
-    {0.633875728, 0.517306387, 0.18608886},
-    {0.548621416, 0.450991869, 0.147327781},
-    {0.453273386, 0.381617755, 0.114353433},
-    {0.34512502, 0.307515979, 0.0846231729},
-    {0.223799825, 0.228585497, 0.0601112172},
-    {0.0929307491, 0.148235962, 0.0345328003},
-    {-0.0307162423, 0.0649442524, 0.0122543387},
-    {-0.151900336, -0.0167501457, -0.0129146883},
-    {-0.258209974, -0.0969540179, -0.0359567776},
-    {-0.341994077, -0.167203814, -0.0579689667},
-    {-0.402879119, -0.230744064, -0.0783710927},
-    {-0.440875322, -0.284121573, -0.0983751863},
-    {-0.449472278, -0.324329317, -0.116383865},
-    {-0.437580347, -0.353303283, -0.134671733},
-    {-0.400320411, -0.371535093, -0.150522217},
-    {-0.338576645, -0.377158105, -0.165870368},
-    {-0.252191454, -0.369642019, -0.179921493},
-    {-0.134308383, -0.353174299, -0.191527113},
-    {0.00320968893, -0.332193047, -0.200643793},
-    {0.166581109, -0.297657192, -0.210301757},
-    {0.351057917, -0.256634653, -0.214941099},
-    {0.554180861, -0.20569846, -0.220309615},
-    {0.765191197, -0.149530336, -0.229491055},
-    {0.975860059, -0.0926222205, -0.237084955},
-    {1.1935252, -0.0367890187, -0.240648761},
-    {1.41275525, 0.0190661699, -0.252355278},
-    {1.62825799, 0.0749667212, -0.26607126},
-    {1.83696568, 0.124341339, -0.283051521},
-    {2.03822684, 0.166425586, -0.301190734},
-    {2.2285006, 0.198421389, -0.3207151},
-    {2.40707397, 0.217244849, -0.343762279},
-    {2.57658505, 0.223397434, -0.36616084},
-    {2.73468971, 0.214717314, -0.390771091},
-    {2.88521791, 0.191697553, -0.410982758},
-    {3.02863193, 0.156667128, -0.425325125},
-    {3.17928624, 0.10831143, -0.434437543},
-    {3.33341575, 0.0504275486, -0.432625055},
-    {3.48925805, -0.0123783574, -0.421018302},
-    {3.65417171, -0.0828449726, -0.398099691},
-    {3.82613516, -0.155666307, -0.36782369},
-    {3.9978919, -0.22815001, -0.329179049},
-    {4.17598057, -0.300059795, -0.282195926},
-    {4.3510704, -0.361049533, -0.229718313},
-    {4.50640821, -0.414904922, -0.175531507},
-    {4.64888382, -0.458645463, -0.118289098},
-    {4.77446032, -0.489034921, -0.0552075654},
-    {4.85228252, -0.506108105, 0.00157614751},
-    {4.87153244, -0.515984595, 0.0440213531},
-    {4.84027576, -0.520296514, 0.0800820813},
-    {4.74592543, -0.515390992, 0.102829881},
-    {4.581635, -0.50536406, 0.111044362},
-    {4.34972334, -0.489459604, 0.104424208},
-    {4.06362343, -0.473769277, 0.0862850398},
-    {3.73459554, -0.458122402, 0.0563199148},
-    {3.36238241, -0.44309023, 0.0109739453},
-    {2.9616518, -0.429804146, -0.0426197648},
-    {2.54402685, -0.416933596, -0.103663057},
-    {2.12053156, -0.402167439, -0.16889675},
-    {1.69675517, -0.384859234, -0.231274322},
-    {1.30645645, -0.362471908, -0.294432938},
-    {0.959521651, -0.33009994, -0.35156405},
-    {0.671589255, -0.287580311, -0.399650753},
-    {0.445033252, -0.239673093, -0.435009003},
-    {0.278706104, -0.189265862, -0.457054585},
-    {0.173494577, -0.135266125, -0.462807834},
-    {0.123746082, -0.0768970028, -0.456969231},
-    {0.117277555, -0.0194122177, -0.436067164},
-    {0.134953693, 0.0321860649, -0.404938608},
-    {0.172234833, 0.0746553019, -0.362003744},
-    {0.227025822, 0.10787908, -0.309889883},
-    {0.306458205, 0.138997599, -0.249575794},
-    {0.394624531, 0.159294471, -0.190147966},
-    {0.481063992, 0.167821139, -0.129306391},
-    {0.568242967, 0.167459056, -0.0647190735},
-    {0.64214009, 0.161389634, 0.00156220142},
-    {0.701543629, 0.140997052, 0.0707076043},
-    {0.735775173, 0.112102747, 0.13136442},
-    {0.74149549, 0.0780973956, 0.189082041},
-    {0.728067219, 0.0412813351, 0.24142164},
-    {0.697077274, 0.00421186397, 0.290196002},
-    {0.640508831, -0.0364929251, 0.33730489},
-    {0.547457278, -0.0791584849, 0.376618415},
-    {0.415510029, -0.124870285, 0.406167358},
-    {0.25269869, -0.171917409, 0.432802111},
-    {0.0554139353, -0.22001715, 0.45042637},
-    {-0.171576411, -0.269505113, 0.460343003},
-    {-0.426325351, -0.315183669, 0.457931876},
-    {-0.704208255, -0.354902178, 0.440088362},
-    {-0.996966124, -0.393770069, 0.412336439},
-    {-1.29524863, -0.424366564, 0.374440104},
-    {-1.59436238, -0.445883811, 0.324920356},
-    {-1.87972426, -0.458937198, 0.268799096},
-    {-2.12644148, -0.45995155, 0.208803445},
-    {-2.32518554, -0.445584536, 0.152732059},
-    {-2.46922183, -0.41673401, 0.0953137726},
-    {-2.55974245, -0.370992005, 0.0425540134},
-    {-2.5893116, -0.315869242, 0.000855220947},
-    {-2.57311678, -0.257432878, -0.0325927734},
-    {-2.5170455, -0.19193311, -0.060395658},
-    {-2.42400455, -0.125559121, -0.0744462535},
-    {-2.30144024, -0.0576744378, -0.0801337138},
-    {-2.16253996, 0.00509767747, -0.0763697773},
-    {-2.00439382, 0.0645179525, -0.0658679456},
-    {-1.82456768, 0.121497869, -0.051166825},
-    {-1.63546813, 0.168523297, -0.0345549434},
-    {-1.44118035, 0.204274625, -0.0116574699},
-    {-1.25241363, 0.228967994, 0.00814709533},
-    {-1.07967627, 0.238562599, 0.0272366349},
-    {-0.926178455, 0.238978311, 0.0436489731},
-    {-0.793266773, 0.227305114, 0.0590636209},
-    {-0.683003187, 0.204091698, 0.0655820072},
-    {-0.598430455, 0.172746927, 0.0705373064},
-    {-0.538867056, 0.131524816, 0.0715183914},
-    {-0.498243719, 0.0839839056, 0.0671284497},
-    {-0.470264971, 0.0311561059, 0.061693944},
-    {-0.455807775, -0.0246502031, 0.0573176146},
-    {-0.451214492, -0.0776544139, 0.046445258},
-    {-0.45505932, -0.13162145, 0.0341208354},
-    {-0.460962564, -0.186395794, 0.0199034568},
-    {-0.462831467, -0.238076717, 0.00409678929},
-    {-0.460964143, -0.285092473, -0.0125849135},
-    {-0.455092669, -0.324329346, -0.031927634},
-    {-0.436757952, -0.361817032, -0.0492918342},
-    {-0.399788439, -0.388682783, -0.0681306049},
-    {-0.34331575, -0.407191783, -0.0820087045},
-    {-0.256548166, -0.416883647, -0.0947335362},
-    {-0.145353258, -0.417731732, -0.104710661},
-    {-0.00713700522, -0.411462784, -0.111129269},
-    {0.153822526, -0.396807492, -0.114902928},
-    {0.324846029, -0.374247074, -0.114922166},
-    {0.501645744, -0.344765812, -0.111827672},
-    {0.687338054, -0.307348102, -0.107872598},
-    {0.870982349, -0.264511794, -0.103524685},
-    {1.05042017, -0.216958985, -0.0959640443},
-    {1.22649956, -0.166923806, -0.0920896083},
-    {1.39004898, -0.113852628, -0.0860559866},
-    {1.53509307, -0.060901437, -0.0856216475},
-    {1.65633106, -0.00486629829, -0.0872492045},
-    {1.75181723, 0.049795147, -0.0953026786},
-    {1.81977022, 0.103168689, -0.107743591},
-    {1.86538076, 0.154072046, -0.119539529},
-    {1.88492966, 0.201029018, -0.137864396},
-    {1.87268353, 0.242453694, -0.157872021},
-    {1.83489561, 0.277299017, -0.183049753},
-    {1.77950704, 0.304532945, -0.204571962},
-    {1.71196914, 0.325696051, -0.230206087},
-    {1.62795138, 0.339362174, -0.248930827},
-    {1.54242253, 0.347400606, -0.264411509},
-    {1.46461987, 0.350289613, -0.273140937},
-    {1.3894043, 0.349246591, -0.279132217},
-    {1.31946933, 0.340046436, -0.278761387},
-    {1.25531662, 0.325014263, -0.273407012},
-    {1.20401764, 0.309533089, -0.263030827},
-    {1.16132677, 0.290945143, -0.247452557},
-    {1.12428403, 0.271736473, -0.22862637},
-    {1.08987308, 0.25167644, -0.201846898},
-    {1.06257558, 0.232576326, -0.175365269},
-    {1.0419277, 0.214217871, -0.145183936},
-    {1.02242362, 0.191789582, -0.116241261},
-    {0.992203593, 0.169205055, -0.0828607902},
-    {0.944030941, 0.150065631, -0.0519816205},
-    {0.882300735, 0.133982837, -0.0284749512},
-    {0.80038929, 0.12276493, -0.00926407333},
-    {0.687966704, 0.121454, -0.00323991384},
-    {0.55688566, 0.122096464, -0.00131453271},
-    {0.427066833, 0.122379139, 0.00204442814},
-    {0.305030197, 0.118155517, 0.0175920893},
-    {0.170206115, 0.115794264, 0.0314103886},
-    {0.0019587928, 0.12482354, 0.0299304519},
-    {-0.188903332, 0.139290363, 0.0244929269},
-    {-0.38654989, 0.155586302, 0.0157962143},
-    {-0.5728392, 0.176288828, 0.0103919422},
-    {-0.739772975, 0.194995895, 0.0164114684},
-    {-0.910886347, 0.210865036, 0.0251071788},
-    {-1.08223724, 0.226207644, 0.0349023789},
-    {-1.24599481, 0.246511042, 0.0448462293},
-    {-1.41377187, 0.261747569, 0.057568118},
-    {-1.585832, 0.273149937, 0.071352087},
-    {-1.76176155, 0.289013535, 0.0913561881},
-    {-1.94813502, 0.299437612, 0.110470943},
-    {-2.14163303, 0.310513079, 0.131840751},
-    {-2.33574462, 0.314155847, 0.157853663},
-    {-2.54085755, 0.318313032, 0.18356134},
-    {-2.76017118, 0.321431667, 0.210959584},
-    {-2.99908924, 0.318229854, 0.239616022},
-    {-3.24845719, 0.306580812, 0.273861706},
-    {-3.49724984, 0.294395298, 0.307472229},
-    {-3.74517822, 0.273299575, 0.341216356},
-    {-3.99254417, 0.246195108, 0.377000868},
-    {-4.24178886, 0.212538958, 0.406915575},
-    {-4.49342775, 0.175989524, 0.443963885},
-    {-4.7459321, 0.13071005, 0.479914784},
-    {-4.99291563, 0.0810240284, 0.513005495},
-    {-5.22638416, 0.0271410774, 0.5458197},
-    {-5.43468904, -0.0272410326, 0.579158723},
-    {-5.61814833, -0.0841026977, 0.608205914},
-    {-5.76639128, -0.141814753, 0.631383955},
-    {-5.86724377, -0.194078192, 0.650656462},
-    {-5.91745186, -0.244188488, 0.668158829},
-    {-5.91614819, -0.290304422, 0.680814862},
-    {-5.8718276, -0.335265577, 0.690387189},
-    {-5.78255463, -0.377683729, 0.696971953},
-    {-5.64137697, -0.41054824, 0.702637196},
-    {-5.44682407, -0.435657352, 0.707642376},
-    {-5.20655155, -0.45037353, 0.703905463},
-    {-4.92227745, -0.454164833, 0.702637196},
-    {-4.59775543, -0.439398676, 0.705264568},
-    {-4.23994207, -0.416369855, 0.710092425},
-    {-3.8607626, -0.38583824, 0.716289163},
-    {-3.45125604, -0.343370557, 0.721819878},
-    {-3.04260302, -0.290945768, 0.730003953},
-    {-2.65532804, -0.230478004, 0.736592591},
-    {-2.29330873, -0.16363138, 0.737191141},
-    {-1.97897995, -0.0930266827, 0.732718289},
-    {-1.72163689, -0.0195785053, 0.717236936},
-    {-1.52654064, 0.0514570139, 0.692150593},
-    {-1.40012574, 0.120720595, 0.654667139},
-    {-1.33607674, 0.183437049, 0.607463956},
-    {-1.32657933, 0.239566863, 0.550463438},
-    {-1.3598994, 0.287950426, 0.489414036},
-    {-1.41316128, 0.324814737, 0.425572723},
-    {-1.48740602, 0.354100019, 0.359886557},
-    {-1.57154799, 0.373070657, 0.290831923},
-    {-1.66147482, 0.383962423, 0.225581586},
-    {-1.75286555, 0.384236991, 0.163633823},
-    {-1.84411359, 0.375310749, 0.109080046},
-    {-1.93562961, 0.359851032, 0.0596123561},
-    {-2.02839994, 0.337053329, 0.0131522827},
-    {-2.11724615, 0.307970077, -0.0265233666},
-    {-2.1919744, 0.273249716, -0.060063079},
-    {-2.26336098, 0.236068323, -0.0877495557},
-    {-2.32895017, 0.191386506, -0.109872043},
-    {-2.39040303, 0.141501963, -0.127973959},
-    {-2.43523908, 0.0882102251, -0.138867244},
-    {-2.46526456, 0.0318368711, -0.149607643},
-    {-2.46795797, -0.0261800289, -0.155527428},
-    {-2.45209455, -0.0848288089, -0.158570424},
-    {-2.42334414, -0.141586959, -0.159826145},
-    {-2.38586998, -0.192750394, -0.161277369},
-    {-2.33688426, -0.238764361, -0.157474011},
-    {-2.26558924, -0.277686357, -0.151270509},
-    {-2.16367292, -0.309105694, -0.135832712},
-    {-2.04200196, -0.337233156, -0.119227365},
-    {-1.92396486, -0.361390561, -0.0994394273},
-    {-1.80333281, -0.377956331, -0.0755608678},
-    {-1.653826, -0.381830812, -0.0497866645},
-    {-1.50064397, -0.377524048, -0.0174940825},
-    {-1.3190167, -0.361768752, 0.0191088133},
-    {-1.14125896, -0.337339908, 0.0598073602},
-    {-1.01267791, -0.306135565, 0.101167031},
-    {-0.869575083, -0.269970685, 0.137600109},
-    {-0.764378071, -0.227885917, 0.17496942},
-    {-0.650155902, -0.182566449, 0.210559055},
-    {-0.601664543, -0.135185495, 0.240854651},
-    {-0.616529822, -0.0864256918, 0.263873309},
-    {-0.663325071, -0.0360835716, 0.282004654},
-    {-0.757282197, 0.0101784952, 0.294752985},
-    {-0.896809578, 0.0542143211, 0.302660376},
-    {-1.12818182, 0.0942270681, 0.301257908},
-    {-1.40511322, 0.123659566, 0.293392718},
-    {-1.69104064, 0.149117827, 0.288138062},
-    {-1.98890734, 0.168789387, 0.282368004},
-    {-2.30714369, 0.181377143, 0.278809488},
-    {-2.64212513, 0.182624251, 0.277928174},
-    {-2.87593889, 0.173279092, 0.288454056},
-    {-2.76585793, 0.166577742, 0.327547699},
-    {-2.72443652, 0.137710646, 0.385797411},
-    {-2.81581736, 0.0606964082, 0.471227199},
-    {-2.96729612, -0.0596199743, 0.561943233},
-    {-3.10467076, -0.165916428, 0.629983962},
-    {-3.17781472, -0.252750099, 0.663190782},
-    {-3.19472384, -0.319407314, 0.659851909},
-    {-3.21696401, -0.35440442, 0.642582953},
-    {-3.28289914, -0.385649323, 0.621556938},
-    {-3.40962338, -0.434495986, 0.608373284},
-    {-3.53163743, -0.495328933, 0.584002793},
-    {-3.60559511, -0.531666636, 0.55579716},
-    {-3.62508702, -0.557627499, 0.524562299},
-    {-3.53484631, -0.552764833, 0.483272225},
-    {-3.35989571, -0.510818303, 0.446458161},
-    {-3.15441656, -0.460184425, 0.420268327},
-    {-2.897789, -0.418546557, 0.405851364},
-    {-2.57175326, -0.361377776, 0.402492434},
-    {-2.20933485, -0.288677841, 0.405202866},
-    {-1.82366967, -0.21271874, 0.412835389},
-    {-1.40095627, -0.131089389, 0.421332538},
-    {-0.967600226, -0.0376869664, 0.422446638},
-    {-0.565772057, 0.0443581454, 0.421166211},
-    {-0.201707318, 0.111188158, 0.415529102},
-    {0.103176586, 0.189242437, 0.399815202},
-    {0.319496959, 0.278421134, 0.373708397},
-    {0.459259629, 0.356608391, 0.332802266},
-    {0.544480741, 0.406643629, 0.280289382},
-    {0.597523749, 0.425419331, 0.219312146},
-    {0.611992598, 0.416022152, 0.153879419},
-    {0.604548395, 0.389300197, 0.0933569819},
-    {0.595430672, 0.360349894, 0.0363490656},
-    {0.58509165, 0.329348773, -0.0172683373},
-    {0.57482034, 0.28592518, -0.0626430288},
-    {0.581375837, 0.222457081, -0.097036317},
-    {0.610113621, 0.139489904, -0.125828877},
-    {0.657937288, 0.0339154378, -0.144153506},
-    {0.717650235, -0.087905094, -0.149241835},
-    {0.808109343, -0.201228425, -0.145134613},
-    {0.924482882, -0.300075918, -0.131156549},
-    {1.05329096, -0.382074326, -0.102511942},
-    {1.20371842, -0.457473904, -0.0692254007},
-    {1.38794589, -0.52731365, -0.0319941565},
-    {1.59305775, -0.597737432, 0.0162481163},
-    {1.79345322, -0.658465147, 0.0681228265},
-    {1.98480988, -0.696907997, 0.12436381},
-    {2.1631279, -0.706513226, 0.182402879},
-    {2.29939556, -0.685464203, 0.233422756},
-    {2.38319731, -0.644836545, 0.273377955},
-    {2.40422177, -0.594730556, 0.300777942},
-    {2.33372641, -0.538284957, 0.312109321},
-    {2.15433455, -0.480429262, 0.30996111},
-    {1.87667406, -0.418640286, 0.290276587},
-    {1.52188826, -0.344965398, 0.244338557},
-    {1.117167, -0.261789501, 0.184442654},
-    {0.690412641, -0.176900938, 0.112274878},
-    {0.266867667, -0.0946895257, 0.0429505855},
-    {-0.152636543, -0.0137418956, -0.0235967468},
-    {-0.542508721, 0.0714792609, -0.085089013},
-    {-0.871404231, 0.155386746, -0.136969984},
-    {-1.11255109, 0.240607888, -0.16831474},
-    {-1.26002932, 0.32800737, -0.183978811},
-    {-1.31564677, 0.41424495, -0.184512898},
-    {-1.28502214, 0.495672733, -0.169245914},
-    {-1.19720697, 0.567208707, -0.144885167},
-    {-1.07616782, 0.625574827, -0.107138418},
-    {-0.927824855, 0.669257879, -0.0665648431},
-    {-0.765329361, 0.694361866, -0.0132855522},
-    {-0.60990423, 0.693189502, 0.0368168801},
-    {-0.459399492, 0.672068, 0.0885792226},
-    {-0.317387372, 0.630298674, 0.138463274},
-    {-0.207577169, 0.579546928, 0.18357794},
-    {-0.135592297, 0.515760005, 0.221773654},
-    {-0.0942870677, 0.4379884, 0.260252059},
-    {-0.0777583197, 0.350988001, 0.295571029},
-    {-0.0918683782, 0.257965058, 0.329507798},
-    {-0.138352633, 0.165363878, 0.356082201},
-    {-0.216106534, 0.0720408782, 0.376835644},
-    {-0.320800722, -0.0178491399, 0.387061089},
-    {-0.447045475, -0.104806706, 0.391313553},
-    {-0.588859916, -0.187132284, 0.389983982},
-    {-0.745493114, -0.263768256, 0.379412025},
-    {-0.926561058, -0.340558857, 0.35841018},
-    {-1.11342764, -0.408094704, 0.320026577},
-    {-1.28244293, -0.456467122, 0.273313969},
-    {-1.42510056, -0.489367425, 0.218730643},
-    {-1.53624773, -0.497925073, 0.154668525},
-    {-1.60675049, -0.482416689, 0.0906744301},
-    {-1.63249147, -0.453715831, 0.0277022328},
-    {-1.61037874, -0.405470103, -0.0269691162},
-    {-1.53992057, -0.346461922, -0.0772237107},
-    {-1.42964053, -0.270087153, -0.12566258},
-    {-1.28808975, -0.182785392, -0.159552038},
-    {-1.12529552, -0.086376287, -0.185851291},
-    {-0.951211452, 0.00925159082, -0.200128838},
-    {-0.771816015, 0.0999805555, -0.20592846},
-    {-0.571914494, 0.189096794, -0.204942808},
-    {-0.349651217, 0.277007788, -0.20002532},
-    {-0.121184498, 0.359965295, -0.191580713},
-    {0.111524105, 0.434779078, -0.178075686},
-    {0.335576743, 0.494492143, -0.161314145},
-    {0.536532402, 0.539505541, -0.143288821},
-    {0.707140982, 0.57046771, -0.125895381},
-    {0.858892858, 0.586198449, -0.109665945},
-    {0.998838365, 0.582656384, -0.0913579613},
-    {1.12318635, 0.563655615, -0.0760426},
-    {1.24178326, 0.529326439, -0.0600792095},
-    {1.33895826, 0.477932245, -0.0439400747},
-    {1.42433, 0.412825972, -0.0228635781},
-    {1.49137402, 0.332827538, 0.00260604359},
-    {1.53294516, 0.246822953, 0.0235753376},
-    {1.56262839, 0.155869007, 0.046093367},
-    {1.60447407, 0.0649372041, 0.0634192973},
-    {1.64398754, -0.0221258886, 0.0862163678},
-    {1.67660046, -0.102687836, 0.108550094},
-    {1.69189823, -0.182920411, 0.128620729},
-    {1.69226444, -0.262304991, 0.144401178},
-    {1.69352794, -0.332244545, 0.15351361},
-    {1.70826089, -0.395865232, 0.165702298},
-    {1.72871459, -0.452518076, 0.177549362},
-    {1.73042679, -0.493690789, 0.185107797},
-    {1.69517434, -0.513911068, 0.183245391},
-    {1.63138807, -0.515720427, 0.175062031},
-    {1.59347439, -0.505497038, 0.155475736},
-    {1.5581646, -0.477285564, 0.124547735},
-    {1.5401566, -0.435972184, 0.0860447288},
-    {1.46663201, -0.387451231, 0.0377125964},
-    {1.36647832, -0.330947518, -0.017377682},
-    {1.3115865, -0.263021499, -0.0806219876},
-    {1.26026523, -0.197293937, -0.141922623},
-    {1.22710967, -0.129025906, -0.205039576},
-    {1.13628972, -0.0668201298, -0.269466043},
-    {1.08101666, -0.00539438147, -0.330858529},
-    {1.08086705, 0.0472016223, -0.379513621},
-    {1.10955119, 0.0915665179, -0.417476416},
-    {1.15192044, 0.12711373, -0.446602553},
-    {1.18008816, 0.153831705, -0.46712923},
-    {1.2548511, 0.171366781, -0.469922811},
-    {1.35274315, 0.181111068, -0.46214065},
-    {1.46506894, 0.180928171, -0.44922033},
-    {1.58113575, 0.170003235, -0.42788589},
-    {1.7208488, 0.146473885, -0.401113987},
-    {1.87404728, 0.115428433, -0.366443545},
-    {2.05652809, 0.0791107491, -0.328263968},
-    {2.25251794, 0.0404402539, -0.28832221},
-    {2.44902825, -0.00324930111, -0.237190098},
-    {2.66263819, -0.0431411155, -0.183114126},
-    {2.88097072, -0.0746188983, -0.118079998},
-    {3.09259987, -0.114320233, -0.0515009165},
-    {3.2760818, -0.155438051, 0.012820214},
-    {3.43546486, -0.192980692, 0.0764903054},
-    {3.5583396, -0.22032924, 0.133316934},
-    {3.63314509, -0.237079516, 0.186820507},
-    {3.58816481, -0.247322723, 0.222721502},
-    {3.47859955, -0.249999866, 0.243806466},
-    {3.269063, -0.251662731, 0.244987115},
-    {3.13736558, -0.256302088, 0.240397647},
-    {3.04594183, -0.258297533, 0.245086849},
-    {2.871243, -0.252494156, 0.25908801},
-    {2.62424254, -0.254256785, 0.279291689},
-    {2.32842135, -0.257399559, 0.294789493},
-    {2.02253985, -0.25342536, 0.300393283},
-    {1.71607256, -0.263166606, 0.296226591},
-    {1.40317452, -0.272277117, 0.278392762},
-    {1.07772624, -0.276922554, 0.263177574},
-    {0.717833221, -0.275158852, 0.253583997},
-    {0.309296072, -0.272244841, 0.241112635},
-    {-0.0852411464, -0.267343998, 0.230916664},
-    {-0.434032887, -0.251121551, 0.214071617},
-    {-0.745129287, -0.238455385, 0.204242378},
-    {-1.04107666, -0.232465386, 0.197592273},
-    {-1.32413232, -0.223527297, 0.201370493},
-    {-1.59472823, -0.211820811, 0.219046563},
-    {-1.85602868, -0.196007043, 0.246799603},
-    {-2.07206655, -0.179578111, 0.272873044},
-    {-2.23632264, -0.163398549, 0.30059284},
-    {-2.37688351, -0.151026934, 0.333750069},
-    {-2.51154566, -0.159646586, 0.37541458},
-    {-2.65745592, -0.178652808, 0.419181496},
-    {-2.80746293, -0.206466421, 0.465215176},
-    {-2.96276069, -0.237754241, 0.506588399},
-    {-3.08979058, -0.271083802, 0.538402319},
-    {-3.18057537, -0.298012018, 0.554030299},
-    {-3.24958181, -0.33254391, 0.561510921},
-    {-3.3138423, -0.377022624, 0.562540829},
-    {-3.37634087, -0.422570676, 0.556405842},
-    {-3.42200279, -0.470244586, 0.541407049},
-    {-3.4301331, -0.50818032, 0.513554275},
-    {-3.38504314, -0.529349387, 0.473577172},
-    {-3.29466152, -0.529691577, 0.422812462},
-    {-3.1478982, -0.514260292, 0.363149315},
-    {-2.95634341, -0.495458007, 0.298242122},
-    {-2.73238111, -0.46992448, 0.234332502},
-    {-2.47206545, -0.433645159, 0.173135251},
-    {-2.15713811, -0.382346302, 0.108167604},
-    {-1.80696404, -0.314265579, 0.0451662093},
-    {-1.41410351, -0.234642193, -0.0159622431},
-    {-1.01679289, -0.156540975, -0.0679383576},
-    {-0.623423159, -0.0901665762, -0.119110957},
-    {-0.228529096, -0.0256479159, -0.166153029},
-    {0.15978007, 0.032302469, -0.211498976},
-    {0.520652235, 0.0832688883, -0.257693022},
-    {0.852274716, 0.127716899, -0.30219093},
-    {1.16664207, 0.155783325, -0.35436967},
-    {1.43366551, 0.167220354, -0.39797169},
-    {1.64526939, 0.161878452, -0.437185854},
-    {1.81570518, 0.141249835, -0.468330771},
-    {1.95594263, 0.116076939, -0.495430946},
-    {2.09300232, 0.0774821565, -0.513100505},
-    {2.23148036, 0.0302047562, -0.519566536},
-    {2.37320209, -0.0252488293, -0.512774527},
-    {2.50485969, -0.0818426535, -0.495571434},
-    {2.62194777, -0.144059613, -0.465333313},
-    {2.73597002, -0.206682593, -0.420120388},
-    {2.84721518, -0.265913367, -0.367956758},
-    {2.95177436, -0.319473833, -0.305766165},
-    {3.03496742, -0.364071488, -0.239351779},
-    {3.08852792, -0.397893935, -0.168979883},
-    {3.11035347, -0.417463064, -0.096359618},
-    {3.08388853, -0.418330371, -0.0295830127},
-    {2.99683809, -0.395765483, 0.0294981133},
-    {2.85164285, -0.358970314, 0.0700985193},
-    {2.62809777, -0.311008364, 0.0920566246},
-    {2.31728148, -0.255431533, 0.0933398232},
-    {1.94215775, -0.198950306, 0.07903447},
-    {1.50813651, -0.13611117, 0.0515308976},
-    {1.04935193, -0.0678007007, 0.00930504501},
-    {0.591556191, 0.0101366546, -0.0418548584},
-    {0.159547284, 0.0920321047, -0.0934864134},
-    {-0.237724662, 0.17843391, -0.149890348},
-    {-0.595753312, 0.265351146, -0.202685878},
-    {-0.920441687, 0.357872218, -0.247017533},
-    {-1.20603168, 0.45055753, -0.285840094},
-    {-1.43474722, 0.537347496, -0.309761226},
-    {-1.6082139, 0.619721353, -0.315427274},
-    {-1.71415412, 0.70628953, -0.309174925},
-    {-1.75969982, 0.787336946, -0.287923694},
-    {-1.7596333, 0.854266763, -0.255232006},
-    {-1.73433876, 0.902466416, -0.205829695},
-    {-1.6977253, 0.928396523, -0.148842737},
-    {-1.65277839, 0.927565277, -0.0877661854},
-    {-1.61950505, 0.900859892, -0.0256586857},
-    {-1.60674, 0.85472697, 0.044917576},
-    {-1.59803712, 0.781367242, 0.124596626},
-    {-1.64895892, 0.684493542, 0.20834741},
-    {-1.76252866, 0.576792419, 0.281278521},
-    {-1.92967248, 0.456459165, 0.346358001},
-    {-2.15321946, 0.327575058, 0.404471219},
-    {-2.39636731, 0.215234816, 0.44555673},
-    {-2.70032525, 0.11853797, 0.474261075},
-    {-3.07453322, 0.0312881246, 0.484836876},
-    {-3.47411656, -0.0481130406, 0.482608557},
-    {-3.88025141, -0.115841001, 0.463352799},
-    {-4.26185751, -0.161662146, 0.425578386},
-    {-4.58159208, -0.178978935, 0.38059476},
-    {-4.89277887, -0.173691615, 0.342347056},
-    {-5.19634914, -0.141831383, 0.310536683},
-    {-5.4344244, -0.0822322443, 0.286003649},
-    {-5.62460232, -0.00250638113, 0.282342762},
-    {-5.75507879, 0.0893498883, 0.2977584},
-    {-5.85789108, 0.183938995, 0.340789318},
-    {-5.99149132, 0.259182006, 0.41340068},
-    {-6.0909543, 0.317835808, 0.517133951},
-    {-6.16658974, 0.347462803, 0.654264748},
-    {-6.21821642, 0.345340788, 0.808430493},
-    {-6.28777218, 0.302323937, 0.975847244},
-    {-6.35212469, 0.211235911, 1.14446247},
-    {-6.42000723, 0.0859959647, 1.2821995},
-    {-6.50378275, -0.0685328692, 1.38656819},
-    {-6.64088535, -0.251463205, 1.45763838},
-    {-6.81132793, -0.449359149, 1.48823488},
-    {-7.00235558, -0.652742624, 1.46861327},
-    {-7.23432302, -0.856092751, 1.4077363},
-    {-7.49893904, -1.05412781, 1.32041454},
-    {-7.69702673, -1.21975672, 1.1987952},
-    {-7.71161127, -1.3369894, 1.04736304},
-    {-7.45970821, -1.41293287, 0.878261089},
-    {-7.02287626, -1.4466877, 0.714659631},
-    {-6.41569853, -1.4307822, 0.57356286},
-    {-5.63157988, -1.36401081, 0.473065376},
-    {-4.71486139, -1.26718354, 0.41858077},
-    {-3.74175262, -1.14246905, 0.405685127},
-    {-2.63478613, -0.983421385, 0.411066204},
-    {-1.47320032, -0.799552381, 0.438639253},
-    {-0.390389949, -0.611461818, 0.482159644},
-    {0.560876667, -0.401868135, 0.519523919},
-    {1.35605836, -0.182269409, 0.54074049},
-    {1.93580556, 0.0156074371, 0.535387456},
-    {2.28098011, 0.214018926, 0.498738289},
-    {2.49034953, 0.401937872, 0.424491882},
-    {2.56196904, 0.551029146, 0.323905975},
-    {2.54003596, 0.696994185, 0.191060826},
-    {2.41275311, 0.823358774, 0.039409712},
-    {2.23870063, 0.898514867, -0.113051213},
-    {1.98929942, 0.943594933, -0.254533648},
-    {1.76012516, 0.964646876, -0.395942599},
-    {1.49242425, 0.949759781, -0.510762453},
-    {1.28035927, 0.902190089, -0.604746819},
-    {1.1146723, 0.835450709, -0.668233514},
-    {1.01378751, 0.747844219, -0.701491714},
-    {0.989509761, 0.63270843, -0.708359122},
-    {1.00694406, 0.490159601, -0.682344496},
-    {1.11094785, 0.331499428, -0.637704551},
-    {1.21761239, 0.16655457, -0.57098788},
-    {1.35060441, 0.00523499819, -0.490696669},
-    {1.50900137, -0.14760147, -0.397738487},
-    {1.71737885, -0.296721995, -0.287162274},
-    {1.95456934, -0.435354233, -0.16622813},
-    {2.15964198, -0.545372248, -0.0338731743},
-    {2.36349082, -0.639522851, 0.0985563472},
-    {2.52475429, -0.714118481, 0.2376872},
-    {2.62426019, -0.756105602, 0.379478544},
-    {2.63561678, -0.760927677, 0.523681045},
-    {2.54276276, -0.730580807, 0.651521087},
-    {2.33069539, -0.67826283, 0.761599422},
-    {1.99927664, -0.603788257, 0.844578266},
-    {1.60684264, -0.514484525, 0.891113758},
-    {1.13366258, -0.419344723, 0.914667547},
-    {0.565333009, -0.326108575, 0.9100945},
-    {-0.0584359765, -0.23375383, 0.872547328},
-    {-0.720716596, -0.138222992, 0.81576103},
-    {-1.43575883, -0.0453552268, 0.755004466},
-    {-2.14754343, 0.0381557122, 0.69231081},
-    {-2.81336594, 0.113699079, 0.62553072},
-    {-3.403409, 0.192349821, 0.568087339},
-    {-3.91777468, 0.270671248, 0.524357736},
-    {-4.32839012, 0.351819456, 0.494414836},
-    {-4.63467121, 0.432999849, 0.491787523},
-    {-4.84949398, 0.509923339, 0.516730309},
-    {-4.95907021, 0.576345742, 0.564314544},
-    {-4.97868586, 0.632149398, 0.624336779},
-    {-4.94332933, 0.672201216, 0.695786178},
-    {-4.86733627, 0.696778178, 0.767571568},
-    {-4.80728865, 0.707584023, 0.836353123},
-    {-4.78580332, 0.695350528, 0.904519796},
-    {-4.83013964, 0.657967031, 0.958932579},
-    {-4.95182705, 0.596607924, 0.999572515},
-    {-5.12637615, 0.521962464, 1.02421594},
-    {-5.36100912, 0.433110774, 1.02939737},
-    {-5.62950563, 0.33976379, 1.01166153},
-    {-5.9316473, 0.253405482, 0.977298975},
-    {-6.27061749, 0.170352444, 0.930996478},
-    {-6.59910583, 0.0925909206, 0.871682167},
-    {-6.89534712, 0.0234324113, 0.806135416},
-    {-7.13614082, -0.0242755096, 0.744313717},
-    {-7.29106236, -0.04777392, 0.689683616},
-    {-7.33188295, -0.0470820777, 0.647114456},
-    {-7.30075407, -0.0329478309, 0.629837394},
-    {-7.21595287, -0.0191688407, 0.633311868},
-    {-7.04129171, -0.00616251025, 0.653259575},
-    {-6.77793646, 0.00380119169, 0.684362531},
-    {-6.46523809, 0.0083740335, 0.725667536},
-    {-6.10901451, 0.0112583246, 0.772322237},
-    {-5.72953129, 0.00576711213, 0.820514619},
-    {-5.33027554, -0.0133760702, 0.867109716},
-    {-4.91758823, -0.0349100009, 0.907683551},
-    {-4.48890829, -0.0519501939, 0.935003459},
-    {-4.06190109, -0.0639101341, 0.944465935},
-    {-3.66115808, -0.0719041526, 0.938231647},
-    {-3.30302525, -0.0752341598, 0.924112558},
-    {-2.98568678, -0.0774790123, 0.890522718},
-    {-2.70989466, -0.0754115209, 0.835240602},
-    {-2.47431016, -0.0669365302, 0.768585861},
-    {-2.27380419, -0.0451133624, 0.685394406},
-    {-2.09873867, -0.0131598972, 0.586187601},
-    {-1.94652104, 0.0171538889, 0.483822405},
-    {-1.80880547, 0.0444740094, 0.378380507},
-    {-1.65931082, 0.0791107416, 0.264944792},
-    {-1.4915632, 0.115159161, 0.152438641},
-    {-1.30775321, 0.150315061, 0.0412877351},
-    {-1.08732545, 0.185833573, -0.0670470595},
-    {-0.83329165, 0.221069455, -0.175282106},
-    {-0.540945649, 0.249105096, -0.276100785},
-    {-0.216737464, 0.264914781, -0.368898004},
-    {0.138711736, 0.267263412, -0.448239207},
-    {0.520253122, 0.258500218, -0.518594444},
-    {0.933818877, 0.239486232, -0.577824771},
-    {1.36437547, 0.204568371, -0.621973991},
-    {1.82662261, 0.152393654, -0.656494796},
-    {2.35515642, 0.0790623724, -0.676942766},
-    {2.89172244, -0.0118955951, -0.681690753},
-    {3.42201257, -0.115857624, -0.665291369},
-    {3.96860194, -0.231546253, -0.620603383},
-    {4.4952836, -0.344366729, -0.553314745},
-    {4.95958567, -0.450855762, -0.466181397},
-    {5.33700323, -0.553437114, -0.365828335},
-    {5.60617065, -0.642434001, -0.252526581},
-    {5.69487476, -0.712584913, -0.131503493},
-    {5.56301737, -0.758034527, -0.0103937015},
-    {5.21835804, -0.77537775, 0.102996163},
-    {4.69155025, -0.760960937, 0.195766658},
-    {4.05969954, -0.710393667, 0.254515201},
-    {3.44943309, -0.612102449, 0.264309406},
-    {2.82214117, -0.511534274, 0.253834963},
-    {2.11974764, -0.440606683, 0.245472506},
-    {1.36178243, -0.388180912, 0.245288923},
-    {0.53274107, -0.356023341, 0.253085136},
-    {-0.273126811, -0.316962957, 0.253401071},
-    {-0.952430248, -0.247037843, 0.219982624},
-    {-1.50407922, -0.150358796, 0.167036116},
-    {-1.95661473, -0.0418607146, 0.118593708},
-    {-2.30664492, 0.0545348078, 0.0901423246},
-    {-2.56677389, 0.130470276, 0.100051306},
-    {-2.72076225, 0.187645599, 0.140511096},
-    {-2.73428035, 0.240424976, 0.195267811},
-    {-2.6037302, 0.305081218, 0.247465745},
-    {-2.37793112, 0.375930876, 0.295088798},
-    {-2.1098609, 0.442803234, 0.340617567},
-    {-1.83816981, 0.500528276, 0.38978824},
-    {-1.58633089, 0.537543297, 0.435317099},
-    {-1.37085843, 0.553290427, 0.478152156},
-    {-1.2199955, 0.551449299, 0.512296557},
-    {-1.13993824, 0.540386856, 0.524811864},
-    {-1.12452567, 0.522002161, 0.518514931},
-    {-1.16522002, 0.494819671, 0.494011194},
-    {-1.26313245, 0.456947029, 0.461149693},
-    {-1.40832269, 0.404199243, 0.422829032},
-    {-1.5684886, 0.335540175, 0.379794449},
-    {-1.7370801, 0.256013989, 0.334570944},
-    {-1.90485013, 0.173744664, 0.282700568},
-    {-2.04349637, 0.094816111, 0.224875137},
-    {-2.13758278, 0.0170042291, 0.161595076},
-    {-2.17788553, -0.0561296009, 0.0970645994},
-    {-2.18008542, -0.125768214, 0.0395417362},
-    {-2.12303305, -0.183718592, -0.0175938513},
-    {-1.98761022, -0.226154566, -0.0649352446},
-    {-1.78974748, -0.257765412, -0.103929117},
-    {-1.52917862, -0.280180633, -0.140212551},
-    {-1.19369805, -0.29157114, -0.167034343},
-    {-0.806868911, -0.301149219, -0.189549372},
-    {-0.401348293, -0.305268079, -0.196783751},
-    {-0.00465184078, -0.297880352, -0.193331555},
-    {0.378727734, -0.280263782, -0.181916878},
-    {0.748396337, -0.254140407, -0.163625494},
-    {1.10959351, -0.222597092, -0.139896125},
-    {1.46126103, -0.191534013, -0.113906227},
-    {1.77272451, -0.160938606, -0.0860851035},
-    {2.01410961, -0.124188505, -0.0533784255},
-    {2.17201352, -0.0808213502, -0.0246110875},
-    {2.2359786, -0.0335197486, -0.0023046853},
-    {2.21403384, 0.0201169848, 0.0087682493},
-    {2.1100781, 0.069968082, 0.00954691228},
-    {1.92647707, 0.120217457, 0.00117974496},
-    {1.67751467, 0.169587508, -0.00994473416},
-    {1.37579024, 0.217361271, -0.0220336635},
-    {1.03169632, 0.263339132, -0.0377309844},
-    {0.667664886, 0.306623131, -0.0522310585},
-    {0.305978, 0.35047254, -0.065533869},
-    {-0.0354886316, 0.387288094, -0.0667976439},
-    {-0.372791588, 0.419501543, -0.0629493892},
-    {-0.703223467, 0.448530942, -0.0472591296},
-    {-1.01604342, 0.471468627, -0.0206524245},
-    {-1.32203722, 0.484531701, 0.0194711126},
-    {-1.6232127, 0.491914719, 0.0719507337},
-    {-1.92127144, 0.489192128, 0.129401237},
-    {-2.20715213, 0.47533071, 0.191214219},
-    {-2.49579406, 0.454450727, 0.263195306},
-    {-2.81156039, 0.41874373, 0.34079507},
-    {-3.14990091, 0.378812343, 0.420537561},
-    {-3.51243353, 0.326752692, 0.504879236},
-    {-3.90873599, 0.261958927, 0.587185323},
-    {-4.32311869, 0.189541742, 0.662346125},
-    {-4.76380777, 0.103805102, 0.725168765},
-    {-5.23499489, 0.00335725909, 0.777272403},
-    {-5.70385122, -0.103367455, 0.812429965},
-    {-6.1565299, -0.207347736, 0.82981205},
-    {-6.60470104, -0.306864381, 0.828000367},
-    {-7.02436733, -0.404474556, 0.810249925},
-    {-7.38936806, -0.499327809, 0.788772941},
-    {-7.67207003, -0.578463018, 0.759107649},
-    {-7.86674213, -0.647222877, 0.723835409},
-    {-7.96363163, -0.710696816, 0.690267265},
-    {-7.93407869, -0.763287842, 0.66159445},
-    {-7.7517662, -0.804451585, 0.640729189},
-    {-7.40970325, -0.836554408, 0.627060592},
-    {-6.8942194, -0.859933972, 0.621473372},
-    {-6.21258211, -0.86846894, 0.624314368},
-    {-5.4053359, -0.853565276, 0.63898325},
-    {-4.53111076, -0.810733914, 0.667952716},
-    {-3.59512281, -0.74787432, 0.706844091},
-    {-2.59734464, -0.667540073, 0.751521349},
-    {-1.58575034, -0.56800276, 0.79594487},
-    {-0.672641873, -0.450888425, 0.830315888},
-    {0.112588324, -0.319324166, 0.846922755},
-    {0.759254873, -0.172045395, 0.840737104},
-    {1.23855817, -0.0249737035, 0.804136038},
-    {1.57072663, 0.105085507, 0.740816236},
-    {1.76562941, 0.209163412, 0.647946},
-    {1.81390274, 0.301484406, 0.518377662},
-    {1.74145138, 0.377710044, 0.367705524},
-    {1.58564198, 0.4284603, 0.212361917},
-    {1.35407484, 0.452766657, 0.052922152},
-    {1.06207919, 0.449926645, -0.105756111},
-    {0.744064391, 0.435222983, -0.264281511},
-    {0.430272967, 0.412009358, -0.412939578},
-    {0.142390147, 0.380625099, -0.542044222},
-    {-0.128971145, 0.345086396, -0.657109559},
-    {-0.34512496, 0.30797556, -0.747517169},
-    {-0.49577409, 0.271542072, -0.816888571},
-    {-0.563527226, 0.233607322, -0.864035308},
-    {-0.537470341, 0.196376041, -0.89087373},
-    {-0.420455456, 0.151412547, -0.890657544},
-    {-0.232120872, 0.0981347635, -0.86501646},
-    {0.00694734883, 0.0354286283, -0.823095918},
-    {0.266468585, -0.0327649228, -0.764546871},
-    {0.546808898, -0.100376464, -0.68883729},
-    {0.848466873, -0.165560275, -0.599309385},
-    {1.15810645, -0.236281365, -0.498773277},
-    {1.47034001, -0.306536853, -0.388858825},
-    {1.77184784, -0.371943384, -0.265910029},
-    {2.04415703, -0.426744342, -0.134758383},
-    {2.25495553, -0.467916012, -0.00643987395},
-    {2.38590598, -0.486407489, 0.118078239},
-    {2.41537189, -0.484295756, 0.235725015},
-    {2.31294203, -0.469545692, 0.339811385},
-    {2.08914232, -0.440795511, 0.430579066},
-    {1.74969912, -0.403597504, 0.499503195},
-    {1.30355597, -0.357187301, 0.547343433},
-    {0.777023137, -0.302010864, 0.572118819},
-    {0.186901167, -0.241951704, 0.573250711},
-    {-0.44923842, -0.180479586, 0.555155754},
-    {-1.10567868, -0.123913869, 0.530890882},
-    {-1.76101327, -0.0707610771, 0.499486446},
-    {-2.4071312, -0.0206926186, 0.465348214},
-    {-3.00041986, 0.0300243665, 0.435084343},
-    {-3.49859381, 0.0921152458, 0.409260213},
-    {-3.87517977, 0.159859821, 0.39040345},
-    {-4.10876083, 0.237531617, 0.385032475},
-    {-4.18107224, 0.318899989, 0.397956848},
-    {-4.10828686, 0.402534306, 0.424279481},
-    {-3.92544985, 0.486031771, 0.464277446},
-    {-3.66065526, 0.56990236, 0.511741757},
-    {-3.36455154, 0.653826594, 0.563672602},
-    {-3.07440853, 0.73412621, 0.612304091},
-    {-2.82579851, 0.809072495, 0.652870893},
-    {-2.64811826, 0.87307632, 0.681255519},
-    {-2.55728674, 0.9190346, 0.699195147},
-    {-2.56508517, 0.944543064, 0.709537864},
-    {-2.67496872, 0.94964689, 0.709774792},
-    {-2.86307859, 0.9348768, 0.708146214},
-    {-3.10973597, 0.901608229, 0.696368217},
-    {-3.38691711, 0.85494864, 0.682865918},
-    {-3.68021107, 0.797911048, 0.665583968},
-    {-3.99670076, 0.730849981, 0.645218849},
-    {-4.33704567, 0.652905405, 0.623959601},
-    {-4.67893505, 0.56266582, 0.608270168},
-    {-5.02055216, 0.469266653, 0.586985767},
-    {-5.35608244, 0.373536199, 0.563872099},
-    {-5.65022421, 0.281663746, 0.536335349},
-    {-5.89431334, 0.20031701, 0.505821943},
-    {-6.07790852, 0.128000587, 0.473436207},
-    {-6.1746521, 0.0684019104, 0.440774947},
-    {-6.18320084, 0.0147760101, 0.414664477},
-    {-6.09141445, -0.0358108729, 0.395159155},
-    {-5.90868235, -0.0790831, 0.377794564},
-    {-5.65424776, -0.115558296, 0.364911914},
-    {-5.32545328, -0.147988468, 0.352420926},
-    {-4.93483162, -0.17344217, 0.34153226},
-    {-4.50032902, -0.191218063, 0.334614784},
-    {-4.02811241, -0.205136165, 0.328379154},
-    {-3.52260542, -0.215129897, 0.318767786},
-    {-2.98769927, -0.225206763, 0.310004562},
-    {-2.43323779, -0.230860442, 0.29723385},
-    {-1.86695385, -0.232340366, 0.283997536},
-    {-1.30710495, -0.226886243, 0.264176369},
-    {-0.755087674, -0.216626436, 0.23998189},
-    {-0.209400803, -0.206585303, 0.207621828},
-    {0.314608157, -0.198202029, 0.170291781},
-    {0.782119513, -0.196178213, 0.125300914},
-    {1.20173955, -0.204786912, 0.0748607144},
-    {1.55610991, -0.21860525, 0.0191551726},
-    {1.8241781, -0.237811178, -0.0430853739},
-    {2.01113272, -0.26238811, -0.107022017},
-    {2.12231636, -0.297576576, -0.174854293},
-    {2.16406536, -0.338663161, -0.235211268},
-    {2.1423316, -0.388382465, -0.289869189},
-    {2.06497765, -0.444375098, -0.339680225},
-    {1.93815005, -0.493374854, -0.379413784},
-    {1.78389847, -0.53441304, -0.413952351},
-    {1.61239755, -0.566091537, -0.436948448},
-    {1.42414618, -0.590468884, -0.450484127},
-    {1.23785663, -0.604769468, -0.453610241},
-    {1.06060684, -0.606814623, -0.442345709},
-    {0.910906851, -0.5928967, -0.423047066},
-    {0.792006373, -0.56122458, -0.398091972},
-    {0.698993146, -0.523056746, -0.361737698},
-    {0.623968184, -0.472383589, -0.311300814},
-    {0.561533213, -0.410997182, -0.255262554},
-    {0.502227843, -0.34430021, -0.197115317},
-    {0.432570904, -0.266844541, -0.136437893},
-    {0.344205916, -0.186703667, -0.0766875669},
-    {0.23466149, -0.105822049, -0.0196740273},
-    {0.0877115577, -0.0250704512, 0.0327179953},
-    {-0.0983723179, 0.053193789, 0.0830236897},
-    {-0.318741828, 0.12608178, 0.128804624},
-    {-0.572347283, 0.196126133, 0.167183325},
-    {-0.842469513, 0.258335948, 0.203219771},
-    {-1.13182342, 0.312875509, 0.234910205},
-    {-1.42809379, 0.358038485, 0.262247503},
-    {-1.71325648, 0.390430838, 0.286292344},
-    {-1.99396241, 0.412413836, 0.308557868},
-    {-2.25908732, 0.425866306, 0.330923259},
-    {-2.49000311, 0.421162367, 0.352566063},
-    {-2.6814518, 0.409786552, 0.369933754},
-    {-2.82237697, 0.390930861, 0.381967992},
-    {-2.91760969, 0.35940209, 0.387526751},
-    {-2.96558213, 0.324704856, 0.391377985},
-    {-2.96577239, 0.290035367, 0.387529373},
-    {-2.92374587, 0.252380878, 0.381706715},
-    {-2.83067584, 0.216014355, 0.36847043},
-    {-2.68380523, 0.178615808, 0.350340784},
-    {-2.49722195, 0.145249277, 0.326851368},
-    {-2.27473497, 0.119419269, 0.301324517},
-    {-2.01644397, 0.0990659818, 0.274037093},
-    {-1.73501623, 0.0824001506, 0.244321436},
-    {-1.43230104, 0.0697498918, 0.215604484},
-    {-1.12476599, 0.0621538907, 0.186545327},
-    {-0.797868907, 0.0599224493, 0.158086941},
-    {-0.468146056, 0.0617515743, 0.133393109},
-    {-0.160468578, 0.062716037, 0.113122933},
-    {0.123696178, 0.0650939047, 0.0943160728},
-    {0.37616694, 0.0672223568, 0.0838733763},
-    {0.584854782, 0.0717619359, 0.0731812343},
-    {0.750591278, 0.0742894858, 0.0675441623},
-    {0.857911706, 0.0777648613, 0.0626221374},
-    {0.901894093, 0.0815062672, 0.0622895509},
-    {0.881973207, 0.0855303556, 0.0639856607},
-    {0.804168403, 0.0893216506, 0.0700051859},
-    {0.677872777, 0.0962834731, 0.0786570534},
-    {0.503325284, 0.103073433, 0.0908573419},
-    {0.303321153, 0.114901692, 0.103861935},
-    {0.080744721, 0.129146978, 0.126276091},
-    {-0.175248802, 0.146221444, 0.152749687},
-    {-0.445863843, 0.1674757, 0.182330817},
-    {-0.720733225, 0.187330127, 0.215754166},
-    {-0.997745633, 0.203764513, 0.254363954},
-    {-1.28281713, 0.219411105, 0.296919942},
-    {-1.57274532, 0.230580941, 0.34156549},
-    {-1.87097776, 0.236650333, 0.393413275},
-    {-2.18028116, 0.236583814, 0.442847788},
-    {-2.48994374, 0.232017934, 0.495960176},
-    {-2.80204201, 0.216446668, 0.549654722},
-    {-3.13484526, 0.190955147, 0.598675728},
-    {-3.47913599, 0.148527235, 0.652290463},
-    {-3.82729673, 0.0957971215, 0.70111537},
-    {-4.17732, 0.0334831029, 0.741315126},
-    {-4.53800917, -0.0392999239, 0.772277415},
-    {-4.88895369, -0.114726886, 0.792131662},
-    {-5.2186594, -0.198200509, 0.80049181},
-    {-5.50166655, -0.277522743, 0.800311327},
-    {-5.71839428, -0.355512321, 0.788463175},
-    {-5.84671545, -0.426256835, 0.771491587},
-    {-5.85827589, -0.482284129, 0.753037095},
-    {-5.73446465, -0.520047009, 0.729143023},
-    {-5.47737026, -0.535295367, 0.706461728},
-    {-5.09645367, -0.533863723, 0.69069618},
-    {-4.60589218, -0.512259841, 0.680379689},
-    {-4.01705408, -0.465904534, 0.676397383},
-    {-3.37835312, -0.399673194, 0.680604279},
-    {-2.70516419, -0.320671082, 0.687355518},
-    {-2.02781796, -0.227235422, 0.695353925},
-    {-1.38243175, -0.121760756, 0.700192869},
-    {-0.80375433, -0.00346345617, 0.694456279},
-    {-0.33097741, 0.113599308, 0.673337579},
-    {-0.00460946653, 0.227354974, 0.634809434},
-    {0.166165382, 0.333877265, 0.575229406},
-    {0.175178051, 0.423122525, 0.500800192},
-    {0.0560427867, 0.499511987, 0.411533743},
-    {-0.156934455, 0.558352292, 0.321922839},
-    {-0.420488715, 0.608530462, 0.222372264},
-    {-0.718568027, 0.651147842, 0.120435953},
-    {-1.01469231, 0.687798738, 0.0256236661},
-    {-1.28187656, 0.715038896, -0.0596167967},
-    {-1.51467299, 0.733834803, -0.13135007},
-    {-1.69898927, 0.743404329, -0.187736854},
-    {-1.82500768, 0.74965322, -0.228452533},
-    {-1.87887657, 0.747927248, -0.254533619},
-    {-1.86361301, 0.735430956, -0.26449734},
-    {-1.78934836, 0.715069532, -0.263080657},
-    {-1.65473151, 0.684509754, -0.252187997},
-    {-1.47494757, 0.639015436, -0.228794262},
-    {-1.27246737, 0.580544651, -0.200391158},
-    {-1.0535531, 0.504735291, -0.163741902},
-    {-0.818159759, 0.423588097, -0.119859233},
-    {-0.582217634, 0.336554527, -0.0760430917},
-    {-0.363619208, 0.242220894, -0.029366849},
-    {-0.151900351, 0.146737427, 0.0179317165},
-    {0.0439956859, 0.0545514226, 0.0666628554},
-    {0.20680283, -0.0325964913, 0.113062322},
-    {0.350409418, -0.113579527, 0.161179349},
-    {0.468638122, -0.18859075, 0.210748971},
-    {0.551597834, -0.253774583, 0.257458419},
-    {0.600974441, -0.308428466, 0.302563608},
-    {0.59450835, -0.353238821, 0.341681898},
-    {0.539373159, -0.384511709, 0.378380537},
-    {0.436910957, -0.401153088, 0.40385589},
-    {0.27641803, -0.404031336, 0.426642537},
-    {0.0550037697, -0.392107248, 0.439108372},
-    {-0.214819163, -0.371174634, 0.43947041},
-    {-0.522803962, -0.342554271, 0.433188617},
-    {-0.859232068, -0.30390951, 0.426104873},
-    {-1.20053244, -0.254855454, 0.412535936},
-    {-1.51497769, -0.197703168, 0.403140903},
-    {-1.78750241, -0.12826249, 0.398651183},
-    {-1.99338055, -0.0512391999, 0.401078969},
-    {-2.12234545, 0.0393151715, 0.412743211},
-    {-2.17502451, 0.140303701, 0.433302015},
-    {-2.15689754, 0.237559363, 0.464564443},
-    {-2.09087038, 0.335072994, 0.501638174},
-    {-1.99017012, 0.435267776, 0.547420561},
-    {-1.87700939, 0.533389747, 0.595257699},
-    {-1.79742968, 0.624959469, 0.633129895},
-    {-1.78234148, 0.70269835, 0.659465909},
-    {-1.80472744, 0.769867122, 0.680371463},
-    {-1.85082328, 0.836242378, 0.69452095},
-    {-1.9547689, 0.885644853, 0.706129134},
-    {-2.12050557, 0.909772873, 0.714759231},
-    {-2.34387636, 0.92182833, 0.711649776},
-    {-2.59731102, 0.919716716, 0.701855659},
-    {-2.86607742, 0.895951927, 0.689973712},
-    {-3.14317632, 0.852803409, 0.675748885},
-    {-3.40582347, 0.791909814, 0.65695864},
-    {-3.64639616, 0.720892072, 0.63212961},
-    {-3.86177731, 0.640922785, 0.599390626},
-    {-4.04475546, 0.552932799, 0.561928153},
-    {-4.19546795, 0.462474227, 0.513966203},
-    {-4.30577517, 0.373719245, 0.454838961},
-    {-4.3629775, 0.287650019, 0.387160867},
-    {-4.33811092, 0.216186166, 0.314818293},
-    {-4.22306919, 0.153282449, 0.247171894},
-    {-4.02114868, 0.100943483, 0.184273362},
-    {-3.74020243, 0.0635613948, 0.125455409},
-    {-3.39750934, 0.0387709662, 0.0714352503},
-    {-2.99484921, 0.0242210068, 0.0217325911},
-    {-2.53707075, 0.0094201155, -0.0232828204},
-    {-2.04294968, -0.00276707485, -0.0588159561},
-    {-1.53200507, -0.0139746964, -0.0886142403},
-    {-1.00135612, -0.0261301417, -0.114105761},
-    {-0.464986593, -0.0369553044, -0.134326041},
-    {0.0698862821, -0.0470321886, -0.152168453},
-    {0.59444958, -0.0540494248, -0.16635257},
-    {1.10723972, -0.066105105, -0.172555},
-    {1.58333099, -0.0824675485, -0.176213279},
-    {1.99851155, -0.0988300219, -0.179339468},
-    {2.34598136, -0.115425266, -0.178591162},
-    {2.61777425, -0.132918477, -0.175664514},
-    {2.80344844, -0.153188646, -0.170094013},
-    {2.88780475, -0.1765351, -0.161962628},
-    {2.86854792, -0.201038465, -0.156327099},
-    {2.74491572, -0.222379863, -0.147695377},
-    {2.53268623, -0.242201135, -0.141991794},
-    {2.24369574, -0.255809128, -0.142952472},
-    {1.89172328, -0.259245306, -0.151120856},
-    {1.47296166, -0.255684853, -0.161793336},
-    {1.00282919, -0.242417261, -0.173752248},
-    {0.497122824, -0.222512975, -0.186522961},
-    {-0.018228231, -0.200064436, -0.195618764},
-    {-0.521440387, -0.168320581, -0.202902049},
-    {-0.97922349, -0.125535443, -0.211598784},
-    {-1.38507581, -0.0705615431, -0.218699157},
-    {-1.7290535, -0.00793854333, -0.21854949},
-    {-2.00222635, 0.0617848411, -0.203600422},
-    {-2.21486831, 0.13338621, -0.172387227},
-    {-2.37456703, 0.200787172, -0.124271333},
-    {-2.46915889, 0.258223057, -0.0646215156},
-    {-2.51870871, 0.311561793, -1.75088644e-05},
-    {-2.53581309, 0.360711157, 0.0665796995},
-    {-2.53913808, 0.399084121, 0.131978065},
-    {-2.54964828, 0.420388401, 0.192803279},
-    {-2.58738875, 0.427612245, 0.251342922},
-    {-2.66895413, 0.421581626, 0.303095669},
-    {-2.78138709, 0.399066925, 0.348719478},
-    {-2.92078853, 0.363081545, 0.389507562},
-    {-3.07228827, 0.324249387, 0.413300931},
-    {-3.22636819, 0.283625901, 0.417707473},
-    {-3.38023186, 0.241090164, 0.405385762},
-    {-3.53615785, 0.198604271, 0.37974456},
-    {-3.69085288, 0.149217591, 0.352490395},
-    {-3.83324265, 0.0974696428, 0.320430666},
-    {-3.94252515, 0.0448569953, 0.286940813},
-    {-3.99024916, 0.00361827901, 0.247930303},
-    {-3.97121096, -0.021555284, 0.199333712},
-    {-3.8658154, -0.0228639748, 0.148782507},
-    {-3.66818762, -0.00629231986, 0.0986561179},
-    {-3.39552975, 0.0251416229, 0.0531962663},
-    {-3.04944086, 0.0567796528, 0.018756086},
-    {-2.64195848, 0.0873428658, -0.00121476175},
-    {-2.17968607, 0.119718596, -0.0182756223},
-    {-1.71666396, 0.164405331, -0.0321357623},
-    {-1.25647092, 0.220005184, -0.0473090112},
-    {-0.803012609, 0.286908776, -0.0636588782},
-    {-0.372856081, 0.347956568, -0.083185792},
-    {-0.00571606867, 0.389008284, -0.103335872},
-    {0.327694803, 0.398013443, -0.123567402},
-    {0.611992657, 0.382831663, -0.151037708},
-    {0.806321502, 0.365564704, -0.184819296},
-    {0.946724594, 0.354995579, -0.234645933},
-    {1.01878965, 0.340860695, -0.285129577},
-    {1.04320323, 0.310813516, -0.338158429},
-    {1.03259432, 0.260695159, -0.385034233},
-    {0.97550869, 0.18378827, -0.415231645},
-    {0.911937773, 0.0944099948, -0.432492018},
-    {0.825486243, -0.00108759617, -0.439293116},
-    {0.749344349, -0.0864916593, -0.443134248},
-    {0.712611854, -0.161602676, -0.443450212},
-    {0.727594256, -0.22901471, -0.440374017},
-    {0.742759228, -0.298538566, -0.422780961},
-    {0.754499197, -0.371454567, -0.395826191},
-    {0.782054007, -0.444423556, -0.355466187},
-    {0.784829497, -0.508024633, -0.305300474},
-    {0.786375403, -0.558166683, -0.251655847},
-    {0.794429541, -0.594434083, -0.195840493},
-    {0.824864805, -0.62119782, -0.150231972},
-    {0.854885459, -0.636745811, -0.102099992},
-    {0.869052947, -0.645026922, -0.0554070994},
-    {0.85594964, -0.642848551, -0.0115909558},
-    {0.787972152, -0.633619964, 0.0391759127},
-    {0.669693649, -0.618321598, 0.079932414},
-    {0.488666445, -0.5942536, 0.117743134},
-    {0.283429682, -0.562200427, 0.148707941},
-    {0.0602916479, -0.516754627, 0.165768802},
-    {-0.193740651, -0.470250458, 0.167904228},
-    {-0.463340431, -0.41277644, 0.159998745},
-    {-0.760674953, -0.353030205, 0.152632296},
-    {-1.07275903, -0.293716252, 0.143952236},
-    {-1.37338591, -0.238526195, 0.131813392},
-    {-1.66609955, -0.18185018, 0.125595838},
-    {-1.93591189, -0.119382881, 0.12574397},
-    {-2.12709022, -0.0536004454, 0.127789274},
-    {-2.26207972, 0.0140577666, 0.130845189},
-    {-2.36163521, 0.0828032717, 0.141365737},
-    {-2.41732454, 0.141618356, 0.160946533},
-    {-2.41307235, 0.182243839, 0.188997895},
-    {-2.39565706, 0.216312036, 0.216326475},
-    {-2.37355828, 0.247026533, 0.241678014},
-    {-2.34728551, 0.269026041, 0.265090972},
-    {-2.34018493, 0.280333489, 0.278643221},
-    {-2.3446908, 0.284640193, 0.287339896},
-    {-2.34704232, 0.278024137, 0.289035052},
-    {-2.36790442, 0.256055802, 0.280971169},
-    {-2.38804173, 0.226240888, 0.264176369},
-    {-2.43440247, 0.186997622, 0.243174523},
-    {-2.50331521, 0.137061611, 0.214283884},
-    {-2.58834839, 0.082753405, 0.173983306},
-    {-2.64192915, 0.0303498786, 0.119323358},
-    {-2.66792655, -0.0270865504, 0.062992245},
-    {-2.64987421, -0.0821682438, 0.010425197},
-    {-2.58221245, -0.129709184, -0.0437505022},
-    {-2.44156456, -0.172207668, -0.096359618},
-    {-2.24429631, -0.206339836, -0.137219414},
-    {-1.9798522, -0.210068271, -0.181707263},
-    {-1.65148139, -0.213250861, -0.215705991},
-    {-1.27366471, -0.231908068, -0.230305865},
-    {-0.853918076, -0.231981605, -0.241594091},
-    {-0.443558902, -0.22745268, -0.249615356},
-    {-0.0283217356, -0.22620447, -0.249295607},
-    {0.388771385, -0.209758863, -0.245604113},
-    {0.760784626, -0.19868426, -0.237356305},
-    {1.08174825, -0.204919964, -0.225583375},
-    {1.39378977, -0.207665682, -0.200024828},
-    {1.65293038, -0.207180887, -0.172098532},
-    {1.84566236, -0.217008919, -0.132929251},
-    {1.96367502, -0.246607691, -0.098308675},
-    {1.94767058, -0.277936757, -0.078477405},
-    {1.83365989, -0.300506651, -0.0665857643},
-    {1.65633023, -0.327754855, -0.0445819348},
-    {1.42026639, -0.339290977, -0.0378594846},
-    {1.14713156, -0.321153373, -0.0440498218},
-    {0.86720711, -0.284254581, -0.0492379144},
-    {0.548504949, -0.259671241, -0.0560808182},
-    {0.19629477, -0.239721447, -0.0541453436},
-    {-0.179541498, -0.211920604, -0.0493543223},
-    {-0.51340884, -0.167056844, -0.0460119843},
-    {-0.804318726, -0.115497336, -0.0350376703},
-    {-1.03588617, -0.0636134967, -0.0145760439},
-    {-1.1947124, -0.0124448705, 0.0148816463},
-    {-1.30745554, 0.0454102792, 0.052406162},
-    {-1.40679264, 0.0956571326, 0.102264516},
-    {-1.50086665, 0.136684, 0.164660066},
-    {-1.58781064, 0.167059973, 0.236489907},
-    {-1.68879569, 0.184835866, 0.313912302},
-    {-1.8160373, 0.194048062, 0.388358146},
-    {-1.97522438, 0.195417672, 0.455263734},
-    {-2.16765547, 0.182840481, 0.512280405},
-    {-2.38673472, 0.147898361, 0.566446245},
-    {-2.63984752, 0.100146815, 0.621107519},
-    {-2.95872927, 0.0316398554, 0.662820041},
-    {-3.30826473, -0.0501905307, 0.698987007},
-    {-3.66192436, -0.143908933, 0.720852435},
-    {-4.00394106, -0.239811435, 0.721833348},
-    {-4.33198357, -0.336743265, 0.7044698},
-    {-4.64749146, -0.441776633, 0.671525121},
-    {-4.9084754, -0.540699661, 0.625580609},
-    {-5.09291983, -0.626752257, 0.569426119},
-    {-5.19397068, -0.691952825, 0.498754919},
-    {-5.16956043, -0.738213062, 0.426753342},
-    {-5.00164509, -0.75289607, 0.3538706},
-    {-4.69517422, -0.745163977, 0.28616482},
-    {-4.2795763, -0.727638543, 0.2330966},
-    {-3.77276444, -0.688693404, 0.191725925},
-    {-3.19158101, -0.622412145, 0.166849688},
-    {-2.57338333, -0.54469049, 0.154511318},
-    {-1.92481875, -0.465675801, 0.151395231},
-    {-1.27128696, -0.375645012, 0.156506747},
-    {-0.641149163, -0.278251708, 0.165120333},
-    {-0.0558253229, -0.188690543, 0.169892699},
-    {0.456582457, -0.102488302, 0.16786401},
-    {0.86808151, -0.0287687108, 0.15738216},
-    {1.17002857, 0.040992137, 0.140027374},
-    {1.33185792, 0.105634227, 0.108866021},
-    {1.36233747, 0.158828884, 0.0646341816},
-    {1.30270791, 0.201730475, 0.0182572342},
-    {1.1703949, 0.237215713, -0.0317114629},
-    {0.973097503, 0.259946913, -0.0804496482},
-    {0.730088353, 0.267928541, -0.125446409},
-    {0.462028593, 0.269349068, -0.166469485},
-    {0.184076473, 0.265867174, -0.195494324},
-    {-0.082846649, 0.258699715, -0.217684805},
-    {-0.338194191, 0.252597034, -0.231353447},
-    {-0.556227326, 0.241771892, -0.231785789},
-    {-0.747721195, 0.222482845, -0.21911484},
-    {-0.904328704, 0.195661038, -0.195785061},
-    {-1.03185284, 0.164266393, -0.163309574},
-    {-1.12440872, 0.128564969, -0.11936944},
-    {-1.15955937, 0.0933940411, -0.0681134388},
-    {-1.16093099, 0.0616316497, -0.0093511492},
-    {-1.14036906, 0.0238589365, 0.0564180687},
-    {-1.10250735, -0.0237190071, 0.127772659},
-    {-1.05794299, -0.0829739794, 0.214490891},
-    {-1.01580954, -0.149230063, 0.299790144},
-    {-0.985215366, -0.214733467, 0.379204422},
-    {-0.958188593, -0.272897333, 0.44873628},
-    {-0.954696715, -0.324977934, 0.511192977},
-    {-0.981850684, -0.37647438, 0.568136156},
-    {-1.04318106, -0.421639413, 0.621830583},
-    {-1.14020419, -0.467417747, 0.667251527},
-    {-1.26717961, -0.509903669, 0.708456993},
-    {-1.43299925, -0.54409188, 0.733167052},
-    {-1.61975408, -0.5621171, 0.743260503},
-    {-1.83157027, -0.573211074, 0.73983103},
-    {-2.03898716, -0.577239573, 0.73700732},
-    {-2.21217847, -0.576201677, 0.727979064},
-    {-2.35869217, -0.569450259, 0.71926558},
-    {-2.48236132, -0.554902375, 0.708620548},
-    {-2.53505158, -0.529924393, 0.701585114},
-    {-2.51679635, -0.497465461, 0.699993253},
-    {-2.41368508, -0.446132779, 0.699455142},
-    {-2.21907926, -0.390710354, 0.704083979},
-    {-1.97159696, -0.331363261, 0.714426756},
-    {-1.71294045, -0.263668507, 0.728993356},
-    {-1.47674882, -0.189372286, 0.746087611},
-    {-1.2642529, -0.117121391, 0.7652933},
-    {-1.06898832, -0.0410499536, 0.781835854},
-    {-0.911972404, 0.0301756319, 0.789995253},
-    {-0.827322125, 0.101410598, 0.789404929},
-    {-0.838546395, 0.177203387, 0.77877903},
-    {-0.942008972, 0.25282985, 0.758974612},
-    {-1.11434686, 0.317239225, 0.733768284},
-    {-1.33273625, 0.364771426, 0.708461821},
-    {-1.58204067, 0.403101832, 0.675648987},
-    {-1.84859586, 0.421542853, 0.646765292},
-    {-2.13691783, 0.398828298, 0.632464826},
-    {-2.45170712, 0.352100641, 0.626007497},
-    {-2.77174878, 0.322205573, 0.606690049},
-    {-3.01884413, 0.372239292, 0.548390985},
-    {-3.20177293, 0.414412439, 0.497814},
-    {-3.34887052, 0.409453869, 0.471267968},
-    {-3.49435782, 0.357937753, 0.461552322},
-    {-3.71910715, 0.241372809, 0.49287048},
-    {-3.92233825, 0.0927471444, 0.521968305},
-    {-4.02676582, -0.0409627818, 0.523597836},
-    {-4.03192043, -0.1526898, 0.501930952},
-    {-3.98279953, -0.235366777, 0.459694535},
-    {-3.88364387, -0.325643033, 0.421066433},
-    {-3.73200226, -0.419768989, 0.38775},
-    {-3.51527214, -0.459652215, 0.33705911},
-    {-3.21515965, -0.47773698, 0.28335914},
-    {-2.85013366, -0.482016474, 0.239019662},
-    {-2.39820147, -0.498962104, 0.203914613},
-    {-1.82676518, -0.540590882, 0.18540208},
-    {-1.24217415, -0.556984782, 0.16800721},
-    {-0.612564802, -0.587475657, 0.161661595},
-    {0.0201493986, -0.621729851, 0.171196282},
-    {1.55133748, -0.736799657, 0.13977845},
-    {7.24613714, -1.13173509, -0.371142983},
-    {10.0882349, -1.56603599, -0.470934659},
-    {10.2007837, -1.66763747, -0.153424636},
-    {9.4514637, -1.60849988, 0.210582674},
-    {8.71675968, -1.60284352, 0.198475003},
-    {7.82163572, -1.52316213, 0.488960683},
-    {7.03309488, -1.3586731, 0.532111704},
-    {5.13426828, -1.44720328, 0.948606253},
-    {0.0916361511, -1.91040719, 1.52222359},
-    {-3.0895648, -2.07609034, 1.6511302},
-    {-1.8957628, -1.68269467, 1.65399182},
-    {-3.08964872, -1.71849751, 1.84493315},
-    {1.2096467, -1.21116555, 1.7464751},
-    {6.55484247, -1.09143627, 2.13292265},
-    {7.81726599, -0.924588859, 2.40418482},
-    {6.0185256, -0.442262858, 2.18435574},
-    {3.35352802, -0.153300226, 1.97142243},
-    {1.08765149, -0.0239684358, 1.72149968},
-    {-0.896945596, 0.0544849187, 1.46636844},
-    {-2.57471347, 0.127583906, 1.23604679},
-    {-3.9405098, 0.185178518, 1.04627943},
-    {-4.92501402, 0.270074695, 0.897400796},
-    {-5.34608841, 0.344419748, 0.819269538},
-    {-5.211339, 0.428607792, 0.743787348},
-    {-5.01868963, 0.496770293, 0.627143741},
-    {-5.17634439, 0.545591533, 0.547809005},
-    {-5.77615166, 0.544793308, 0.487780154},
-    {-6.44406986, 0.579147995, 0.474976122},
-    {-4.48984289, 0.66865921, 0.566700935},
-    {-0.989660859, 0.764473915, 0.65025568},
-    {-1.86859989, 0.736669958, 0.695370495},
-    {-1.6849544, 0.854166865, 0.738255382},
-    {-2.07234883, 0.960190237, 0.799847364},
-    {-1.57392585, 1.10066819, 0.879198849},
-    {0.460851461, 1.2192508, 0.885533094},
-    {0.981794178, 1.32511997, 0.854688346},
-    {1.41646361, 1.28750622, 0.744640708},
-    {1.07639396, 1.00902843, 0.519224584},
-    {0.841149747, 0.749694765, 0.360151321},
-    {0.430508912, 0.484647989, 0.258073688},
-    {0.146550328, 0.274831444, 0.182612509},
-    {0.415734231, 0.134006232, 0.131222814},
-    {0.555890083, 0.0411050096, 0.0991675705},
-    {0.601084292, -0.012029158, 0.0740791783},
-    {0.510192811, -0.0341617167, 0.0496019945},
-    {0.376516223, -0.0159036051, 0.0406724736},
-    {0.234907717, 0.0178190302, 0.0293817092},
-    {0.152197435, 0.0500617325, 0.0317263305},
-    {0.106485665, 0.0732751489, 0.0424683616},
-    {0.188214839, 0.0759689659, 0.0265382342},
-    {0.61352253, 0.0460210033, -0.00129790464},
-    {1.00733101, -0.0137993395, -0.0204610135},
-    {1.19685841, -0.091969952, -0.0317752957},
-    {1.31433129, -0.147667974, -0.0395601243},
-    {1.07867193, -0.197387233, -0.0245279465},
-    {0.763811052, -0.211288691, -0.00345961144},
-    {0.408043861, -0.192764506, 0.024176985},
-    {0.0195688941, -0.154131979, 0.0534542575},
-    {-0.248832569, -0.0985972285, 0.079150863},
-    {-0.414851636, -0.0198778212, 0.0896434709},
-    {-0.542137146, 0.0598194525, 0.0815646946},
-    {-0.399203718, 0.0893498883, 0.0652736276},
-    {-0.0428716913, 0.0971536934, 0.0671617165},
-    {0.0811604187, 0.104836069, 0.0757087693},
-    {0.103093453, 0.103023559, 0.0805144161},
-    {0.0229711998, 0.103394441, 0.0836718082},
-    {-0.0939378664, 0.110456504, 0.0805476606},
-    {-0.0885368064, 0.114489734, 0.076604031},
-    {-0.0272076298, 0.120849326, 0.0682591945},
-    {0.0211148467, 0.12597093, 0.0643182397},
-    {0.0579938814, 0.117084235, 0.0664345846},
-    {0.0815847218, 0.109254412, 0.0717120245},
-    {0.089192003, 0.10323973, 0.0705871806},
-    {0.0972900763, 0.100778714, 0.0690074861},
-    {0.09062206, 0.102175519, 0.0652327985},
-    {0.102014095, 0.10513588, 0.0586141497},
-    {0.112189233, 0.104603261, 0.056053862},
-    {0.11591401, 0.104087792, 0.0503669009},
-    {0.0903560072, 0.0976026654, 0.0500842184},
-    {0.0816164538, 0.0850607455, 0.0445212275},
-    {0.108997121, 0.0726416484, 0.0365410894},
-    {0.136150941, 0.0570124462, 0.0280846898},
-    {0.149220958, 0.0384882763, 0.0144160446},
-    {0.160378695, 0.0218597595, -0.00244527217},
-    {0.161442921, 0.0122318491, -0.0179264247},
-    {0.13648349, 0.00779203372, -0.0389282405},
-    {0.109445535, 0.00162285473, -0.0625573695},
-    {0.11094211, -0.00334907207, -0.0850723833},
-    {0.113768943, -0.0105260415, -0.100245647},
-    {0.11380329, -0.0183839351, -0.110116005},
-    {0.109412275, -0.031534411, -0.113922849},
-    {0.0977390632, -0.0434570573, -0.118861519},
-    {0.118138723, -0.0514825881, -0.1143547},
-    {0.108115248, -0.0546480492, -0.109732464},
-    {0.0966555029, -0.0581207275, -0.107318118},
-    {0.0979552418, -0.0602185987, -0.102731869},
-    {0.0897432715, -0.0615604743, -0.100793876},
-    {0.0863087103, -0.0637211874, -0.103148066},
-    {0.0852299929, -0.0643613189, -0.106179498},
-    {0.087405175, -0.0622054599, -0.108888462},
-    {0.088210918, -0.0616486594, -0.102000207},
-    {0.080229722, -0.0614798479, -0.0955856442},
-    {0.0693541765, -0.0585391149, -0.0902106017},
-    {0.0561843887, -0.0581899211, -0.0774731413},
-    {0.0399254523, -0.0572109856, -0.0613504425},
-    {0.0269181989, -0.0577575862, -0.0507677421},
-    {0.00870997272, -0.0551136546, -0.0413892642},
-    {-0.00745596923, -0.0510794707, -0.0381980985},
-    {-0.0212846547, -0.0472553372, -0.0359120443},
-    {-0.0317970961, -0.0450367667, -0.0265732538},
-    {-0.0466130972, -0.0425424799, -0.0111586154},
-    {-0.0605704784, -0.0443232507, 0.00761195831},
-    {-0.0828466415, -0.0452363119, 0.024958523},
-    {-0.0966729969, -0.0474098139, 0.0414845869},
-    {-0.110998742, -0.0487449244, 0.0577832162},
-    {-0.116303235, -0.0491772629, 0.0713188499},
-    {-0.113393232, -0.0414117537, 0.0768228844},
-    {-0.11631985, -0.0320166349, 0.0828756541},
-    {-0.11518456, -0.0221680216, 0.08394593},
-    {-0.103914976, -0.0152883492, 0.0879140869},
-    {-0.104097895, -0.00818797108, 0.0909238607},
-    {-0.0979286954, -0.00138690695, 0.0875150189},
-    {-0.0949854702, 0.00711026555, 0.0832248405},
-    {-0.0827302411, 0.0130300168, 0.0798658952},
-    {-0.0773259848, 0.0221424475, 0.0767064765},
-    {-0.0656174868, 0.0299145151, 0.0672892034},
-    {-0.0569726638, 0.0369085744, 0.059163399},
-    {-0.0482850857, 0.0433754474, 0.0492259637},
-    {-0.0285046473, 0.051974006, 0.0385273919},
-    {-0.00421038549, 0.0589746162, 0.0273530316},
-    {0.017053457, 0.0652919412, 0.0203665327},
-    {0.0299526379, 0.0669943839, 0.0183806084},
-    {0.0326051526, 0.0655761361, 0.0164114684},
-    {0.0308757909, 0.06675677, 0.00937760528},
-    {0.0340971872, 0.0666625351, 0.00246820413},
-    {0.0410524383, 0.0689350963, -0.00808233954},
-    {0.0367577523, 0.0727415085, -0.0173005834},
-    {0.0362224169, 0.073083356, -0.0253693461},
-    {0.036306262, 0.0694359839, -0.0326995999},
-    {0.0341349766, 0.0664408132, -0.039044641},
-    {0.0333035514, 0.0624167249, -0.0424036086},
-    {0.0365128517, 0.0594069585, -0.0429357141},
-    {0.0380593091, 0.0551833138, -0.0463611856},
-    {0.0371613652, 0.0475175679, -0.0469431877},
-    {0.0380960926, 0.0433301963, -0.0459862873},
-    {0.0404232368, 0.0398738086, -0.0458162054},
-    {0.0435799733, 0.0346803479, -0.0492212921},
-    {0.0415951386, 0.0295758937, -0.0547097176},
-    {0.0387078188, 0.0235392377, -0.0591485202},
-    {0.0375395343, 0.0157399271, -0.0677014738},
-    {0.0387733281, 0.00838814303, -0.0711245686},
-    {0.0403545834, 0.00111541664, -0.0719240457},
-    {0.0438127741, -0.00760597317, -0.0672632381},
-    {0.0435799733, -0.0145566948, -0.0582006946},
-    {0.0392893143, -0.0221196469, -0.0495337099},
-    {0.0397886746, -0.0292230472, -0.042686291},
-    {0.0301144011, -0.0353418402, -0.0318449922},
-    {0.0204330795, -0.042409461, -0.0235801172},
-    {0.0177403707, -0.0486640036, -0.0125454338},
-    {0.0123450682, -0.0527080595, -0.00232080976},
-    {0.00870997459, -0.0587386638, 0.00764823798},
-    {0.00540089794, -0.0623803027, 0.0196374003},
-    {6.31441362e-05, -0.0659388155, 0.0290990304},
-    {-0.00246439083, -0.0669032708, 0.039275676},
-    {-0.00243113376, -0.0657226443, 0.0499678254},
-    {0.00678106397, -0.0667536035, 0.0571347103},
-    {-0.00266695651, -0.0658496171, 0.0590656325},
-    {-0.00508096907, -0.0651240125, 0.0573278144},
-    {-0.00331244525, -0.0626130998, 0.0539254025},
-    {-0.00223159161, -0.0602254458, 0.0543098226},
-    {-0.00409398554, -0.0572132692, 0.0540573224},
-    {-0.00470924098, -0.0538831428, 0.0549397469},
-    {-0.00825111475, -0.0510064065, 0.0541581959},
-    {-0.00889106095, -0.0450488664, 0.0524706542},
-    {-0.00844529271, -0.0387415253, 0.0510282889},
-    {-0.00924580358, -0.0343098603, 0.05168055},
-    {-0.00902889948, -0.0279104672, 0.0484020561},
-    {-0.00795180164, -0.0224718675, 0.0489701107},
-    {-0.00937480014, -0.0160245392, 0.0491328612},
-    {-0.0157672055, -0.011031447, 0.0457441732},
-    {-0.0167815443, -0.00404747017, 0.0451621786},
-    {-0.0125412708, 0.00195542444, 0.0384276211},
-    {-0.00895556062, 0.0112260766, 0.0349109471},
-    {-0.00572358072, 0.0174365751, 0.0318261012},
-    {-0.00688328594, 0.024511205, 0.0244741552},
-    {-0.00545752421, 0.027862655, 0.0193547159},
-    {-0.00424364209, 0.032235954, 0.014831759},
-    {-0.00397758605, 0.0368753076, 0.0106746294},
-    {-0.00288010389, 0.0378231481, 0.00922794919},
-    {-0.000296636485, 0.0394280478, 0.0074668359},
-    {0.00216262904, 0.0427575149, 0.00681144837},
-    {-0.000554631231, 0.040202029, 0.00316156307},
-    {-0.00673792046, 0.042745173, 0.00169522827},
-    {0.00129365479, 0.0404171869, 0.00415624958},
-    {0.0043865582, 0.042013526, 0.0053867586},
-    {0.00837740302, 0.0412985049, 0.00680018403},
-    {0.00658152439, 0.0397021584, 0.00902840495},
-    {0.00523461308, 0.038205605, 0.0102422852},
-    {0.00757923257, 0.0349962935, 0.01168897},
-    {0.00924914144, 0.0344777852, 0.00941791758},
-    {0.0121869426, 0.0309995431, 0.0116519574},
-    {0.00897602923, 0.0290765334, 0.0120215416},
-    {0.0141510284, 0.0263187233, 0.0134329498},
-    {0.0177312102, 0.0232581608, 0.0129736569},
-    {0.0176561158, 0.0191493146, 0.0113397697},
-    {0.0159267541, 0.0159566365, 0.00961040426},
-    {0.0334360749, 0.00996835344, 0.0111916251},
-    {0.0747702494, 0.00611040695, 0.0119265951},
-    {0.091291219, 0.0033411351, 0.0151260328},
-    {0.0878670812, -0.000446591526, 0.0170245785},
-    {0.0722807944, -0.00745631615, 0.0179745536},
-    {0.0478534997, -0.0117797321, 0.0179246645},
-    {0.0293404199, -0.0159600396, 0.0214630105},
-    {0.0248562656, -0.0191794224, 0.0242601316},
-    {0.0283563044, -0.0195168201, 0.0242510065},
-    {0.0357146859, -0.0222556964, 0.0241271034},
-    {0.0614284277, -0.0243770909, 0.0227207281},
-    {0.117876202, -0.0202436484, 0.0225473866},
-    {0.219243631, 0.00449958863, 0.0275026914},
-    {0.186120123, 0.00804952532, 0.0300574321},
-    {0.108293325, -0.00436019292, 0.0303445626},
-    {0.0612560883, -0.0190796517, 0.0286666844},
-    {0.0263089947, -0.0323587805, 0.027380744},
-    {0.0173020866, -0.0433588885, 0.0241651852},
-    {0.0261200294, -0.0438228846, 0.0240772124},
-    {0.0422995836, -0.0411290638, 0.022048533},
-    {0.0670720488, -0.0358578265, 0.0201730393},
-    {0.0759031326, -0.0311031435, 0.0183977727},
-    {0.0646483153, -0.0277763642, 0.0165278688},
-    {0.038890738, -0.0273273923, 0.0142165031},
-    {0.0127643058, -0.0260379314, 0.012320349},
-    {0.0109880837, -0.0259306021, 0.0103420597},
-    {0.0147273494, -0.0220915582, 0.010484742},
-    {0.0150540071, -0.0208458025, 0.0108046336},
-    {0.0127673326, -0.0196283925, 0.0112566296},
-    {0.0129336184, -0.0180320553, 0.00796418078},
-    {0.0124513898, -0.0163858309, 0.00980994664},
-    {0.00842728931, -0.0129769854, 0.00734892301},
-    {0.00417038891, -0.00926882494, 0.00952726044},
-    {-0.000552111538, -0.00552740833, 0.00871246401},
-    {0.000844684895, -0.00176936295, 0.0070163561},
-    {-0.00186576392, 0.000575258862, 0.0101258885},
-    {-0.0034621018, 0.00390096242, 0.0108409133},
-    {-0.00214844896, 0.00504833134, 0.0123374797},
-    {-0.00206530653, 0.00784192234, 0.011605829},
-    {-0.00518239755, 0.0107745845, 0.00974040944},
-    {-0.00667730626, 0.0135943145, 0.0109996907},
-    {-0.00693746284, 0.0175197199, 0.0104917148},
-    {-0.0073199179, 0.0183844008, 0.00997623242},
-    {-0.00824607629, 0.0207234751, 0.0113689974},
-    {-0.00871671364, 0.0219595302, 0.01168897},
-    {-0.0092520453, 0.0224857405, 0.0130766444},
-    {-0.00994722266, 0.0234727301, 0.0141001046},
-    {0.0130832745, 0.0238219276, 0.0147652477},
-    {0.0365803763, 0.0250448752, 0.0173834786},
-    {0.0452070497, 0.026125228, 0.0166578721},
-    {0.0350162908, 0.0250948165, 0.0163894761},
-    {0.0133493328, 0.0253683794, 0.0155135281},
-    {-0.00751946028, 0.0231068954, 0.0141998716},
-    {-0.0118579911, 0.0257221144, 0.0120139793},
-    {1.70134008e-05, 0.0269314628, 0.0106907208},
-    {0.0856833905, 0.0383718871, 0.0125203934},
-    {0.13342388, 0.051009547, 0.0161620416},
-    {0.0945962742, 0.050178133, 0.0152308438},
-    {0.0650564656, 0.0398634039, 0.010917508},
-    {0.0309653729, 0.0277553741, 0.0100384522},
-    {-0.00484378077, 0.0152733531, 0.00490302034},
-    {-0.0131828124, 0.00751793431, 0.00190228084},
-    {0.00170281646, 0.0063403151, 0.000662245322},
-    {0.00810169149, 0.00602458464, 0.000906716101},
-    {0.00274033495, 0.00835740566, 0.000830545556},
-    {0.00274033449, 0.00893940218, -0.00202955911},
-    {0.00344427559, 0.00825914368, -0.00706144981},
-    {0.00117725483, 0.00548067177, -0.00640285946},
-    {-0.00209427206, 0.00202515768, -0.00904893875},
-    {-0.00107061875, -0.00157687534, -0.0101412516},
-    {0.000445599901, -0.00461283978, -0.0100943903},
-    {-0.000868052943, -0.00679117581, -0.0114413006},
-    {-0.000586879672, -0.00746236322, -0.0112861004},
-    {-6.98838849e-05, -0.00880322699, -0.0103271892},
-    {0.000212800689, -0.00983419456, -0.0121396976},
-    {-0.000601996901, -0.00966790877, -0.0132870665},
-    {-0.000286054797, -0.0108485334, -0.0118071269},
-    {-0.00183250732, -0.0101335086, -0.0116075855},
-    {-0.00178530347, -0.0107455449, -0.010507958},
-    {-0.00244776253, -0.0127275568, -0.00976181962},
-    {-0.00151656533, -0.0121289305, -0.00618668878},
-    {-0.00271533034, -0.0128802378, -0.00588435167},
-    {-0.00257488992, -0.0122732241, -0.00211431109},
-    {-0.00292495033, -0.0129447356, 0.00121048326},
-    {-0.00296324631, -0.0109150475, 0.00112985959},
-    {-0.000834795879, -0.0113640185, 0.00610178523},
-    {-0.00308619672, -0.00831696857, 0.00662835687},
-    {-0.00191232399, -0.00740753952, 0.00700083375},
-    {-0.00111899234, -0.00684962748, 0.0106111364},
-    {-0.000784910517, -0.00481238216, 0.0100261169},
-    {-0.00283021829, -0.00539438007, 0.0124871377},
-    {-0.00198216364, -0.00368164293, 0.0122709684},
-    {-0.000651882263, -0.00273381709, 0.0129693653},
-    {-3.66270542e-05, -0.000139768235, 0.0143827889},
-    {-0.00163296494, 4.31453809e-05, 0.0143162776},
-    {-0.000801539049, 0.00260393647, 0.0169768371},
-    {-0.00069975201, 0.00364750298, 0.0160773862},
-    {-0.00120062358, 0.00612918427, 0.0188891161},
-    {0.000463301083, 0.00631638756, 0.0171447322},
-    {0.000295943348, 0.00666129543, 0.0156133007},
-    {0.000927827088, 0.00699386513, 0.0157795846},
-    {0.00164285279, 0.0101865418, 0.0147153586},
-    {0.00185902393, 0.00985397212, 0.0152308457},
-    {0.00492774136, 0.0107262116, 0.0151905306},
-    {0.00365490443, 0.0121154469, 0.014831759},
-    {0.00237450772, 0.0130466446, 0.0134848468},
-    {0.00479874481, 0.0136770196, 0.012030106},
-    {0.00405398943, 0.0151584707, 0.00811383594},
-    {0.0042739138, 0.0148473587, 0.00794433337},
-    {0.00560044032, 0.015923379, 0.00533687603},
-    {0.00699723512, 0.0160564054, 0.00447219331},
-    {0.00824437384, 0.015075326, 0.0017617424},
-    {0.00747946277, 0.0162725803, 0.00132940151},
-    {0.00781203434, 0.0147261247, -3.41371633e-05},
-    {0.00771226175, 0.0151750948, -0.002860985},
-    {0.00836228579, 0.0142575074, -0.00306254253},
-    {0.00739631895, 0.0143603012, -0.00683520082},
-    {0.008359164, 0.012564417, -0.00451739971},
-    {0.00837740116, 0.0108350534, -0.00618668878},
-    {0.00829426106, 0.0105856266, -0.00573771819},
-    {0.0088621499, 0.00930724852, -0.00573923066},
-    {0.0082111191, 0.00875648856, -0.00495617837},
-    {0.00698060822, 0.0062123253, -0.00760011282},
-    {0.0078957146, 0.00499468995, -0.00601074798},
-    {0.00637895707, 0.004727853, -0.00623909337},
-    {0.00810169056, 0.00211098138, -0.00650853105},
-    {0.00744620617, -0.000671880785, -0.00582086109},
-    {0.00693072192, -0.000139768235, -0.00467349356},
-    {0.00655632839, -0.0051242928, -0.00391714787},
-    {0.00718518998, -0.00657550897, -0.0053844885},
-    {0.00594963972, -0.00735654542, -0.00650263019},
-    {0.00621569622, -0.00817134324, -0.00582086109},
-    {0.00611055922, -0.00980147533, -0.00353899924},
-    {0.00616581086, -0.0112642469, -0.00535526266},
-    {0.00441175327, -0.0115741426, -0.00543286232},
-    {0.00684865192, -0.0116209555, -0.0026979181},
-    {0.00461935811, -0.0129603557, -0.00156396092},
-    {0.00408724509, -0.011862874, -0.00219584419},
-    {0.00224147993, -0.0140578374, -0.00187990209},
-    {0.00229136576, -0.0140744671, -0.000632763142},
-    {0.00325078075, -0.0142347049, -0.00086959335},
-    {0.000995413866, -0.0141613651, -0.00159936328},
-    {0.00288999244, -0.0132097844, -8.80099833e-07},
-    {0.00234125159, -0.0135090984, -0.000932076713},
-    {0.00157382083, -0.0119933831, 0.000887990929},
-    {0.00136016798, -0.0129936123, 0.000647632405},
-    {0.00180216576, -0.0117582753, 0.00214258814},
-    {0.000574093545, -0.0107034128, -6.33634627e-05},
-    {-0.00123388041, -0.010183393, 0.00194465695},
-    {0.000695027877, -0.00855379924, 0.00287585426},
-    {-0.000834796345, -0.00772237312, 0.00339133758},
-    {-0.00101770973, -0.00486226752, 0.00550316088},
-    {-0.000153027009, -0.00383129995, 0.00508744735},
-    {-0.00148330838, -0.00429689791, 0.00507081952},
-    {-0.00271381857, -0.0022349616, 0.00517059024},
-    {-0.00153319375, -0.00301650213, 0.00718263909},
-    {-0.00256416202, 0.000841313973, 0.00728241075},
-    {-0.00366164418, 0.00182239711, 0.00638447143},
-    {-0.00369893224, 0.00256715296, 0.0071927188},
-    {-0.00386118656, 0.00351850549, 0.00648424309},
-    {-0.0038445578, 0.00456610182, 0.00502093323},
-    {-0.00448019616, 0.00496035768, 0.00712041743},
-    {-0.0044930703, 0.00614581024, 0.00626807287},
-    {-0.00587323727, 0.00716015184, 0.00548653118},
-    {-0.00442454079, 0.00725941872, 0.00469340291},
-    {-0.00633400772, 0.0108994246, 0.00466583297},
-    {-0.00495665288, 0.00993610546, 0.00459665246},
-    {-0.00507506821, 0.0100368857, 0.00495441817},
-    {-0.00540763885, 0.0115833357, 0.00437242165},
-    {-0.0048921546, 0.0130133871, 0.00447219238},
-    {-0.00499192625, 0.0126143061, 0.00447219238},
-    {-0.00539101008, 0.0115833376, 0.00420613494},
-    {-0.0044930703, 0.0140609853, 0.00339133944},
-    {-0.00568226166, 0.0128385387, 0.000726743601},
-    {-0.00394808408, 0.0113972053, 0.00233140448},
-    {-0.00334570231, 0.0117662493, 0.000747403596},
-    {-0.0040214248, 0.0117581896, 0.00179096917},
-    {-0.0030040131, 0.0109337494, -0.00130755943},
-    {-0.00194134843, 0.00956524163, -0.000595474849},
-    {-0.00181963341, 0.0084791705, -0.00123889977},
-    {-0.00223159161, 0.00771090901, -0.000401979312},
-    {-0.000961387414, 0.00619623298, 0.000151458662},
-    {-0.00269920565, 0.00622744253, -0.000901843188},
-    {-0.00331244525, 0.00330233434, -0.00179676013},
-    {-0.00299650338, 0.00228799554, -0.00357601116},
-    {-0.00238607591, 0.000566139352, -0.00340167992},
-    {-0.00250571012, -0.000544898678, -0.00364302914},
-    {-0.00198216364, -0.00256753224, -0.00374229625},
-    {-0.00299650338, -0.00421375548, -0.00444069412},
-    {-0.00228147721, -0.00474586803, -0.00414138101},
-    {-0.00249764789, -0.0051615811, -0.0049395496},
-    {-0.00203809608, -0.00773648219, -0.00419126637},
-    {-0.00183679839, -0.00859992951, -0.00643987115},
-    {-0.00111748057, -0.0102665359, -0.00651925895},
-    {0.000235476065, -0.0107034128, -0.00717432145},
-    {-0.0018990211, -0.0119959023, -0.00698485738},
-    {-0.00130039442, -0.0112309903, -0.00738394214},
-    {-0.00121725211, -0.0123617295, -0.00824862532},
-    {-0.000669583678, -0.013835229, -0.00650853105},
-    {-0.00164959347, -0.0136753824, -0.00595388934},
-    {-0.00179622672, -0.0133800991, -0.00627134321},
-    {-0.00191564963, -0.0128273275, -0.00495617837},
-    {-0.00175097364, -0.0137837362, -0.00451739971},
-    {-0.00255408394, -0.0139605869, -0.00577147957},
-    {-0.00131702307, -0.0126776714, -0.00322681223},
-    {-0.00239283778, -0.013654219, -0.00448150979},
-    {-0.00274707563, -0.0120457867, -0.00422452344},
-    {-0.00272937445, -0.0117239449, -0.00352183427},
-    {-0.00406072848, -0.0108485334, -0.00216258713},
-    {-0.00326255988, -0.00990070868, -0.00380881061},
-    {-0.00329581671, -0.0105991066, -0.00118150446},
-    {-0.00369490124, -0.00876996946, -0.00104847667},
-    {-0.00474249758, -0.00873671286, 0.000880431384},
-    {-0.0045096986, -0.0072900313, 0.00159545848},
-    {-0.00407735724, -0.00752283074, 0.00226059835},
-    {-0.00653837807, -0.00514495233, 0.00234374264},
-    {-0.00479238341, -0.00356524321, 0.0017950004},
-    {-0.0045263269, -0.00258416077, 0.00447219238},
-    {-0.00624662358, 0.000180709176, 0.00420966372},
-    {-0.00662152097, 0.000309200957, 0.00410636328},
-    {-0.00687094778, 0.00134017132, 0.00473824702},
-    {-0.00662581157, 0.00212814705, 0.00495763775},
-    {-0.0063055791, 0.00571347168, 0.00468836352},
-    {-0.00492440397, 0.00614682166, 0.00543513522},
-    {-0.00637209322, 0.00830751844, 0.00237699924},
-    {-0.00419375673, 0.00842392072, 0.00264305528},
-    {-0.0055739237, 0.00925534405, 0.00517058931},
-    {-0.00520809647, 0.0121320784, 0.00236037001},
-    {-0.00396095775, 0.0126143042, 0.0031751669},
-    {-0.0045696618, 0.0130804088, 0.00309706386},
-    {-0.00304638897, 0.0134789888, 0.00262642652},
-    {-0.00303834304, 0.0143667348, 0.00313815568},
-    {-0.00258079031, 0.0153247528, 0.00212757057},
-    {-0.00191564974, 0.0149090383, 0.000497975852},
-    {-0.00319604576, 0.0162393209, 0.00084717432},
-    {-0.00168285053, 0.0162060671, -0.000433220761},
-    {-0.0027304471, 0.0162725803, 0.000680889469},
-    {-0.00176599307, 0.0158734955, 0.000381576363},
-    {-0.00173172832, 0.015241107, -0.00156295276},
-    {-0.000412109774, 0.0156712718, -0.000140344724},
-    {-0.000667502871, 0.0153701045, -0.00253042998},
-    {0.000395714305, 0.0151750948, -0.00267807115},
-    {-5.47671225e-05, 0.0142736323, -0.00233693467},
-    {0.000464446144, 0.0132561661, -0.00215150137},
-    {-0.000151514774, 0.0116130672, -0.00240143295},
-    {-0.000834795763, 0.012015678, -0.00294412742},
-    {0.00160959573, 0.0110179689, -0.00148081826},
-    {0.000595256686, 0.00947151333, -0.000532991951},
-    {0.000994341215, 0.00917220116, -8.402206e-05},
-    {-7.08915759e-05, 0.0069691739, -0.000724472338},
-    {-0.000352568924, 0.00652826717, -0.0010152196},
-    {0.000545371091, 0.00611255364, -0.00227898685},
-    {0.00030881702, 0.00544097787, -0.00139338407},
-    {-0.000917938538, 0.00393421901, 0.00199454231},
-    {-0.000570755219, 0.00192216877, -0.00114371255},
-    {0.000343146501, 0.00217964081, 0.00150748761},
-    {-0.00071839639, 0.000891200267, 0.000996830873},
-    {-0.00116736628, 0.00060851546, 0.00254328363},
-    {-0.000409509055, -0.000915766228, 0.000968614127},
-    {0.000154332956, -0.00255787652, 0.00214258954},
-    {-0.000328885624, -0.00280234707, 0.00322606089},
-    {0.000188662671, -0.00362210209, 0.00427104067},
-    {0.00120295282, -0.00352795469, 0.00564475451},
-    {-0.000877123093, -0.00562415598, 0.00208121259},
-    {0.000154332956, -0.00465199724, 0.00373892765},
-    {0.00160959666, -0.0050784382, 0.00201117108},
-    {0.00200868095, -0.00695746113, 0.00290911039},
-    {0.00313941925, -0.00594312139, 0.00201117154},
-    {0.00264056376, -0.00609277794, 0.00272619724},
-    {0.00376676884, -0.00517266663, 0.00301644066},
-    {0.00379329571, -0.00648864405, 0.0040993914},
-    {0.00461935811, -0.00571032194, 0.00327493856},
-    {0.00475238636, -0.00556066539, 0.00292573962},
-    {0.00545985345, -0.0047695511, 0.00301644113},
-    {0.00544112921, -0.00528709963, 0.00289784698},
-    {0.0054341564, -0.00574357901, 0.00260979822},
-    {0.00600809138, -0.00465667853, 0.00300031621},
-    {0.00696397759, -0.00373152853, 0.00440567732},
-    {0.00749609154, -0.00230147573, 0.00236037048},
-    {0.00789571181, -0.00207725889, 0.00221124943},
-    {0.00875985902, -0.00123725086, 0.00192802818},
-    {0.00954139698, 0.000675030053, 0.00157882972},
-    {0.00828166306, -0.000706146006, 0.00185546745},
-    {0.00986187533, 0.000261331908, 0.0010008635},
-    {0.0111055542, 0.00111541618, 0.000649242196},
-    {0.00984071102, 0.000924456865, 0.00121300202},
-    {0.0102327438, 0.00240590749, 0.000291379169},
-    {0.0109381946, 0.00258730864, -0.000333449803},
-    {0.0097666895, 0.00482303882, -0.00199415651},
-    {0.010372825, 0.00308616506, -0.000649392139},
-    {0.00869334675, 0.00421690429, -5.07659279e-05},
-    {0.00967442617, 0.00454947399, -0.0013810466},
-    {0.00920076761, 0.00387324812, -0.00101471576},
-    {0.00994249992, 0.00411511632, -0.00172419893},
-    {0.00917335413, 0.00538089918, -0.00138880662},
-    {0.00869334396, 0.00616244087, -0.00212933007},
-    {0.00724968687, 0.00488909753, -0.000434228918},
-    {0.00638519973, 0.00482303882, -0.00137621909},
-    {0.00676594861, 0.00540508563, -0.00165970041},
-    {0.00696880557, 0.00514917495, 0.00090671517},
-    {0.00613708794, 0.00584045099, 0.000952488277},
-    {0.00329551357, 0.00475437893, 0.000666406471},
-    {0.00238005095, 0.00505034486, 0.00092023937},
-    {0.00420364551, 0.00395084685, 0.00174511457},
-    {0.00240776525, 0.0034353626, 0.000730774831},
-    {0.00195879606, 0.00273696566, -0.000699277734},
-    {0.00318930647, 0.00410050293, -0.000217050314},
-    {0.00245765154, 0.00217159558, -0.000666019972},
-    {0.00204193708, 0.000558630098, 0.000730775297},
-    {7.9772668e-05, 0.00143994112, -0.000217049848},
-    {0.000811427599, 0.000475485809, 0.000614374876},
-    {0.000977712683, 0.000791428611, -0.000449849758},
-    {0.000961084152, -0.00101251295, 0.000565498136},
-    {-1.99985225e-05, -0.000921308529, 0.00232711388},
-    {-0.000103140716, -0.0011160234, 0.00128434366},
-    {-0.00128023874, -0.00146400277, 0.00138785411},
-    {-0.00198216364, -0.0022515899, 0.00121300248},
-    {-0.00247190055, -0.00307282433, 0.00241722865},
-    {-0.00231221458, -0.00249597873, 0.00187159143},
-    {-0.00333014666, -0.00355344219, 0.00149032334},
-    {-0.00226384075, -0.0032377115, 0.00156522403},
-    {-0.00209427206, -0.00408555474, 8.27992335e-05},
-    {-0.00298944884, -0.0037859492, 0.0015168502},
-    {-0.00110085239, -0.00467935391, 0.00127951615},
-    {-0.00266393321, -0.0030165019, 0.00322505226},
-    {-0.00362838712, -0.00238461816, 0.00226059835},
-    {-0.0041272426, -0.00424701255, 0.0003483193},
-    {-0.0031129031, -0.00374815683, 0.00274282554},
-    {-0.00475912634, -0.00363175711, 0.00186151406},
-    {-0.00449306984, -0.0044132974, 0.00124625908},
-    {-0.00534112472, -0.00391444191, 0.000348319765},
-    {-0.00465935515, -0.00311627332, 0.00257653929},
-    {-0.00642197859, -0.00273381709, 0.00280934013},
-    {-0.00625569327, -0.00243450352, 0.00275945431},
-    {-0.00603952212, -0.00323267304, -0.000981962308},
-    {-0.00680443365, -0.00290010218, 0.0014624293},
-    {-0.00668803509, -0.00273381663, -0.000333450502},
-    {-0.00657163514, -0.00255090301, 0.00227722665},
-    {-0.005601638, -0.00210898812, 0.00212958595},
-    {-0.00724634994, -0.000883515924, 0.00245207921},
-    {-0.00609369902, -0.000137622468, -0.000723951496},
-    {-0.00537277199, -0.000274942722, 0.000305943657},
-    {-0.00745597016, -0.000496526249, -0.000111736823},
-    {-0.00600475352, -0.000383653678, 0.00182321947},
-    {-0.00514962804, 0.000617633574, 0.00121568423},
-    {-0.00547415297, -0.00047233887, 0.00023191981},
-    {-0.00494203996, 0.000990971457, 0.000963573344},
-    {-0.00399421481, 0.00132354163, -0.000266936142},
-    {-0.00539101008, 0.0023378809, -0.000715906033},
-    {-0.00308619672, 0.00263165077, -0.000385854859},
-    {-0.00451452611, 0.00298639433, -0.000947096152},
-    {-0.0038445578, 0.00448296079, 0.000497975852},
-    {-0.00208193483, 0.00308616413, -0.00196304452},
-    {-0.0021533398, 0.00245428039, -0.00107684312},
-    {-0.00212516915, 0.003784562, -0.00110501307},
-    {-0.00226484868, 0.00401736097, -0.00192978745},
-    {-0.00140923564, 0.0045666066, -0.0029012966},
-    {-0.000884681824, 0.00479890173, -0.00299401302},
-    {-0.000701767858, 0.00484878803, -0.00299401302},
-    {-0.00144200516, 0.00549247349, -0.00427709101},
-    {9.73138958e-06, 0.00458273245, -0.00272392575},
-    {-0.000169655541, 0.00388433272, -0.00126464665},
-    {-0.00103433826, 0.00428341748, -0.00101521914},
-    {-0.000884681242, 0.00365153281, -0.00183001673},
-    {-0.000385825522, 0.00459935935, -0.00121476152},
-    {-0.00135028013, 0.00376793509, -0.0031935554},
-    {-0.000868053059, 0.00230462337, -0.00184664526},
-    {-0.00173172809, 0.00222853664, -0.00299804425},
-    {-0.00149349985, 0.00281474413, -0.00300688669},
-    {-0.00186576403, -0.000488967635, -0.00168036018},
-    {-0.00366164418, 0.00153971231, -0.00251178583},
-    {-0.00331244525, 0.000625143759, -0.00134778954},
-    {-0.00471478375, 0.000906318426, -0.00183707103},
-    {-0.00465028547, -0.000673896167, -0.00109533826},
-    {-0.00431015622, -0.000455710571, 0.000514604151},
-    {-0.00585339032, -0.00187128014, 0.000134293456},
-    {-0.00535775255, -0.00256753177, 0.00111323036},
-    {-0.0047309082, -0.0025282281, 0.000742868986},
-    {-0.0043245675, -0.000951239374, 0.000473587774},
-    {-0.00447644154, -0.0026673032, 0.000132148154},
-    {-0.00474703312, -0.00247985427, -0.0016435755},
-    {-0.00434341328, -0.00245113182, -0.00106510497},
-    {-0.00432678498, -0.00398095604, -0.000932076247},
-    {-0.00356187299, -0.00306638749, -0.00039996393},
-    {-0.00248958543, -0.00228635897, -0.000595475314},
-    {-0.00121725188, -0.0016030781, 0.000930317212},
-    {-0.00337895937, -0.00228484743, -0.000832305988},
-    {-0.00108154188, -0.00326163811, 0.000340272672},
-    {0.000113029731, -0.00238461839, -0.000399964163},
-    {-0.00139311107, -0.00107701262, 0.000146257691},
-    {-0.000600923784, -0.000704065431, -0.000964261126},
-    {-0.00156645104, -0.00055548083, 0.0010134601},
-    {-0.000585368136, -0.00137027912, 0.00129614444},
-    {-0.000409508822, 0.000664446037, 0.00111373467},
-    {-0.000806903234, -8.6128246e-05, 0.00224557938},
-    {0.000711656176, 4.31453809e-05, 0.00282596843},
-    {-0.000409508822, 8.39610584e-05, 0.00246820273},
-    {4.65153717e-05, 0.000625143293, 0.00219408423},
-    {0.00165948155, 0.000675029121, 0.00154557219},
-    {0.000909589231, 0.000411655754, 0.00135300402},
-    {0.00105783227, 0.0006644479, 0.00287131919},
-    {0.00129365479, 0.000808057841, 0.00129614491},
-    {0.00127702649, 0.00152308494, 0.00222734176},
-    {0.000380598009, 0.00158355059, 0.00140397809},
-    {0.00152752665, 0.00315804267, 0.0023657335},
-    {0.001509825, 0.00183902541, 0.00201117061},
-    {0.00194468605, 0.00243815547, 0.00153297512},
-    {0.00154308206, 0.00210508192, 0.000963574741},
-    {0.000566290691, 0.00331252767, 0.00245155906},
-    {0.00183181395, 0.00343788369, 0.00162972277},
-    {0.00181932957, 0.00418793736, 0.000889550894},
-    {0.00267382176, 0.00368479034, 0.000730775297},
-    {0.00220822287, 0.00395084871, -0.000167164486},
-    {0.00109411241, 0.00403398788, -0.000566249015},
-    {0.00270254281, 0.00269615045, 0.000420375261},
-    {0.00124376942, 0.00288662268, -0.000449848827},
-    {0.00142869842, 0.00248653023, 0.000404251739},
-    {0.00119166612, 0.00442309724, 0.000455849804},
-    {0.00336365192, 0.00459885551, 0.00130723044},
-    {0.00202530925, 0.00326907681, 0.00216082809},
-    {0.00131028262, 0.00403398788, 0.00277608354},
-    {0.00169273862, 0.00265382277, 0.000564490445},
-    {0.00244454923, 0.00400224281, 0.000791242346},
-    {0.00121855759, 0.00341551611, 0.00159331271},
-    {0.00210845168, 0.00310279382, 0.00161208631},
-    {0.0022581087, 0.0027203369, 0.0010799733},
-    {0.00207519415, 0.00213833898, 0.00226059929},
-    {0.00242439355, 0.00361827714, 0.00137928687},
-    {0.00318628154, 0.000841817353, 0.00288744364},
-    {0.00245765061, 0.00143994112, 0.000680889469},
-    {0.0029731344, 0.00145657035, 0.00106334547},
-    {0.00220822287, 0.00124039873, 0.00156220142},
-    {0.00286639039, 0.000137015712, 0.00226274319},
-    {0.00239113648, 0.00104085635, 0.00192802818},
-    {0.00260579516, 0.000358080491, 0.000936364755},
-    {0.00252309232, 0.000686293468, 0.00149032287},
-    {0.00199205265, 0.000309201889, 0.000298433937},
-    {0.00214170921, 0.000675028656, -8.79634172e-07},
-    {0.00337977731, -0.000964140054, 0.00101698702},
-    {0.00260730716, 0.00115725538, -0.000117279589},
-    {0.0018590244, -0.000472338405, 0.000414832961},
-    {0.0025407935, -0.000106510706, -0.000915448181},
-    {0.00350524695, -0.000721765682, 0.00186151406},
-    {0.0022581087, 0.00120714167, 9.88910906e-05},
-    {0.00254079304, -0.000705137849, -0.000250307843},
-    {0.00091270986, -0.00152850198, 0.000855741091},
-    {0.00185365998, 0.000188511796, -0.000672457041},
-    {0.000578627456, -0.000405824743, 0.00107997376},
-    {0.0014931967, 9.3031209e-05, 0.00053123245},
-    {0.00207519461, 7.64029101e-05, -0.000200421549},
-    {0.000329200178, -0.00145342154, 0.0014125444},
-    {0.00131028355, -0.000755023211, 0.00264305435},
-    {0.000595256453, 0.000342458487, 0.00109660253},
-    {0.00076758815, -0.000286905095, -0.000627724454},
-    {0.000926754205, -0.000807055272, 3.13045457e-05},
-    {0.00196081097, 3.33739445e-06, -0.000966341468},
-    {0.002231288, 0.000240006484, 0.000838056207},
-    {0.000927827088, 0.000575257931, -0.000749162864},
-    {0.00083208736, -0.000899640378, -0.000176234636},
-    {0.00155769498, 5.17121516e-05, -0.000418103999},
-    {0.000894570025, -0.000721766148, -0.000998591073},
-    {0.00209396915, 0.000342995394, -0.000535137486},
-    {0.00192553806, -0.00103770848, 0.00088043185},
-    {0.00124376849, 0.00132354023, 0.000198662281},
-    {0.00273479172, 0.00159967551, -0.000111736357},
-    {0.0027119068, 0.000754953828, -0.00223446498},
-    {0.00357176014, 0.00100759882, -0.00229561515},
-    {0.0022414804, 0.00139005436, -0.00296075596},
-    {0.00209182338, 0.00142331142, -0.000150536653},
-    {0.00284010707, 0.00134016993, -0.00124801882},
-    {0.00355513277, 0.00167273916, -0.00262818532},
-    {0.00317267724, 0.00280347979, -0.000233679079},
-    {0.00276704202, 0.00155130122, -0.00085346913},
-    {0.000396721996, 0.00166417425, -0.00262717786},
-    {0.0038522284, 0.0026316517, 0.000580010004},
-    {0.00297313486, 0.0033355928, 0.000481346622},
-    {0.00144482288, 0.00234140875, 0.000565498136},
-    {0.0011498977, 0.00327819725, 0.00128434366},
-    {0.00162219279, 0.00221241126, 0.000887990464},
-    {0.000561999623, 0.00388433458, -0.000898820115},
-    {0.00215833751, 0.00248753885, 0.00265968405},
-    {0.00212507951, 0.00308616413, 0.000165405683},
-    {0.000799838454, 0.0036636279, -1.49887055e-05},
-    {0.000343147432, 0.00319237122, 0.00152465282},
-    {-0.000236169435, 0.00496518752, -8.402206e-05},
-    {-0.000352568692, 0.00318593485, 0.000414833892},
-    {-0.000801539049, 0.00330233527, 0.000813918188},
-    {0.000977208838, 0.0036958768, 0.000420376658},
-    {-0.00108154188, 0.00238562049, 0.000580581836},
-    {-0.0014500512, 0.00351850642, 0.000531233381},
-    {-0.0012479896, 0.00263165263, -6.3362997e-05},
-    {-0.00164959347, 0.00248753699, 0.00109660253},
-    {-0.00197411771, 0.002660261, -0.000277664512},
-    {-0.00184913562, 0.00253742328, 0.000182033516},
-    {-0.00210259459, 0.0018415451, -0.000143986195},
-    {-0.00150598341, 0.0019221683, 0.000613871962},
-    {-0.0014248403, 0.0018363432, 0.00166197121},
-    {-0.00221546693, 0.000809569377, 0.00219408423},
-    {-0.00176813861, 0.00238561956, 0.000374603085},
-    {-0.00283021829, 0.000724914949, 0.000797288492},
-    {-0.00148330827, 0.000758172479, 0.00330819516},
-    {-0.00128023897, 0.00179317035, 0.00200058986},
-    {-0.00120169611, 0.000789282843, 0.0027776924},
-    {-0.0020154207, 0.00135679962, 0.00438904949},
-    {-0.00297987484, 0.00060851546, 0.00339133851},
-    {-0.000490132021, -0.00101251388, 0.00274232216},
-    {0.000106479041, -9.34093259e-05, 0.00430641044},
-    {-0.000280512031, 0.000272619538, 0.00361305196},
-    {-0.00130039442, 0.000724914484, 0.00194465648},
-    {-0.000169655075, 0.000309202354, 0.00385693647},
-    {2.98868399e-05, 0.000492115971, 0.00241025537},
-    {0.00145993917, -0.000638625119, 0.00251002656},
-    {0.000329200411, 0.000408972148, 0.00287585426},
-    {0.000783713534, 0.000229081605, 0.00306481449},
-    {0.00175067154, 0.000137016177, 0.00178212626},
-    {0.00107395672, 0.00018070871, 0.00230695773},
-    {0.0011107407, -0.000272796489, 0.00292574055},
-    {0.00185902393, 0.00145656895, 0.00352436537},
-    {0.000162914861, -0.000721766613, 0.0031585386},
-    {0.00073533901, 0.000793444458, 0.0023069568},
-    {0.000146286329, 0.00112399971, 0.00344122294},
-    {0.00185365905, 0.000583305024, 0.00164480694},
-    {0.00116062607, -0.000355938915, 0.00352436537},
-    {0.00189228053, 0.000159545336, 0.000464718789},
-    {0.00157633866, 0.000226059463, 0.0020610569},
-    {0.00119388266, 0.00117388461, 0.00164534338},
-    {0.000695027877, 0.00217159558, 0.00317516597},
-    {0.00102759805, -0.000156396534, 0.00209431443},
-    {0.00102558266, 0.000519326422, 0.00240370445},
-    {0.00192553853, 0.000891199801, 0.00246014167},
-    {0.00184793887, 0.000358080026, 0.00148460129},
-    {0.00101429503, 0.000716045499, 0.00246014167},
-    {0.00217043119, 0.00108368788, 0.000726744067},
-    {0.0023171131, 0.000840777997, 0.000117129646},
-    {0.00330570596, 0.000741543248, 0.00103008887},
-    {0.00240776525, 0.00109074172, 0.000780660659},
-    {0.00113845523, 0.00121268397, -0.000659973593},
-    {0.00229136529, 0.00109074265, 6.56344928e-05},
-    {0.00186406332, 8.39610584e-05, 0.000130132772},
-    {0.00272907107, 0.000222840346, -0.000226168893},
-    {0.00235787849, -0.000222910661, 0.000531233381},
-    {0.00232462329, 0.00177251128, -0.00101521937},
-    {0.00278316648, 0.00029358035, 0.00142010348},
-    {0.00284922519, -0.00060107559, 0.000168623403},
-    {0.00179956458, -0.000464275945, 0.000339752994},
-    {0.0019909793, -0.000532415695, -0.000964261126},
-    {0.00317267678, 2.6517082e-05, -0.000483106356},
-    {0.00155971036, -0.00038919691, -0.00051636342},
-    {0.00275091664, -0.00217348617, -0.000208484475},
-    {0.00230799359, -0.00218507624, -0.00226235809},
-    {0.00142668304, 0.000126287807, -0.000882191118},
-    {0.00262393546, -0.00246776105, 0.00122963125},
-    {0.00135587691, -0.00156231131, 0.000717901625},
-    {0.000493469881, -0.00209286343, -0.00151457847},
-    {0.00189228146, -0.00108759385, 0.00131277274},
-    {0.000462228665, -0.0015531932, -0.000865563052},
-    {0.000695027644, -0.00156982103, -0.000217050314},
-    {0.00227473699, -0.00186913437, 0.000963574741},
-    {-0.000202912604, -0.00221833354, 0.000497976784},
-    {-0.00065188203, -0.00278370292, -0.000383335399},
-    {0.00111074094, -0.00102108018, 0.00066426117},
-    {-0.000735025154, -0.00220170477, -0.000765791629},
-    {-6.98838849e-05, -0.00221833261, 0.000963574275},
-    {0.00112233078, -0.00151237706, 0.000130133238},
-    {-0.00152782956, -0.00128767267, 0.000563417096},
-    {-0.00174936466, -0.00128713669, 0.000531233381},
-    {-0.00146667974, -0.000821537338, 0.000381575897},
-    {-0.000667502871, -0.00268947403, -0.00196606829},
-    {-0.000394944334, -0.00195710501, -0.000483643031},
-    {-0.000989995548, -0.00201224047, 0.000549373217},
-    {-0.000755407847, -0.00195710408, 0.000168623403},
-    {-0.00231473404, -0.00156982103, 0.000697517302},
-    {-0.00178010215, -0.00172199681, -0.000240733381},
-    {-0.000668511027, -0.00142016402, 0.00162871554},
-    {-0.00294661801, -0.00201879092, 0.000714146066},
-    {-0.00198216387, -0.00248438935, 0.00119637372},
-    {-0.00158660673, -0.00112538645, 0.00174259441},
-    {-0.00298684812, -0.0022660729, 0.000941045117},
-    {-0.0027304471, -0.00216844724, 0.00187814375},
-    {-0.00228147721, -0.00105433678, 0.000980202574},
-    {-0.00346210203, -0.00156982057, 0.0010134615},
-    {-0.00297987484, -0.00110422261, 0.00164534384},
-    {-0.00304638897, -0.000971193891, 0.000697518699},
-    {-0.00315496349, -0.000691443682, 0.000331691001},
-    {-0.00162853044, -0.000844817143, 0.00176839437},
-    {-0.00318294438, -0.000851267017, 0.00119435741},
-    {-0.00214844896, -0.000838165637, 0.00134602981},
-    {-0.00376141537, -0.00132039282, 0.0013792878},
-    {-0.00214576698, -0.00151081616, 0.00107836444},
-    {-0.0039408016, -0.000802893657, 0.000936363824},
-    {-0.00331244525, -0.000173024833, -0.000383335399},
-    {-0.00356187299, -0.00140353572, 0.00141254487},
-    {-0.00399421435, -0.000771651976, 0.00292574009},
-    {-0.00411817245, 0.0003097062, 0.00501589291},
-    {-0.00482349517, -0.000446591526, 0.00306949671},
-    {-0.00477575511, -0.000422453508, 0.00124625955},
-    {-0.00535775349, -0.000572110061, 0.00206105644},
-    {-0.00567369489, -0.000272796489, 0.00473824795},
-    {-0.00512495358, -0.00058873836, 0.00152894482},
-    {-0.00555729493, -0.000522223767, 0.00478813425},
-    {-0.0038445578, -0.00103770802, 0.00352436583},
-    {-0.00374478661, -0.000289424323, 0.0034744814},
-    {-0.00582738221, 0.000229082536, 0.00253270147},
-    {-0.00492648454, -1.74678862e-05, 0.00322398078},
-    {-0.0048921546, 0.00147319818, 0.00247676997},
-    {-0.00522472523, -0.000289424323, 0.00206105737},
-    {-0.00458578672, -0.000303030014, 0.00429028645},
-    {-0.00532449596, 0.000758172479, 0.00229385635},
-    {-0.00609369949, 0.00154453935, 0.00470016338},
-    {-0.00708711892, 4.31458466e-05, 0.00480476208},
-    {-0.00761923101, -0.00133702112, 0.00365739316},
-    {-0.00626274757, 0.000148458872, 0.00512876641},
-    {-0.00660489174, 0.000924456865, 0.00410636421},
-    {-0.00627887249, 0.000470952131, 0.00282294583},
-    {-0.00492648408, 0.000308664981, 0.00306949532},
-    {-0.00492541119, 0.000857943203, 0.00430590753},
-    {-0.00503727607, 0.0004709512, 0.00240370492},
-    {-0.00466901064, 0.00228263205, 0.00233140495},
-    {-0.00376141537, 0.00102422759, 0.00202779891},
-    {-0.00464272685, 0.0022879946, 0.00309202448},
-    {-0.00415042182, 0.00176092098, 0.000952487811},
-    {-0.00417122757, 0.00267742528, 0.00221125036},
-    {-0.0027304471, 0.00125702703, 0.00194465602},
-    {-0.00302976044, 0.00142331375, -0.000167165417},
-    {-0.00307007204, 0.00209953869, 0.000130132772},
-    {-0.0014999368, 0.00300302031, 0.000265176408},
-    {-0.00254056021, 0.00223113596, 0.000649241265},
-    {-0.00146667974, 0.00175588252, 0.000132148154},
-    {-0.00219833455, 0.00238776626, 0.000182033982},
-    {-0.00107061886, 0.00308314199, -0.00114371255},
-    {-0.000394945033, 0.00204232289, -0.00189116667},
-    {-0.0008287495, 0.00201891689, -0.00340115977},
-    {2.98868399e-05, 0.00139005575, -0.00342635461},
-    {4.65151388e-05, 0.00303627877, -0.00276121381},
-    {0.000379085774, 0.00240439503, -0.00256167166},
-    {0.000761542004, 0.00135679822, -0.00168035994},
-    {0.000811427366, 0.00170599716, -0.00355938263},
-    {0.00249090814, 0.00258730957, -0.00287761376},
-    {0.00368816289, 0.000475487206, -0.00360926799},
-    {0.00431500562, 0.00292189373, -0.00375590147},
-    {0.00427391473, 0.0030550533, -0.00558162527},
-    {0.00555055495, 0.00227136677, -0.00552154798},
-    {0.0057334695, 0.00305290753, -0.00685182959},
-    {0.00605646335, 0.00300251739, -0.00680345483},
-    {0.00624895189, 0.00316930795, -0.00650263019},
-    {0.00547545776, 0.0028834031, -0.00860265084},
-    {0.00656489562, 0.00326907868, -0.00755022746},
-    {0.00674780831, 0.00300302217, -0.00903016515},
-    {0.00729805976, 0.0035830033, -0.0102541242},
-    {0.00802820362, 0.00326907774, -0.00961216353},
-    {0.00748375338, 0.00233412581, -0.00971837156},
-    {0.00752934813, 0.00318593578, -0.00939599238},
-    {0.00695944298, 0.00280902302, -0.00922214799},
-    {0.00557272602, 0.00264777569, -0.00631971657},
-    {0.00587025099, 0.00308938278, -0.00431142095},
-    {0.00726329256, 0.00220485218, -0.00109836203},
-    {0.00496855658, 0.00260393741, 0.000364947598},
-    {0.00195879606, 0.0027203369, -0.000100650825},
-    {0.00147707178, 0.00264777662, -0.00285292277},
-    {0.00209396915, 0.00264309486, -0.00491219293},
-    {0.00220822333, 0.000608514994, -0.0028277277},
-    {0.00343873329, 0.00107411342, -0.00276121381},
-    {0.00458912551, 0.000761195552, 0.000275254715},
-    {0.00200814358, 0.000875107944, -0.000500807771},
-    {-0.000651882496, 0.000525372103, -0.00124801812},
-    {-0.0031129031, 0.0012570275, -0.000632763375},
-    {-0.0037473063, 0.000148459803, -0.00203056657},
-    {0.00122714066, 0.000309200957, -0.000350078335},
-    {-0.00188829307, 0.000222840812, 0.000357438345},
-    {-0.00334570231, -0.00186913367, 0.00171185704},
-    {-0.00259741908, -0.000123139471, 0.00260979775},
-    {-0.00269920565, -0.00133500574, 0.00246820366},
-    {-0.00414387137, -0.00203541992, 0.00390682183},
-    {-0.00540814269, -0.000948015135, 0.00529001188},
-    {-0.0056071803, -0.000721766613, 0.00512070395},
-    {-0.00559055246, -0.000655252021, 0.00522047561},
-    {-0.00662581157, -0.00149365142, 0.00416805036},
-    {-0.00513402419, 0.00010008458, 0.00343567971},
-    {-0.00461751595, -0.000171952415, 0.00433969963},
-    {-0.00465935562, -0.000139768235, 0.00513733085},
-    {-0.00535775302, 0.000608514994, 0.00545327365},
-    {-0.00381130097, -0.00128713623, 0.00774800964},
-    {-0.0051582111, -0.000721766613, 0.00733229704},
-    {-0.00577900931, -0.000690020621, 0.00756358635},
-    {-0.00600626552, -0.000987823121, 0.0084464075},
-    {-0.00687094871, -0.000173024833, 0.00758172479},
-    {-0.00742372032, -0.000238531735, 0.00880517997},
-    {-0.0084395716, -0.00182035752, 0.0100516155},
-    {-0.00706897955, -0.000641648192, 0.00649935752},
-    {-0.00687094871, -5.66258095e-05, 0.00784778129},
-    {-0.00502518285, -0.000555481296, 0.00623481441},
-    {-0.00665477803, -5.66258095e-05, 0.0067669265},
-    {-0.00475912634, 0.000392344315, 0.00470499042},
-    {-0.0056071803, 0.000625144225, 0.00578584429},
-    {-0.0034621018, -0.000505595934, 0.00483801868},
-    {-0.00480901171, -0.000755023211, 0.00423939154},
-    {-0.00424716948, 0.000148459338, 0.00508039352},
-    {-0.00299650338, -0.00115410797, 0.00216082716},
-    {-0.00135618052, -0.00096153887, 0.0016448074},
-    {-0.00234799134, 0.000808056444, 0.000248548575},
-    {-0.00216507749, -0.000256167259, -0.00146418926},
-    {-0.00264730444, 0.00182239665, -0.001730246},
-    {-0.00226484868, 0.00178914005, -0.0021459586},
-    {-0.00211871928, 0.00208341377, -0.00283679785},
-    {-0.00137334538, 0.0015102108, -0.00271508284},
-    {-0.00086099864, 0.00171254808, -0.00485237595},
-    {0.000262686284, 0.00323582115, -0.00447395118},
-    {-0.000601996668, 0.00207182392, -0.0038753245},
-    {0.00243726722, 0.00286623789, -0.0056502847},
-    {0.00173506583, 0.00300251832, -0.00457825745},
-    {0.0022581087, 0.00425015995, -0.00572109036},
-    {0.00202530925, 0.00338547817, -0.00603703177},
-    {0.00405398849, 0.00335222064, -0.00557143334},
-    {0.00312279095, 0.00411713263, -0.00585411815},
-    {0.00445307232, 0.00320256455, -0.0021293303},
-    {0.00576622132, 0.00309926597, -0.0034495336},
-    {0.00639860984, 0.00370142004, -0.00334321195},
-    {0.00413659401, 0.00192216877, -0.00113591086},
-    {0.00422027428, 0.00401735911, 8.22632574e-05},
-    {0.00427015964, 0.00290325144, -0.0021459586},
-    {0.00425050687, 0.00200279057, -0.000111736823},
-    {0.00397084653, 0.00183902495, -0.000466478057},
-    {0.00501844194, 0.00207182486, 0.000265176874},
-    {0.0059904065, 0.00200799201, -0.0010672505},
-    {0.00633058231, 0.00106756296, -0.000659973361},
-    {0.00660834368, 0.00140722049, -0.000260499772},
-    {0.00782866217, -0.00120399334, 0.000265176408},
-    {0.00708037894, -0.000572110061, 0.000348318368},
-    {0.00728193671, -0.000544899609, -0.000208483543},
-    {0.00544372946, -0.000980264042, 0.00114598498},
-    {0.00594964065, -0.00186913391, 0.000547861215},
-    {0.00418701582, -0.00230147573, 0.00114648836},
-    {0.00396494567, -0.00345045258, 0.00272619678},
-    {0.000678398879, -0.00413061259, 0.00438904949},
-    {-0.00253090495, -0.0036650144, 0.00440567825},
-    {-0.000585368136, -0.00559392245, 0.00556967501},
-    {-0.000801539747, -0.00707386062, 0.0061017843},
-    {-0.00206530653, -0.00692420406, 0.00553641841},
-    {-0.00128376612, -0.00489552459, 0.00483802054},
-    {-0.00171610725, -0.00632557692, 0.00633458421},
-    {0.000961084384, -0.00551128387, 0.00866005849},
-    {-5.16464934e-05, -0.00472065713, 0.00935185794},
-    {-0.00043571135, -0.00434678327, 0.00891200453},
-    {-0.000103140948, -0.0051615811, 0.00816372409},
-    {-0.00247346098, -0.0040600677, 0.00669285562},
-    {-0.00149993692, -0.0023014762, 0.00731566828},
-    {-0.000583759043, -0.00269519561, 0.00842495263},
-    {-0.00123186503, -0.00312483869, 0.00796670001},
-    {-0.00361175882, -0.0026673032, 0.00759835355},
-    {-0.00341221644, -0.00285021658, 0.00866257865},
-    {-0.00351198739, -0.00183587754, 0.00823023636},
-    {-0.00439329911, -0.00253427518, 0.00887875073},
-    {-0.00507506821, -0.00198553386, 0.00841315277},
-    {-0.00484226923, -0.00165296299, 0.00816372316},
-    {-0.00580672268, -0.00328255841, 0.00871246401},
-    {-0.00658826344, -0.00311627286, 0.00964366086},
-    {-0.0080515733, -0.00371489977, 0.00961040426},
-    {-0.0080848299, -0.00394769898, 0.0098930886},
-    {-0.00883311313, -0.00324930181, 0.0111734858},
-    {-0.0095037967, -0.00167362299, 0.00974041037},
-    {-0.00928208325, -0.00107096555, 0.00989308674},
-    {-0.00937219895, -0.00142499246, 0.010330257},
-    {-0.00765248854, -0.000738394912, 0.0112399962},
-    {-0.00717026088, -0.000538852997, 0.0106413709},
-    {-0.00618212391, -1.27861276e-05, 0.0100790262},
-    {-0.00683179032, 0.00116691133, 0.00746371597},
-    {-0.00455958396, 0.00163948303, 0.0071161259},
-    {-0.00311844586, 0.0013739313, 0.00516101532},
-    {-0.00244776229, 0.00168936839, 0.00314191077},
-    {-0.000236169668, 0.00308616413, 0.0021441998},
-    {0.000977712916, 0.00308616413, -0.000882190419},
-    {0.00204193755, 0.0030529066, -0.00301064155},
-    {0.00290662074, 0.00406724541, -0.00269469968},
-    {0.00347652589, 0.00367975282, -0.00586822722},
-    {0.00612772629, 0.00401628716, -0.00486069825},
-    {0.00643186644, 0.0033023362, -0.00475663599},
-    {0.00800754409, 0.00437311037, -0.00569085637},
-    {0.00466870889, 0.00470288703, -0.00673167501},
-    {0.0036715332, 0.005464043, -0.00660240138},
-    {0.0072134072, 0.00666129356, -0.00763336942},
-    {0.00628220942, 0.00658218516, -0.00967363827},
-    {0.00566427317, 0.00562979234, -0.0107139368},
-    {0.00487936754, 0.00575982733, -0.0103992466},
-    {0.0048403563, 0.00538948039, -0.00886012614},
-    {0.00423690211, 0.00478227297, -0.0109258164},
-    {0.0021749658, 0.00544741331, -0.0110754734},
-    {0.0047664959, 0.00543733547, -0.00943176821},
-    {0.00187565223, 0.00272033596, -0.00846479554},
-    {0.00127702649, 0.00326907868, -0.00878073834},
-    {-0.000585368369, 0.00386770582, -0.011258387},
-    {-0.00103433814, 0.00350187672, -0.00874748081},
-    {-0.00113511714, 0.00364750298, -0.0117053408},
-    {-0.00183679839, 0.00293489778, -0.0116580082},
-    {-0.00188239268, 0.0022547394, -0.0132039245},
-    {-0.00015151524, 0.00337338494, -0.01434978},
-    {0.000362457242, 0.00238776626, -0.0128380954},
-    {-0.000868053059, 0.00183902588, -0.0125221545},
-    {0.00180913857, -0.000738394912, -0.0110921003},
-    {0.00346716191, -0.000223447103, -0.0102333184},
-    {0.000994341215, -0.00103770848, -0.0104602175},
-    {0.000848211814, 0.000229083002, -0.0101090036},
-    {-0.000119769713, 0.00258730864, -0.00949576311},
-    {-0.00125319103, 0.0024886108, -0.0114005348},
-    {0.00263804593, 0.00193829229, -0.0104476195},
-    {0.00207519461, 0.00192216737, -0.0111918729},
-    {4.65158373e-05, 0.000708284322, -0.00859782379},
-    {-0.0011673664, -1.27865933e-05, -0.010834611},
-    {-0.00109641824, -0.000880291685, -0.00889159366},
-    {-0.00179622683, -0.000254655723, -0.010544369},
-    {-0.00392770069, 0.00039234478, -0.010726274},
-    {-0.00278033246, -0.000272796024, -0.0111253597},
-    {-0.00284684682, -0.00183587777, -0.0122062117},
-    {-0.00472586928, -0.00260078907, -0.0144676901},
-    {-0.00668803509, -0.00358187174, -0.0174275655},
-    {-0.00760260317, -0.00316615915, -0.0198553298},
-    {-0.00672129169, -0.0016197064, -0.0247607436},
-    {-0.00602289382, -0.00166959199, -0.0288014691},
-    {-0.00292998948, -0.00208530505, -0.03349071},
-    {0.00420213304, -0.000367528293, -0.0382625982},
-    {0.00169273908, 0.000708287116, -0.0411232114},
-    {-0.00763585977, 0.000275945757, -0.0446151942},
-    {-0.0118267834, -0.00145932101, -0.0460736752},
-    {-0.00840077084, -0.00133702205, -0.0473422632},
-    {-0.00484226923, -0.0012039938, -0.0476748496},
-    {-0.00810095482, -7.72848725e-05, -0.0472762659},
-    {-0.0145560056, -0.000824220013, -0.0433101282},
-    {-0.0160332602, -0.00147005031, -0.041256234},
-    {-0.0146959266, -0.00104476279, -0.0382625982},
-    {-0.0153348651, -0.000655252486, -0.0394104645},
-    {-0.0229340959, -0.00127050793, -0.0373817906},
-    {-0.0229033586, -0.0016574983, -0.0361502692},
-    {-0.0249751117, -8.61287117e-05, -0.0369934291},
-    {-0.0231336374, 0.000907829031, -0.0385291576},
-    {-0.0226015244, -0.000339311082, -0.0369494483},
-    {-0.0296852738, 0.00430004625, -0.0322103202},
-    {0.0150454389, 0.0106687713, -0.0277538784},
-    {-0.00123388052, 0.015457781, -0.0236965157},
-    {-0.00331244525, 0.0196315385, -0.0218174923},
-    {-0.00753659289, 0.0185305271, -0.0220734738},
-    {-0.00755271688, 0.0191214196, -0.0247891732},
-    {-0.00827832613, 0.0173373073, -0.0301196594},
-    {-0.00677117705, 0.0168046895, -0.0319941491},
-    {-0.00863357075, 0.0158901252, -0.030547468},
-    {-0.00276370416, 0.0168899782, -0.0267974678},
-    {-0.00248958566, 0.0197076276, -0.0223959666},
-    {0.00163051649, 0.024219403, -0.0179403685},
-    {0.0024445497, 0.0280440617, -0.0128501887},
-    {0.00468587317, 0.0335662365, -0.00984496251},
-    {0.00656489376, 0.0348632671, -0.00470675062},
-    {0.0697970912, 0.0426368453, 0.00271007279},
-    {0.100782074, 0.0567630306, 0.00912817847},
-    {0.0744258836, 0.0586586744, 0.0148317553},
-    {0.0600084141, 0.0533997677, 0.0184320975},
-    {0.072164394, 0.0473679155, 0.0208512805},
-    {0.0854057372, 0.0350743905, 0.0224304851},
-    {0.103555828, 0.0233439896, 0.0217964239},
-    {0.0957103893, 0.015790347, 0.019437857},
-    {0.0653134435, 0.0116498508, 0.0178581532},
-    {0.029129792, 0.0104193427, 0.0142996442},
-    {0.000927826855, 0.00790843368, 0.0134183336},
-    {-0.00387630332, 0.00540508749, 0.0136748161},
-    {0.0121011194, 0.00775824068, 0.0140378792},
-    {0.0182628054, 0.00663055805, 0.0167546216},
-    {0.0116355857, 0.00463110348, 0.0201730374},
-    {0.0149024343, 0.0035539805, 0.0209599193},
-    {0.0198011938, 0.0030529066, 0.019720545},
-    {0.0147798872, 0.00343788182, 0.0173834804},
-    {0.0169577189, 0.00293650804, 0.0183237456},
-    {0.0164588634, 0.00127365626, 0.0143162757},
-    {0.0132480478, 0.00137393083, 0.0120946001},
-    {0.0162893571, 0.00106392242, 0.00955783762},
-    {0.0360971428, 0.00143994158, 0.00771475304},
-    {0.0459245965, 0.00107411388, 0.00493779033},
-    {0.0395473056, -0.00152850151, 0.00480627362},
-    {0.0253524426, -0.00322730886, 0.00506062713},
-    {0.0121520748, -0.00426364085, 0.00522047468},
-    {0.0150217572, -0.00344733195, 0.00475789979},
-    {0.0205162186, -0.0029333597, 0.00410636421},
-    {0.0174909011, -0.00410271995, 0.0076010339},
-    {0.0170574896, -0.00642534858, 0.0091780629},
-    {0.0207490213, -0.00680780411, 0.00906166248},
-    {0.0241246112, -0.00782214385, 0.0143661592},
-    {0.0319687352, -0.0063497643, 0.0160290096},
-    {0.0478701405, -0.00803831406, 0.0205020793},
-    {0.0592606775, -0.00843739882, 0.0220651627},
-    {0.0611230582, -0.00812145695, 0.0234619603},
-    {0.0554784387, -0.00944569148, 0.0225594826},
-    {0.0882608071, -0.0036650144, 0.0241769813},
-    {0.160320237, 0.0165810119, 0.0307736788},
-    {0.140757024, 0.0253351219, 0.0337882638},
-    {0.124943331, 0.0234727282, 0.0353347212},
-    {0.122931257, 0.0187169705, 0.03540124},
-    {0.106512867, 0.0123225469, 0.0336371064},
-    {0.0657336935, 5.17121516e-05, 0.032621257},
-    {0.038084805, -0.00799286366, 0.0305734258},
-    {0.0302106477, -0.0090193972, 0.0292320568},
-    {0.0313721262, -0.00971981138, 0.0298639368},
-    {0.0426718406, -0.00557890302, 0.0291773435},
-    {0.054156214, -0.00302809151, 0.0288803298},
-    {0.0566612594, 0.00216247654, 0.0269973986},
-    {0.0505926758, 0.00356687931, 0.0274613667},
-    {0.0342267007, 0.00375881465, 0.0226546731},
-    {0.0175371971, 0.00374425063, 0.0183993317},
-    {0.00972431246, 0.00448295986, 0.0154802687},
-    {0.0107885385, 0.00491530215, 0.0126035362},
-    {0.0148292677, 0.00489867153, 0.0121878237},
-    {0.00982408412, 0.00549729774, 0.00936097465},
-    {0.0040207319, 0.00686083687, 0.00375716574},
-    {0.00666466635, 0.00704375049, 0.00650087185},
-    {0.0040041022, 0.00744283432, 0.00379042234},
-    {0.00245765154, 0.00725992443, 0.00475487765},
-    {9.6400734e-05, 0.00745946402, 0.00350773754},
-    {0.000219351379, 0.00743679004, 0.00129110599},
-    {-0.00602289382, 0.00681095244, -0.00204618718},
-    {-0.008170655, 0.00513201067, -0.00796754938},
-    {-0.00498890225, 0.00434086146, -0.00815792382},
-    {-0.00312953163, 0.00400073128, -0.0092463363},
-    {-0.00533844251, 0.00339835184, -0.0083623426},
-    {-0.00565001182, 0.00303476723, -0.0118020885},
-    {-0.00691761449, 0.00411927653, -0.00995868072},
-    {-0.00785908569, 0.00461497949, -0.00894803088},
-    {-0.00686612166, 0.00259160018, -0.00714363251},
-    {0.000994340982, 0.00273696473, -0.00869759545},
-    {-0.00511789881, 0.00258327788, -0.0038848985},
-    {-0.00853380002, 0.00114062801, -0.00192978769},
-    {-0.000535482774, 0.000242688227, -0.000732534798},
-    {-0.000751653221, 0.000758172013, -0.00480652135},
-    {-0.00171610736, 0.000641772058, -0.0143180341},
-    {0.00516809896, 0.000857943203, -0.0202045273},
-    {0.00782866124, -0.000538852997, -0.0176104791},
-    {0.00772888958, 0.00082468614, -0.0150663182},
-    {0.00944162812, 0.000408972614, -0.00668554474},
-    {0.00764574856, -0.0022848472, -0.00151407486},
-    {0.00796169043, -0.00353198592, 0.00512070395},
-    {0.00694735069, -0.00501192454, 0.0110072009},
-    {0.00611592457, -0.00521146646, 0.0134349633},
-    {0.00796168856, -0.00464609684, 0.0158793572},
-    {0.00659815315, -0.00547752297, 0.0165444966},
-    {0.00499224011, -0.00510816835, 0.0171093587},
-    {0.00658152159, -0.00243450375, 0.0181574579},
-    {0.0060075717, -0.000755560119, 0.0170760714},
-    {0.00613255333, 0.000159544405, 0.0196540281},
-    {0.00328303012, -0.000883515459, 0.018060714},
-    {0.00339590223, -0.00277009746, 0.0169319939},
-    {0.00465154182, -0.00230040262, 0.0176940076},
-    {0.00756260473, -0.00299987313, 0.0165112428},
-    {0.00689746346, -0.00341558619, 0.011306515},
-    {0.0057999827, -0.00299987337, 0.0103420597},
-    {0.00674780831, -0.00255090347, 0.00899515022},
-    {0.00449237693, -0.00423743809, 0.0103531452},
-    {0.0032096894, -0.00211158814, 0.00943768211},
-    {0.00235787942, -0.00258416031, 0.0099097183},
-    {-0.00198216387, -0.0026174176, 0.00939423498},
-    {-0.00290455762, -0.0037119654, 0.00804732367},
-    {-0.00411172258, -0.00432128645, 0.00675251801},
-    {-0.00465935515, -0.00358187174, 0.00754846912},
-    {-0.0042955433, -0.00325383642, 0.00672510359},
-    {-0.0043257121, -0.00221457798, 0.00456284359},
-    {-0.00505340099, -0.00291521871, 0.00182321854},
-    {-0.00434287731, -0.00243772264, -0.00249193888},
-    {-0.00495665241, -0.000415902585, -0.00746456534},
-    {-0.00370777491, -0.000446591526, -0.0111945551},
-    {0.000912710326, -0.000690021086, -0.0108991107},
-    {-0.000435711816, -0.00115410751, -0.0129544949},
-    {0.000828056596, -5.66253439e-05, -0.012256098},
-    {0.00126039679, 0.000841314439, -0.0136030084},
-    {0.000246057287, 0.00120714121, -0.014550834},
-    {0.000267724972, 0.00282514794, -0.0145755243},
-    {-0.000875562662, 0.00295206299, -0.0175112467},
-    {0.000229429454, 0.00303627783, -0.0190904178},
-    {0.00219159457, 0.00434993254, -0.022050295},
-    {0.00325581967, 0.00398410251, -0.0208197851},
-    {0.00368614518, 0.00347013352, -0.016800724},
-    {0.00362164644, 0.00398410531, -0.014467692},
-    {0.0026571916, 0.00340210414, -0.00987822004},
-    {0.00227473746, 0.00361827621, -0.0059705181},
-    {0.00182576641, 0.00340210507, -0.0046402365},
-    {0.000509594567, 0.00342175784, -0.000579350628},
-    {0.00115619157, 0.00302186655, 0.00387910847},
-    {-0.00151656521, 0.00398410251, 0.00565281697},
-    {-0.00102224457, 0.00414736615, 0.0075797094},
-    {-0.00347873056, 0.00529775815, 0.00809720811},
-    {-0.00362838712, 0.00451621553, 0.00916143414},
-    {-0.00417712796, 0.00566358352, 0.00984320138},
-    {-0.00440992741, 0.00669455202, 0.0108908005},
-    {-0.00474703312, 0.00859776326, 0.0086923074},
-    {-0.00406072848, 0.00582987024, 0.0102921752},
-    {-0.00230025128, 0.00700298557, 0.0112056686},
-    {-0.00289673219, 0.00434993161, 0.00894526392},
-    {-0.0040214248, 0.00332501018, 0.00964365993},
-    {-0.00360478531, 0.00386180496, 0.0108795334},
-    {-0.00381130097, 0.0022713677, 0.00992634427},
-    {-0.00534112472, 0.00310279196, 0.00859606359},
-    {-0.00340868928, 0.00132555608, 0.00824081711},
-    {-0.00436004205, 0.00187067315, 0.00778985023},
-    {-0.00331244525, 0.00267045246, 0.00876235124},
-    {-0.00468253437, 0.00261552678, 0.00935341977},
-    {-0.00445981324, 0.00148982601, 0.00999286026},
-    {-0.00440992787, 0.00117388461, 0.00931108929},
-    {-0.00357045559, 0.000497480389, 0.010416083},
-    {-0.00504181115, -0.00123725086, 0.00922794733},
-    {-0.00339558767, -0.00253427494, 0.0105415992},
-    {-0.00368280779, -0.00168974791, 0.0106433891},
-    {-0.00360218459, -0.00238310662, 0.0114173712},
-    {-0.0030040131, -0.00411988469, 0.0114288144},
-    {-0.00126713736, -0.00492878165, 0.0114894304},
-    {9.73092392e-06, -0.00580152683, 0.0118204858},
-    {0.000262686284, -0.00662489049, 0.0125702787},
-    {0.00137304165, -0.00686627254, 0.0131453052},
-    {0.00279022031, -0.00720688887, 0.0125037655},
-    {0.00252416474, -0.00840414129, 0.0119217671},
-    {0.00432004407, -0.00808820035, 0.0137176458},
-    {0.00646512304, -0.00850391388, 0.0134848505},
-    {0.00681432243, -0.00669140462, 0.015147699},
-    {0.00764574856, -0.00737317372, 0.0147818699},
-    {0.00702394079, -0.00775260665, 0.0121268537},
-    {0.00623383746, -0.00614014408, 0.0115302429},
-    {0.00874766428, -0.00570477918, 0.0118607972},
-    {0.0111195985, -0.0059950226, 0.0131427031},
-    {0.0281503219, -0.00645431411, 0.0152909234},
-    {0.0649274737, -0.00493079703, 0.0171416085},
-    {0.0891088545, -0.00476249633, 0.0197704267},
-    {0.0824710652, -0.0051242928, 0.0204149093},
-    {0.0517864153, -0.00587070687, 0.0230151359},
-};
-
-const float MAG_DATA[IMU_DATA_SIZE][MOTION_SENSOR_AXIS_NUM] = {
-    {-28.3021793, -8.44066620, -6.65198565},
-    {-25.7122631, -8.22895145, -6.54569578},
-    {-26.3388481, -8.0867815, -7.24580717},
-    {-23.3181839, -7.37590933, -7.80581093},
-    {-22.9030933, -7.37590933, -7.10572004},
-    {-22.9064999, -8.15786266, -5.63555479},
-    {-21.0482521, -7.87351608, -5.56560802},
-    {-22.2906704, -6.94938326, -7.66586733},
-    {-23.217905, -7.23373556, -7.03573847},
-    {-22.6921253, -7.73134327, -6.75565481},
-    {-22.5883446, -7.73134327, -6.82566404},
-    {-22.8095207, -7.30481815, -6.89576721},
-    {-21.5641842, -7.87351179, -5.84563446},
-    {-21.3498096, -7.80242872, -6.54567528},
-    {-22.4913692, -7.37590885, -7.17575407},
-    {-22.2804012, -7.09156322, -7.38575697},
-    {-22.2837791, -7.30482054, -7.8058362},
-    {-23.0068512, -7.02047682, -8.29587173},
-    {-22.8026848, -7.1626482, -7.73582745},
-    {-22.7057247, -7.23373079, -7.24581146},
-    {-22.2838306, -7.09156084, -6.96572781},
-    {-22.2837791, -6.94938755, -7.38578081},
-    {-22.2871647, -6.80721092, -7.2457881},
-    {-22.8026848, -6.7361269, -7.31577301},
-    {-23.3181839, -6.52287006, -7.17573023},
-    {-23.1106281, -6.87830353, -7.17573023},
-    {-22.8026848, -6.7361269, -7.38578081},
-    {-22.5917072, -6.73613024, -7.59578419},
-    {-22.4913311, -6.94938707, -7.38578272},
-    {-22.6989422, -6.87830019, -7.2457633},
-    {-23.0171432, -6.80720806, -7.10579395},
-    {-22.3909607, -6.94938421, -7.17577934},
-    {-22.4879551, -7.09156322, -6.96570492},
-    {-23.0102558, -6.87830019, -7.03573751},
-    {-22.7022991, -7.0204711, -7.03576136},
-    {-23.1140709, -6.94938755, -6.96572876},
-    {-23.2247353, -7.37590551, -7.10579395},
-    {-23.1140671, -7.02047491, -7.03573656},
-    {-22.5951271, -6.87830019, -7.10574579},
-    {-22.601963, -6.87829494, -7.03578424},
-    {-22.8061619, -7.16264629, -7.03576088},
-    {-22.5985699, -6.94938469, -6.89574194},
-    {-23.0171432, -6.87829494, -6.82575607},
-    {-22.4879646, -6.87830162, -6.75567818},
-    {-22.6886864, -7.30482626, -6.75563097},
-    {-22.6988888, -7.23373556, -6.61568356},
-    {-22.3943424, -7.51807785, -6.75574636},
-    {-22.7057629, -7.23373079, -6.96577454},
-    {-22.6989746, -7.09156179, -7.03573656},
-    {-22.4913845, -7.37590837, -7.03573656},
-    {-22.3944283, -7.51808071, -6.7557478},
-    {-22.5985622, -7.73134041, -6.6157074},
-    {-22.903183, -7.51808071, -6.33562517},
-    {-23.0172005, -7.16264439, -6.61572695},
-    {-22.7057571, -7.660254, -6.68573809},
-    {-22.6921253, -7.4469986, -6.75565434},
-    {-22.7958202, -7.66025829, -6.54563046},
-    {-22.9931335, -7.44700146, -6.33553743},
-    {-22.3807774, -7.30482578, -6.33560324},
-    {-22.3876266, -7.37590885, -6.26563787},
-    {-22.8027363, -7.44699574, -6.1956296},
-    {-22.8061428, -7.30481911, -6.33566904},
-    {-22.9064617, -6.94938755, -6.1956296},
-    {-23.0000877, -6.94939661, -6.33558273},
-    {-23.5361252, -7.30481815, -6.8257556},
-    {-23.2213345, -6.80721378, -6.6857152},
-    {-23.2144089, -6.73613024, -6.75567818},
-    {-23.3147602, -6.66504669, -6.89567375},
-    {-23.1072025, -6.30961418, -6.96568155},
-    {-22.8962307, -6.30961847, -6.82564068},
-    {-22.7959023, -6.09635496, -7.10569859},
-    {-22.8962212, -5.88309908, -7.10567427},
-    {-22.7958736, -5.31440353, -7.59575796},
-    {-22.9999676, -5.45658255, -7.66574097},
-    {-23.1071358, -5.31440306, -7.66576767},
-    {-23.0068169, -4.88787603, -7.94582891},
-    {-22.9999542, -4.46137476, -8.08579254},
-    {-22.8927994, -4.17703867, -8.15577412},
-    {-22.685276, -4.10595274, -8.15577507},
-    {-22.2753143, -3.64387703, -8.40084457},
-    {-22.481163, -3.32399297, -8.50584412},
-    {-22.8061428, -2.75525045, -8.85599804},
-    {-22.6989079, -2.39982963, -9.06599522},
-    {-22.1298237, -2.15101957, -8.92599392},
-    {-22.4811287, -1.76009572, -9.13591862},
-    {-22.5883293, -1.26247358, -9.34597397},
-    {-23.2109509, -0.764867902, -9.20595646},
-    {-22.5951462, -0.196138099, -9.06599712},
-    {-22.2854404, 0.51474005, -9.13602066},
-    {-22.4258785, 0.727904081, -9.03087711},
-    {-23.0000153, 0.941185057, -8.92589378},
-    {-22.7958736, 1.58098602, -8.64588737},
-    {-23.5222893, 2.29185081, -8.29584408},
-    {-23.0535812, 2.54063892, -8.29583168},
-    {-22.6887054, 2.93159986, -8.57585049},
-    {-23.2144604, 3.50034666, -7.87581682},
-    {-23.3649387, 3.71356678, -7.980793},
-    {-22.7958202, 4.56661654, -7.45574188},
-    {-23.0484409, 4.67318439, -6.93062973},
-    {-23.520504, 4.77986097, -7.14068937},
-    {-23.3597221, 5.0997014, -6.615592},
-    {-23.1037827, 5.27744818, -5.98553896},
-    {-22.8979626, 5.6328969, -5.67051077},
-    {-22.8927956, 6.16599321, -5.9855175},
-    {-23.5205269, 6.80582237, -5.46048546},
-    {-23.4185181, 6.55703926, -5.21546364},
-    {-23.6225986, 6.91243553, -4.86540461},
-    {-23.5101719, 6.80571413, -4.72534132},
-    {-23.8266506, 7.12565565, -4.30531931},
-    {-23.9927464, 7.33902788, -3.9903307},
-    {-23.4185028, 7.48116302, -3.7452848},
-    {-23.6191311, 8.26303291, -3.25519466},
-    {-23.5152779, 8.19194984, -2.83514571},
-    {-23.1071701, 8.61854839, -2.6251471},
-    {-23.3112831, 8.76067924, -2.20508385},
-    {-23.0968952, 9.04494095, -1.43497014},
-    {-23.207468, 9.18719482, -0.804913759},
-    {-22.8961926, 9.54262829, -0.104829729},
-    {-23.1072407, 9.82701778, 0.665259063},
-    {-23.8335857, 9.96918869, 1.36534488},
-    {-23.3147411, 10.2535372, 2.27545714},
-    {-22.9999676, 10.0402327, 2.83552527},
-    {-22.7890377, 10.1112738, 3.4655993},
-    {-23.0000057, 10.0402317, 4.16568565},
-    {-23.5188217, 9.82697201, 5.07579708},
-    {-23.2074871, 9.25828648, 6.05591345},
-    {-23.3043861, 9.18711281, 6.40593815},
-    {-23.2179184, 8.90297127, 7.31610441},
-    {-23.6295052, 8.4053278, 7.73614264},
-    {-23.7332668, 7.76554632, 8.36622238},
-    {-23.2006721, 7.05453396, 8.8562212},
-    {-23.0968952, 6.77018738, 9.34628105},
-    {-22.9064617, 5.98841524, 9.62639523},
-    {-23.3147602, 5.63291311, 10.5364733},
-    {-23.4219322, 5.56186199, 11.0965624},
-    {-23.1071701, 4.92204809, 11.3065691},
-    {-23.311264, 4.0689826, 11.6565905},
-    {-22.9965763, 3.50026393, 12.1466265},
-    {-23.3181839, 2.78948212, 12.2167044},
-    {-23.1105938, 1.93644094, 12.5667486},
-    {-23.314661, 1.22555304, 12.9867744},
-    {-23.5153637, 0.514646232, 13.1267414},
-    {-23.3078442, -0.480560243, 12.9867249},
-    {-22.8825302, -1.54689634, 13.1966715},
-    {-22.5747547, -2.32882738, 13.2667055},
-    {-22.6818752, -3.32401586, 12.706665},
-    {-22.8893051, -4.31922007, 12.3566256},
-    {-22.9931183, -5.31442308, 12.4266338},
-    {-22.6818848, -6.30962563, 11.9365797},
-    {-22.2701988, -7.0204854, 11.3065262},
-    {-22.5848713, -7.80242968, 10.8164883},
-    {-22.5849247, -8.86872578, 10.3264284},
-    {-22.5883293, -9.15307426, 9.69636917},
-    {-22.6886673, -9.57958794, 8.92626095},
-    {-22.6920967, -10.2193718, 8.08617115},
-    {-23.0068836, -11.0013304, 7.45610523},
-    {-22.3739948, -11.2856522, 6.89600468},
-    {-22.2770481, -11.570014, 5.98591328},
-    {-22.1732197, -11.9254465, 5.07580328},
-    {-22.2735901, -11.9965229, 4.16568565},
-    {-22.6886997, -12.1386957, 3.67562556},
-    {-23.1140709, -11.9254656, 2.6955092},
-    {-22.6989231, -11.5700312, 1.71538413},
-    {-22.2804012, -11.4989357, 0.665253818},
-    {-22.5883293, -11.4989262, -0.174843311},
-    {-22.5815182, -11.0013075, -0.94492203},
-    {-22.3739948, -10.3615322, -1.92503798},
-    {-22.3739948, -10.2904463, -2.62512064},
-    {-23.0000057, -9.43741608, -3.46523523},
-    {-22.6920967, -8.93981361, -4.51537991},
-    {-22.6955166, -8.51329613, -5.21548462},
-    {-22.5985432, -7.73134041, -5.70558691},
-    {-22.8026657, -6.87830257, -6.61568165},
-    {-23.0068512, -5.81200361, -7.24573946},
-    {-22.4913464, -4.74569464, -7.59580803},
-    {-23.1106281, -3.82157683, -8.08584499},
-    {-23.5222797, -2.61311793, -8.36585236},
-    {-23.3112831, -1.61792052, -8.29581833},
-    {-22.8962383, -0.551628292, -8.43583488},
-    {-23.0968761, 0.159195006, -8.64580536},
-    {-23.2075253, 1.29662168, -8.85588646},
-    {-23.4184837, 2.0075047, -8.43586063},
-    {-23.1003532, 3.00265956, -7.73572683},
-    {-22.9965572, 4.14003754, -7.73572445},
-    {-22.7924442, 4.99310541, -7.38570642},
-    {-22.8027172, 5.6329813, -6.89571905},
-    {-23.1071892, 6.48595142, -6.05556917},
-    {-23.5188026, 7.41003656, -5.14543867},
-    {-23.4150639, 7.90764332, -4.51536226},
-    {-23.7263832, 8.33415985, -3.8152771},
-    {-23.4116058, 8.9028101, -2.69512916},
-    {-23.9338856, 9.47154236, -1.92504728},
-    {-23.6260567, 9.5426712, -0.874931812},
-    {-23.3113213, 9.47154045, 0.105196349},
-    {-23.2075253, 9.75588608, 1.01530719},
-    {-23.2109509, 9.68484402, 2.06543064},
-    {-22.9999866, 9.68480015, 3.11555743},
-    {-23.0000153, 9.82697201, 3.9556613},
-    {-23.3147449, 9.61375809, 4.58574057},
-    {-23.2040825, 9.61367035, 5.49583864},
-    {-23.3078442, 9.25823879, 6.40594673},
-    {-23.6225891, 8.54741764, 7.52609301},
-    {-23.6191311, 8.12086105, 8.15615368},
-    {-23.4150791, 7.55221033, 9.13628578},
-    {-23.1037636, 6.91243315, 9.69635391},
-    {-22.9030743, 5.98838234, 10.466485},
-    {-22.9999866, 5.13527822, 11.3065462},
-    {-23.408144, 4.49544001, 11.3065052},
-    {-23.3043861, 3.42914724, 11.5865383},
-    {-23.4150448, 2.29182506, 12.3566751},
-    {-23.411602, 1.58093786, 12.3566504},
-    {-23.0935078, 0.870032966, 12.4966173},
-    {-23.3147087, -0.338351607, 12.7767506},
-    {-23.1106319, -1.19137263, 12.7067661},
-    {-22.8996773, -1.90225077, 12.8467579},
-    {-23.3113213, -2.54204488, 12.846734},
-    {-23.3250523, -3.2528615, 12.7068148},
-    {-23.4219513, -4.10592222, 12.3567209},
-    {-23.2144089, -4.95896339, 12.4267311},
-    {-23.2075214, -5.66984272, 12.0766401},
-    {-23.2075405, -6.38070488, 11.9366226},
-    {-22.5882816, -7.23373938, 11.6566114},
-    {-22.5849247, -7.80243063, 11.3765564},
-    {-22.6852798, -8.51329327, 10.6764517},
-    {-22.3671932, -9.29523277, 10.1863575},
-    {-22.4641819, -9.72173977, 9.2062149},
-    {-22.2601204, -10.2193441, 8.71617508},
-    {-22.7822037, -10.6458635, 7.87609673},
-    {-22.3570175, -11.0012712, 7.0359683},
-    {-22.0424442, -11.2145185, 6.33588409},
-    {-22.8722572, -11.2145185, 5.70581865},
-    {-22.7685318, -11.7121143, 4.72571754},
-    {-23.0728321, -11.5699282, 3.67560458},
-    {-22.8585777, -11.4277411, 3.04554033},
-    {-22.5440407, -11.5699015, 2.34547448},
-    {-22.3400421, -11.3566561, 1.57540047},
-    {-22.5508823, -11.3566656, 0.735318065},
-    {-22.8619785, -11.2144976, -0.104760759},
-    {-22.547472, -11.0012341, -1.01484179},
-    {-22.8619919, -10.5747347, -2.13495851},
-    {-22.5474796, -10.503644, -2.48497963},
-    {-22.8483181, -10.0771246, -2.76496434},
-    {-22.8517189, -9.4373703, -3.60505724},
-    {-22.5474434, -8.93978691, -4.16513729},
-    {-22.4267464, -8.65544033, -4.58508635},
-    {-21.9151077, -8.30002308, -5.21518087},
-    {-22.5371914, -7.66027212, -5.98524094},
-    {-22.9486027, -7.02051735, -6.47526407},
-    {-23.0522785, -6.23859835, -6.61527538},
-    {-22.8414764, -5.66993189, -7.24530697},
-    {-22.9383183, -4.74586582, -7.52528048},
-    {-23.0385761, -3.96395874, -7.5952611},
-    {-22.5202351, -3.11095953, -7.66526508},
-    {-22.6307144, -2.61335611, -7.94533634},
-    {-22.8209763, -1.9025979, -8.01521397},
-    {-23.5570641, -1.04955316, -8.08529758},
-    {-23.3532352, -0.480879337, -8.01531982},
-    {-23.0352135, 0.301002949, -7.80524969},
-    {-23.5499344, 1.01180375, -7.66521454},
-    {-23.1250343, 2.00689101, -7.45512533},
-    {-23.0248051, 2.5755775, -7.24513721},
-    {-23.0351086, 3.28647995, -6.82517672},
-    {-23.4496918, 3.78405881, -6.54515743},
-    {-23.757206, 4.42377615, -6.33512163},
-    {-23.5429897, 5.20561886, -5.845047},
-    {-23.232069, 5.77427959, -5.42501926},
-    {-23.02141, 6.12965536, -5.4950037},
-    {-23.2286873, 6.76939583, -4.79495955},
-    {-23.2321072, 7.33809137, -4.16493797},
-    {-23.2321262, 7.62241983, -3.88491917},
-    {-23.4290199, 8.11987305, -3.11483002},
-    {-23.8470325, 8.68857384, -2.62480998},
-    {-23.2287102, 8.75969505, -2.27480412},
-    {-23.4290009, 8.75961304, -1.5047369},
-    {-23.63624, 9.11502457, -1.01470745},
-    {-23.6397114, 9.18614674, -0.174667001},
-    {-23.6397457, 9.47047234, 0.59537977},
-    {-23.6397266, 9.68371868, 1.22541487},
-    {-23.2149029, 9.68358994, 1.71545231},
-    {-23.2252769, 9.47047424, 2.20547533},
-    {-23.221838, 9.47043133, 3.11552453},
-    {-23.4221134, 9.39926529, 3.7455585},
-    {-23.5326157, 9.04393959, 4.37560081},
-    {-23.435955, 8.7596941, 5.42567444},
-    {-24.0507145, 8.5463686, 5.91568756},
-    {-23.8365345, 8.47520733, 5.9856739},
-    {-23.3150444, 7.90651417, 6.54569578},
-    {-23.7363834, 7.69334793, 7.45576477},
-    {-23.9332142, 7.47999144, 8.0157547},
-    {-23.5257664, 6.7692523, 8.57581139},
-    {-23.5292091, 6.41388226, 8.71583176},
-    {-23.5188217, 5.98728657, 9.06580544},
-    {-23.4117527, 5.84509182, 9.62581158},
-    {-23.9262333, 5.20532894, 10.255825},
-    {-23.9262142, 4.63668442, 10.3258276},
-    {-23.6155205, 4.28127956, 10.8158493},
-    {-23.4152164, 3.71269107, 11.305912},
-    {-23.3116302, 3.2862072, 11.5159216},
-    {-23.4048615, 2.5753181, 11.8658705},
-    {-23.4048748, 2.00667167, 12.0758801},
-    {-23.2045994, 1.22483146, 12.355938},
-    {-23.3116493, 0.656205118, 12.2159548},
-    {-23.1010094, 0.300778866, 12.355938},
-    {-23.4082966, -0.338966042, 12.2859116},
-    {-23.5118828, -0.907614231, 12.4959192},
-    {-23.8261223, -1.33408237, 12.7759562},
-    {-23.4220657, -2.18701339, 12.5660181},
-    {-23.2252007, -2.68454099, 12.3560801},
-    {-23.2080441, -3.53757882, 12.7059784},
-    {-23.2080574, -3.82190323, 12.4259644},
-    {-23.1078873, -4.1772995, 12.2159786},
-    {-23.004282, -4.95919514, 11.6559486},
-    {-23.2114391, -5.88324976, 11.5159435},
-    {-23.1044292, -6.38082409, 11.4459171},
-    {-22.8869667, -6.73624039, 10.8158274},
-    {-22.8938351, -7.16271877, 10.3958492},
-    {-23.3185177, -7.51812172, 10.185894},
-    {-22.9109554, -8.08677101, 9.69590569},
-    {-23.1078682, -8.15785313, 8.92581367},
-    {-22.9040871, -8.58434105, 8.85582542},
-    {-23.5291862, -8.86866951, 8.22580528},
-    {-23.5257759, -9.29515553, 7.87577391},
-    {-23.1112785, -9.72164631, 7.59576082},
-    {-22.5966511, -10.0059776, 7.03574038},
-    {-22.8038635, -9.86381149, 6.61571884},
-    {-23.3219604, -10.2903023, 5.98568344},
-    {-23.214922, -10.2192144, 5.63565731},
-    {-23.4255466, -10.2192211, 5.00563002},
-    {-23.4220657, -10.7167835, 4.44559765},
-    {-23.4220657, -11.0011101, 4.09557819},
-    {-22.9075012, -11.3565264, 3.46554399},
-    {-23.3288574, -11.4276257, 2.76551032},
-    {-23.5361061, -11.640871, 2.20547342},
-    {-23.3323116, -11.4276323, 1.64543951},
-    {-23.1182041, -11.2143698, 1.36542881},
-    {-22.8004799, -11.2143555, 0.45538649},
-    {-22.9144363, -11.2854586, -0.244671896},
-    {-22.5864582, -11.143259, -0.734659076},
-    {-22.7036953, -10.6457157, -1.50473869},
-    {-22.7105274, -10.4324827, -1.85477817},
-    {-23.0145607, -10.0059805, -2.48479199},
-    {-23.118185, -9.65057278, -3.04482388},
-    {-23.0145607, -9.22408104, -3.39484477},
-    {-22.8175621, -9.08192253, -3.53490019},
-    {-23.3425751, -8.58435059, -4.44499111},
-    {-23.4393654, -8.01569176, -4.58496571},
-    {-23.0145264, -7.30487204, -4.79492474},
-    {-23.5395889, -6.9494586, -5.28499079},
-    {-23.121685, -6.38080406, -5.63499308},
-    {-23.5430088, -6.09646749, -5.91505098},
-    {-23.0111446, -5.45675278, -6.19498253},
-    {-23.5326729, -4.88809156, -6.05499458},
-    {-23.8469429, -4.4615922, -5.98501301},
-    {-23.639698, -3.96401715, -6.47504425},
-    {-24.0576725, -3.53751516, -6.89509058},
-    {-23.6431847, -2.89777517, -6.82508612},
-    {-23.8469429, -2.68454218, -6.68505478},
-    {-23.7467518, -2.25803518, -6.82508707},
-    {-23.9540482, -1.68937898, -7.1051054},
-    {-23.6431847, -1.47613275, -7.1051054},
-    {-23.2287064, -0.765311241, -6.89509058},
-    {-23.4324684, 0.158737078, -6.82506275},
-    {-23.5395603, 0.514166415, -6.89509201},
-    {-23.2217522, 0.727370024, -7.0350523},
-    {-23.221756, 1.153862, -6.89504385},
-    {-23.6431656, 1.79364645, -7.03510046},
-    {-23.4393654, 2.36232686, -6.89511538},
-    {-23.8469601, 2.93093371, -6.61505175},
-    {-23.9505863, 3.4995892, -6.40503836},
-    {-23.3322773, 3.99719238, -6.54506969},
-    {-23.3356934, 4.21046877, -6.40508175},
-    {-23.4393368, 4.63696241, -6.19506788},
-    {-23.6431656, 4.99234152, -5.98503494},
-    {-23.1147308, 5.48981714, -5.70495749},
-    {-23.0145226, 5.91633987, -5.21494818},
-    {-23.3253803, 6.12958717, -4.79492331},
-    {-23.3288765, 6.62719631, -4.51492643},
-    {-23.8434696, 7.05364847, -4.58491373},
-    {-23.5360489, 6.98260498, -3.88488626},
-    {-23.5430088, 7.33809137, -3.25488043},
-    {-23.9575348, 7.62241983, -3.11487079},
-    {-23.8469429, 7.62234306, -2.4848063},
-    {-23.6707668, 7.97781134, -1.73227525},
-    {-24.0697327, 8.08455372, -1.46978569},
-    {-23.8607788, 8.40440273, -1.29477167},
-    {-23.8469601, 8.47532654, -0.664696455},
-    {-24.1578293, 8.40424442, -0.0346587114},
-    {-23.8504238, 8.40428543, 0.385360599},
-    {-23.9039974, 7.97781277, 0.945393622},
-    {-23.903923, 8.40430546, 1.36542177},
-    {-23.8539104, 8.33324337, 1.92545414},
-    {-24.1578579, 8.33316422, 2.415488},
-    {-24.0568466, 8.29765224, 2.78300929},
-    {-24.2148895, 8.08443451, 3.25554061},
-    {-24.2684364, 7.97783089, 3.88558078},
-    {-24.1613255, 7.97779179, 4.23559856},
-    {-24.157877, 7.76450729, 4.72562647},
-    {-24.2149048, 7.76456594, 5.25066566},
-    {-23.7485619, 7.65794277, 5.67069244},
-    {-23.757206, 7.69357824, 5.84572411},
-    {-23.5879002, 6.91152334, 6.40572548},
-    {-23.9575539, 6.84051514, 6.68576145},
-    {-24.1682453, 6.91163301, 7.31581497},
-    {-23.4479961, 6.48519039, 7.56084919},
-    {-23.9040222, 6.48508549, 8.08584595},
-    {-23.9540672, 6.34290218, 8.08583927},
-    {-24.0646591, 5.95201921, 8.61089993},
-    {-24.0698853, 5.95207024, 8.92594528},
-    {-24.1683178, 5.34781981, 9.20593643},
-    {-24.2201157, 5.09902906, 9.66097164},
-    {-24.0594292, 4.67248774, 9.87095928},
-    {-23.7467899, 4.42368603, 9.97595787},
-    {-23.8539295, 3.78397489, 10.6060162},
-    {-23.7571735, 3.57078528, 10.5360508},
-    {-23.5429611, 3.2863996, 10.5360107},
-    {-24.0507145, 2.78874278, 10.7459641},
-    {-24.0472507, 2.22006536, 11.165967},
-    {-23.7433357, 1.79362082, 11.2360134},
-    {-23.7485619, 1.90028083, 11.2360458},
-    {-24.3702984, 0.834048271, 11.4460583},
-    {-23.757206, 0.229898334, 11.3761072},
-    {-23.9039688, 0.194308266, 11.5510654},
-    {-24.0646076, -0.125535265, 11.2360754},
-    {-23.8573494, -0.765274048, 10.9560575},
-    {-24.3685932, -1.61829746, 11.026021},
-    {-24.275404, -1.83149815, 10.9560795},
-    {-23.7641411, -2.25796556, 11.2361393},
-    {-24.0507336, -2.47131062, 11.0259819},
-    {-23.6327915, -2.68456841, 10.605938},
-    {-23.843504, -3.11104822, 10.2559347},
-    {-24.2824955, -3.39529037, 10.39608},
-    {-24.0611877, -4.24832678, 10.5360107},
-    {-23.8469753, -4.31942844, 10.6059771},
-    {-24.1613827, -4.31941891, 10.1859674},
-    {-23.6501865, -4.6037302, 9.97599125},
-    {-23.757225, -4.95913553, 9.62598515},
-    {-23.9645081, -5.24346447, 9.55598164},
-    {-23.6501007, -5.81213284, 9.4859581},
-    {-24.2683983, -5.74105644, 9.34593391},
-    {-23.9505615, -5.95431185, 9.20589256},
-    {-24.0647125, -6.52295828, 8.9959259},
-    {-24.0646591, -7.16270018, 9.2059412},
-    {-23.6431847, -7.37594986, 9.06590176},
-    {-23.3253956, -7.44703627, 8.64584446},
-    {-22.9143562, -7.80244398, 8.36584282},
-    {-23.5395794, -7.9446063, 8.01583385},
-    {-23.6569977, -7.87352562, 7.80587149},
-    {-23.7606602, -8.44218636, 7.52585125},
-    {-23.2389698, -8.65543365, 7.24582148},
-    {-23.2390079, -8.86868095, 7.03580618},
-    {-23.3391933, -9.01084614, 6.89578533},
-    {-23.1319313, -9.36625767, 6.61576796},
-    {-23.3426094, -9.29517651, 6.5457716},
-    {-23.2389698, -9.79275799, 6.26575279},
-    {-23.4462814, -9.57950783, 5.63570881},
-    {-23.8573589, -9.65058708, 5.21567488},
-    {-23.4462814, -9.86383915, 5.14567566},
-    {-23.7467709, -10.1481552, 4.58562183},
-    {-23.6570168, -10.2903404, 4.02559996},
-    {-23.8642941, -9.93492699, 3.74557996},
-    {-23.6535492, -9.6505909, 3.46555829},
-    {-23.7537537, -9.72166824, 3.04552913},
-    {-23.2320919, -9.93491173, 2.48549008},
-    {-23.2389698, -9.43734264, 2.20546985},
-    {-23.7571735, -9.29517651, 1.71543646},
-    {-24.0611782, -9.22408867, 1.29541552},
-    {-23.8504333, -9.22408676, 1.01539981},
-    {-24.1648312, -9.22408962, 1.08540082},
-    {-24.0681229, -9.22409439, 0.80537349},
-    {-23.6466141, -8.86867905, 0.245347217},
-    {-24.4792519, -8.6554327, -0.104683995},
-    {-24.1753368, -8.37110424, -0.314711571},
-    {-23.7572441, -8.08677101, -0.314704686},
-    {-24.4792004, -7.73136044, -0.734724462},
-    {-24.3790283, -7.51811171, -1.15476549},
-    {-24.0681419, -7.5891943, -1.36477804},
-    {-24.2719231, -7.30486536, -1.50477707},
-    {-24.1682987, -6.9494524, -1.64478624},
-    {-24.4757328, -7.16270256, -1.8547883},
-    {-24.1648121, -6.73620749, -1.8547883},
-    {-23.8573723, -6.16754532, -2.06481433},
-    {-23.6535625, -5.88321018, -2.2748394},
-    {-24.0681229, -5.88321018, -2.13483},
-    {-24.275423, -6.02537537, -2.76487446},
-    {-23.9645081, -5.52779818, -2.97488856},
-    {-24.068161, -5.31454992, -3.18490386},
-    {-24.1718178, -5.31454992, -3.32491302},
-    {-24.1683369, -5.31455803, -3.39490223},
-    {-24.3615494, -4.67484522, -3.81486869},
-    {-24.475666, -4.39049006, -3.53489828},
-    {-24.5828571, -4.1772356, -3.81493115},
-    {-25.3048038, -3.89291501, -3.95492458},
-    {-25.4048939, -3.89292502, -4.02491283},
-    {-24.5723171, -3.82185364, -4.23490953},
-    {-24.1681747, -3.53749418, -4.4449749},
-    {-24.0645695, -3.67965865, -4.86500168},
-    {-24.3720932, -3.53750396, -4.86498356},
-    {-24.2649498, -3.25318599, -4.79496098},
-    {-23.9575539, -2.75559878, -4.93498755},
-    {-24.4757137, -2.68451476, -5.07499743},
-    {-24.5723553, -2.61345959, -5.21496916},
-    {-24.3650875, -2.18696713, -5.2149682},
-    {-23.9575539, -1.83152914, -5.49502373},
-    {-23.8504047, -1.76046169, -5.56500959},
-    {-24.2614536, -1.26290226, -5.49498415},
-    {-24.2614822, -1.40506768, -5.49498367},
-    {-24.3720741, -1.26286936, -5.28500986},
-    {-24.1648121, -0.694210827, -5.56502771},
-    {-24.4686832, 0.0876531601, -5.42498112},
-    {-24.3580666, 0.0876141861, -5.494946},
-    {-24.5688114, 0.443044126, -5.3549571},
-    {-24.3755322, 0.443126321, -5.42503929},
-    {-24.1718044, 0.798559904, -5.14504099},
-    {-23.9575634, 1.43825793, -5.28500986},
-    {-23.8609028, 1.79371953, -5.21504354},
-    {-24.3720741, 2.22016406, -4.44495773},
-    {-24.682991, 2.29124665, -4.09493446},
-    {-24.8902588, 2.50449109, -4.16493797},
-    {-24.2683887, 3.1442318, -3.95492339},
-    {-24.4686928, 3.28634357, -3.88488865},
-    {-24.4686928, 3.5706718, -3.60487151},
-    {-24.779562, 3.78391623, -3.4648633},
-    {-24.6759033, 3.71283364, -2.69481802},
-    {-24.7795467, 4.28149176, -2.48480701},
-    {-24.993845, 4.77912664, -2.27481747},
-    {-25.0868816, 4.70795107, -1.854756},
-    {-25.190506, 4.56578827, -1.43473256},
-    {-24.9868107, 4.49473715, -1.15472376},
-    {-25.3083382, 4.70807648, -0.944739103},
-    {-24.9938831, 4.7791276, -0.944730699},
-    {-24.9938793, 4.77912664, -0.734716952},
-    {-25.304718, 4.99237204, -0.31469208},
-    {-24.4757328, 4.85020781, 0.105334282},
-    {-24.8866863, 4.92125893, 0.735381007},
-    {-25.5049286, 5.56096554, 0.805391312},
-    {-24.8937073, 5.63214588, 0.805378139},
-    {-25.204628, 5.41890144, 0.945385993},
-    {-25.2941647, 5.41876841, 1.50543571},
-    {-25.3047848, 5.5610323, 1.71544111},
-    {-25.0974312, 5.84536314, 1.92545509},
-    {-24.7936401, 5.63218212, 1.99545622},
-    {-25.4084377, 5.27670288, 2.27547765},
-    {-25.4049034, 5.56099987, 2.41548705},
-    {-25.6085625, 5.56096554, 2.55549693},
-    {-25.4048367, 5.41883564, 2.90551758},
-    {-25.208252, 5.34785128, 3.18553853},
-    {-25.2976799, 5.13447428, 3.53555489},
-    {-25.1905212, 5.34768677, 3.67556047},
-    {-25.1940594, 5.20555687, 3.88557506},
-    {-24.9762135, 4.99221611, 3.74556017},
-    {-24.7795467, 5.20555687, 4.44560909},
-    {-25.1869488, 5.27657366, 4.72561502},
-    {-24.9868107, 5.20555592, 4.7956295},
-    {-24.7795658, 5.41880274, 4.7956295},
-    {-24.5723171, 5.27663851, 5.14565039},
-    {-24.4686928, 5.20555687, 4.86563396},
-    {-24.375576, 5.13457155, 5.35568333},
-    {-24.7866154, 4.92129183, 5.77570248},
-    {-25.3189831, 4.92141867, 5.77573586},
-    {-25.3154488, 4.77922153, 6.05574608},
-    {-25.0009518, 4.56594276, 6.33575726},
-    {-25.0975227, 4.28155136, 6.33573961},
-    {-24.7901211, 4.21049881, 6.47575855},
-    {-24.5793571, 3.92614031, 6.75576735},
-    {-24.8867397, 3.57069874, 6.54574394},
-    {-24.9938831, 3.57072783, 6.82577181},
-    {-25.0939503, 3.71286416, 7.31579113},
-    {-25.4084473, 3.14423418, 7.66582584},
-    {-25.4084282, 2.78882074, 7.73583031},
-    {-24.7866344, 2.85990453, 7.73582888},
-    {-24.986805, 2.71768808, 8.08582306},
-    {-24.9762325, 2.43328547, 8.01578045},
-    {-24.7725124, 1.79357398, 8.22580624},
-    {-24.7795277, 1.50929248, 8.43584633},
-    {-24.8902397, 1.43825853, 8.43587494},
-    {-24.7901211, 1.15395093, 8.29587936},
-    {-24.6864624, 0.656375051, 8.57589817},
-    {-24.9832726, 0.229799062, 8.50583649},
-    {-25.297699, 0.158737078, 8.36584187},
-    {-25.0939884, 0.0165935997, 8.36585522},
-    {-25.3977699, -0.765347779, 8.22582054},
-    {-25.5120144, -0.836374402, 8.36587143},
-    {-24.5758514, -0.907475412, 8.50586605},
-    {-24.7831001, -1.40505064, 8.36585522},
-    {-25.0009899, -1.54716671, 8.01587391},
-    {-24.8938503, -1.54718196, 7.87585068},
-    {-24.572298, -1.68939364, 8.08582497},
-    {-24.8831673, -2.11588621, 8.15583038},
-    {-24.9939156, -2.61343455, 7.8758378},
-    {-25.0904293, -2.68454218, 8.01582146},
-    {-25.201128, -3.11101246, 7.80583286},
-    {-25.0044937, -3.11097479, 7.24583292},
-    {-24.997488, -3.18208075, 7.17580414},
-    {-25.3154621, -3.46638823, 7.10582256},
-    {-24.8973274, -3.3242352, 7.10581064},
-    {-25.0974884, -3.46642113, 6.96578026},
-    {-24.8867397, -3.82184315, 6.47573948},
-    {-24.8937836, -3.9639883, 6.40575123},
-    {-25.0009518, -4.24831009, 6.33575678},
-    {-25.0009518, -4.3904748, 6.19574785},
-    {-25.7228966, -4.1772356, 6.05572987},
-    {-25.8229694, -3.96399713, 5.9857173},
-    {-25.5084705, -4.39050055, 5.84569979},
-    {-25.4155159, -4.74588823, 5.84572315},
-    {-24.9974365, -5.0302248, 5.49569321},
-    {-25.090435, -4.88808298, 5.28565884},
-    {-25.2011662, -4.67482138, 5.56569099},
-    {-25.0939884, -4.67482901, 5.3556695},
-    {-24.779562, -5.03024721, 5.28565884},
-    {-24.8761139, -5.03026152, 5.28564644},
-    {-25.3941593, -5.03026199, 5.00563097},
-    {-25.6978512, -5.03027582, 4.72560406},
-    {-25.297699, -4.9591651, 4.5156126},
-    {-24.779562, -5.10132885, 4.72562504},
-    {-24.876152, -5.31458759, 4.86562157},
-    {-24.8690834, -5.38568258, 4.79560757},
-    {-24.6759224, -5.38565826, 4.58561707},
-    {-24.8937645, -5.7410531, 4.44562054},
-    {-25.3012314, -5.314569, 4.30560303},
-    {-24.893774, -5.52780247, 3.95558906},
-    {-24.6794567, -5.74106169, 3.88557911},
-    {-24.6689415, -6.09648657, 3.81556487},
-    {-25.5013943, -5.88323593, 3.95557618},
-    {-24.879652, -6.02539968, 3.95557642},
-    {-24.8831863, -6.23864079, 3.81557083},
-    {-25.2976799, -5.88323069, 3.53555417},
-    {-24.8796673, -6.02539921, 3.11552763},
-    {-25.4013042, -6.59405041, 3.1155293},
-    {-25.3012314, -6.02538872, 3.0455265},
-    {-25.2046986, -6.02538013, 2.97552347},
-    {-24.7795811, -6.02539587, 2.62549996},
-    {-24.9832916, -6.45189238, 2.62549996},
-    {-25.0904293, -6.23864079, 2.55549574},
-    {-25.090435, -6.09647655, 2.41548753},
-    {-25.090435, -6.23864079, 1.92545819},
-    {-24.8796673, -6.2386446, 1.64544308},
-    {-24.9796658, -6.30973005, 1.57544458},
-    {-25.0868816, -5.88323593, 1.575441},
-    {-24.7724895, -6.30973148, 1.22542262},
-    {-24.8831902, -6.23864079, 0.805391312},
-    {-25.2976799, -6.23864079, 0.665382862},
-    {-24.990345, -6.23863554, 0.665378988},
-    {-25.2940598, -5.74107695, 0.875401139},
-    {-24.9868622, -6.02539444, 0.525376379},
-    {-24.7690315, -5.52784014, 0.175371721},
-    {-24.8867054, -5.31456757, 0.105343878},
-    {-24.679491, -5.314569, -0.0346638076},
-    {-24.5688171, -5.17241764, -0.384672374},
-    {-25.086916, -4.88809061, -0.524680376},
-    {-24.7725277, -4.88809776, -0.524671972},
-    {-24.6724224, -4.95917225, -0.664688051},
-    {-24.9833107, -4.67484617, -0.734692931},
-    {-24.5688171, -4.24835443, -0.944705248},
-    {-24.9832726, -4.03510857, -1.01470888},
-    {-25.2941456, -4.17727232, -0.874700665},
-    {-25.6085529, -3.96401739, -1.08472133},
-    {-25.5013657, -3.53753591, -1.29472458},
-    {-25.0797997, -3.46647716, -1.36470854},
-    {-25.7086143, -3.03996396, -1.29472375},
-    {-25.7157574, -2.82669425, -1.29474378},
-    {-25.6085625, -2.61346149, -1.43474221},
-    {-25.3870735, -2.61351371, -1.2946949},
-    {-25.6978893, -2.11594272, -1.2946949},
-    {-25.4906788, -2.11594343, -1.29469585},
-    {-24.876133, -1.68942523, -1.15470672},
-    {-25.3941975, -1.33401847, -1.2247113},
-    {-25.086935, -1.76049209, -1.15471661},
-    {-25.3012123, -1.40505064, -1.15473402},
-    {-25.301199, -1.2628864, -0.804712236},
-    {-25.0868053, -1.04967487, -0.874699414},
-    {-24.8831348, -0.765330076, -0.664696157},
-    {-25.6085529, -0.481001139, -0.804704726},
-    {-25.9194164, -0.409917206, -1.01471734},
-    {-25.8158245, -0.196672767, -0.664697349},
-    {-25.2905827, -0.125629038, -0.244656906},
-    {-25.4013138, -0.125590071, -0.52468878},
-    {-25.6121044, 0.0876744688, -0.454691082},
-    {-25.719326, -0.0544690043, -0.314689666},
-    {-25.6122246, 0.0876738653, -0.104668997},
-    {-25.6050606, 0.229799062, -0.104656108},
-    {-25.7050323, 0.300861061, 0.0353575796},
-    {-25.7050037, 0.0876141861, 0.315373391},
-    {-25.4942493, 0.229757056, 0.17537187},
-    {-25.3030319, 0.194308266, 0.420360804},
-    {-25.7121677, 0.51414448, 0.665381968},
-    {-25.9194489, 0.727391362, 1.15541339},
-    {-25.8193645, 0.514166415, 0.945395112},
-    {-25.8157921, 0.585228384, 0.80539149},
-    {-25.9122143, 0.443022817, 0.945406973},
-    {-25.6013699, 0.514103055, 0.945407271},
-    {-26.0158119, 0.656267881, 1.22542512},
-    {-25.6978893, 0.585143149, 1.43544126},
-    {-25.4397926, 0.833934426, 1.6279496},
-    {-25.7585983, 0.727360308, 1.78545296},
-    {-25.6049614, 0.869533598, 1.78545141},
-    {-25.7121677, 0.869556725, 1.92545819},
-    {-25.9194164, 0.514146328, 1.85545397},
-    {-26.4411583, 0.514168203, 1.64543843},
-    {-25.2870159, 0.940573096, 1.57544506},
-    {-25.394207, 0.7984308, 1.85545754},
-    {-25.3941593, 0.656267226, 2.34548473},
-    {-26.5375481, 0.371960819, 2.48549223},
-    {-25.9229889, 0.158756554, 2.55549574},
-    {-25.6139297, 0.514177978, 2.41548657},
-    {-25.4978504, 0.514104903, 2.27548265},
-    {-25.4942303, 0.443002105, 2.06547117},
-    {-25.7086143, 0.371961415, 2.34548426},
-    {-25.0797997, 0.0875946954, 2.55549622},
-    {-25.2941837, 0.443044126, 2.90551615},
-    {-25.5049286, 0.300900638, 2.90551662},
-    {-25.7086143, 0.229799062, 2.69550514},
-    {-25.7086143, 0.300879329, 3.04552388},
-    {-25.7086048, 0.229797855, 2.69550467},
-    {-25.4477539, 0.407492429, 2.62550068},
-    {-25.9140339, 0.514113426, 2.94051647},
-    {-25.7586269, -0.232240304, 3.25553608},
-    {-26.105072, 0.371859729, 3.18552518},
-    {-25.4977322, 0.0165333133, 3.25553441},
-    {-25.7638988, -0.125591278, 3.0455265},
-    {-25.7013893, -0.125648528, 3.11552668},
-    {-26.0748482, 0.0876549855, 3.5705564},
-    {-25.4637985, -0.765275896, 3.46555614},
-    {-26.0266266, -0.267734766, 3.67556405},
-    {-25.9194164, -0.552083194, 4.09558773},
-    {-25.8122005, -0.623182356, 3.39554381},
-    {-25.7050037, -0.196711734, 3.74555993},
-    {-25.7585983, -0.232242733, 3.57055163},
-    {-25.5978374, -0.552137434, 4.09557676},
-    {-25.8122196, -0.338855833, 3.67555904},
-    {-26.0748482, -0.658706069, 3.5705564},
-    {-25.4531116, -0.658706069, 3.88557506},
-    {-25.4477291, -0.232242733, 3.46554613},
-    {-25.6156578, -1.12070525, 3.95558596},
-    {-25.447834, -0.552111208, 3.78056502},
-    {-25.6084423, -0.978573322, 3.88557673},
-    {-25.8157921, -1.40506649, 3.88557506},
-    {-25.6085529, -1.40506709, 3.95557928},
-    {-25.7049751, -1.33401668, 3.81556535},
-    {-25.5978317, -1.51173735, 3.78056049},
-    {-25.4530354, -1.72493804, 4.5156126},
-    {-25.7693367, -1.724913, 3.88558054},
-    {-25.4048557, -1.90262592, 4.23559952},
-    {-25.9230213, -1.9026252, 4.09559202},
-    {-25.7122059, -1.90264046, 4.30560017},
-    {-25.6085949, -2.18696713, 4.09558821},
-    {-25.7086525, -2.32914519, 4.23559141},
-    {-25.4906406, -2.25810766, 4.16557741},
-    {-25.2905731, -2.18699622, 4.02557659},
-    {-25.2941265, -2.47130823, 4.02557993},
-    {-25.3870544, -2.96892047, 4.16557693},
-    {-25.6978703, -2.54243159, 4.16557693},
-    {-25.805048, -3.03998852, 3.95556951},
-    {-25.390625, -3.03998852, 3.88556576},
-    {-25.7050037, -3.03997636, 4.09558058},
-    {-25.5012856, -3.18212366, 3.95557928},
-    {-25.3905735, -3.67972159, 4.02557516},
-    {-25.4906063, -3.67973256, 4.09557438},
-    {-25.3905926, -3.67972207, 4.02557421},
-    {-25.2940216, -3.8218627, 3.9555757},
-    {-25.1833439, -3.96404767, 4.1655817},
-    {-25.4048557, -4.17725468, 4.02558756},
-    {-25.1976128, -4.24833632, 3.7455709},
-    {-24.876152, -4.24836397, 3.53554964},
-    {-25.2941551, -4.46160078, 3.46554852},
-    {-25.0834007, -4.46160936, 3.6755569},
-    {-24.4616909, -4.532691, 3.74556065},
-    {-25.0833244, -5.03026056, 3.39554238},
-    {-25.3977318, -4.95917177, 3.39554429},
-    {-25.190506, -5.03025389, 3.18553281},
-    {-25.0797997, -5.17243195, 3.11552572},
-    {-24.969099, -5.45676947, 3.32553411},
-    {-25.4942493, -5.81216526, 2.76550627},
-    {-25.3977509, -5.81215477, 2.48549151},
-    {-25.1869583, -5.81215906, 2.55549574},
-    {-24.7724895, -5.81216097, 2.13547373},
-    {-24.6758556, -5.95431089, 2.06546712},
-    {-24.5722408, -5.81214762, 1.99546289},
-    {-25.2869301, -6.38081598, 2.20547795},
-    {-25.4906406, -6.30973911, 1.99546802},
-    {-25.0868626, -6.66513586, 1.85545659},
-    {-24.9762039, -6.66514254, 1.71545529},
-    {-24.7619534, -6.73623037, 1.22543323},
-    {-24.7655067, -6.73622751, 1.43543983},
-    {-24.4546852, -6.59406471, 1.08542156},
-    {-25.0762367, -6.87838984, 0.735406637},
-    {-24.4616585, -7.02054787, 0.735395849},
-    {-24.3650684, -7.16270638, 0.595378876},
-    {-24.8690834, -7.02055168, 0.105377465},
-    {-24.6548328, -7.23379946, -0.0346197262},
-    {-24.2474613, -7.30487728, 0.0353704728},
-    {-24.1438503, -7.02055264, -0.174639717},
-    {-24.1473503, -7.30487537, -0.454661369},
-    {-24.6618824, -7.7313652, -0.664663792},
-    {-24.668869, -7.5892005, -0.734684885},
-    {-24.3615875, -7.80244541, -1.29472458},
-    {-24.3580666, -7.3759551, -1.29471409},
-    {-24.1438885, -7.58920097, -1.85472417},
-    {-24.2545185, -7.66028023, -1.43472147},
-    {-24.4581966, -7.4470396, -1.78472888},
-    {-24.1473598, -7.37595654, -2.34475994},
-    {-24.2509136, -7.30487633, -2.69478011},
-    {-23.425581, -7.66028118, -2.83479953},
-    {-23.9366589, -7.66028404, -2.97477889},
-    {-24.1404266, -7.58920383, -3.32478237},
-    {-24.2475128, -7.51812172, -3.39480042},
-    {-23.8504944, -7.51811838, -3.67489314},
-    {-24.1612396, -7.87352467, -4.02490997},
-    {-24.0437355, -7.58920288, -4.30486202},
-    {-23.8364544, -7.23379421, -4.37486744},
-    {-23.3184605, -7.23379517, -4.79488754},
-    {-23.3185081, -7.30487537, -5.14490652},
-    {-23.2046623, -7.3048811, -5.35485888},
-    {-22.8972931, -7.16271687, -5.28487539},
-    {-23.2149029, -7.0205493, -5.4949255},
-    {-23.0077305, -7.09162807, -5.77493906},
-    {-23.1113167, -7.02054644, -6.1949625},
-    {-23.3185272, -6.52297831, -6.61498308},
-    {-22.9040585, -6.8783865, -6.68498755},
-    {-22.9109364, -6.66513586, -6.75503635},
-    {-22.7936554, -6.52298689, -7.17496443},
-    {-22.7936745, -6.23866224, -7.1749649},
-    {-22.9040585, -6.09649229, -7.31502056},
-    {-22.6900501, -5.88325739, -7.38497496},
-    {-22.8039341, -6.02540541, -7.73506832},
-    {-22.2926559, -6.02539492, -8.08514214},
-    {-21.8612766, -5.74109507, -8.22501659},
-    {-22.265543, -5.5278697, -8.4349432},
-    {-21.9547806, -5.38570786, -8.78495789},
-    {-21.9648933, -5.1724453, -9.1350584},
-    {-21.4502811, -4.88811398, -9.34509659},
-    {-21.557169, -5.03026915, -9.69514465},
-    {-21.2630424, -4.88806677, -9.62529087},
-    {-21.4602928, -4.24835634, -9.90521526},
-    {-21.4469738, -4.17731047, -10.1151037},
-    {-21.8680325, -3.96404767, -10.5351887},
-    {-21.4569454, -4.03511953, -10.6752272},
-    {-21.4469032, -3.75082374, -10.9551458},
-    {-20.7316971, -3.89295578, -11.3052635},
-    {-20.9322529, -3.46648836, -11.3051958},
-    {-21.1394825, -3.18216372, -11.725215},
-    {-20.6214561, -2.82675648, -12.0752335},
-    {-21.0391884, -2.75566268, -12.0052652},
-    {-20.841877, -2.6134584, -12.2153873},
-    {-20.4208717, -2.25808072, -12.7053375},
-    {-20.1099834, -2.18699574, -12.635335},
-    {-19.5919514, -1.54726231, -12.8453465},
-    {-19.6890602, -1.47621369, -13.2652931},
-    {-19.8961563, -1.04972422, -13.1252861},
-    {-19.2810841, -0.694283903, -13.0553598},
-    {-19.3814964, -0.552137434, -13.2653313},
-    {-19.692318, -0.338892967, -13.4053392},
-    {-19.1742859, 0.0875946954, -13.6853533},
-    {-19.3846893, 0.300859839, -14.1754217},
-    {-18.8698406, 0.443044126, -14.1754618},
-    {-18.6530533, 0.65622586, -14.3153448},
-    {-18.1414242, 0.940594375, -14.6654482},
-    {-18.7629948, 1.22492158, -14.6654482},
-    {-18.244997, 1.8646543, -14.4554358},
-    {-18.2418423, 2.14895582, -14.6654034},
-    {-18.1414242, 2.50439119, -14.8754587},
-    {-17.6171417, 2.78866363, -14.8753748},
-    {-17.9373245, 2.85982537, -14.7354927},
-    {-17.7238674, 3.28625941, -14.8754129},
-    {-17.9310207, 3.71274972, -15.1554298},
-    {-16.9954891, 3.99704623, -15.1553869},
-    {-17.1965313, 4.13914824, -15.2253027},
-    {-17.099062, 4.56569815, -15.5754128},
-    {-16.8036785, 4.70801353, -15.5756292},
-    {-16.7944736, 5.4187355, -15.5054932},
-    {-17.0016651, 5.9163084, -15.6455002},
-    {-16.6877556, 5.98735476, -15.9254704},
-    {-15.8589125, 6.27168036, -15.8554659},
-    {-15.4444914, 6.7692523, -15.7854624},
-    {-15.240263, 7.12469578, -15.8555126},
-    {-15.4444914, 7.62223005, -16.2054863},
-    {-15.3378649, 8.33300304, -15.7854185},
-    {-15.4384727, 8.47512627, -15.8553782},
-    {-14.920517, 8.75945091, -16.0653877},
-    {-14.9235191, 9.11489582, -16.2054386},
-    {-14.7163229, 9.47030354, -16.0654316},
-    {-14.0917549, 10.2521534, -15.8553753},
-    {-14.0946903, 10.1811161, -15.8554211},
-    {-13.6831942, 10.5365677, -15.9254704},
-    {-13.0558577, 11.3894501, -15.8553753},
-    {-12.952219, 11.8870192, -15.9253798},
-    {-13.5795412, 12.2425232, -15.7154598},
-    {-13.2688103, 12.3846855, -15.8554659},
-    {-12.0254745, 12.6690121, -15.6454544},
-    {-12.0283194, 13.0955524, -15.4354887},
-    {-11.9218884, 13.7352333, -15.4354448},
-    {-11.3982706, 14.0905304, -15.2953501},
-    {-11.3983459, 14.5170164, -15.155344},
-    {-11.6111431, 15.014698, -15.2954378},
-    {-10.6841373, 15.2991409, -15.0855131},
-    {-10.471426, 15.7255154, -14.9454203},
-    {-9.84711933, 16.080862, -14.7353668},
-    {-9.84434128, 16.3651276, -14.4553118},
-    {-9.43536758, 17.1471424, -14.4553957},
-    {-9.95881462, 17.4315929, -14.0354528},
-    {-9.8552084, 17.7870007, -13.6854343},
-    {-9.33445549, 18.2134285, -13.8254013},
-    {-8.60913181, 18.3555927, -13.7553968},
-    {-8.51334, 18.78228, -13.1254768},
-    {-7.89422989, 19.1377525, -12.9155035},
-    {-7.87870693, 19.3506012, -12.7752695},
-    {-7.77765226, 19.9904041, -12.5652943},
-    {-7.16117334, 20.4170284, -12.3553591},
-    {-7.05244303, 20.2747269, -12.0052652},
-    {-6.74162674, 20.4879704, -11.9352627},
-    {-6.32966995, 20.8434467, -11.515274},
-    {-6.32471132, 21.4119549, -11.1651869},
-    {-6.21618509, 21.4118176, -11.2351236},
-    {-5.80173016, 21.6961403, -10.9551086},
-    {-5.59459019, 21.8383007, -10.6050949},
-    {-5.49829054, 22.2650108, -10.5351887},
-    {-4.87193632, 22.4781036, -10.4651213},
-    {-4.1491065, 22.8335857, -10.3251448},
-    {-3.83830953, 22.7625008, -10.1851377},
-    {-3.53218126, 23.0469799, -9.97519016},
-    {-3.42857599, 22.9758987, -9.69517517},
-    {-2.91054893, 23.1891422, -9.48516464},
-    {-2.80461597, 23.4023094, -9.55513668},
-    {-2.28434682, 23.7576389, -9.27509308},
-    {-1.97579169, 23.8288021, -8.92510509},
-    {-1.56584918, 23.8289528, -8.43513298},
-    {-1.14247859, 23.9708061, -8.50502586},
-    {-0.829475045, 24.6104584, -8.57500362},
-    {-0.421484739, 24.6106968, -8.22506618},
-    {-0.417326182, 24.6816177, -8.01500416},
-    {0.301444709, 24.8950996, -7.59505987},
-    {-0.21447815, 24.7528572, -7.66503811},
-    {-0.00509185297, 24.5395355, -7.80501938},
-    {-0.104460336, 24.5393696, -8.71501064},
-    {-0.732505262, 23.8288021, -9.83515167},
-    {-0.732505262, 23.1179867, -11.5152388},
-    {-1.76631987, 21.7673645, -13.1252861},
-    {-3.01419234, 20.2747936, -14.8754606},
-    {-4.25745726, 18.56884, -16.4855442},
-    {-5.18257713, 16.4362125, -17.9554749},
-    {-6.21863604, 14.5170145, -19.0055294},
-    {-7.14591694, 12.5977297, -19.9154625},
-    {-7.87866926, 10.6076069, -20.1256351},
-    {-8.9120636, 8.33296394, -20.6156044},
-    {-9.74356651, 6.20056105, -20.7556667},
-    {-10.7822094, 4.35248423, -20.6857224},
-    {-11.2947025, 2.29107261, -20.545599},
-    {-12.2271185, 0.229710162, -20.4055901},
-    {-12.7450075, -1.6894691, -19.7755642},
-    {-13.2630348, -3.18217587, -19.1455307},
-    {-13.88167, -5.52785015, -17.9554234},
-    {-14.5031462, -7.44703674, -17.0453873},
-    {-15.124712, -9.2951479, -15.925333},
-    {-15.5390577, -10.9300079, -14.8052855},
-    {-15.5330296, -12.209444, -13.4751453},
-    {-16.0509052, -13.2045708, -11.5850725},
-    {-17.400568, -13.9864731, -9.76502514},
-    {-18.3264389, -14.2707653, -8.22491169},
-    {-19.255415, -14.4129114, -6.61482286},
-    {-20.4011974, -13.702136, -4.86479855},
-    {-21.9547653, -12.7070103, -3.25473785},
-    {-23.2045612, -11.1432486, -1.71469307},
-    {-24.0298004, -10.077034, -0.244625106},
-    {-24.4301147, -8.51325035, 1.64546716},
-    {-24.5407162, -7.30488729, 3.95554757},
-    {-24.43713, -6.16759729, 5.98562813},
-    {-24.4370918, -5.88327646, 8.22570705},
-    {-23.8121872, -5.95436287, 11.0257998},
-    {-21.5437393, -5.95434856, 13.4059649},
-    {-20.3040905, -6.38082743, 15.5760803},
-    {-18.2260876, -7.44704294, 18.096117},
-    {-15.4293442, -8.37109375, 20.196207},
-    {-11.4964323, -9.4373045, 22.0863266},
-    {-7.65863323, -10.7167454, 23.4862862},
-    {-3.93938327, -11.6408281, 24.3965359},
-    {0.204097331, -12.2805548, 24.5365391},
-    {5.07676315, -13.0624237, 24.116415},
-    {9.1136713, -13.6310997, 23.136467},
-    {13.2555466, -13.7732735, 21.736454},
-    {16.9875393, -13.7021627, 19.9862862},
-    {19.8881321, -13.6310835, 17.7461815},
-    {22.5814266, -13.2756786, 15.6460848},
-    {24.6532269, -12.991353, 13.8960056},
-    {26.4127636, -12.3516483, 12.4959936},
-    {28.0716057, -12.0673027, 11.3058901},
-    {28.6936874, -11.4275656, 9.97581196},
-    {29.0039005, -11.0721693, 9.2757988},
-    {29.3146477, -11.2143297, 8.29575729},
-    {29.6249294, -11.4275827, 7.66573906},
-    {29.3146648, -11.5697365, 7.10570145},
-    {29.2110767, -12.4227076, 6.89569187},
-    {28.694273, -12.7780905, 6.40565252},
-    {28.7967243, -13.6310835, 5.91564798},
-    {28.6931343, -14.6262159, 5.14561367},
-    {27.865015, -15.5502491, 4.86559486},
-    {27.0350513, -16.1900177, 4.93560839},
-    {26.3099327, -17.1140709, 3.9555645},
-    {25.7926636, -18.1091824, 3.60554409},
-    {24.652401, -19.2465038, 3.1155231},
-    {23.4092369, -20.3127232, 2.55549693},
-    {22.2706966, -21.0945816, 2.48549414},
-    {21.028635, -21.8764362, 2.41549063},
-    {19.4759312, -22.7293701, 3.53553748},
-    {17.4031315, -23.4402161, 4.79559422},
-    {15.4378347, -23.7955379, 6.54564285},
-    {12.8482637, -24.1509418, 7.80569696},
-    {10.2592478, -24.2931023, 9.41575432},
-    {7.98409605, -24.0087032, 11.1657782},
-    {5.702034, -23.5823002, 12.4258699},
-    {3.73014903, -23.1558895, 13.9659843},
-    {2.47928166, -22.1608982, 15.7161884},
-    {2.17053175, -20.7392426, 17.9562607},
-    {1.76431549, -19.2464237, 19.2161636},
-    {1.87198687, -17.6826038, 20.4061241},
-    {2.70059276, -16.3320732, 21.5961723},
-    {4.72092676, -15.479105, 22.7861843},
-    {6.11807775, -15.1237154, 22.6462059},
-    {8.60536766, -13.9864159, 22.6461563},
-    {12.1752253, -13.6665821, 22.1562347},
-    {13.1591473, -13.0623989, 22.0162315},
-    {15.2293291, -12.0672827, 21.2462463},
-    {16.5757523, -11.7118807, 20.8962345},
-    {17.8198471, -11.4986296, 20.546175},
-    {19.2688427, -11.1432352, 19.7761898},
-    {19.6820927, -11.0721626, 19.3562145},
-    {20.253767, -11.107688, 19.0061169},
-    {20.3045349, -11.1432352, 18.5161362},
-    {20.5644779, -11.107688, 18.7961102},
-    {20.1998787, -11.1432438, 19.146204},
-    {19.1652374, -11.4986372, 19.146162},
-    {17.9199543, -11.1077099, 19.9512787},
-    {17.094902, -11.5697088, 20.3361664},
-    {15.9543085, -11.5697193, 21.2462463},
-    {13.8839931, -11.3209267, 22.1562424},
-    {11.5537977, -11.0010672, 22.4712486},
-    {10.4662991, -10.929987, 23.1362743},
-    {7.66821194, -10.5745916, 24.3263721},
-    {5.34240246, -9.82823563, 25.0962639},
-    {4.09668207, -9.29513741, 25.0963459},
-    {1.30026186, -8.65541363, 25.0963459},
-    {-1.0300858, -7.37596607, 25.6213665},
-    {-3.05328894, -6.736238, 25.7264557},
-    {-4.92126465, -5.56339788, 25.5165291},
-    {-7.76730204, -4.46165371, 25.2364616},
-    {-8.953269, -3.53762412, 24.5713272},
-    {-10.8175488, -2.89789987, 24.0463066},
-    {-11.2809, -1.4052285, 23.9762554},
-    {-12.0001049, -0.694461167, 23.4861355},
-    {-12.3668756, -0.339033633, 23.2061996},
-    {-12.6903887, -0.0190853737, 23.31143},
-    {-12.3711176, 0.30071795, 23.4162846},
-    {-12.6903601, 0.620642483, 23.5214405},
-    {-11.1366396, 0.514022052, 23.6264458},
-    {-12.0604811, 0.194099993, 23.4162827},
-    {-10.8693562, 0.442878485, 24.2563171},
-    {-10.141634, 0.656097949, 24.4662704},
-    {-9.41934109, 0.58503902, 24.8863392},
-    {-8.17907333, 0.656141222, 25.0964012},
-    {-7.97711611, 0.58510232, 25.3065224},
-    {-6.93872023, 0.300757527, 25.3064651},
-    {-6.4182229, -0.0546644777, 25.7964306},
-    {-5.38499975, 0.0164358784, 25.936491},
-    {-4.55629444, -0.623291969, 25.936491},
-    {-4.14195824, -1.40517914, 26.1465015},
-    {-3.20509195, -1.68953371, 26.2863884},
-    {-2.6849463, -2.18711019, 26.146328},
-    {-2.88974428, -2.54252553, 26.3562794},
-    {-2.79074144, -2.61357951, 26.3563957},
-    {-2.16938448, -2.4714191, 26.3563938},
-    {-2.06803513, -2.82680559, 26.2864513},
-    {-2.48008204, -2.54249549, 26.5664043},
-    {-2.80003238, -2.25811982, 26.4966335},
-    {-3.11079621, -1.90271473, 26.3566265},
-    {-3.72999692, -1.47624481, 26.0065517},
-    {-4.24793863, -0.623273671, 26.0765572},
-    {-5.07664871, 0.15861772, 25.6565361},
-    {-5.59451437, 1.08266842, 25.7265415},
-    {-7.03719091, 1.93556643, 25.376358},
-    {-7.97461748, 2.78858805, 25.0264511},
-    {-8.49764633, 3.92593431, 24.4665356},
-    {-9.94265938, 4.99208975, 24.116415},
-    {-10.8775883, 5.77400923, 23.1364231},
-    {-11.8098135, 6.7691412, 22.2263851},
-    {-13.2572594, 7.83531857, 21.5263042},
-    {-13.8874788, 8.0486784, 21.036417},
-    {-14.0917072, 8.61728764, 19.6363106},
-    {-15.2282934, 9.11481571, 18.726223},
-    {-15.9503775, 9.75449848, 17.9561539},
-    {-16.6816425, 10.1810732, 17.3261948},
-    {-17.4129333, 10.3233232, 16.5562286},
-    {-17.7175159, 10.5364771, 15.7861252},
-    {-18.5494766, 10.8208456, 15.3661327},
-    {-18.7630424, 10.5366135, 14.5261536},
-    {-18.7535191, 10.9629631, 14.6660719},
-    {-18.43326, 11.389308, 14.4559736},
-    {-19.2714462, 11.1762066, 13.9660368},
-    {-19.3847408, 10.6787758, 13.8261137},
-    {-19.3846893, 10.9631033, 13.8961172},
-    {-19.2746849, 10.8208494, 14.1760759},
-    {-18.7630749, 10.5366135, 14.3861456},
-    {-18.3517933, 10.7499056, 14.8061972},
-    {-18.1350536, 10.6076059, 15.016118},
-    {-18.6498795, 10.4653969, 15.7861261},
-    {-17.8211784, 10.5364771, 15.9961348},
-    {-17.1965122, 10.6785936, 16.4161167},
-    {-16.7790165, 10.9628706, 16.8361034},
-    {-16.2672501, 10.6786394, 17.2561913},
-    {-15.4324884, 10.9628706, 17.3961277},
-    {-15.2282982, 11.1761618, 17.8861885},
-    {-14.9145889, 11.3893557, 18.1661606},
-    {-13.7752008, 11.5315161, 18.5861797},
-    {-13.050086, 11.9580021, 18.9361935},
-    {-13.0558052, 12.242425, 19.5663052},
-    {-11.809885, 12.2423735, 19.7062683},
-    {-10.9839344, 13.0243187, 19.5663052},
-    {-10.566843, 13.308589, 19.9162788},
-    {-9.63975716, 13.2376108, 20.1963768},
-    {-8.61178684, 13.8775063, 20.1965046},
-    {-7.57300663, 14.2328587, 20.3364697},
-    {-6.53195047, 14.8724813, 20.1963787},
-    {-5.59706974, 14.9435081, 20.6863556},
-    {-5.08154106, 14.9435616, 20.8964119},
-    {-3.9372077, 14.7302084, 21.1063309},
-    {-3.42159367, 14.8013449, 21.3863888},
-    {-2.0703485, 14.6590719, 21.5963078},
-    {-1.76631987, 14.6592379, 21.8064613},
-    {-0.836110651, 14.3038855, 21.7364998},
-    {-0.525294423, 14.2328024, 22.0865192},
-    {0.303582191, 14.5171289, 22.1565189},
-    {0.610140145, 14.8726473, 21.8065968},
-    {0.620694458, 14.8723669, 21.5963516},
-    {1.03091013, 15.3700523, 21.316433},
-    {1.65247369, 15.9386997, 21.1764259},
-    {1.44110191, 16.6496372, 20.6164837},
-    {1.33544695, 17.3605099, 20.126503},
-    {0.823680222, 18.2843819, 19.2163296},
-    {-0.106545553, 18.7818851, 18.5862579},
-    {-0.212288439, 19.1373577, 17.9562626},
-    {-0.42384547, 19.7772236, 17.1862984},
-    {-1.14244533, 20.4878311, 16.2061462},
-    {-1.66495633, 21.1277084, 15.5061741},
-    {-2.80230761, 21.554121, 14.876112},
-    {-3.21669126, 21.554121, 13.8260603},
-    {-4.25512505, 21.9095974, 13.266057},
-    {-4.98274279, 22.051836, 12.8460598},
-    {-5.49835682, 22.1228466, 12.3560095},
-    {-6.63799286, 21.9095974, 11.5159655},
-    {-7.66892195, 21.6962128, 11.3759146},
-    {-8.38623238, 21.4116707, 11.4458542},
-    {-8.70220184, 21.4828968, 11.305891},
-    {-9.22546864, 20.9143906, 11.445941},
-    {-10.4659643, 20.7721577, 11.2359085},
-    {-11.3983269, 20.4878311, 11.165905},
-    {-11.9162645, 19.8481026, 11.2359095},
-    {-12.2214422, 19.7058048, 11.3758717},
-    {-12.7479715, 19.2795181, 11.305932},
-    {-13.4788809, 18.8531628, 11.5159855},
-    {-13.2629824, 18.5686436, 11.6559296},
-    {-14.3078289, 18.2134285, 11.5159864},
-    {-14.9294662, 18.2134285, 11.4459829},
-    {-14.8198757, 18.0000591, 11.3759365},
-    {-14.5061855, 17.5735073, 11.4459181},
-    {-14.8199949, 17.360323, 11.3759356},
-    {-15.4475126, 17.0761261, 11.1659689},
-    {-15.6426535, 17.0758762, 11.2358875},
-    {-15.6486483, 17.4314079, 10.9559145},
-    {-15.1367102, 17.7869377, 10.6759415},
-    {-14.408432, 17.929039, 10.7459259},
-    {-14.6126461, 17.7868137, 10.4658918},
-    {-14.9204607, 18.1421566, 10.2558622},
-    {-14.7132874, 18.4264793, 10.3258657},
-    {-14.7221842, 18.4266739, 10.1159105},
-    {-14.7163038, 18.5687065, 10.1158743},
-    {-14.4113817, 18.5688381, 9.90589809},
-    {-13.9998436, 18.9953938, 9.8359127},
-    {-13.8933411, 19.2796555, 9.90589905},
-    {-13.0615616, 19.4217529, 9.90588093},
-    {-12.445591, 19.7062149, 9.69590282},
-    {-12.5491972, 20.0616207, 9.76590824},
-    {-12.6528168, 19.9194546, 9.55589581},
-    {-12.3391409, 20.4169579, 9.27586365},
-    {-11.821023, 20.8434467, 9.34586906},
-    {-11.1013527, 20.8435917, 9.48590946},
-    {-10.7849836, 21.1988583, 9.6258831},
-    {-10.3678398, 21.1277027, 9.3458519},
-    {-9.94529629, 21.4118137, 9.34580231},
-    {-9.53629875, 21.6962833, 9.20582771},
-    {-9.74350929, 21.980608, 8.92581367},
-    {-9.42738724, 22.2647877, 8.22575283},
-    {-8.80844879, 22.4070225, 8.08575916},
-    {-8.81107044, 22.9757462, 7.66575098},
-    {-8.39143753, 23.1888371, 7.17570496},
-    {-7.76993847, 23.4020805, 6.68568277},
-    {-7.67152452, 23.6865597, 5.63564777},
-    {-7.88129091, 23.6866379, 4.93562126},
-    {-7.46431398, 23.6865578, 4.2355814},
-    {-7.35558796, 23.9707279, 3.53554082},
-    {-7.56793833, 24.3262901, 2.69550157},
-    {-7.05497932, 24.6107769, 1.57544303},
-    {-6.84271479, 24.3973713, 0.525395751},
-    {-7.15347862, 24.6106186, -0.384650797},
-    {-7.46435165, 24.3262901, -1.01468015},
-    {-7.57316303, 24.3975334, -1.85474932},
-    {-7.88907146, 24.8241787, -2.48480392},
-    {-8.09110451, 24.6818562, -3.04481125},
-    {-7.98228884, 24.3973713, -2.90477681},
-    {-8.39407444, 23.7575626, -3.04476857},
-    {-8.70755005, 23.5443974, -3.11478448},
-    {-8.71016788, 23.4733925, -2.62477469},
-    {-8.92265606, 23.4735432, -2.27477932},
-    {-9.96150303, 23.6157875, -1.92477131},
-    {-9.95074368, 23.4733181, -0.874677837},
-    {-10.6731701, 23.0467529, 0.0353767686},
-    {-11.1013899, 22.7628021, 0.7353912},
-    {-12.0282536, 22.691576, 1.71544874},
-    {-12.227066, 22.0516148, 2.76550841},
-    {-12.1234798, 21.4829693, 3.81555557},
-    {-12.8486605, 20.9854012, 4.51559019},
-    {-13.7838831, 20.6300659, 4.93561506},
-    {-14.408432, 20.6301327, 5.14563179},
-    {-14.5120382, 20.345808, 5.42564631},
-    {-15.2372808, 19.848238, 5.70566082},
-    {-15.337903, 19.5638447, 5.14562607},
-    {-15.225296, 19.4214821, 4.93559885},
-    {-15.3348389, 19.563776, 4.72559452},
-    {-15.6516495, 19.7771549, 4.02557278},
-    {-15.7492704, 19.7059383, 3.39553833},
-    {-15.7522345, 20.2035789, 2.83551049},
-    {-15.2402439, 20.1326332, 1.78545237},
-    {-14.7251863, 20.4170284, 0.875399649},
-    {-13.9969797, 20.559124, 0.315374017},
-    {-13.4730864, 20.9854736, -0.384650499},
-    {-13.0587025, 21.4830399, -0.594660401},
-    {-12.7450266, 21.6251297, -0.454645485},
-    {-12.2355309, 21.9807529, 0.385378748},
-    {-11.6138983, 22.3361626, 1.29542637},
-    {-11.1884422, 22.5491085, 2.90550685},
-    {-10.5640497, 22.3357887, 4.58558893},
-    {-9.74349499, 22.1227703, 6.5456953},
-    {-9.53096008, 22.0515461, 8.78577328},
-    {-9.11924553, 21.1986408, 10.6058836},
-    {-8.70747471, 21.0565548, 12.0059671},
-    {-8.29305744, 20.6300659, 12.7760067},
-    {-7.77254629, 20.4878349, 13.8260336},
-    {-6.94633436, 20.4168224, 14.4560909},
-    {-6.74669933, 20.5591946, 14.3861732},
-    {-6.84271479, 20.7011452, 13.8260584},
-    {-6.0040102, 20.7719479, 13.3359299},
-    {-5.91280222, 21.6963596, 12.56602},
-    {-5.80671263, 22.1938515, 11.6559505},
-    {-4.97554207, 22.7624302, 10.8158884},
-    {-4.87195539, 23.4732399, 9.76583576},
-    {-5.49591541, 23.6154747, 9.41583824},
-    {-5.2911458, 23.6866379, 9.13584042},
-    {-4.77072477, 23.4733143, 9.06582165},
-    {-4.3491497, 23.4020061, 9.4157896},
-    {-4.87442064, 22.9757423, 9.97586918},
-    {-5.1851325, 22.9046631, 10.6758995},
-    {-5.39230537, 22.5492573, 11.725956},
-    {-5.29357815, 22.0518379, 12.8460598},
-    {-5.39475155, 21.4120312, 13.68608},
-    {-5.80424738, 20.9854012, 13.9660387},
-    {-6.01387119, 20.7011452, 14.316083},
-    {-6.3322444, 20.6302757, 14.3161688},
-    {-6.94374084, 20.7721558, 13.9660397},
-    {-7.04730844, 20.6299973, 13.6860247},
-    {-7.46173, 20.7721577, 13.1259985},
-    {-7.87871647, 21.1987171, 12.1459732},
-    {-8.7047863, 21.3408051, 11.3759155},
-    {-9.2254734, 21.9095287, 10.3958807},
-    {-9.85519028, 22.0519085, 9.06587029},
-    {-10.1606102, 22.1939259, 7.94577837},
-    {-10.566843, 22.3358669, 6.82569361},
-    {-11.0875778, 22.5491886, 5.70564365},
-    {-11.1994429, 22.5494099, 4.93562746},
-    {-11.7146912, 22.265007, 3.95556951},
-    {-12.5406561, 22.0516891, 2.90551353},
-    {-12.5406752, 21.9095268, 1.99546957},
-    {-13.0644646, 21.9096756, 1.01540899},
-    {-13.6918583, 21.4833336, 0.315364718},
-    {-13.9911137, 20.9143887, -0.664664388},
-    {-14.1924343, 20.5588455, -1.08466828},
-    {-14.8228588, 20.2036476, -1.36470854},
-    {-15.6547422, 19.8483067, -1.71473753},
-    {-16.066124, 19.350666, -1.9947418},
-    {-16.3677578, 18.9950638, -1.64469385},
-    {-17.7144203, 18.7818203, -0.944659948},
-    {-17.8274345, 18.355526, -0.174646005},
-    {-17.9309883, 17.6447144, 1.01541209},
-    {-18.4458752, 17.3603268, 2.41549158},
-    {-18.4521885, 17.2182865, 4.30559254},
-    {-18.5591087, 16.7207756, 5.91569376},
-    {-18.5685806, 16.0101337, 8.08585262},
-    {-18.5589657, 15.0148144, 9.90591145},
-    {-18.5494995, 13.5930195, 12.2859802},
-    {-18.1287708, 12.1002111, 14.4560356},
-    {-18.1382313, 10.4654865, 16.4862251},
-    {-16.7913609, 8.40412998, 18.0263042},
-    {-16.4744091, 5.98728371, 19.6363106},
-    {-15.7553644, 3.42842603, 20.8964558},
-    {-15.0241041, 0.656204522, 21.5263977},
-    {-14.6097012, -1.97379625, 22.2964344},
-    {-13.9852238, -4.46164703, 22.3663902},
-    {-12.7507458, -7.37595701, 22.1565208},
-    {-11.5047398, -10.0059614, 21.596447},
-    {-10.9922705, -12.9914141, 20.8264923},
-    {-10.6841898, -14.9106216, 19.6364765},
-    {-10.1579027, -16.2611179, 18.5162926},
-    {-9.23345757, -17.8249779, 17.3263397},
-    {-8.50555992, -18.3936062, 16.7662735},
-    {-8.71541595, -19.1044502, 16.2762794},
-    {-8.29833031, -19.4598312, 16.0662365},
-    {-8.09112358, -19.317667, 15.996232},
-    {-8.51078892, -18.8201485, 16.6963406},
-    {-8.30873203, -18.3226242, 17.7464771},
-    {-8.82426548, -17.1142044, 18.5164852},
-    {-9.03417873, -15.479331, 19.5665932},
-    {-9.24413109, -13.8444538, 20.8967247},
-    {-9.76233387, -11.9252272, 21.8767891},
-    {-10.1741476, -9.86383247, 22.716795},
-    {-10.6950769, -7.7313571, 23.1368732},
-    {-10.9078779, -5.59887123, 23.557003},
-    {-11.4261475, -3.67963886, 23.4169941},
-    {-11.6334581, -2.40014458, 23.4869995},
-    {-12.2609949, -1.61820316, 23.4170971},
-    {-12.8800764, -0.836306214, 23.0670185},
-    {-12.9895153, 0.0167287886, 22.9971142},
-    {-13.4933729, 0.300961554, 22.3668232},
-    {-14.218853, 0.0166313555, 22.8568535},
-    {-14.3283625, -0.267660469, 22.576931},
-    {-14.7340727, -0.978539824, 22.3667736},
-    {-14.7311049, -1.47613335, 22.1567116},
-    {-14.8436584, -2.82665706, 21.7368259},
-    {-14.7400198, -3.96397734, 21.7368259},
-    {-15.1546316, -4.8169713, 21.4568062},
-    {-14.9443378, -6.02538013, 21.0367336},
-    {-15.3678656, -6.80727959, 20.7568455},
-    {-15.3634243, -7.37594414, 20.3717518},
-    {-16.4563026, -7.69581652, 20.0567951},
-    {-16.2033024, -7.94460583, 19.8468628},
-    {-16.520422, -7.87352371, 19.9869595},
-    {-17.3466606, -7.87352324, 19.8469048},
-    {-16.724678, -7.73135614, 19.6368885},
-    {-16.5112247, -7.58919144, 19.6368046},
-    {-16.9273949, -7.05606556, 19.5318165},
-    {-16.621006, -7.02052069, 19.7068939},
-    {-16.9366665, -6.52293015, 20.267004},
-    {-15.8525667, -6.7361784, 19.9520378},
-    {-15.2303839, -6.842803, 20.2670689},
-    {-15.0688524, -6.59401655, 20.7570229},
-    {-15.2259569, -6.09642744, 20.7920475},
-    {-14.2971888, -6.30967283, 20.8971233},
-    {-15.2213964, -6.52293587, 21.2120171},
-    {-14.4571285, -6.84279823, 21.2122211},
-    {-14.4571285, -7.37593126, 20.8971901},
-    {-14.040864, -8.0156908, 20.7571564},
-    {-14.5563545, -8.58436108, 20.4070816},
-    {-14.6171017, -9.29521561, 19.9521675},
-    {-15.2483664, -9.8283596, 19.6372604},
-    {-15.2393751, -10.8946152, 19.5321274},
-    {-15.1875391, -11.2855816, 19.0070724},
-    {-14.562396, -11.7831621, 18.8670235},
-    {-13.6290026, -11.8542471, 19.147049},
-    {-13.6793375, -12.2807474, 19.5320663},
-    {-12.7042246, -12.2096996, 19.9172478},
-    {-11.9767876, -11.8542709, 20.1622524},
-    {-11.8211994, -12.3874063, 20.0572395},
-    {-11.5142212, -12.1741676, 20.5823593},
-    {-10.3159046, -11.9964352, 20.8272972},
-    {-9.69365406, -11.8542662, 21.3173447},
-    {-9.07398796, -11.7831907, 21.7374325},
-    {-8.44907856, -11.7120972, 22.1574249},
-    {-8.34272289, -11.5699186, 22.2973938},
-    {-8.65383339, -11.0012407, 22.8574486},
-    {-8.34275627, -10.6458178, 23.4875069},
-    {-7.92269135, -10.3614683, 23.4874039},
-    {-7.71786022, -9.508461, 23.8374882},
-    {-7.82674742, -8.72653675, 23.9075985},
-    {-7.31074858, -8.15785885, 24.117672},
-    {-8.03151226, -7.66026688, 23.9775543},
-    {-8.55014229, -6.94941998, 24.1875725},
-    {-8.87187862, -5.95421553, 24.4678154},
-    {-9.28676605, -5.45662117, 24.1177769},
-    {-9.91462135, -5.24335051, 23.8378506},
-    {-10.7500334, -4.81682205, 23.6279297},
-    {-11.678174, -4.46140957, 23.487812},
-    {-12.7127562, -4.24816275, 23.2777424},
-    {-13.7531042, -3.60838199, 22.6477184},
-    {-14.3725891, -3.60839295, 21.8075809},
-    {-15.1934814, -3.46625495, 21.3173904},
-    {-16.029398, -3.4662323, 20.8974361},
-    {-17.5884705, -3.46622086, 19.7773609},
-    {-18.5220966, -3.46622086, 19.0072765},
-    {-19.3455639, -3.39515948, 18.3771305},
-    {-19.7539864, -3.75060463, 17.3969593},
-    {-20.7944679, -4.17710495, 16.2768784},
-    {-21.3230534, -4.24816084, 15.3668814},
-    {-22.2566242, -3.67947817, 14.4567852},
-    {-22.6783409, -3.8927145, 13.5467367},
-    {-23.0831356, -4.2481699, 13.0566082},
-    {-23.4946308, -4.10600901, 12.5665293},
-    {-23.4946117, -3.5373292, 12.0064716},
-    {-24.2206993, -3.7505846, 11.446413},
-    {-24.2206993, -3.60841417, 11.0963774},
-    {-24.7357903, -3.60842371, 10.7463198},
-    {-24.4351501, -3.25296521, 10.2563286},
-    {-23.9061317, -3.39516973, 10.396287},
-    {-23.8990822, -3.6084466, 10.6062679},
-    {-23.6951771, -3.82168794, 10.7462997},
-    {-24.1170464, -3.8927536, 11.1663847},
-    {-24.3208942, -3.89276552, 11.5864067},
-    {-23.6951542, -4.17711353, 12.0064249},
-    {-23.166254, -4.17714167, 12.2163763},
-    {-22.7514515, -4.53256369, 12.6364155},
-    {-22.4437561, -4.60364008, 13.4765148},
-    {-21.9185429, -5.10124302, 13.6864815},
-    {-21.6108131, -5.52774239, 14.5965948},
-    {-21.507122, -5.38557434, 15.0166311},
-    {-20.7811623, -5.52774286, 15.9267168},
-    {-20.1557503, -6.16750383, 16.5567379},
-    {-19.6372719, -6.6650939, 17.0467834},
-    {-19.008728, -6.7361846, 17.3267345},
-    {-19.4234486, -6.80726767, 17.3967419},
-    {-19.2193298, -6.73618078, 17.7468071},
-    {-18.5940495, -6.45184851, 17.8867836},
-    {-18.3929844, -6.38075781, 18.2368889},
-    {-18.4966946, -6.6650939, 18.3068981},
-    {-18.901844, -6.52293587, 18.0967617},
-    {-18.2892799, -6.45183945, 18.3768997},
-    {-18.5030499, -6.16749573, 18.0969524},
-    {-19.0183697, -6.16750002, 18.026907},
-    {-19.2257519, -6.23858404, 17.5368633},
-    {-19.3326721, -6.09641027, 17.4668884},
-    {-18.8110542, -5.88316345, 17.1168251},
-    {-19.1124039, -5.59884405, 16.7666893},
-    {-20.1557693, -5.45666409, 16.6967506},
-    {-20.4701042, -5.38557386, 16.4167595},
-    {-20.8782749, -5.31450272, 16.4867001},
-    {-21.293005, -5.10125208, 16.1366692},
-    {-20.6742039, -4.81690741, 15.7166634},
-    {-20.5705128, -4.81690788, 15.8566751},
-    {-20.8815861, -4.81690788, 16.2067089},
-    {-20.985281, -4.53257132, 15.9266825},
-    {-20.6742134, -4.24823523, 16.5567379},
-    {-19.7409763, -4.10606718, 16.8367634},
-    {-19.6340275, -4.10607672, 17.3967781},
-    {-19.4298553, -3.32413912, 17.886858},
-    {-19.5400543, -3.32411933, 18.376976},
-    {-18.3898792, -3.25307107, 19.0769215},
-    {-17.4566517, -2.75548315, 19.5669632},
-    {-17.7614632, -2.11575818, 19.8469048},
-    {-16.5081329, -1.26280367, 20.546833},
-    {-16.2062798, -0.62300086, 21.1070099},
-    {-15.0689812, 0.158935592, 21.3870754},
-    {-14.8645296, 0.727626443, 21.8771629},
-    {-14.1357861, 2.14927745, 22.4371643},
-    {-13.1968451, 3.3576479, 22.7870941},
-    {-12.2666759, 4.63717794, 22.7171402},
-    {-12.3703527, 5.63234806, 22.507122},
-    {-12.1686325, 6.98301172, 22.2271919},
-    {-11.9584818, 8.76006126, 21.5970955},
-    {-12.0536652, 10.5370197, 20.8969021},
-    {-11.4345026, 11.8876505, 20.0568771},
-    {-12.0536652, 13.167098, 19.2867794},
-    {-12.2581825, 14.3754597, 17.8866348},
-    {-13.5049677, 15.0863457, 16.3465538},
-    {-13.9255219, 15.9394646, 14.9465017},
-    {-14.8555527, 16.7213211, 13.3363504},
-    {-15.7795134, 16.7922192, 12.0761776},
-    {-16.8129463, 16.6499939, 10.7460651},
-    {-17.5447578, 16.579031, 9.345994},
-    {-18.3802929, 16.2948189, 7.80591059},
-    {-19.5206318, 15.7261534, 5.98576593},
-    {-20.3466969, 15.0152626, 4.23562527},
-    {-21.380024, 14.5176229, 2.27547407},
-    {-21.1826553, 13.6647844, 0.385315031},
-    {-21.4768658, 12.8826141, -1.22476232},
-    {-22.3095417, 12.3850832, -2.83489442},
-    {-21.7846146, 11.7452431, -4.37496853},
-    {-21.4736557, 11.1765842, -5.42503881},
-    {-21.1726227, 10.6791391, -6.47517872},
-    {-20.6543789, 10.7502222, -7.10522366},
-    {-20.450388, 11.1767693, -7.80530119},
-    {-20.236536, 11.5320873, -8.15527439},
-    {-19.9288406, 11.9586353, -7.9452858},
-    {-19.4072933, 12.4561663, -7.73524475},
-    {-19.2972145, 13.0247231, -7.315166},
-    {-19.5109653, 13.5934944, -7.38521957},
-    {-20.0226955, 13.4512215, -7.03514719},
-    {-20.2299728, 13.0247278, -7.45517492},
-    {-20.3335972, 12.0295687, -7.8752017},
-    {-21.1626205, 10.5368443, -8.01521111},
-    {-22.1923389, 9.18618679, -8.43518734},
-    {-22.1991405, 7.26705027, -8.4352417},
-    {-22.9212189, 5.1345377, -7.80517292},
-    {-24.0785999, 3.71303225, -6.61520576},
-    {-24.486187, 3.1443181, -5.6350975},
-    {-25.2011471, 2.64665771, -3.95492697},
-    {-25.5120621, 2.43341088, -1.85478687},
-    {-25.7121677, 2.14903378, -0.384683192},
-    {-25.8229694, 1.58041906, 1.3654269},
-    {-25.8301125, 0.300983459, 3.04552817},
-    {-25.82654, -1.04960668, 4.44562244},
-    {-25.7086525, -2.40021992, 4.86562824},
-    {-25.7122383, -4.53268242, 4.72562361},
-    {-25.5049381, -6.23864079, 3.25554061},
-    {-25.086916, -7.09162712, 1.15541828},
-    {-24.2579288, -6.7362175, -0.734694123},
-    {-24.1543045, -6.0964818, -2.69480419},
-    {-23.9540672, -5.31456709, -4.37493658},
-    {-24.1613121, -4.10617399, -5.84502459},
-    {-23.5360928, -2.75562429, -6.89506769},
-    {-23.1216049, -1.90264046, -7.66511393},
-    {-23.5465984, -0.978522182, -8.43524075},
-    {-23.1250343, 0.443087369, -8.7852087},
-    {-22.7139568, 1.93583381, -9.34527206},
-    {-21.8781395, 2.71768689, -10.1852636},
-    {-21.8781395, 3.78392005, -10.3252707},
-    {-21.9918442, 4.99241114, -10.2553587},
-    {-21.3734131, 6.27192163, -10.1153822},
-    {-21.4669819, 7.26696968, -10.1852961},
-    {-21.2596798, 8.75969696, -9.41524696},
-    {-21.1527309, 9.39939213, -8.99519634},
-    {-21.456974, 9.82579803, -8.15508938},
-    {-21.7745056, 10.1102123, -7.17508459},
-    {-22.1821918, 9.89687824, -6.40499496},
-    {-22.3860588, 9.54142857, -5.70493555},
-    {-22.7002563, 8.75957394, -5.07492256},
-    {-23.2149029, 7.97763586, -4.44487},
-    {-24.043745, 7.19573975, -3.74483323},
-    {-24.1508427, 6.69820452, -2.97480583},
-    {-24.9796848, 6.0584712, -2.06475735},
-    {-25.2905827, 5.20549107, -1.5747298},
-    {-25.2834492, 4.21029091, -1.01468134},
-    {-25.4906788, 3.64163899, -0.104635715},
-    {-25.7086048, 2.93090558, 0.735392451},
-    {-25.6049614, 2.22008848, 1.57543945},
-    {-25.2905731, 1.79357398, 2.48549056},
-    {-25.7014332, 1.43814278, 3.04552197},
-    {-25.594265, 0.94054991, 3.8855629},
-    {-25.6978359, 0.585144341, 4.72560501},
-    {-26.0014858, 0.158616498, 5.2156167},
-    {-25.9086189, -0.552138627, 6.12568474},
-    {-25.5978184, -0.694300354, 6.75571537},
-    {-25.5907173, -1.40514803, 7.24571896},
-    {-24.9620686, -2.1870687, 7.87572384},
-    {-24.7619343, -3.11109424, 8.50577927},
-    {-24.5582581, -4.17730236, 8.57579613},
-    {-24.6618824, -5.1724391, 8.50579262},
-    {-24.7725086, -6.52297688, 8.57582664},
-    {-24.0438213, -7.9446044, 8.36580276},
-    {-23.8296089, -8.86866379, 7.52573061},
-    {-23.5257187, -9.93488884, 6.75571585},
-    {-22.9040871, -11.001111, 6.05567932},
-    {-22.7902393, -11.7829762, 5.21561909},
-    {-22.2689075, -12.1383734, 4.09556103},
-    {-22.8938255, -12.4227076, 2.27548432},
-    {-23.1112309, -12.4938221, 1.57544398},
-    {-22.4930611, -12.1384258, 0.175368264},
-    {-22.6934452, -11.4986734, -1.15468788},
-    {-22.7902489, -11.0010891, -2.27472067},
-    {-22.8938351, -9.79271317, -3.88479328},
-    {-23.1010094, -8.6554184, -4.65482855},
-    {-23.3185844, -7.73135996, -5.49492788},
-    {-23.9505615, -6.16755867, -6.33503532},
-    {-23.6362686, -5.03025866, -6.61502838},
-    {-24.1439075, -3.67973256, -6.82497168},
-    {-24.1334629, -2.18707347, -7.17491627},
-    {-23.5153255, -0.765429974, -7.52495766},
-    {-23.629324, 0.371920615, -7.38502407},
-    {-23.9436264, 1.72249186, -7.31504393},
-    {-23.6189651, 2.43320632, -7.38495207},
-    {-23.5188217, 3.07296395, -6.89495039},
-    {-23.8295708, 4.06809711, -6.68494225},
-    {-23.73633, 4.49467516, -6.54500246},
-    {-23.6223984, 5.13431358, -6.61493778},
-    {-23.4083099, 5.27641201, -6.19487476},
-    {-23.6293755, 5.70303249, -5.77493906},
-    {-23.8331299, 5.98732042, -5.77491951},
-    {-23.6189499, 6.05833387, -5.21485329},
-    {-23.8191452, 6.34258795, -5.00480604},
-    {-23.9227695, 6.05826569, -4.65479136},
-    {-24.2404785, 6.27157688, -4.4448185},
-    {-24.3475323, 6.12944937, -4.44483614},
-    {-24.0402317, 5.77407742, -5.07488441},
-    {-24.1438751, 5.06326485, -5.35489655},
-    {-24.0403023, 4.70785856, -5.42490196},
-    {-23.515379, 4.28131151, -6.12489271},
-    {-22.9939747, 3.99695849, -7.24492121},
-    {-22.8938255, 3.21509647, -8.08498096},
-    {-22.2756805, 2.29106879, -9.34506702},
-    {-22.0617619, 1.65129471, -10.675065},
-    {-21.0225925, 0.513978243, -11.6550722},
-    {-20.508028, 0.0164364874, -12.7051506},
-    {-19.7796688, -0.623309016, -13.5451508},
-    {-19.0610676, -0.765434861, -14.5252724},
-    {-17.7175407, -0.836498022, -15.435358},
-    {-17.0867176, -0.33898735, -16.0652485},
-    {-16.8826599, 0.442921728, -16.4153099},
-    {-17.4037037, 1.65131783, -16.3453541},
-    {-17.3000641, 2.78860879, -16.2753506},
-    {-17.2027283, 4.21029186, -15.9254236},
-    {-18.3454437, 5.70302868, -15.2254353},
-    {-18.4427071, 6.91133928, -14.0352917},
-    {-19.2683105, 8.19076443, -12.4251747},
-    {-19.9966183, 9.75458431, -10.6051283},
-    {-20.718483, 10.1810284, -8.7850132},
-    {-21.6508408, 10.465353, -6.96492863},
-    {-23.0975132, 10.1809855, -5.14483643},
-    {-23.6155014, 9.39909267, -3.18474126},
-    {-23.8295898, 8.61728764, -1.36469114},
-    {-23.9262333, 7.69315672, 0.245399103},
-    {-24.758419, 6.69806242, 1.50544953},
-    {-25.1692791, 6.05829954, 2.97551417},
-    {-25.2728329, 4.8499279, 4.23556948},
-    {-25.3728333, 3.57044792, 5.49561405},
-    {-25.3728333, 2.57531691, 5.91563129},
-    {-25.4728565, 1.86448681, 6.96566343},
-    {-25.1727219, 0.869425237, 7.5257225},
-    {-24.9620304, 0.727241576, 8.08573151},
-    {-25.3764, 0.371839017, 8.08573151},
-    {-24.7583733, 0.229696766, 8.01574421},
-    {-25.3657169, 0.371778131, 7.87568426},
-    {-24.8443928, 0.158517852, 7.59566402},
-    {-25.5657177, 0.229576796, 6.8256278},
-    {-25.5763721, 0.300719798, 6.12563181},
-    {-25.7907219, 0.514000177, 5.56562471},
-    {-25.8907928, 0.300735623, 4.44557381},
-    {-26.0943279, 0.300717354, 3.39553046},
-    {-26.4049911, 0.442878485, 2.1354816},
-    {-26.0907269, 0.0874570757, 0.875439227},
-    {-25.7764339, -0.339044005, -0.314598531},
-    {-25.6799049, -1.12089217, -1.50465715},
-    {-24.9478664, -2.32928276, -2.48466539},
-    {-24.6337395, -3.25333762, -3.4646852},
-    {-24.3265896, -4.31952667, -4.23472452},
-    {-24.008934, -5.81221819, -4.58470201},
-    {-23.7017517, -7.66029024, -4.51471663},
-    {-23.0770168, -9.08188629, -4.44469738},
-    {-22.5626812, -10.574563, -4.09470415},
-    {-22.2520542, -11.7829247, -3.04467034},
-    {-21.8310871, -12.8490973, -1.50460768},
-    {-21.9379787, -13.7020674, -0.314580828},
-    {-21.216465, -14.1285601, 1.15545535},
-    {-21.1129036, -14.3417997, 2.48549581},
-    {-21.0093536, -14.4128799, 4.23554897},
-    {-21.5237961, -13.9863853, 5.84558868},
-    {-21.366806, -13.3466606, 7.35062695},
-    {-21.5321407, -12.600358, 8.82071209},
-    {-21.847868, -11.4275494, 9.765769},
-    {-22.355484, -10.4324074, 10.6057415},
-    {-22.3589458, -8.93973064, 11.1657801},
-    {-22.9836521, -7.16272068, 11.6558189},
-    {-23.5014553, -5.52788687, 12.2158356},
-    {-23.6983261, -3.8219893, 11.9357605},
-    {-23.7984161, -2.32932425, 11.025713},
-    {-24.0071945, -0.552330434, 10.2907057},
-    {-24.7943192, 0.727169096, 8.92571449},
-    {-25.0444221, 1.36683416, 8.36565971},
-    {-25.3997498, 2.4329772, 6.82559967},
-    {-25.4408226, 2.57506108, 5.70554876},
-    {-26.0209465, 2.85945392, 3.46551943},
-    {-26.4814892, 2.75279713, 2.41549659},
-    {-25.7157536, 2.00653958, 0.735447884},
-    {-25.7621555, 1.6511066, 0.245443925},
-    {-25.6995945, 0.833628118, -0.734554708},
-    {-25.654974, 0.513812602, -0.664567828},
-    {-25.5496578, -0.339146286, -1.25957668},
-    {-25.3944302, -0.445763648, -1.88958633},
-    {-25.7549553, -0.836707532, -2.69459796},
-    {-25.0338345, -1.26316416, -2.97461629},
-    {-24.926733, -1.54749739, -3.74461484},
-    {-24.7679443, -1.93844795, -3.98960495},
-    {-24.7731819, -2.25828123, -4.51463985},
-    {-24.8267422, -2.89798594, -5.07465887},
-    {-24.4573841, -3.64434004, -5.56462955},
-    {-24.1468239, -4.17743158, -5.77463245},
-    {-23.37043, -5.2436142, -6.61464643},
-    {-23.3773499, -6.09655571, -6.96469784},
-    {-23.0702534, -6.8428812, -6.92971992},
-    {-22.6457806, -8.44216919, -6.61464453},
-    {-22.288538, -9.29511356, -6.50967884},
-    {-21.5120392, -10.4679213, -5.66966009},
-    {-21.8176403, -11.8539476, -4.93461943},
-    {-21.7208309, -13.2044735, -3.46462536},
-    {-21.3067055, -13.9863415, -1.9945966},
-    {-21.3033791, -14.6971178, -0.66456002},
-    {-21.410244, -14.981451, 0.80546391},
-    {-21.8209648, -14.7681999, 2.69549656},
-    {-21.5103531, -14.5549612, 4.23553181},
-    {-21.2031708, -14.412818, 5.56556082},
-    {-21.4102249, -13.7020273, 7.24559402},
-    {-21.4102249, -12.6358366, 8.92563343},
-    {-21.6172638, -11.4985704, 9.97565174},
-    {-21.9244995, -10.2902174, 11.1656551},
-    {-22.348753, -8.86864376, 12.4257526},
-    {-21.831068, -7.44705582, 13.5457773},
-    {-21.9312439, -5.38575315, 14.4557743},
-    {-21.9379654, -3.32442331, 14.9458447},
-    {-22.0415001, -1.47635925, 15.0158472},
-    {-22.2452145, 0.371698946, 15.2258215},
-    {-21.3167076, 2.29086781, 15.1558514},
-    {-21.1129456, 3.8546567, 14.9458752},
-    {-20.9058018, 5.48948812, 14.6658659},
-    {-20.9025993, 6.8399744, 14.1058216},
-    {-21.1195755, 8.19060516, 14.0359011},
-    {-20.4916172, 9.61212254, 13.5458326},
-    {-19.6631489, 10.8915615, 12.8458099},
-    {-18.9414825, 11.8867264, 12.3558207},
-    {-19.0482616, 13.0951433, 11.8658266},
-    {-19.0546589, 14.0192919, 11.0958395},
-    {-18.5335979, 14.8011236, 10.6058006},
-    {-17.7050247, 15.4408436, 9.90577412},
-    {-17.1871681, 16.5070515, 9.27575111},
-    {-17.3911972, 17.5731945, 8.08569241},
-    {-16.1514568, 18.141901, 7.10566902},
-    {-15.5330486, 18.2841263, 5.98563433},
-    {-15.3169127, 19.3501301, 5.00557995},
-    {-14.4913378, 20.6296463, 3.32552338},
-    {-14.0771055, 21.1272049, 1.85547304},
-    {-13.3521433, 21.2693691, 0.0354112536},
-    {-13.035675, 21.4113846, -1.64463305},
-    {-12.2185831, 21.4116707, -3.46474648},
-    {-11.8043032, 21.1984291, -5.7748332},
-    {-11.0764771, 20.5586376, -7.87489605},
-    {-10.6621933, 19.563509, -10.2549858},
-    {-10.3541985, 18.4262867, -12.8451214},
-    {-9.62648106, 16.5070553, -14.8051577},
-    {-9.3157692, 14.1613989, -17.255249},
-    {-9.62648106, 11.8157454, -18.9353142},
-    {-9.10595512, 9.61221123, -20.0552979},
-    {-8.48192883, 7.05328321, -20.8952713},
-    {-7.75960255, 4.77874994, -21.6653557},
-    {-7.65861893, 3.78365684, -22.5054493},
-    {-6.93868685, 3.00182772, -22.8555832},
-    {-6.10761595, 2.78855872, -22.9255257},
-    {-5.37767076, 3.71254992, -23.2054119},
-    {-5.17053604, 5.20523167, -23.2754116},
-    {-4.74901772, 6.83996582, -22.7852154},
-    {-4.23355579, 9.25673199, -21.8752441},
-    {-4.03600597, 11.6736317, -21.1054535},
-    {-3.30864978, 14.3035593, -20.1253567},
-    {-2.78851843, 16.36483, -18.725256},
-    {-2.78851843, 17.8575191, -17.4652081},
-    {-2.79079366, 19.0659466, -16.4152164},
-    {-2.67802095, 19.847559, -15.785018},
-    {-2.16253018, 20.1319485, -15.1550388},
-    {-1.75284433, 20.3453255, -14.9451189},
-    {-1.34080231, 19.989994, -15.4351807},
-    {-1.54793715, 19.4924259, -16.3452148},
-    {-1.43988585, 18.6393337, -17.6051655},
-    {-1.0300858, 17.075695, -19.145319},
-    {-0.408659935, 15.2986851, -20.4053688},
-    {-0.615799546, 13.0241117, -21.6654167},
-    {-0.717200994, 10.2519341, -22.8553963},
-    {-1.02791274, 7.05331993, -23.6254253},
-    {-0.818564415, 3.85468125, -24.3953896},
-    {-0.714994669, 0.584996998, -24.9554081},
-    {-0.402128786, -2.18714046, -24.9553375},
-    {-0.404282898, -4.81708288, -24.3953896},
-    {-0.507869303, -6.94949007, -24.0453739},
-    {-0.298587501, -7.80245018, -23.555294},
-    {-0.505696237, -8.22892952, -23.4852905},
-    {-1.02124381, -7.87353039, -23.6252346},
-    {-0.710653186, -6.59409571, -23.7652359},
-    {-0.710653186, -4.88818121, -24.2552547},
-    {-0.91991365, -2.04497933, -24.8153343},
-    {-1.23279846, 0.584997594, -24.8854046},
-    {-0.197193176, 3.42819953, -24.6053944},
-    {-1.03022122, 6.34255838, -24.1155052},
-    {-1.44438875, 9.0436039, -23.5554867},
-    {-1.23276043, 10.1808052, -22.9953403},
-    {-1.74383366, 10.7493095, -22.4351406},
-    {-1.74161077, 11.104661, -22.5050812},
-    {-2.36282992, 10.1806297, -22.7150898},
-    {-2.78393483, 8.83023834, -22.7852745},
-    {-3.51110125, 6.76896572, -23.1353436},
-    {-3.92297697, 4.35221148, -23.555294},
-    {-4.54428148, 2.21981573, -23.8353043},
-    {-4.95854664, 0.656051695, -23.6252956},
-    {-5.89544153, -0.836587548, -23.835434},
-    {-6.71886015, -1.33418167, -23.6253014},
-    {-7.13313961, -1.33417988, -22.9252758},
-    {-8.05989265, -0.552339613, -22.6451473},
-    {-8.68119812, 0.65601635, -22.2951355},
-    {-9.71923256, 2.07762957, -21.6651783},
-    {-10.8583078, 3.35706806, -21.1751633},
-    {-11.171689, 4.84976578, -20.405201},
-    {-11.9917307, 6.48450375, -19.4250107},
-    {-12.7166128, 7.47961378, -18.6549931},
-    {-13.9589281, 8.40364361, -17.8849773},
-    {-14.1689453, 9.4698782, -17.1150036},
-    {-14.5830965, 10.2517509, -16.1349812},
-    {-15.097827, 11.2468204, -15.3649168},
-    {-15.4114695, 11.8865824, -14.3149319},
-    {-15.1983881, 12.3129587, -13.7548389},
-    {-14.8848362, 13.3080187, -13.1247864},
-    {-14.985363, 13.9476776, -12.7747431},
-    {-15.1923981, 14.4452276, -11.8647299},
-    {-15.1923981, 15.8668079, -11.3747206},
-    {-14.9914055, 17.0041866, -10.7447786},
-    {-14.1571703, 17.5727005, -10.1147013},
-    {-14.4618645, 17.9990463, -9.1346302},
-    {-14.4648046, 18.0701866, -8.57464886},
-    {-13.9472952, 18.6388149, -7.80464268},
-    {-13.6338091, 19.136301, -7.524611},
-    {-13.5302896, 19.4916916, -7.24460793},
-    {-13.4296808, 19.7049961, -7.10463047},
-    {-12.8057404, 19.9892387, -7.10460711},
-    {-13.0098877, 20.1313324, -7.10458279},
-    {-13.6279907, 19.9180298, -7.24455976},
-    {-12.5957747, 19.8470211, -7.66458988},
-    {-11.9861975, 19.9183655, -8.01469612},
-    {-11.4740887, 19.8474216, -8.57476044},
-    {-11.3648548, 19.7051296, -9.69472218},
-    {-11.6615734, 19.4915562, -10.1845808},
-    {-11.1468658, 18.9940739, -11.1646185},
-    {-11.1524239, 18.2834206, -12.0046978},
-    {-11.4657383, 17.5016212, -13.0547457},
-    {-10.8336086, 16.7195091, -13.894599},
-    {-11.0350714, 16.0086117, -14.5945196},
-    {-11.4517832, 15.0846577, -15.4345665},
-    {-11.552496, 13.9473534, -16.4145222},
-    {-10.8308725, 12.8101597, -16.9745693},
-    {-10.5121813, 11.3173857, -18.0944214},
-    {-11.0295668, 9.82475567, -19.1444168},
-    {-11.1357889, 8.19001007, -19.4944706},
-    {-11.4545851, 6.12885761, -20.0546398},
-    {-10.8336754, 3.85436702, -20.8246403},
-    {-10.8363962, 1.57988191, -20.9647026},
-    {-10.5231342, -0.907873034, -21.0346451},
-    {-10.5285873, -2.82695794, -21.1747608},
-    {-10.4223309, -4.60393, -21.0347004},
-    {-10.0082893, -5.4568696, -20.8246975},
-    {-9.38998222, -5.6700983, -20.8947544},
-    {-9.28114223, -4.88825083, -21.3846455},
-    {-8.55667877, -3.60884595, -21.7346458},
-    {-8.24617577, -1.47649562, -22.2246513},
-    {-7.52172613, 1.65093541, -22.6446552},
-    {-6.48173428, 5.27586126, -22.3645287},
-    {-6.07285118, 9.11414528, -21.6646461},
-    {-5.24719, 12.6681137, -20.544693},
-    {-4.93431234, 15.7244091, -18.6546326},
-    {-4.10393476, 18.2831669, -16.7645702},
-    {-2.65504074, 20.557663, -14.8045607},
-    {-1.82716644, 21.7659874, -13.1245604},
-    {-1.72366071, 22.6900024, -12.0745535},
-    {-1.19959652, 23.1162434, -11.3044481},
-    {-0.684340954, 22.9741573, -11.5144844},
-    {-0.274802238, 23.0453892, -12.0745525},
-    {0.242657244, 22.4767666, -12.9845562},
-    {0.139153942, 21.0552101, -14.8045635},
-    {-0.173453033, 18.994009, -17.3946247},
-    {-0.279119909, 16.222023, -19.7046909},
-    {-0.380438238, 12.7391376, -21.9446468},
-    {-0.483941555, 8.26120472, -23.8346615},
-    {-0.792093098, 3.49896073, -24.8145981},
-    {-1.62010753, -1.90299368, -24.9545975},
-    {-1.31190848, -5.74118042, -23.8346634},
-    {-1.72142351, -8.513237, -23.0645332},
-    {-2.44587302, -10.4323339, -22.1545315},
-    {-2.75170183, -11.7117186, -21.3144112},
-    {-3.58408856, -11.6406584, -20.9645271},
-    {-4.82600927, -10.7877226, -21.2445297},
-    {-5.44438839, -9.43724728, -21.3844681},
-    {-6.68623781, -7.37598801, -21.594471},
-    {-8.0314455, -4.81719637, -21.6644707},
-    {-9.68436813, -2.8270371, -21.5244102},
-    {-10.8337317, -0.552475989, -20.9646397},
-    {-12.492259, 0.940176666, -20.0546913},
-    {-13.9355965, 1.7219938, -19.2845764},
-    {-15.3843145, 1.86414945, -18.1645756},
-    {-16.6201973, 1.65086782, -17.0444736},
-    {-18.072052, 1.01119232, -16.1345215},
-    {-18.7932148, 0.229317993, -14.8744793},
-    {-20.0317822, -0.836865842, -13.4744406},
-    {-20.2419796, -2.04517007, -12.4944792},
-    {-21.2767143, -3.25348759, -11.0244837},
-    {-22.2013206, -4.39074755, -9.97442245},
-    {-22.8221207, -5.67013931, -8.64443016},
-    {-23.4464035, -6.94952917, -7.24446058},
-    {-23.1394119, -7.7313776, -5.84449053},
-    {-23.5533447, -8.72646713, -4.79448938},
-    {-23.1359863, -9.79262447, -3.18448162},
-    {-23.132534, -10.5744705, -1.36447668},
-    {-23.5291576, -11.3562813, 0.38553828},
-    {-23.2291241, -11.9249229, 2.55550551},
-    {-22.9289856, -12.0671043, 4.58549547},
-    {-22.2013016, -11.7827873, 6.7554698},
-    {-22.0910988, -11.2852316, 8.3654356},
-    {-21.8875637, -10.5744658, 10.3954353},
-    {-21.9943886, -9.43723583, 12.1454411},
-    {-21.7874489, -7.80245781, 13.545433},
-    {-21.4770508, -5.95444822, 14.6654263},
-    {-21.0598564, -4.46183348, 15.9253874},
-    {-21.2634373, -1.83199871, 16.6253471},
-    {-20.9563599, 0.442493021, 16.5553818},
-    {-20.6427212, 2.29045987, 16.2753525},
-    {-20.6427364, 4.42278242, 15.7853537},
-    {-20.7527676, 6.27084637, 15.1554222},
-    {-20.4391346, 8.4742012, 14.105402},
-    {-20.7428875, 10.0378094, 12.6353703},
-    {-20.012207, 11.5303316, 11.0253458},
-    {-20.0252647, 12.8099089, 9.69543743},
-    {-20.3356285, 13.7339106, 8.08545303},
-    {-20.4456329, 14.4447918, 5.98548508},
-    {-20.5491009, 15.1555653, 4.37549448},
-    {-19.9184914, 15.5818586, 2.76549911},
-    {-19.9185104, 15.439703, 0.945521474},
-    {-19.7115974, 15.5818586, -0.804464877},
-    {-18.9938126, 15.2976618, -2.34446955},
-    {-19.4011955, 15.0132408, -3.67442894},
-    {-19.191124, 14.7999592, -4.9343996},
-    {-19.0876808, 14.2313414, -5.7043891},
-    {-19.1975555, 14.3736038, -6.61442137},
-    {-19.1878948, 14.1602125, -7.03434706},
-    {-18.8807068, 13.8048792, -7.80436325},
-    {-18.7804928, 13.3784733, -8.08438396},
-    {-18.9842281, 13.4495001, -8.08435631},
-    {-18.7868862, 13.2364197, -8.01443386},
-    {-18.7869205, 13.6628838, -7.80443621},
-    {-18.7805214, 13.9470882, -7.4543891},
-    {-18.5736065, 13.8760128, -7.10439396},
-    {-18.7900982, 14.0894022, -6.54446459},
-    {-19.5079079, 14.2314529, -5.63443136},
-    {-19.4012432, 14.3735504, -4.72441912},
-    {-20.2289219, 15.0132437, -3.7444303},
-    {-20.4424038, 14.942275, -2.55446625},
-    {-20.1319866, 14.942275, -1.29447818},
-    {-20.3357201, 14.4446821, -0.524474382},
-    {-20.5426083, 14.4446821, 0.385520875},
-    {-20.5523739, 14.3737669, 1.71550357},
-    {-20.1352539, 14.2315607, 2.69549704},
-    {-20.7528248, 13.9471931, 3.32549715},
-    {-21.1666489, 13.8761177, 4.09549093},
-    {-21.7909603, 13.805089, 4.65549231},
-    {-21.2734509, 13.3786268, 5.07549191},
-    {-21.7907181, 12.6678581, 5.425488},
-    {-22.2980289, 12.5966263, 5.98546457},
-    {-22.0944843, 12.5256004, 5.91547203},
-    {-22.2980328, 11.8147802, 5.9154644},
-    {-22.3047352, 11.5305662, 5.77548075},
-    {-22.9187679, 11.1040106, 5.42546988},
-    {-23.0222034, 10.7486238, 5.145473},
-    {-23.1256886, 10.5353956, 4.72547626},
-    {-23.4394932, 10.1800537, 4.44548512},
-    {-23.8498917, 9.61139297, 3.95548415},
-    {-23.9498501, 9.04273605, 3.88548303},
-    {-24.4671059, 8.61627674, 3.39548969},
-    {-24.8844547, 8.26093197, 2.62549901},
-    {-24.474123, 7.55020189, 1.78550863},
-    {-24.8844357, 6.9815464, 1.50551236},
-    {-24.9949474, 6.48407841, 1.15550888},
-    {-25.3089314, 6.05764818, 0.315507591},
-    {-25.2019577, 5.7022295, -0.244482085},
-    {-25.0984383, 5.41791821, -0.384481072},
-    {-25.316, 5.13370562, -0.87450242},
-    {-25.6620979, 4.99140882, -2.09945488},
-    {-25.2054253, 4.63609886, -2.69448161},
-    {-24.4741936, 4.28065348, -2.90445304},
-    {-24.3636589, 4.28059292, -3.53441787},
-    {-24.8880272, 4.49388456, -3.60444617},
-    {-24.7915554, 4.77825212, -3.74447584},
-    {-23.9498539, 5.20459127, -4.19940853},
-    {-24.0603237, 5.48896599, -4.58443785},
-    {-23.9534359, 5.84431458, -4.30442333},
-    {-23.4395313, 6.6262002, -4.23443747},
-    {-24.0672112, 7.12380934, -3.67447686},
-    {-24.1637383, 7.90558386, -3.25444937},
-    {-23.8050671, 8.50978088, -2.09947109},
-    {-23.9655094, 9.57600403, -1.25949097},
-    {-23.3445988, 9.78923512, -0.524491429},
-    {-23.494669, 10.3222523, 0.105515406},
-    {-23.2359924, 10.5354834, 0.945510268},
-    {-23.232563, 10.6065159, 1.78550565},
-    {-23.0290623, 10.7487154, 2.31050181},
-    {-22.9187489, 11.2461634, 2.69549894},
-    {-23.1325283, 11.6727209, 2.41549873},
-    {-23.1359348, 11.6727695, 2.06550241},
-    {-22.2529812, 11.9214945, 1.57550633},
-    {-22.4184208, 12.3481026, 0.315497249},
-    {-22.0978565, 12.3479538, -0.629478097},
-    {-22.0877438, 12.2411928, -1.99443829},
-    {-21.9375706, 12.5611124, -3.46444249},
-    {-21.0014877, 12.2411909, -5.03939962},
-    {-20.8496056, 11.9569349, -6.19440174},
-    {-21.3218193, 11.7082586, -6.92944241},
-    {-20.6960869, 11.2817259, -7.03440666},
-    {-20.6961155, 11.6015739, -7.76939917},
-    {-20.5458374, 11.2817936, -7.66443729},
-    {-20.3857594, 11.8148022, -7.55940104},
-    {-20.2304802, 12.3478813, -7.24440432},
-    {-19.7649784, 12.6677284, -6.40441179},
-    {-20.2223492, 13.520524, -5.21437454},
-    {-19.9152851, 13.7338037, -4.72440195},
-    {-20.1287136, 14.5157576, -4.09444284},
-    {-20.2256355, 14.4801111, -3.56941748},
-    {-20.9965382, 13.9469547, -2.7294085},
-    {-20.9464893, 13.6626749, -2.13442469},
-    {-20.9531384, 13.307395, -2.27444673},
-    {-21.6739635, 12.8808823, -2.41443324},
-    {-22.0910988, 12.3123188, -2.5544436},
-    {-22.2979946, 11.1750898, -3.04443645},
-    {-22.4015007, 10.4643164, -3.25443554},
-    {-23.2290897, 9.39816475, -3.32443333},
-    {-23.846405, 8.04765892, -3.81441355},
-    {-23.6429558, 6.69724131, -3.53443289},
-    {-24.5670166, 5.84424782, -3.18440914},
-    {-24.460062, 5.34667873, -3.04439616},
-    {-24.363678, 4.9202857, -2.34443617},
-    {-24.973772, 4.49373102, -1.43441594},
-    {-24.7704468, 4.49376297, -0.454442471},
-    {-25.2947159, 4.63597679, 0.455528915},
-    {-25.1877365, 4.49379349, 1.57551444},
-    {-25.1806412, 4.06727409, 2.90549421},
-    {-25.5836678, 3.49858332, 3.95546031},
-    {-25.6835251, 3.07209921, 5.21542311},
-    {-25.1664581, 2.43242073, 6.19539022},
-    {-25.4802666, 1.43738103, 6.96538019},
-    {-25.1735973, 0.584498227, 7.80536604},
-    {-24.9561405, -0.481698394, 8.43530941},
-    {-24.8632927, -0.837022364, 9.27533054},
-    {-24.3426495, -1.12134278, 10.3952866},
-    {-23.7291203, -1.19238591, 11.7952881},
-    {-23.4153976, -1.33455372, 12.7052441},
-    {-22.8982487, -0.979173124, 14.1052084},
-    {-22.0709209, -0.979173124, 15.3651733},
-    {-21.3403053, -0.552754879, 16.0650921},
-    {-20.9332752, 0.371269047, 16.9051399},
-    {-20.3127728, 0.868799806, 17.4651241},
-    {-19.6922035, 1.43740726, 17.9551086},
-    {-19.4821243, 2.36136961, 18.0250702},
-    {-19.165451, 3.07207251, 17.8150024},
-    {-19.0652847, 3.71178007, 17.7450409},
-    {-19.6857357, 4.35145998, 17.1150608},
-    {-20.4030113, 5.13322687, 16.0650311},
-    {-21.0201263, 5.70179605, 14.9450359},
-    {-21.6505337, 6.19942379, 14.3151445},
-    {-22.2777519, 6.62594891, 12.9152346},
-    {-23.0085411, 6.55494308, 11.1653242},
-    {-23.5083866, 6.98121548, 9.90526485},
-    {-23.7187366, 7.1944828, 7.94533491},
-    {-24.1288986, 7.47874641, 5.84539747},
-    {-24.4390831, 7.19444513, 3.95545459},
-    {-24.3356762, 7.62089729, 2.06552124},
-    {-23.9220333, 8.18950272, -0.104412615},
-    {-23.6222458, 8.61607456, -1.4343977},
-    {-23.3154202, 9.18472195, -2.76437378},
-    {-22.3777752, 9.8243227, -4.37430525},
-    {-22.1743355, 10.0375919, -6.12427759},
-    {-21.1268539, 10.606019, -7.10415554},
-    {-20.2060413, 11.1036863, -8.29419994},
-    {-19.795639, 11.3880367, -9.6941843},
-    {-18.444849, 11.1747141, -10.7440948},
-    {-18.1377144, 10.7483072, -11.9340944},
-    {-17.6175976, 10.1085844, -12.9140282},
-    {-17.3010902, 9.04236126, -13.8239231},
-    {-17.5079212, 8.18946362, -14.8738852},
-    {-16.7840805, 6.83903027, -15.7138567},
-    {-16.2701435, 5.84401274, -16.3438797},
-    {-16.2762604, 5.41762829, -16.5539665},
-    {-15.8595352, 4.77791357, -16.4139214},
-    {-16.3765793, 4.63576269, -16.5539188},
-    {-16.5772781, 4.77785015, -16.4138298},
-    {-17.1977081, 5.84397602, -16.1338406},
-    {-17.1977272, 7.26548624, -15.4338627},
-    {-17.9245987, 8.47380066, -14.3839436},
-    {-18.2285233, 10.3927498, -12.7039223},
-    {-17.4013996, 12.8092995, -10.6739988},
-    {-17.5079746, 14.6573067, -8.85409737},
-    {-16.7810249, 16.2209034, -6.89413881},
-    {-16.5742188, 17.0027294, -5.77418327},
-    {-16.6806831, 17.4292412, -5.07422924},
-    {-16.5803185, 17.5003796, -5.14424515},
-    {-17.1945686, 17.0027313, -5.84418106},
-    {-17.4044781, 16.3631115, -7.24415207},
-    {-17.1976757, 15.2969828, -8.78409863},
-    {-17.5078735, 13.4490299, -9.69406605},
-    {-17.6081791, 12.5250006, -10.9539862},
-    {-17.8149185, 11.4588709, -11.6539631},
-    {-18.2411289, 10.6061554, -11.6541023},
-    {-18.5450115, 10.3928404, -11.8640242},
-    {-19.2592335, 10.1084042, -10.9539585},
-    {-19.5727158, 10.3216772, -9.97402477},
-    {-20.3061886, 11.1036406, -8.85415268},
-    {-20.5063934, 11.8142967, -7.24415588},
-    {-20.5064125, 12.7382784, -5.5642066},
-    {-20.302927, 13.4490805, -3.81429124},
-    {-20.5064468, 14.2308588, -1.99433756},
-    {-20.9166927, 14.3729515, -0.104398221},
-    {-21.23349, 14.4441366, 1.22555482},
-    {-20.7231579, 14.3020954, 3.11548519},
-    {-21.1368561, 14.2310171, 4.23545313},
-    {-20.3997536, 14.301878, 5.28540039},
-    {-20.4063091, 14.0887613, 6.40537405},
-    {-20.3028927, 13.5912294, 7.38534403},
-    {-20.0895634, 13.3779001, 8.15528774},
-    {-19.7761917, 13.591073, 8.99524498},
-    {-19.7730198, 13.7331724, 9.76519585},
-    {-19.5564842, 13.6619387, 9.83514118},
-    {-19.5629406, 14.0884914, 9.90517235},
-    {-19.1590481, 14.0886497, 10.3952084},
-    {-19.2624454, 14.0886497, 10.8151913},
-    {-18.8456535, 13.9464455, 11.1651583},
-    {-18.9394875, 14.2305861, 11.0950985},
-    {-18.4226437, 14.3016586, 10.8151112},
-    {-18.1188145, 14.7282133, 10.3951702},
-    {-17.8086681, 15.2257385, 9.97518635},
-    {-17.4985256, 15.5100384, 9.41521168},
-    {-17.6019077, 15.8654127, 9.06522655},
-    {-17.0819244, 16.220726, 8.71522713},
-    {-17.1884174, 17.0026112, 8.15526295},
-    {-17.2917709, 17.4290562, 7.45529556},
-    {-17.0850029, 17.5712051, 6.8253212},
-    {-16.8751831, 17.7132931, 6.19534016},
-    {-16.6715069, 18.1398029, 5.56537485},
-    {-16.3643665, 18.5663166, 5.07540274},
-    {-16.2640247, 18.9217548, 5.07540846},
-    {-16.467783, 19.4192123, 4.51542377},
-    {-15.8474941, 19.5613594, 4.23543549},
-    {-15.2241325, 19.8455925, 4.16543436},
-    {-15.4368868, 20.3432541, 3.53546524},
-    {-14.7160997, 20.6276245, 3.25547791},
-    {-14.0957069, 20.9830017, 2.55550241},
-    {-13.9893656, 21.0540047, 2.48550439},
-    {-13.9893847, 21.2672329, 2.20551682},
-    {-13.5786772, 21.3383789, 1.92552459},
-    {-13.5786772, 21.2673035, 1.78552961},
-    {-13.4724398, 21.5515347, 1.78553259},
-    {-13.3747625, 21.764904, 1.99551952},
-    {-13.1622133, 21.906908, 2.20551538},
-    {-12.648119, 21.6226807, 2.62549996},
-    {-12.9583178, 21.4094505, 2.90549016},
-    {-13.2685118, 21.1251545, 3.25547767},
-    {-13.7884245, 21.0541496, 3.32547641},
-    {-13.8859882, 21.1961575, 4.02544594},
-    {-14.1932278, 20.2721081, 4.86541176},
-    {-14.6216135, 19.917078, 5.42542219},
-    {-15.2390423, 19.4905605, 5.91539907},
-    {-15.442914, 18.7086601, 6.89536047},
-    {-15.55231, 18.6377163, 7.59536123},
-    {-16.376564, 18.1401215, 8.15533066},
-    {-16.9909153, 17.216013, 8.99527836},
-    {-17.5140533, 16.1500034, 9.90527916},
-    {-17.7271786, 15.155056, 10.9552908},
-    {-18.2411022, 14.23102, 12.0752325},
-    {-18.5450726, 13.3069277, 12.285183},
-    {-19.7988873, 11.9566889, 12.7752666},
-    {-19.795639, 10.6062031, 13.4752226},
-    {-19.582325, 9.46890068, 13.8951588},
-    {-20.4062996, 8.33165359, 14.5251093},
-    {-21.0267715, 6.69691467, 14.8750982},
-    {-20.9266529, 5.20436811, 15.0851221},
-    {-21.0267582, 3.71174836, 15.1550894},
-    {-21.8573112, 1.57951474, 15.0851221},
-    {-22.0540771, -0.552805424, 15.0150337},
-    {-22.1608753, -2.4007504, 14.5250788},
-    {-22.3811855, -4.53297281, 14.0352087},
-    {-22.5880737, -6.66524315, 12.7752438},
-    {-22.5812435, -8.37106991, 11.1652384},
-    {-23.108551, -10.0768986, 9.48533916},
-    {-22.7845974, -11.6405306, 7.38534594},
-    {-22.784626, -11.9248371, 5.00542498},
-    {-22.5710316, -12.4934177, 2.20551944},
-    {-22.3676052, -12.2091265, -0.454396605},
-    {-22.5811958, -10.9297905, -2.97432709},
-    {-22.5846157, -9.29505157, -5.21428347},
-    {-22.274416, -7.30492973, -7.1042304},
-    {-22.6880589, -5.95449543, -8.50418568},
-    {-22.1641941, -4.24869299, -9.06411648},
-    {-22.374464, -2.68502021, -8.99414635},
-    {-23.1085701, -1.83206928, -9.06422901},
-    {-23.5325775, -1.05018282, -9.13431358},
-    {-23.3154488, -1.26346195, -9.13422871},
-    {-23.2051468, -1.76102436, -8.64418602},
-    {-23.1982403, -2.04535508, -8.22414398},
-    {-23.6153221, -2.96932578, -7.59418917},
-    {-24.0323753, -3.6089952, -6.96423006},
-    {-23.725666, -4.24866581, -6.47427034},
-    {-23.6084156, -4.74622965, -5.84420204},
-    {-23.5085011, -5.52805185, -5.70422602},
-    {-23.1948204, -5.45698166, -5.70420694},
-    {-23.7152691, -5.24374914, -5.49423456},
-    {-23.9186134, -5.03053045, -5.07422924},
-    {-24.5319614, -4.60409689, -5.63416815},
-    {-24.6318779, -3.89335704, -5.8441391},
-    {-23.701437, -2.68508673, -6.26412201},
-    {-23.5980511, -1.76111567, -6.68410444},
-    {-23.187933, -0.694977522, -7.59409189},
-    {-23.3948193, 0.584371567, -7.73408222},
-    {-23.8186855, 1.22411096, -8.0841465},
-    {-23.5084763, 2.14809346, -8.50413513},
-    {-23.2982159, 2.57451797, -8.99409008},
-    {-22.8777676, 2.29016638, -9.55401134},
-    {-23.0845833, 2.14801741, -9.97399426},
-    {-22.7778606, 1.4372927, -10.3240128},
-    {-22.467659, 0.655468285, -10.8139944},
-    {-21.6371479, 0.0868462846, -10.813962},
-    {-21.7371807, -0.268544674, -11.2339096},
-    {-21.8439503, -0.197453454, -10.9539557},
-    {-22.047266, -0.12639755, -11.0239201},
-    {-22.0439129, 0.655405581, -10.9538889},
-    {-21.9473457, 2.00587153, -10.7439632},
-    {-21.8505993, 3.49849558, -10.6040344},
-    {-21.6404858, 4.49352074, -10.3940096},
-    {-22.1608276, 5.63075256, -9.90405941},
-    {-21.7405815, 6.41250849, -9.7640028},
-    {-21.6371479, 6.98110819, -9.48401546},
-    {-21.7438831, 7.40759802, -9.134058},
-    {-21.8305225, 7.12311268, -9.13391495},
-    {-21.827177, 6.4834075, -9.20388317},
-    {-22.0372391, 5.63055515, -9.48389816},
-    {-21.9406395, 4.91988039, -9.69394684},
-    {-21.5237579, 3.78265452, -10.25389},
-    {-22.0439262, 3.21408677, -10.1139288},
-    {-22.8709831, 2.71656513, -9.55395222},
-    {-22.1473656, 2.14796758, -9.34396267},
-    {-22.8709126, 2.21904349, -9.20396805},
-    {-22.2473526, 2.50331593, -8.50397301},
-    {-22.6574268, 3.71155238, -7.94397354},
-    {-23.3947678, 4.56456804, -7.45409536},
-    {-23.6014423, 5.34638643, -6.6841321},
-    {-23.8977985, 6.05700016, -5.70408487},
-    {-24.0081158, 7.05211306, -4.23419046},
-    {-24.2183475, 7.69181919, -2.83426762},
-    {-24.0115891, 7.90504551, -1.78431273},
-    {-24.1184864, 8.04723263, -1.15434897},
-    {-24.3147297, 7.90496778, -0.524351716},
-    {-24.5179882, 7.76278019, 0.0356289558},
-    {-24.7247143, 7.76278019, 0.805590451},
-    {-24.5179882, 7.62063313, 1.2955662},
-    {-24.7247143, 7.26525974, 1.6455487},
-    {-24.6248703, 7.05207396, 1.85553622},
-    {-24.4216595, 6.83888769, 1.92553067},
-    {-24.4075909, 6.27015543, 2.13552737},
-    {-25.0313511, 5.91482019, 2.27552032},
-    {-25.4553776, 5.7727704, 2.69549704},
-    {-25.4376163, 5.20401239, 2.90548301},
-    {-25.2344723, 5.06189728, 3.46545458},
-    {-25.3413506, 4.77763319, 3.6754446},
-    {-25.3484325, 4.77769566, 3.6054523},
-    {-25.344902, 4.42229414, 3.88543725},
-    {-25.7512264, 3.99579072, 3.74543977},
-    {-24.9243965, 3.78256822, 3.81543517},
-    {-25.245079, 3.64050627, 3.95543742},
-    {-25.7583656, 3.14295769, 3.81544065},
-    {-25.3378735, 3.14290309, 3.885432},
-    {-25.6549969, 2.85866117, 4.23541975},
-    {-25.8616657, 2.92973399, 4.30541515},
-    {-25.6585503, 2.85868669, 4.02543402},
-    {-25.6549969, 2.71651268, 4.0254302},
-    {-25.4517899, 2.64546418, 3.60545325},
-    {-25.6549969, 2.64543867, 3.60545135},
-    {-25.7583656, 2.50328898, 3.46545815},
-    {-25.5480671, 2.78756022, 3.32546258},
-    {-25.5409603, 3.14287734, 3.18546796},
-    {-25.9542999, 3.28502584, 3.25546408},
-    {-25.6442432, 3.21395278, 2.83548594},
-    {-25.2379913, 3.99581861, 2.62550044},
-    {-25.3484554, 3.99587703, 2.69549608},
-    {-25.2379532, 4.42226362, 2.27551794},
-    {-25.3377495, 5.06189823, 2.27551794},
-    {-25.4482384, 5.63055515, 2.55550385},
-    {-24.7212181, 6.4834075, 2.41551042},
-    {-24.5109768, 7.47840929, 3.18547058},
-    {-24.6143208, 7.97592497, 3.39545846},
-    {-23.8874073, 9.04199123, 3.46545196},
-    {-23.5808754, 10.108139, 3.39545703},
-    {-23.0606251, 10.8899059, 3.88542819},
-    {-22.3405552, 12.0982094, 3.60544491},
-    {-21.6137733, 12.9510441, 3.53544712},
-    {-21.0920792, 14.1592159, 3.04547453},
-    {-20.7722092, 14.6920996, 2.62550139},
-    {-19.8470612, 15.4384537, 1.85554743},
-    {-19.0267963, 16.1492996, 0.665614367},
-    {-18.729517, 16.7181244, -0.664338112},
-    {-18.1031208, 16.7890816, -2.6242044},
-    {-17.7836399, 16.4335365, -4.9340353},
-    {-18.2001324, 15.7228603, -7.31390619},
-    {-17.5831699, 14.1592941, -9.41381645},
-    {-17.8900909, 11.4584522, -11.5836525},
-    {-17.8368912, 8.40226746, -13.4385252},
-    {-17.7742977, 6.34102869, -14.3833179},
-    {-18.7042522, 3.28487968, -15.0832729},
-    {-19.1238079, 0.726308644, -14.6633883},
-    {-19.7018318, -2.57855392, -14.2785349},
-    {-20.4621964, -3.85792255, -12.9134445},
-    {-20.0472527, -5.1017065, -12.1434755},
-    {-20.6270428, -6.62975931, -10.8136864},
-    {-21.2271671, -6.84299517, -9.76356602},
-    {-21.5521374, -7.48264265, -9.02874565},
-    {-22.0170612, -7.90908003, -7.66383743},
-    {-22.17206, -7.90908003, -7.0338788},
-    {-22.7869473, -8.54873753, -6.08890629},
-    {-22.1669979, -8.65534687, -5.56394386},
-    {-22.7817574, -8.97517109, -5.14394379},
-    {-23.5618744, -9.18839264, -4.61900854},
-    {-23.2571335, -9.50822926, -4.40904665},
-    {-23.7168407, -9.93465614, -3.884058},
-    {-22.9436378, -10.0057335, -3.95406055},
-    {-23.1536999, -10.3611059, -3.67409539},
-    {-23.417141, -10.8941631, -3.67411757},
-    {-22.17206, -11.1073723, -3.35911489},
-    {-22.3270512, -11.3205919, -3.35911489},
-    {-22.220335, -11.9247046, -2.55415392},
-    {-22.0221062, -12.1734848, -2.62418222},
-    {-22.9470348, -12.3866892, -2.62416244},
-    {-22.2271214, -12.6354551, -1.78422511},
-    {-22.3221493, -12.9197149, -1.36422658},
-    {-22.1136742, -13.559371, -1.43421865},
-    {-21.3937416, -13.7015285, -1.50422347},
-    {-21.1904221, -13.9147625, -1.71422076},
-    {-21.2904415, -14.4122572, -1.99419117},
-    {-20.8738289, -14.6254606, -2.13416982},
-    {-20.670475, -14.6965504, -2.69414568},
-    {-20.6672306, -14.6965332, -2.83412242},
-    {-20.3638248, -14.7676392, -3.74409366},
-    {-19.7437973, -14.5544205, -4.30405426},
-    {-20.0570278, -14.1279936, -5.63398886},
-    {-19.8438892, -13.2040176, -6.82386541},
-    {-20.1571178, -12.0668564, -8.08381557},
-    {-20.057066, -10.2900372, -9.763731},
-    {-21.0903454, -7.58925343, -10.9536591},
-    {-21.3970814, -5.03061724, -11.3735991},
-    {-21.9204903, -2.96947098, -10.9536924},
-    {-22.1237392, -0.552990556, -10.2537022},
-    {-22.7369461, 1.50808918, -8.99372578},
-    {-23.3603783, 2.00562668, -7.45384836},
-    {-24.1939487, 3.0717752, -6.26397085},
-    {-24.6038189, 3.28496981, -4.65405178},
-    {-25.0171909, 3.42711806, -2.55417919},
-    {-25.3200703, 3.14277029, -1.01425707},
-    {-25.6336327, 2.92957568, 0.805616975},
-    {-25.6336231, 2.0056262, 2.20552707},
-    {-25.3200703, 1.22379863, 3.67542744},
-    {-25.9436684, 0.655233264, 5.14533901},
-    {-25.6300793, -0.481953532, 5.91528034},
-    {-26.1538677, -1.40587032, 6.82524014},
-    {-25.2274036, -2.2587347, 6.89524555},
-    {-25.1275787, -3.04053187, 7.17524099},
-    {-24.9103127, -3.96452022, 7.24520302},
-    {-24.8069839, -4.60417843, 7.24520302},
-    {-24.3971405, -5.1727581, 7.59519148},
-    {-24.2937965, -5.31490326, 8.01516724},
-    {-24.2973156, -5.7413373, 8.50515079},
-    {-24.297369, -6.0256319, 8.92512703},
-    {-24.4006748, -6.16777897, 9.48509216},
-    {-24.1939678, -6.38099909, 10.0450592},
-    {-23.3706627, -6.59421635, 10.7450361},
-    {-22.6404419, -6.52315044, 11.5849447},
-    {-22.8505173, -6.66529369, 12.2849264},
-    {-22.1304932, -6.52314281, 13.1948967},
-    {-21.6137581, -6.45206881, 14.3148327},
-    {-21.4170494, -6.16775846, 15.014884},
-    {-20.8001919, -5.52808714, 15.9948654},
-    {-19.8633671, -5.24380255, 17.1147442},
-    {-19.9634399, -4.81736803, 17.7446728},
-    {-19.1334171, -4.10663795, 18.4445972},
-    {-18.5196838, -3.39587831, 19.2846298},
-    {-17.4891777, -2.54297662, 20.3346195},
-    {-16.8689995, -1.54793823, 20.8245945},
-    {-17.2855625, 0.0157148708, 21.1046238},
-    {-16.1455383, 1.36610103, 21.2445717},
-    {-15.0054226, 2.71648836, 21.1745319},
-    {-14.5979357, 4.28017855, 21.2446175},
-    {-14.2907906, 6.27029085, 21.2446613},
-    {-14.187356, 8.18930435, 20.89468},
-    {-13.4608507, 9.8239727, 20.1946697},
-    {-13.3546038, 11.8140106, 19.3546677},
-    {-13.0473738, 13.5198421, 18.1647625},
-    {-12.6339169, 15.2256241, 16.8348293},
-    {-12.6309814, 17.1445751, 15.084878},
-    {-12.223238, 18.6372604, 13.1950235},
-    {-11.918725, 19.6324368, 10.9551659},
-    {-11.9158888, 20.9117165, 8.71524525},
-    {-11.4940386, 21.6933212, 6.19532251},
-    {-11.1867085, 22.475214, 3.39545965},
-    {-10.7705202, 22.9015789, 0.105633549},
-    {-10.7705202, 22.4751358, -3.25421548},
-    {-10.8738308, 21.2668762, -7.03401375},
-    {-9.93552017, 19.7030449, -10.5337458},
-    {-10.1475, 17.3577328, -13.753643},
-    {-9.93816185, 14.5147142, -16.763443},
-    {-9.32603836, 10.6768627, -19.3534622},
-    {-9.1245985, 6.69677353, -20.6835079},
-    {-8.60245323, 2.71654439, -22.0133324},
-    {-8.49905682, -1.33470416, -22.2933197},
-    {-8.08303928, -4.88841724, -21.7332878},
-    {-7.65662909, -7.94461012, -21.0330372},
-    {-8.07262802, -10.4321947, -19.9131565},
-    {-7.03923321, -12.564393, -18.933218},
-    {-7.03927135, -14.0569363, -18.0232735},
-    {-6.52253151, -15.1941147, -17.3233128},
-    {-7.04690456, -15.8338337, -16.763485},
-    {-7.46285105, -16.0470753, -16.4835491},
-    {-7.97706842, -16.2602768, -16.5534992},
-    {-8.49912357, -15.9049454, -15.9236183},
-    {-8.80654335, -15.4784832, -16.1335621},
-    {-8.79866314, -15.336278, -16.6233997},
-    {-9.52209663, -14.6255407, -16.5534039},
-    {-9.83486938, -13.7726717, -16.9034328},
-    {-10.6670856, -12.9198103, -17.1835117},
-    {-11.6896162, -11.5693684, -17.2533188},
-    {-12.7230253, -10.5032635, -17.0433311},
-    {-13.4464054, -9.50823402, -17.0433292},
-    {-14.3794289, -8.442132, -16.483408},
-    {-15.8262949, -7.3049531, -16.0634327},
-    {-16.6530762, -6.09670019, -15.7134542},
-    {-17.6865005, -5.38596392, -14.9434977},
-    {-19.1366291, -4.8173666, -14.3135748},
-    {-19.5404625, -4.81739235, -13.3335133},
-    {-20.367054, -4.8884635, -12.4935656},
-    {-20.983757, -4.31988573, -11.3036041},
-    {-21.5970383, -4.03561163, -10.1136208},
-    {-22.5235691, -4.03562117, -8.92367268},
-    {-23.0435772, -4.74634218, -7.94376469},
-    {-23.4602795, -5.17277002, -6.89386559},
-    {-23.4567966, -5.24384975, -5.77391672},
-    {-24.2868652, -5.03062439, -4.37403297},
-    {-24.6895599, -5.38600731, -3.18407083},
-    {-24.9031792, -5.9545784, -2.13416839},
-    {-24.8034496, -6.30993891, -0.944263518},
-    {-25.2096958, -6.02565622, 0.175675333},
-    {-25.1169262, -6.30993462, 1.22558999},
-    {-25.6300983, -6.02564716, 2.41551304},
-    {-25.1134434, -5.52813482, 3.18546343},
-    {-25.5267105, -5.67028189, 4.23539209},
-    {-25.2167683, -5.59920835, 4.72535944},
-    {-25.3165894, -5.45706844, 5.56529665},
-    {-25.4163189, -5.38600206, 6.40522909},
-    {-24.8996449, -5.45707607, 7.03518677},
-    {-24.5932751, -5.74136019, 7.73514652},
-    {-25.0030174, -5.81243706, 8.64506817},
-    {-24.4898968, -6.52316284, 9.48502731},
-    {-23.7668056, -7.37603331, 10.1149807},
-    {-22.8402805, -8.79749489, 10.7449589},
-    {-22.1136742, -10.0057268, 11.3748932},
-    {-21.0870781, -11.4272022, 11.3749371},
-    {-20.2571564, -13.0618725, 10.7449579},
-    {-19.5370483, -15.0519352, 10.2550068},
-    {-17.89011, -17.1841717, 9.13511276},
-    {-16.9538612, -18.747736, 7.10521507},
-    {-15.8112383, -20.1691399, 4.79535246},
-    {-14.8813162, -21.2352333, 1.85554898},
-    {-13.7391157, -21.4483871, -1.50418663},
-    {-12.8148651, -20.8087921, -5.14397144},
-    {-12.0973454, -19.4584694, -8.78376579},
-    {-11.3712912, -16.828743, -13.0534477},
-    {-10.4413166, -13.346158, -16.8332062},
-    {-10.1286526, -8.22891045, -19.7029572},
-    {-10.0280685, -2.89844203, -21.1029148},
-    {-10.1259594, 3.00056958, -21.2427902},
-    {-10.0226536, 8.18887234, -20.0528736},
-    {-10.2346897, 12.595479, -18.0931149},
-    {-10.5419388, 15.7936964, -15.503252},
-    {-10.639802, 17.9968357, -12.9833412},
-    {-11.1646309, 19.4895592, -10.8136005},
-    {-11.6840258, 20.2003536, -8.57378006},
-    {-12.6139956, 20.6267948, -7.03387833},
-    {-13.1306496, 20.76894, -5.49397802},
-    {-13.5468712, 20.4847164, -4.51405859},
-    {-14.6777058, 20.1292133, -3.81407046},
-    {-15.9205713, 19.2053318, -3.53410363},
-    {-15.8112097, 18.6366177, -3.4640789},
-    {-16.8444424, 18.2101765, -3.81405544},
-    {-17.5675945, 17.3573036, -4.30401993},
-    {-18.813942, 15.722743, -5.00400972},
-    {-19.5339508, 14.6565952, -5.70394039},
-    {-19.6307774, 13.7325392, -6.40385342},
-    {-19.8373718, 12.4532309, -7.24379587},
-    {-20.1538734, 11.1029453, -8.43376064},
-    {-19.8406582, 9.46822166, -9.48366261},
-    {-20.1473751, 8.11780167, -10.533555},
-    {-20.354002, 6.76741648, -11.5834827},
-    {-20.1473427, 5.27490044, -12.3534222},
-    {-19.8373528, 3.85343766, -13.4033546},
-    {-19.4274578, 2.21879983, -13.8233614},
-    {-18.7009411, 0.44195044, -14.2432938},
-    {-18.0810623, -0.908422947, -14.4532776},
-    {-17.868185, -2.47205281, -14.8731613},
-    {-17.4581337, -3.96455717, -15.3631678},
-    {-17.4518623, -5.24387789, -15.5030699},
-    {-16.7349567, -6.30995035, -15.7131424},
-    {-16.1120605, -7.3049655, -15.6431036},
-    {-16.0057278, -8.15783405, -15.3630819},
-    {-15.5835838, -9.29497528, -15.4329424},
-    {-15.3769808, -9.72140789, -15.5029383},
-    {-15.4892502, -10.1478539, -15.4330759},
-    {-14.7661972, -10.9296465, -15.7130508},
-    {-14.2467642, -11.071784, -15.9929857},
-    {-14.1493139, -10.9296532, -16.0630703},
-    {-13.9398232, -10.9296465, -16.2030144},
-    {-13.426157, -10.7875109, -16.2730579},
-    {-13.2224607, -10.4321566, -16.9030533},
-    {-13.5266609, -10.2899971, -16.9729538},
-    {-12.5940647, -9.72141457, -17.4628658},
-    {-12.1865873, -8.29998112, -17.9529266},
-    {-12.0748405, -7.66033077, -18.7227116},
-    {-11.6561251, -7.16283274, -19.3525543},
-    {-10.8327007, -6.16782808, -19.6325817},
-    {-11.3546658, -4.60423422, -20.1226482},
-    {-10.9387579, -3.25388265, -20.3325768},
-    {-10.6289196, -2.04565907, -20.8225384},
-    {-10.8409233, -0.553117216, -21.2426167},
-    {-10.9387197, 1.01042449, -21.1725082},
-    {-10.3162937, 2.4318397, -21.312439},
-    {-9.8052969, 3.92439747, -21.4525414},
-    {-10.0065413, 4.49291277, -20.7524853},
-    {-9.90051842, 5.27467012, -20.8924179},
-    {-9.90586662, 5.8433075, -21.1725082},
-    {-9.69394398, 5.84323931, -21.1023998},
-    {-9.99571133, 5.84313822, -20.4022942},
-    {-10.3027563, 5.41668081, -20.1922569},
-    {-11.5529947, 4.84823608, -20.332468},
-    {-12.0664806, 3.85321474, -20.2624187},
-    {-12.7835245, 2.78709126, -19.9823341},
-    {-13.8248281, 1.57895029, -19.5625343},
-    {-14.232049, -0.0557228513, -19.2824554},
-    {-15.1585073, -1.8325212, -18.302494},
-    {-15.9905853, -3.04070258, -17.5326653},
-    {-16.1971073, -4.74640894, -16.5527554},
-    {-17.333086, -5.88355255, -15.4328556},
-    {-18.5754204, -6.59426022, -13.9630318},
-    {-19.3919907, -7.09176683, -12.4930515},
-    {-20.6311321, -7.4471221, -11.0231895},
-    {-21.5637093, -7.51819229, -9.55336189},
-    {-22.3829803, -7.44712353, -7.66349077},
-    {-22.9061089, -7.16283703, -6.33366013},
-    {-23.7356377, -6.9496212, -5.00380707},
-    {-24.2415466, -6.02571106, -3.81386828},
-    {-24.6545773, -4.60429382, -2.83396244},
-    {-25.3772736, -3.6803751, -2.20402575},
-    {-25.377306, -2.6853857, -1.85405993},
-    {-25.7866364, -1.19291508, -1.57407546},
-    {-25.9931641, -0.340065837, -1.85404944},
-    {-25.5767097, 0.797037542, -1.99402392},
-    {-25.573122, 1.57879317, -2.62394643},
-    {-24.8610516, 2.36063886, -3.3239162},
-    {-25.1672516, 2.14740229, -4.1638155},
-    {-24.6475182, 1.86309469, -5.00371408},
-    {-24.5373726, 1.29448915, -5.91357613},
-    {-24.0177116, 0.725905478, -6.75346613},
-    {-23.7149124, 0.0152447531, -7.03348017},
-    {-23.7149124, -0.695456207, -7.24345827},
-    {-23.8250732, -1.76148295, -7.73345613},
-    {-23.6116123, -2.47221136, -7.80340004},
-    {-24.1243801, -2.61436439, -7.31342649},
-    {-23.608263, -2.75650549, -7.38341999},
-    {-24.0211697, -2.11687517, -7.03345728},
-    {-24.2206612, -1.33513832, -6.82343388},
-    {-24.2206707, -0.482299417, -6.47347307},
-    {-24.7472858, 0.512736559, -5.7736125},
-    {-24.7472858, 1.0102278, -5.28366661},
-    {-24.8540783, 1.29453599, -3.95381927},
-    {-25.8899479, 1.43669844, -3.18391609},
-    {-25.5732327, 0.725949347, -2.34397817},
-    {-25.4664211, 0.299506724, -1.36406767},
-    {-25.8899803, -0.624350369, -0.524182618},
-    {-25.7831783, -1.97470486, 0.52571553},
-    {-25.5766907, -2.82755113, 1.15565205},
-    {-25.5766907, -3.96467519, 2.20554233},
-    {-25.9824905, -5.10181761, 3.39541674},
-    {-25.7795792, -6.16786432, 4.44530916},
-    {-24.8610649, -7.09177208, 5.7051959},
-    {-24.237999, -8.15783596, 6.965065},
-    {-23.5188313, -9.57924175, 7.24504519},
-    {-22.5861015, -10.9295874, 7.80497885},
-    {-22.1799259, -12.5642271, 7.38504457},
-    {-21.3505363, -14.2699146, 6.54511452},
-    {-20.0050297, -15.9755936, 5.49521112},
-    {-19.3887501, -17.2548866, 3.32542729},
-    {-18.0465736, -18.1077347, 0.455716491},
-    {-16.8954048, -18.5340328, -2.20395875},
-    {-16.279068, -17.8944263, -5.70360899},
-    {-15.2528362, -16.8284206, -9.06329155},
-    {-14.7366142, -14.1988096, -12.4229527},
-    {-14.4298162, -10.8585129, -15.4326811},
-    {-13.919385, -6.59426594, -17.4625759},
-    {-13.7129335, -2.11680317, -18.7224541},
-    {-13.6097031, 2.14744735, -19.2124062},
-    {-13.5006123, 5.48771858, -18.5123692},
-    {-14.117157, 8.68585014, -17.6024151},
-    {-14.0168104, 11.3865786, -16.3425884},
-    {-14.2233276, 12.8790579, -15.15271},
-    {-14.5448551, 13.518899, -13.6830149},
-    {-14.8457584, 13.8740988, -12.8429775},
-    {-15.364954, 14.3716507, -12.0730944},
-    {-16.1849861, 14.6558208, -11.3730907},
-    {-16.0968647, 14.3718109, -11.5132484},
-    {-16.7226009, 14.1587048, -11.3733292},
-    {-17.0232525, 13.5189037, -11.3032331},
-    {-17.3330765, 12.5239048, -11.0932522},
-    {-18.055912, 11.9553347, -11.3732252},
-    {-18.572319, 11.0314083, -11.4432192},
-    {-18.9885502, 9.96538448, -11.6532335},
-    {-19.6017799, 9.18351364, -11.7231607},
-    {-19.7050629, 8.40173531, -11.8631468},
-    {-19.4888077, 7.40662384, -11.9330339},
-    {-20.2115192, 6.55377769, -11.9330339},
-    {-20.8925343, 5.84317112, -11.6531658},
-    {-20.61796, 4.99016047, -11.1630449},
-    {-21.1923447, 4.45719481, -10.9181356},
-    {-21.0325241, 4.13733625, -11.3380423},
-    {-21.2022972, 3.07140017, -11.0232258},
-    {-21.3372517, 2.75142455, -10.7080593},
-    {-21.9867287, 2.43183732, -10.6033611},
-    {-21.9566135, 2.00518823, -10.6030712},
-    {-22.4363747, 1.57887173, -10.2882462},
-    {-21.6469364, 0.61932224, -10.4980831},
-    {-21.6469326, -0.126913339, -10.288105},
-    {-21.9616489, -0.340095669, -10.0781727},
-    {-22.7358818, -1.51275682, -9.65821934},
-    {-22.7926903, -2.89860702, -9.9032402},
-    {-21.7501678, -4.0357666, -9.62317657},
-    {-21.6469364, -5.13735247, -9.55318546},
-    {-21.9567184, -6.52321863, -8.71327496},
-    {-21.9465523, -8.4421072, -7.9432826},
-    {-22.880579, -9.50815678, -7.45337439},
-    {-21.7468605, -11.0716934, -5.21363688},
-    {-21.1724758, -11.8534451, -4.09372616},
-    {-21.6436024, -13.4880705, -1.64403331},
-    {-21.4404774, -13.7723656, 0.175768137},
-    {-21.5504036, -13.9856033, 1.64560115},
-    {-21.6469517, -14.1277151, 3.04545212},
-    {-21.6435642, -13.8434191, 3.5353992},
-    {-22.256115, -13.7012539, 3.95534778},
-    {-22.9855194, -13.13272, 4.16533136},
-    {-22.5726452, -12.2798824, 4.30531549},
-    {-23.2916756, -11.7823868, 3.675385},
-    {-22.772171, -11.2848883, 2.9754591},
-    {-23.6013565, -10.9295483, 1.71560276},
-    {-23.8043442, -10.574193, 0.595733941},
-    {-24.0177116, -9.86350536, -0.454161525},
-    {-23.6048336, -8.3710413, -1.43405068},
-    {-24.0142918, -6.80750227, -2.20395637},
-    {-24.7332554, -5.74146605, -3.11383629},
-    {-24.7297249, -4.39114952, -3.81374359},
-    {-24.8364468, -2.82761312, -4.16371775},
-    {-25.0499229, -1.33511889, -4.65369606},
-    {-24.6405354, -0.197983861, -4.72370625},
-    {-25.053442, 1.01020765, -4.51372957},
-    {-24.7437611, 2.28946853, -4.16376734},
-    {-24.4305935, 2.7158649, -4.58370399},
-    {-24.2276249, 2.85802889, -4.9336834},
-    {-24.6370258, 2.36051345, -5.28362608},
-    {-24.9537468, 1.86307156, -5.70362091},
-    {-24.7402515, 1.15232491, -6.05354118},
-    {-24.6370773, 0.441628277, -6.19352818},
-    {-24.3273735, -0.5533517, -6.33351183},
-    {-24.4340668, -0.837614298, -6.54350996},
-    {-24.3308315, -0.837616086, -6.75348854},
-    {-24.1243954, -0.482264102, -6.89347172},
-    {-23.6151409, -0.055805672, -7.03350353},
-    {-24.5478039, 0.725993812, -7.03352785},
-    {-24.5478745, 2.5738225, -6.75355816},
-    {-23.6082916, 3.71086669, -6.40352726},
-    {-23.5085049, 5.20337582, -5.9835906},
-    {-23.40868, 6.12731695, -5.35367775},
-    {-23.6256104, 7.40669918, -5.00376606},
-    {-23.9317799, 7.54880142, -4.65378475},
-    {-23.8146477, 8.04614449, -4.72370577},
-    {-22.9923153, 8.3304615, -5.07368612},
-    {-22.892477, 8.11728764, -5.56365681},
-    {-22.6893997, 7.40662384, -6.54357624},
-    {-22.7892323, 6.55374336, -7.17348862},
-    {-23.0955219, 5.27444124, -7.45343542},
-    {-22.7960873, 4.35061836, -7.94346142},
-    {-23.2056255, 3.63988376, -8.08342075},
-    {-22.8890572, 3.00019813, -8.08337116},
-    {-23.3054695, 2.78701091, -7.5934453},
-    {-22.892458, 3.14236093, -6.96351051},
-    {-23.7148552, 3.71089602, -6.2635622},
-    {-24.4374962, 3.92410874, -6.12357664},
-    {-24.2242184, 4.42153788, -5.14364481},
-    {-24.1209946, 4.91902924, -4.02376556},
-    {-24.5373116, 5.27441072, -3.04388762},
-    {-24.7473202, 5.55872345, -2.41396785},
-    {-25.1637402, 5.06126499, -1.85403872},
-    {-24.8434963, 4.99009943, -1.08409095},
-    {-24.9537945, 4.77695131, -0.594158709},
-    {-24.6511002, 4.49272871, -0.104223706},
-    {-25.373745, 4.13737774, 0.665695786},
-    {-25.6799145, 3.92413664, 0.945673227},
-    {-25.776001, 3.71086907, 1.22565114},
-    {-26.0821438, 3.56870127, 1.22565472},
-    {-25.5695839, 3.49765873, 1.50562084},
-    {-25.4699154, 2.85805464, 1.7155962},
-    {-25.2563744, 2.78693295, 1.92557657},
-    {-25.6692848, 2.64479303, 2.34553313},
-    {-25.5660744, 2.28944421, 2.76548529},
-    {-25.4592533, 1.93407083, 2.83547616},
-    {-25.8685532, 1.93404651, 2.76548386},
-    {-25.8756886, 1.86302412, 2.69549251},
-    {-25.9824753, 2.00518703, 2.41552377},
-    {-25.8720779, 1.79193163, 2.55550694},
-    {-25.8721161, 1.43658149, 2.41552305},
-    {-25.7689915, 1.50765073, 1.99557352},
-    {-25.5518284, 1.1522367, 1.64561737},
-    {-25.9682407, 0.512634277, 1.36564767},
-    {-26.0785675, -0.411229521, 0.735714018},
-    {-25.5553951, -1.05089104, 0.455755472},
-    {-25.6550636, -1.54839194, -0.104173027},
-    {-25.4485836, -2.4722929, -0.454130918},
-    {-25.8649769, -3.3251133, -0.384146422},
-    {-25.3454304, -4.10688353, -0.454130024},
-    {-25.1354828, -4.67544556, -0.734088719},
-    {-24.5093288, -5.38614845, -1.15401947},
-    {-24.8259392, -5.59934187, -1.64397967},
-    {-24.7332363, -5.74146461, -2.20394373},
-    {-24.9290333, -5.67041254, -2.41388202},
-    {-25.0357876, -5.52826834, -3.25379372},
-    {-24.9361439, -4.67542934, -3.5337739},
-    {-24.7227097, -4.10689306, -3.74372005},
-    {-24.6196041, -3.46727014, -4.09367752},
-    {-24.3991737, -3.11197495, -4.16360235},
-    {-25.0146828, -2.54343939, -4.58353138},
-    {-25.0217266, -2.61448312, -4.58356476},
-    {-24.9254608, -2.82766485, -4.58360052},
-    {-25.6373177, -2.89876842, -4.37357569},
-    {-25.0111637, -3.11199856, -4.23356009},
-    {-24.7087364, -3.75158858, -3.81365013},
-    {-24.4062214, -4.60439348, -3.39373398},
-    {-24.9220829, -5.24401188, -3.32374287},
-    {-25.2422009, -5.74147654, -2.90383601},
-    {-24.9326229, -6.31002855, -2.48388743},
-    {-24.6230087, -6.73644447, -1.92395365},
-    {-24.7121563, -7.16286659, -1.50396597},
-    {-25.0146828, -7.58927965, -1.22398269},
-    {-24.4988174, -7.66034937, -1.08400249},
-    {-24.8153191, -7.58927917, -1.43397307},
-    {-24.3957443, -7.44714546, -1.29397285},
-    {-24.1928463, -7.37607527, -1.6439358},
-    {-24.2925091, -7.44714499, -1.50394344},
-    {-24.5023556, -6.87859631, -1.99389076},
-    {-24.2925186, -6.80753136, -2.13385916},
-    {-24.5058575, -6.38111591, -2.20387173},
-    {-24.7087555, -6.16791487, -2.62380672},
-    {-24.715765, -5.95469856, -2.7638135},
-    {-25.0146637, -5.81257486, -2.62379527},
-    {-24.7016811, -6.16792345, -2.76376247},
-    {-24.4953823, -6.02578831, -2.76376247},
-    {-24.9045086, -6.16792774, -2.69375896},
-    {-24.9044704, -6.45219755, -2.34380794},
-    {-25.117857, -6.73646402, -1.92388642},
-    {-24.8118477, -7.0207324, -1.6439358},
-    {-24.282074, -7.66035271, -1.43392479},
-    {-23.8694382, -8.08675575, -1.43392599},
-    {-24.8975067, -8.58423042, -0.734013736},
-    {-24.9044609, -8.93957043, -0.314091146},
-    {-24.7943096, -9.15276909, -0.174096361},
-    {-24.1823635, -9.36597919, -0.454070956},
-    {-23.9726257, -9.934515, -0.244094655},
-    {-24.079237, -10.4319963, 0.315823048},
-    {-23.2540188, -10.8584023, -0.0341282524},
-    {-22.8413963, -11.6401463, -0.384079546},
-    {-22.8379955, -12.4929523, -0.664033771},
-    {-21.8065777, -13.1325598, -1.22395325},
-    {-21.0911427, -13.9143333, -2.13384843},
-    {-20.675211, -14.1275225, -3.32366848},
-    {-20.2495365, -14.4117317, -5.073349},
-    {-19.5339317, -13.7010813, -6.68316269},
-    {-19.4437923, -12.4929829, -8.71297646},
-    {-19.0311623, -10.9294872, -11.0226612},
-    {-18.6184883, -8.44209957, -13.1223822},
-    {-19.0311432, -5.24402666, -14.1722393},
-    {-19.3406143, -1.47742307, -15.012125},
-    {-18.4089737, 1.64955735, -15.0120831},
-    {-18.5153141, 4.35017395, -14.6621733},
-    {-19.0342827, 6.19797564, -13.6123571},
-    {-19.5501633, 7.40614176, -12.4225101},
-    {-19.4469891, 8.25895977, -11.5826235},
-    {-20.1625748, 8.40101814, -10.8126621},
-    {-20.4720955, 7.69033575, -10.3227272},
-    {-20.684967, 7.4061389, -10.0428238},
-    {-21.410553, 5.98480654, -9.90287495},
-    {-22.3391399, 4.42129898, -9.90287495},
-    {-22.6418476, 2.85774279, -9.90281487},
-    {-22.745039, 1.08103216, -9.34288883},
-    {-23.1678867, -1.19309533, -8.57307625},
-    {-23.4672089, -2.75664735, -7.73310471},
-    {-23.680357, -4.17798996, -6.47332096},
-    {-24.0896492, -5.88364315, -5.3534441},
-    {-23.8867836, -6.80752516, -4.09362841},
-    {-24.1963139, -7.66034746, -2.97377372},
-    {-24.6090393, -8.15782547, -1.36398101},
-    {-24.6090908, -8.44209957, -0.314118147},
-    {-24.5023899, -8.86851025, 1.1556927},
-    {-24.1789093, -9.29490566, 1.85560894},
-    {-23.9761162, -9.65024948, 2.90546155},
-    {-24.3886814, -9.93452168, 3.60536337},
-    {-24.1824341, -10.3609276, 4.16528463},
-    {-23.5599899, -10.7162619, 4.79519415},
-    {-22.8345661, -11.1426601, 5.56507778},
-    {-23.0477009, -11.7822847, 5.4951005},
-    {-22.325655, -12.3508272, 5.70507002},
-    {-22.2225094, -13.3457756, 5.63508081},
-    {-21.9164391, -14.1986065, 5.00517416},
-    {-21.0845165, -14.5539141, 4.23527193},
-    {-20.5687695, -15.2645903, 2.90545797},
-    {-20.4688549, -15.7620821, 1.01572502},
-    {-19.2278709, -16.3306046, -0.943990648},
-    {-18.9183941, -16.3306046, -2.97370958},
-    {-18.3058147, -16.3306446, -4.86347389},
-    {-17.7806721, -15.9041824, -6.82313108},
-    {-17.0616856, -15.1935244, -8.92286396},
-    {-16.1333828, -14.4828444, -10.672617},
-    {-15.5115461, -13.3457537, -12.7022848},
-    {-14.8837099, -12.1375761, -14.1719551},
-    {-14.3708839, -10.7162342, -15.7817631},
-    {-13.1507416, -8.93957615, -17.5317879},
-    {-12.4257412, -7.02073812, -18.861557},
-    {-11.8039618, -4.5333662, -20.0513382},
-    {-10.7697411, -2.04601049, -20.541214},
-    {-10.1535616, 1.00992751, -21.3111649},
-    {-9.62983418, 3.78148055, -21.4509697},
-    {-9.01090908, 6.33990335, -21.1010227},
-    {-8.80199814, 9.04042721, -20.471056},
-    {-7.78357553, 10.8173313, -20.2613621},
-    {-7.48177481, 12.0967007, -19.9115772},
-    {-6.97095776, 12.7364168, -19.9116879},
-    {-6.96336746, 12.3098593, -19.8415298},
-    {-6.75451803, 11.3859177, -20.2614193},
-    {-7.06399012, 10.0356264, -20.9613247},
-    {-6.33684254, 8.54311562, -21.5911236},
-    {-6.95579624, 6.12680531, -22.2210388},
-    {-6.95834208, 3.56839204, -22.5710468},
-    {-7.38116646, 0.228271797, -22.8512554},
-    {-7.27296305, -3.32517552, -22.3611965},
-    {-7.78610706, -6.94966221, -21.7312222},
-    {-8.29677677, -10.5741329, -20.401289},
-    {-8.40253353, -13.701129, -18.371624},
-    {-8.50567818, -16.1174374, -16.2719116},
-    {-8.90517139, -17.6808186, -14.2419901},
-    {-9.52402496, -18.8178978, -12.7022123},
-    {-10.0423183, -19.7417965, -11.5124273},
-    {-10.7642593, -19.3153915, -11.0924883},
-    {-11.4862204, -18.9600544, -10.5325718},
-    {-12.4087887, -18.3204002, -10.7424755},
-    {-12.9244127, -16.8279934, -11.8623066},
-    {-13.7523537, -15.2645388, -12.282279},
-    {-15.19911, -13.2746716, -13.5421295},
-    {-16.530756, -10.431962, -14.3818836},
-    {-17.3618793, -8.29995823, -14.521946},
-    {-18.3900394, -6.38114977, -14.1719561},
-    {-19.4277477, -4.46232176, -13.5421295},
-    {-20.5620861, -3.60951757, -12.6322708},
-    {-21.2775536, -2.96993232, -11.3723793},
-    {-22.112606, -2.82776165, -10.3926229},
-    {-22.6249523, -3.11204481, -9.48272324},
-    {-23.243763, -3.18311262, -8.64284897},
-    {-23.5497246, -3.82272673, -8.01291466},
-    {-23.5394077, -4.1070261, -7.52291489},
-    {-24.1615906, -4.1780839, -6.54308748},
-    {-24.1581059, -4.39129114, -5.84317732},
-    {-24.2646751, -4.74661636, -5.63322973},
-    {-24.4744453, -4.67554235, -5.00334454},
-    {-23.9484043, -4.67556667, -4.51336718},
-    {-24.3573074, -4.53344154, -3.81346297},
-    {-24.7732353, -4.53343391, -3.46353197},
-    {-24.9900398, -4.74660969, -2.76368403},
-    {-24.6841316, -4.60446787, -1.9238205},
-    {-24.8797798, -4.74662447, -1.64383149},
-    {-25.4987335, -4.462358, -1.57384133},
-    {-25.7084427, -5.0308814, -1.15391862},
-    {-25.0860786, -5.38622475, -0.593997359},
-    {-25.1892376, -5.52835846, -0.244051769},
-    {-25.0861263, -5.7415576, 0.105892628},
-    {-25.0861073, -6.45222569, 0.805785179},
-    {-25.0825729, -7.1628933, 1.22572219},
-    {-24.7732735, -7.5892911, 1.5056777},
-    {-24.1580582, -8.29995728, 1.78563011},
-    {-24.257658, -8.93955517, 2.48552275},
-    {-23.9518528, -10.0766201, 2.90545559},
-    {-23.5428181, -11.0715628, 2.97544551},
-    {-22.5083504, -11.9954195, 3.18541121},
-    {-22.3020992, -12.777153, 3.4653697},
-    {-21.6800289, -13.9852715, 3.18541098},
-    {-20.6522694, -15.1223536, 2.90545607},
-    {-20.2430439, -16.2594433, 2.20555949},
-    {-19.9369869, -17.0411949, 1.2257129},
-    {-19.3149738, -17.8229065, 0.175876379},
-    {-17.765131, -18.0360832, -1.0139302},
-    {-16.5276451, -18.7467518, -3.04361653},
-    {-15.6056662, -18.7468014, -5.35329247},
-    {-15.5085773, -17.6097813, -8.15291595},
-    {-14.7806368, -15.5487871, -11.2324047},
-    {-14.5744143, -13.0614443, -13.8919992},
-    {-14.6775446, -9.72129726, -15.9916801},
-    {-14.3681622, -5.95474768, -17.1115112},
-    {-14.574419, -2.25926518, -17.9513836},
-    {-15.2962933, 0.5123505, -18.0213737},
-    {-15.3993864, 2.57328415, -17.8114071},
-    {-16.1213226, 4.06569576, -17.391468},
-    {-16.0151424, 3.99459839, -17.1814537},
-    {-16.2244148, 3.42609262, -17.1815014},
-    {-16.849329, 2.21800089, -16.9016342},
-    {-16.9463615, 0.157014936, -16.4816055},
-    {-16.7430973, -2.82779217, -16.4816532},
-    {-16.5399055, -5.81259966, -15.9217815},
-    {-17.0463047, -8.93955803, -14.5918522},
-    {-16.946291, -12.4929085, -12.702179},
-    {-16.3138885, -15.0512457, -10.4973688},
-    {-15.9059896, -16.6857967, -9.06264496},
-    {-15.3904514, -17.9649925, -7.03296757},
-    {-15.7998762, -18.959898, -5.07326078},
-    {-15.8544388, -19.9548531, -3.25356722},
-    {-15.0751896, -20.2390614, -2.55365491},
-    {-14.6686239, -20.7365837, -1.64382219},
-    {-14.1575651, -20.9142971, -1.36388147},
-    {-14.5626202, -20.9497528, -1.36385691},
-    {-14.6127129, -20.9142056, -2.20371628},
-    {-14.4624815, -19.9548531, -3.14858365},
-    {-14.7718019, -20.0614529, -4.30340052},
-    {-14.7747374, -18.675684, -5.98315668},
-    {-15.3904467, -17.8228607, -7.24293375},
-    {-15.3949594, -16.7568951, -9.02769375},
-    {-15.9969978, -14.6248045, -11.3721457},
-    {-16.7778244, -12.5994558, -12.4920473},
-    {-16.7824326, -9.50807953, -13.7519026},
-    {-18.0244141, -6.41668463, -14.5918293},
-    {-19.0087852, -1.05112731, -14.5918932},
-    {-20.0400372, 1.47175014, -14.0669727},
-    {-20.0367775, 6.62406731, -12.0722427},
-    {-20.3445206, 8.72052193, -9.97254276},
-    {-21.422266, 11.2788525, -6.40306711},
-    {-22.0409107, 12.6646471, -3.14858365},
-    {-21.6834126, 12.6646967, 2.20556569},
-    {-21.5803375, 11.5986977, 5.84499693},
-    {-22.0460358, 10.2129202, 8.08465672},
-    {-22.5150433, 7.44137621, 11.4441643},
-    {-22.2021942, 4.06565666, 13.8237801},
-    {-21.7931156, 0.299154758, 14.4537086},
-    {-22.3087769, -3.25421143, 14.4537086},
-    {-22.0061417, -6.94967651, 14.0338278},
-    {-21.6933861, -9.93450642, 12.1440763},
-    {-21.6933861, -12.1375799, 8.92457104},
-    {-21.7898006, -13.7721014, 5.56504869},
-    {-21.6833496, -14.1984863, 1.99559939},
-    {-21.3773022, -13.2746296, -1.36389232},
-    {-21.7964592, -11.7111835, -3.81353784},
-    {-21.9994144, -10.0055647, -5.5632596},
-    {-21.9994144, -8.58422565, -6.5431118},
-    {-22.8278313, -7.80248737, -6.54313374},
-    {-23.0272999, -7.37609053, -6.12315416},
-    {-23.6631813, -7.87355423, -5.2833786},
-    {-23.7525558, -8.72635841, -4.30345154},
-    {-23.137188, -10.0766373, -2.62371731},
-    {-22.92416, -11.8532972, -0.524015248},
-    {-22.9241409, -12.7060986, 1.92560744},
-    {-22.102541, -13.6299801, 4.58520317},
-    {-21.4837914, -14.0563822, 7.73472691},
-    {-20.6555271, -13.7010345, 10.0443573},
-    {-19.7274017, -13.2035656, 12.2840185},
-    {-18.5931473, -12.3507643, 14.6636467},
-    {-17.2556629, -10.8583689, 16.8333473},
-    {-16.1303806, -9.2949028, 19.1431198},
-    {-15.6086721, -7.37608767, 20.2628708},
-    {-14.7718019, -5.38623762, 21.2425442},
-    {-14.3651791, -3.18314052, 22.432457},
-    {-13.8554459, -0.62470597, 22.9924641},
-    {-13.4371719, 2.21792293, 22.9223785},
-    {-12.9187317, 4.56310415, 22.5723839},
-    {-13.4429617, 6.69520855, 22.0126114},
-    {-13.2280369, 9.18243122, 20.6126919},
-    {-13.334013, 11.172348, 19.3529243},
-    {-14.0499458, 13.2331772, 17.6731148},
-    {-14.3564205, 14.5833883, 15.9933453},
-    {-14.6686954, 15.7205048, 14.0336885},
-    {-15.2873402, 16.9997005, 12.0740013},
-    {-16.1122417, 17.923563, 9.83435822},
-    {-16.730938, 18.3499622, 7.17477369},
-    {-16.6277409, 18.2788963, 4.79515553},
-    {-17.4494972, 18.0656376, 2.20557165},
-    {-18.1712532, 17.4971066, -0.663973212},
-    {-18.4868774, 16.6444283, -2.83364987},
-    {-19.0024204, 15.3652325, -5.14328432},
-    {-19.2054462, 13.23318, -7.52288866},
-    {-19.9304752, 10.7458992, -9.34262943},
-    {-20.4459991, 8.18750095, -11.0223684},
-    {-20.2397671, 5.13163137, -12.1421938},
-    {-20.6587906, 1.79155219, -12.352232},
-    {-20.9648895, -1.61968231, -11.72229},
-    {-21.4771137, -4.39128351, -10.7424154},
-    {-21.8829231, -7.23396397, -8.92263603},
-    {-21.9793129, -9.57913589, -7.03290129},
-    {-21.8762589, -11.0004606, -4.58329678},
-    {-22.6046467, -11.7111349, -1.43384981},
-    {-22.9002247, -12.2796278, 1.64565957},
-    {-23.2094784, -11.7111015, 4.79513168},
-    {-23.3126564, -10.4319191, 7.17472553},
-    {-23.5188351, -8.86847591, 9.13438702},
-    {-23.5256615, -6.59437132, 10.8141413},
-    {-23.518774, -4.32027864, 12.1438742},
-    {-23.3126373, -1.97511709, 12.4238272},
-    {-23.3092079, 0.867486298, 12.4937906},
-    {-23.5187836, 2.85734701, 12.4238262},
-    {-23.2027512, 4.63392353, 11.9338665},
-    {-22.3815079, 6.33953094, 12.0038767},
-    {-22.2885723, 7.68988276, 11.6540031},
-    {-22.2885723, 8.61374092, 11.8639679},
-    {-21.4572201, 9.18218327, 12.4938154},
-    {-20.5327511, 9.82181835, 12.983757},
-    {-19.9207096, 10.3193674, 13.5437155},
-    {-19.405262, 10.1772337, 14.4535646},
-    {-18.9930344, 10.2482977, 15.4334068},
-    {-17.9587612, 10.1771889, 16.0632725},
-    {-17.7525768, 10.4614525, 16.7631531},
-    {-16.9247589, 10.7456741, 17.5329914},
-    {-16.5185452, 10.3193655, 17.8830051},
-    {-15.5907269, 10.3904324, 18.3029366},
-    {-14.5596933, 10.7457628, 18.722868},
-    {-14.2533283, 11.101141, 19.3528061},
-    {-13.5345078, 11.7407846, 19.4228344},
-    {-13.1163759, 11.9538879, 19.4927406},
-    {-12.1856756, 12.3091679, 19.632679},
-    {-11.3664551, 13.0199299, 19.5627708},
-    {-11.263401, 13.58846, 19.3528061},
-    {-10.4385424, 14.4412575, 19.2828159},
-    {-10.2296648, 15.0807962, 19.2127914},
-    {-10.0154047, 15.4359589, 18.4427986},
-    {-10.2269478, 16.0756626, 17.7429924},
-    {-9.70879745, 16.9283943, 16.6231461},
-    {-10.1211576, 17.7811871, 16.0632381},
-    {-10.5416775, 18.5631008, 15.0834923},
-    {-10.5416632, 19.0605659, 13.9636736},
-    {-11.0627165, 19.9845619, 12.6339331},
-    {-11.7789106, 20.908287, 11.1641273},
-    {-11.9794903, 21.2634773, 9.06443214},
-    {-12.1913042, 21.6189499, 7.03478479},
-    {-12.7124662, 21.9744244, 4.93514395},
-    {-13.0218382, 21.6901569, 2.83546209},
-    {-13.6375856, 21.6190224, 0.105904028},
-    {-13.0160999, 20.9793549, -2.41368461},
-    {-13.7349548, 19.9843559, -4.93326759},
-    {-14.2474909, 18.9183025, -7.59280109},
-    {-14.3593559, 17.0707664, -9.97250557},
-    {-14.8749132, 14.7966366, -12.2121487},
-    {-14.7747755, 12.2383013, -14.5218172},
-    {-14.3534994, 9.18231297, -16.3413982},
-    {-14.978034, 5.55799866, -17.3213348},
-    {-14.6686954, 1.93361354, -18.3011799},
-    {-14.0471287, -2.2593205, -18.5810852},
-    {-13.9411345, -6.09690046, -17.8811474},
-    {-14.2474909, -9.72127247, -16.7612839},
-    {-13.7378426, -12.6349974, -14.9416695},
-    {-13.316823, -15.1222658, -12.841897},
-    {-12.9101248, -16.9700222, -11.4421988},
-    {-12.8184748, -18.1071758, -10.6024647},
-    {-12.5034647, -17.9649944, -10.672389},
-    {-11.7844391, -17.3964844, -11.3023252},
-    {-12.0853615, -16.5436249, -12.6320028},
-    {-12.5980358, -14.9801521, -14.3116894},
-    {-12.5980358, -12.7060423, -15.7114582},
-    {-12.4892626, -9.9344635, -17.5310574},
-    {-12.9044914, -6.87863874, -18.5109425},
-    {-13.2108803, -3.39643002, -19.0707951},
-    {-13.8382511, -0.0562642179, -19.2809143},
-    {-13.7409344, 3.07066321, -18.7211151},
-    {-13.5229988, 6.12640095, -18.2309895},
-    {-14.3534851, 8.82697868, -17.2512512},
-    {-13.9439182, 11.3854132, -15.9215117},
-    {-13.9439182, 13.9437857, -14.3817654},
-    {-13.6289454, 15.9335308, -12.3520164},
-    {-13.2165804, 18.1365757, -10.0423975},
-    {-12.9073076, 19.8421593, -6.89292002},
-    {-13.219449, 20.9082184, -4.09340096},
-    {-12.1912708, 21.9032135, -0.733959794},
-    {-11.358181, 22.4715233, 3.0454247},
-    {-10.945816, 21.6898022, 7.03476334},
-    {-10.0180645, 20.4816837, 11.1640625},
-    {-9.20129585, 19.0605583, 14.6635675},
-    {-8.58275032, 17.2128448, 17.6730671},
-    {-7.86096144, 14.5123177, 20.4026394},
-    {-6.8324976, 11.7407846, 22.6423225},
-    {-5.79650021, 9.04017925, 24.2519627},
-    {-5.07235479, 6.05537176, 25.4417152},
-    {-4.97411203, 3.14170933, 26.0017338},
-    {-4.97653437, 0.654419661, 26.3517342},
-    {-5.59026337, -1.83293521, 26.4216099},
-    {-6.72438431, -4.53345013, 25.7217255},
-    {-7.9667325, -6.87862921, 24.8119793},
-    {-10.2295694, -8.65528297, 23.5520821},
-    {-12.9130888, -9.43701649, 22.0823631},
-    {-15.4875116, -9.86340809, 20.2626209},
-    {-17.7588692, -9.50808144, 18.5829277},
-    {-19.5115547, -8.22888947, 17.2531433},
-    {-21.0613899, -6.52329445, 15.9933786},
-    {-22.2986984, -4.24916983, 14.6635923},
-    {-22.8006668, -2.33042526, 13.8236122},
-    {-22.7043705, -0.340551168, 13.7536812},
-    {-22.494751, 1.08075023, 14.0336075},
-    {-22.1854877, 2.43100309, 14.6635027},
-    {-21.5602837, 3.78119802, 15.4333115},
-    {-21.2444382, 4.98925161, 15.9231634},
-    {-20.7356071, 6.48169374, 16.4831352},
-    {-19.2925739, 7.97406864, 16.2731705},
-    {-18.461565, 9.8216877, 15.9931526},
-    {-17.9525108, 11.3852186, 15.3633261},
-    {-17.8431721, 12.877491, 14.4534254},
-    {-17.740097, 14.1566677, 13.4735947},
-    {-18.0493279, 14.2277365, 12.4237814},
-    {-18.5583401, 14.3697605, 11.3039331},
-    {-19.2893295, 14.0145931, 10.8140821},
-    {-20.0108242, 13.2328711, 10.3241673},
-    {-20.728981, 12.2379103, 9.13436222},
-    {-21.2344875, 11.8824387, 8.57441235},
-    {-21.6567116, 11.5983181, 8.36449146},
-    {-21.6566982, 11.8115158, 7.8045907},
-    {-21.141346, 12.3089733, 8.01455307},
-    {-20.5262146, 13.0907421, 8.01456738},
-    {-20.5262146, 13.8724613, 7.66462851},
-    {-20.4133759, 14.4408236, 6.96471834},
-    {-19.9013062, 14.1566172, 6.47481537},
-    {-20.6259785, 13.8013449, 7.03472471},
-    {-21.0349617, 13.3748999, 7.80457926},
-    {-20.3233128, 12.5933332, 8.92442513},
-    {-20.3200684, 12.0958261, 9.20436096},
-    {-20.8288422, 12.1667919, 8.50445461},
-    {-21.3474121, 12.0957775, 7.94456625},
-    {-21.7529984, 11.9535503, 6.47480631},
-    {-22.1686401, 12.2378607, 5.00507259},
-    {-21.6500759, 12.5220709, 3.95526218},
-    {-21.3375416, 12.5220194, 2.97543478},
-    {-21.4472599, 12.7353163, 1.43570912},
-    {-21.9726448, 13.0197248, 0.035940513},
-    {-21.8729153, 12.6644506, -1.08387566},
-    {-21.4539471, 12.6643505, -1.71374798},
-    {-21.4472599, 12.5931845, -2.34361696},
-    {-21.6500626, 11.8114223, -3.74334764},
-    {-21.03829, 11.1008606, -5.07315111},
-    {-21.1446934, 9.67960453, -6.68288612},
-    {-20.8321247, 8.25825214, -8.36257362},
-    {-20.9351788, 6.97907782, -9.2024231},
-    {-20.9418335, 5.27357769, -9.97234821},
-    {-20.7291031, 3.49688053, -10.7421532},
-    {-21.1446552, 1.72027409, -11.7220154},
-    {-21.0448265, -0.269544601, -12.2119665},
-    {-20.2235508, -2.54361963, -12.4919529},
-    {-19.6984119, -4.32029486, -12.7018099},
-    {-19.183012, -5.81267118, -12.491847},
-    {-18.4679298, -7.02077293, -12.4219294},
-    {-18.2617493, -7.66036177, -12.071991},
-    {-18.2617168, -8.72634792, -12.2119665},
-    {-17.6432762, -9.79232883, -12.071991},
-    {-17.327795, -10.3608408, -12.3518686},
-    {-17.4278088, -10.5029659, -12.5617971},
-    {-17.6370583, -10.6451054, -12.9117737},
-    {-18.0461979, -10.147644, -12.9117346},
-    {-17.7338657, -9.65018272, -13.2616339},
-    {-17.0185642, -9.50806046, -13.4016867},
-    {-16.7187023, -9.36594296, -13.6817551},
-    {-16.9186554, -8.79740906, -13.6116877},
-    {-17.1216583, -8.6552763, -13.8216114},
-    {-17.1278896, -8.79741192, -13.8216915},
-    {-17.3371086, -8.79741383, -13.5417776},
-    {-17.3309288, -8.79741001, -13.6116877},
-    {-17.5339508, -9.0106039, -13.5416622},
-    {-17.9493694, -8.72634411, -13.0517855},
-    {-18.364809, -8.79741096, -12.9118481},
-    {-18.6645565, -8.5131464, -12.6317863},
-    {-18.9899139, -8.01568699, -12.2820244},
-    {-19.6114655, -7.87355661, -12.0720968},
-    {-19.1830635, -7.73142862, -11.7919712},
-    {-19.3891582, -7.30503941, -11.5820065},
-    {-20.3168201, -6.87864685, -10.8821278},
-    {-20.5294743, -6.31011438, -10.6722307},
-    {-20.8321781, -5.74160147, -10.1822529},
-    {-21.3408566, -5.45735312, -9.69227791},
-    {-21.9658623, -5.38627577, -9.48237514},
-    {-21.8694859, -5.10199928, -9.20248032},
-    {-21.9725628, -4.81773806, -8.78255177},
-    {-22.3815365, -5.10200739, -8.36259747},
-    {-22.5809097, -4.7466979, -8.08259392},
-    {-22.8901024, -4.53350163, -7.8726325},
-    {-22.9999866, -4.74667978, -7.73270798},
-    {-22.8006134, -4.67559814, -7.66276884},
-    {-22.3849087, -4.74667168, -7.45277834},
-    {-23.1065235, -4.88880348, -7.31280327},
-    {-23.3126888, -5.10199928, -7.10283947},
-    {-23.4191437, -4.95986176, -7.10286283},
-    {-22.694149, -5.24413109, -7.17282629},
-    {-23.3092079, -5.52839994, -7.31277943},
-    {-22.7938404, -5.9547925, -7.59273052},
-    {-22.3815365, -6.31011963, -7.87268162},
-    {-22.3883343, -6.80757236, -8.01271057},
-    {-22.085741, -7.16289759, -8.22272682},
-    {-21.1578369, -7.4471612, -8.57266808},
-    {-20.9483662, -7.94462204, -8.64262962},
-    {-20.7356777, -8.51314926, -9.06250477},
-    {-20.0237675, -9.01061726, -9.55251122},
-    {-19.6081829, -9.57913876, -9.76244545},
-    {-19.5985508, -10.0765867, -9.7623558},
-    {-19.0863552, -10.4319201, -10.1823139},
-    {-18.7771168, -10.8583136, -10.6022406},
-    {-18.6740284, -11.3557739, -10.742219},
-    {-17.7494221, -11.7111101, -10.882225},
-    {-17.849556, -11.8532333, -10.8122025},
-    {-18.268034, -11.7821865, -10.3923397},
-    {-17.7494545, -11.9953728, -10.2523336},
-    {-17.7557068, -11.6400614, -10.5323496},
-    {-18.3148155, -12.066433, -9.86738205},
-    {-18.479002, -11.6400652, -9.65750408},
-    {-19.3021297, -10.7872696, -9.41253185},
-    {-20.2300568, -10.2187386, -9.41253185},
-    {-21.0613899, -9.29488564, -9.55256748},
-    {-21.1611996, -8.15782356, -9.27258396},
-    {-21.1545353, -6.94970274, -9.48249149},
-    {-21.6733761, -5.52837324, -9.69248772},
-    {-22.085741, -4.53345203, -9.55250645},
-    {-22.29533, -3.60958099, -9.27258396},
-    {-22.391716, -3.11214066, -9.6924572},
-    {-22.0790615, -3.89387417, -9.55245018},
-    {-21.982666, -4.67558289, -9.2025671},
-    {-21.3574619, -6.31011152, -8.78258133},
-    {-21.4073372, -7.26949835, -8.6075964},
-    {-21.453886, -8.37101746, -7.94267082},
-    {-21.2543221, -9.36594105, -7.31282759},
-    {-22.4947567, -10.6806622, -5.6681242},
-    {-22.178772, -11.4268379, -4.72324753},
-    {-21.2625828, -12.2796602, -3.04358006},
-    {-22.2818165, -12.9902811, -1.50379896},
-    {-21.8762112, -12.91924, 0.945778608},
-    {-22.6341801, -12.9191856, 3.04542732},
-    {-22.4947567, -12.7060413, 4.2002387},
-    {-22.6493912, -12.1730471, 6.40487289},
-    {-22.4845676, -11.4268303, 8.18954182},
-    {-22.4846191, -10.4319143, 10.1841908},
-    {-22.0756702, -9.36593628, 11.1640415},
-    {-22.0207844, -8.86847496, 12.2838278},
-    {-22.0157642, -7.90909195, 13.3336077},
-    {-22.0722542, -6.45225286, 14.1734991},
-    {-22.1787243, -5.67052507, 15.0133867},
-    {-21.8712482, -5.45732546, 15.538311},
-    {-20.938509, -4.49795389, 15.9581909},
-    {-20.7356071, -3.5385561, 16.6231098},
-    {-20.5262146, -3.04111004, 17.1829815},
-    {-20.4231415, -2.11726046, 17.8828583},
-    {-20.6325665, -1.90404963, 18.0228729},
-    {-19.907774, -1.6908673, 18.5127487},
-    {-19.1862564, -1.61980164, 18.8626881},
-    {-18.471035, -2.54362702, 19.5626507},
-    {-18.1618156, -3.39641547, 19.7026253},
-    {-17.7494545, -4.46240234, 20.4025078},
-    {-16.8186302, -5.24413157, 21.0323582},
-    {-15.9940243, -5.45732784, 21.3822975},
-    {-15.1723347, -5.17305899, 21.6622963},
-    {-15.3785009, -4.88879681, 22.0122356},
-    {-14.5508537, -4.32028008, 22.3621292},
-    {-14.2445698, -3.39641452, 22.9220829},
-    {-14.1327562, -3.11219025, 23.0619106},
-    {-13.6202202, -2.47258568, 22.991972},
-    {-13.6203241, -1.12234581, 23.1319485},
-    {-13.3168373, -0.269519627, 23.2020359},
-    {-14.2533092, 0.441195935, 22.9222298},
-    {-14.4507542, 1.00966203, 22.9220829},
-    {-14.3505783, 1.15181589, 22.8521423},
-    {-13.9440222, 1.43612599, 22.7822533},
-    {-14.3564539, 1.22292721, 22.9222298},
-    {-14.1473007, 0.796506524, 22.7822056},
-    {-13.9469385, 0.44121784, 22.7123127},
-    {-14.1502361, 0.156933337, 22.5722885},
-    {-14.4507351, 0.29900372, 22.4321671},
-    {-15.2725582, 0.583248675, 22.1521664},
-    {-15.799881, 0.867595911, 21.802412},
-    {-16.2061462, 1.57821095, 21.3124008},
-    {-17.1340351, 2.43100309, 20.8924694},
-    {-17.2401772, 3.14169002, 19.9826603},
-    {-18.1617966, 3.42589903, 19.4226723},
-    {-18.683567, 4.27874756, 18.5129013},
-    {-19.0959702, 4.77621078, 17.9529934},
-    {-19.6114273, 4.98940897, 16.8331776},
-    {-20.2267227, 5.91323423, 15.9932823},
-    {-20.2299995, 6.26859903, 15.503397},
-    {-20.9451351, 6.97918844, 14.9434261},
-    {-20.9483891, 7.54774904, 14.453536},
-    {-20.9483662, 7.90307856, 13.6136789},
-    {-21.3441677, 8.40034485, 13.2636089},
-    {-21.0448265, 8.82685757, 12.5638018},
-    {-20.851757, 9.46661377, 11.934},
-    {-21.0547295, 9.82190323, 11.5840349},
-    {-20.8485985, 10.5325632, 10.9541388},
-    {-20.8453064, 11.3142443, 10.744153},
-    {-20.0173168, 11.7405939, 10.6741457},
-    {-20.1171799, 12.0958767, 10.4641628},
-    {-20.2300186, 12.593482, 10.5342073},
-    {-19.7113361, 12.7355642, 10.6741648},
-    {-18.9832821, 12.8775959, 10.8840895},
-    {-18.6803932, 13.0198298, 11.3740482},
-    {-18.577301, 12.4513016, 12.3538866},
-    {-18.1649456, 11.8827734, 13.0537691},
-    {-18.5804653, 11.4564257, 13.9636469},
-    {-18.5773392, 10.4614515, 15.0834351},
-    {-18.9928398, 8.96911335, 16.1332912},
-    {-18.6835384, 7.68992186, 17.1831207},
-    {-18.3773861, 5.7001009, 17.813055},
-    {-18.380579, 3.49707532, 18.4429893},
-    {-19.102335, 1.50721478, 18.9329128},
-    {-19.0959167, -1.05120766, 18.8628445},
-    {-19.6146469, -3.46745038, 18.5829296},
-    {-19.0959835, -5.7415719, 18.0229836},
-    {-19.501894, -7.58929205, 16.9730854},
-    {-19.6049862, -9.22380924, 15.8532715},
-    {-20.3363838, -10.8583431, 14.383605},
-    {-20.030304, -11.8532782, 12.913867},
-    {-20.2365227, -12.6350098, 11.3741112},
-    {-20.7520599, -13.2035408, 9.7643671},
-    {-21.1678162, -13.4167538, 8.36460304},
-    {-21.4837914, -13.4878464, 6.82486391},
-    {-21.8996372, -13.4878597, 4.86516666},
-    {-22.1989403, -13.2035532, 3.04543447},
-    {-22.614769, -12.8482323, 1.64565194},
-    {-23.1235428, -11.9954109, 0.245877683},
-    {-22.820982, -10.7162275, -0.803973675},
-    {-23.0238361, -10.1476898, -1.99377716},
-    {-22.9207439, -9.29488945, -2.76365876},
-    {-23.6425285, -8.65528965, -3.95347333},
-    {-23.5428715, -7.80248928, -4.44341183},
-    {-22.9241409, -7.09182072, -5.14330626},
-    {-22.9241791, -6.66542006, -6.12315464},
-    {-23.0204544, -5.74156475, -6.89298916},
-    {-22.9139099, -5.10197163, -7.24291086},
-    {-22.8176193, -4.46235847, -7.94284868},
-    {-22.2022457, -3.96488118, -8.57277775},
-    {-21.8962746, -3.18313718, -9.06272793},
-    {-22.0958481, -3.18315983, -9.6225872},
-    {-21.7831364, -3.11210442, -10.0424891},
-    {-21.2709084, -3.32529235, -10.3224754},
-    {-21.2675991, -4.10703516, -10.5324116},
-    {-20.6456947, -5.03090572, -10.6723585},
-    {-20.2332592, -5.95476961, -10.6023684},
-    {-19.8306122, -7.09182405, -10.6724529},
-    {-19.8370724, -8.72635651, -10.1825924},
-    {-19.3117828, -10.2898226, -10.0425196},
-    {-19.418066, -11.3558283, -9.48263741},
-    {-18.4836845, -12.0664759, -9.20262432},
-    {-18.4836521, -13.06141, -8.78268909},
-    {-18.3837223, -13.4167528, -8.29279613},
-    {-18.6899033, -13.6299391, -8.01281166},
-    {-18.796154, -13.9142199, -7.8028698},
-    {-18.1775055, -13.9852867, -8.01283646},
-    {-18.6899033, -14.1274042, -7.80284452},
-    {-19.102335, -14.1984711, -7.52288866},
-    {-18.8897324, -14.1273737, -7.52283955},
-    {-18.5804462, -13.9141769, -7.5228405},
-    {-18.7866783, -13.7720461, -7.24288702},
-    {-19.0863228, -12.990283, -7.66274261},
-    {-18.9864216, -12.9192266, -8.15268803},
-    {-19.5082779, -12.4217892, -8.15273857},
-    {-19.8176212, -12.2085905, -7.662817},
-    {-20.4328518, -11.9243174, -7.3828392},
-    {-21.1611862, -11.3558016, -7.52286482},
-    {-20.8485985, -11.0715332, -7.24288702},
-    {-20.4361668, -10.4319372, -7.17289829},
-    {-20.9484406, -10.3608637, -6.82293224},
-    {-21.5636139, -9.72126961, -6.61294365},
-    {-21.9759598, -9.43700504, -6.4729681},
-    {-21.8695335, -8.93954372, -6.33297062},
-    {-22.3849182, -8.86847687, -6.33297157},
-    {-22.9071217, -8.29995346, -6.26302528},
-    {-22.793869, -8.0867548, -5.77304649},
-    {-22.4879742, -7.73142767, -5.70307684},
-    {-22.6941719, -7.16290283, -5.77306557},
-    {-23.2130127, -7.09183502, -5.91306353},
-    {-23.1166935, -6.66543341, -5.70313883},
-    {-23.2197952, -6.73649931, -6.33303404},
-    {-23.4225693, -6.31010723, -6.54297924},
-    {-23.4225693, -6.23904133, -6.68295574},
-    {-23.3194866, -5.88371181, -6.75294399},
-    {-22.7972889, -5.88372278, -7.31280279},
-    {-22.1753902, -5.9547925, -7.73270655},
-    {-21.969244, -6.45225048, -7.87268305},
-    {-21.6633568, -6.45224571, -8.36262321},
-    {-21.6733761, -6.87863398, -8.50267887},
-    {-21.3640842, -7.37609434, -9.06258869},
-    {-21.2543182, -7.94462299, -9.27249622},
-    {-20.6259594, -8.2999506, -9.3423996},
-    {-20.220253, -8.93954182, -9.13249302},
-    {-20.0108433, -10.0765867, -8.85251236},
-    {-19.5018272, -11.000452, -8.92255497},
-    {-19.1990757, -11.7111292, -9.06258869},
-    {-19.1990757, -12.2796574, -8.57266903},
-    {-19.1894855, -13.3456078, -7.59275675},
-    {-19.2989578, -14.1273632, -6.68295527},
-    {-18.9864941, -14.9090681, -5.91306353},
-    {-18.5772724, -15.6197462, -5.07322216},
-    {-18.3742657, -15.9040298, -4.51333237},
-    {-18.4836845, -16.5436649, -3.67350054},
-    {-19.0991421, -16.6147099, -3.04358673},
-    {-18.8897705, -16.9700203, -2.48366332},
-    {-18.9960308, -17.1832409, -1.99375546},
-    {-18.8897514, -17.4674816, -1.36384904},
-    {-18.4773064, -17.2542858, -0.943915725},
-    {-18.4836712, -17.2543297, -0.524000883},
-    {-18.7866783, -17.183218, 0.105913021},
-    {-19.6114082, -17.112154, 0.735808492},
-    {-19.7113075, -17.1121292, 1.50568581},
-    {-19.0895481, -16.7567787, 1.78564084},
-    {-18.983263, -16.8278236, 2.90545297},
-    {-19.2989426, -16.4725361, 3.81530237},
-    {-19.6082821, -16.1882725, 4.44519758},
-    {-20.2299995, -15.8329601, 5.07509708},
-    {-20.3265858, -15.5486603, 6.40486622},
-    {-20.5327511, -14.90907, 7.45468616},
-    {-20.4297295, -14.5537415, 8.29454422},
-    {-19.9045067, -13.9851704, 9.48429775},
-    {-20.3233261, -13.1324129, 10.7441149},
-    {-20.220253, -12.4217587, 11.8639212},
-    {-20.8453541, -11.0715208, 13.1937485},
-    {-21.0482082, -9.50807381, 14.033577},
-    {-20.7323627, -7.873559, 15.1533308},
-    {-21.0448647, -5.95478439, 16.2031822},
-    {-20.6358967, -3.32534456, 16.6931343},
-    {-21.1578712, -1.19334447, 17.0431442},
-    {-20.9516716, 1.00970888, 16.5532227},
-    {-20.5359955, 3.71018338, 16.203249},
-    {-20.62603, 6.26842642, 15.2232876},
-    {-20.6358433, 8.11624432, 13.9635878},
-    {-20.4264679, 9.89283371, 12.4938221},
-    {-20.3168392, 11.3140602, 11.1640005},
-    {-20.938509, 12.237958, 9.69427586},
-    {-21.1512966, 13.232975, 8.01459026},
-    {-20.7455063, 13.6594715, 6.47486973},
-    {-20.5262489, 13.8724642, 5.07507944},
-    {-19.7951069, 14.2276287, 4.23520756},
-    {-20.7389164, 14.1568289, 3.46535802},
-    {-20.639122, 14.4411449, 2.7654767},
-    {-20.0139828, 14.1567802, 2.13558316},
-    {-20.7355919, 14.0146465, 2.06559539},
-    {-20.7389355, 14.085763, 2.20557427},
-    {-20.6456757, 14.228055, 2.69548845},
-    {-20.8420105, 13.943634, 2.97544098},
-    {-20.8420048, 14.0146971, 3.3253808},
-    {-20.7388783, 13.943634, 3.60533428},
-    {-20.745472, 13.872673, 4.37521839},
-    {-21.0679741, 13.4464817, 4.65518808},
-    {-20.9484081, 13.0908957, 5.42503214},
-    {-21.147934, 12.6643991, 6.1948905},
-    {-20.9418049, 12.6643963, 6.68480778},
-    {-20.8419914, 12.5223169, 7.24472189},
-    {-21.1479721, 12.6643991, 7.94459248},
-    {-20.8386993, 12.3801355, 8.29453182},
-    {-21.2509918, 12.3801355, 8.57448578},
-    {-21.0547771, 12.1670866, 8.64451599},
-    {-21.3607578, 12.3802328, 8.50452423},
-    {-20.9451351, 12.0959234, 8.71447468},
-    {-20.2234936, 12.4512529, 8.50450993},
-    {-20.5360336, 12.8066301, 7.87462854},
-    {-20.8452969, 12.6644993, 7.52468729},
-    {-20.7389355, 12.7355156, 7.38469791},
-    {-20.5360279, 12.9487619, 6.68482685},
-    {-20.5392876, 13.5884056, 6.26490498},
-    {-20.85186, 13.5173941, 5.91497183},
-    {-20.9483414, 13.3751583, 5.14508009},
-    {-21.2576809, 13.5172892, 4.93511534},
-    {-21.6666832, 13.5883036, 4.72514677},
-    {-21.6766663, 13.1620607, 4.16524744},
-    {-21.1645107, 12.8778496, 4.02527761},
-    {-21.1578789, 12.8066816, 4.09526014},
-    {-21.4604836, 12.8065786, 3.81530046},
-    {-21.7798157, 12.7356644, 3.88529706},
-    {-21.7864857, 12.7357645, 3.4653697},
-    {-21.5735741, 12.7356644, 3.25539851},
-    {-21.8795795, 12.0960178, 2.90545344},
-    {-22.5048981, 11.4565182, 2.4155333},
-    {-22.0857773, 11.2432261, 2.06559181},
-    {-22.0857506, 11.3853598, 1.50568283},
-    {-22.192215, 11.4564714, 0.945770979},
-    {-22.1922245, 11.2432737, 0.245882481},
-    {-22.5014725, 11.1722069, -0.59398061},
-    {-22.0856686, 10.9589624, -1.22387326},
-    {-21.9860115, 11.0300732, -1.99375463},
-    {-22.2919731, 11.1721582, -2.48366451},
-    {-22.2919254, 10.8168297, -3.1135633},
-    {-22.1955681, 10.1062565, -3.8834672},
-    {-22.0924664, 9.96412277, -4.5833559},
-    {-21.9926834, 9.53776646, -4.93331861},
-    {-22.0958099, 8.89816856, -5.70319939},
-    {-21.8862476, 8.68492603, -5.91314507},
-    {-22.0924664, 8.68492603, -5.98313427},
-    {-22.0958099, 8.47176838, -6.33309984},
-    {-22.0924511, 8.11639595, -6.61303425},
-    {-22.3983898, 7.76102543, -6.96295547},
-    {-22.0891037, 7.40569353, -6.8229785},
-    {-22.7111149, 7.3346653, -7.03296661},
-    {-22.4981194, 6.90819263, -6.89294434},
-    {-21.9859924, 6.90822887, -6.75298977},
-    {-22.6113853, 6.83723402, -6.8230238},
-    {-23.0169735, 6.97929573, -6.96295547},
-    {-22.7110958, 6.62399817, -6.82300091},
-    {-22.3020802, 6.55296898, -6.82302523},
-    {-22.8244495, 6.55303717, -6.40313244},
-    {-22.910574, 6.41073036, -6.40302229},
-    {-23.1201458, 6.41076469, -6.40304708},
-    {-23.0171051, 6.19756985, -6.33305836},
-    {-22.7043514, 5.91326857, -6.05308056},
-    {-23.2368813, 5.91343641, -5.98319721},
-    {-23.7491264, 6.1266017, -5.9131856},
-    {-23.4363346, 6.05550337, -5.98315477},
-    {-23.4328995, 5.70013714, -5.91314602},
-    {-23.4363155, 5.41590166, -5.84317732},
-    {-23.329813, 5.13160467, -5.98313475},
-    {-23.2232571, 4.70517445, -6.05310202},
-    {-22.9173298, 4.42093849, -6.33307838},
-    {-23.2266006, 3.99454093, -6.54304457},
-    {-23.8521996, 3.85246587, -6.61307812},
-    {-23.3229294, 3.21275687, -7.03292036},
-    {-23.2163944, 2.71526551, -6.75294209},
-    {-23.2198048, 2.21783042, -6.89294243},
-    {-23.7387581, 1.79145658, -6.96295547},
-    {-23.6425476, 1.36510479, -6.8230238},
-    {-23.6425476, 0.654440343, -7.03299046},
-    {-23.5394077, 0.156971693, -6.893013},
-    {-23.8487282, -0.553694546, -6.82302284},
-    {-23.649416, -1.19326162, -6.61310053},
-    {-23.9070473, -1.61966097, -6.82306767},
-    {-23.4465656, -1.69071388, -6.54313326},
-    {-23.5394268, -2.40142322, -5.91316843},
-    {-24.2113762, -3.00548553, -5.77319813},
-    {-24.0480785, -3.11211634, -5.77314854},
-    {-24.0480347, -3.2542491, -5.56318235},
-    {-23.9449234, -3.53851509, -5.07326078},
-    {-24.0463448, -3.8583169, -4.4083581},
-    {-24.2577305, -4.24916792, -4.5833559},
-    {-23.5927353, -4.3912878, -3.9884758},
-    {-23.8453121, -4.46236706, -3.95345664},
-    {-24.3677578, -4.53341675, -3.81351042},
-    {-24.47435, -4.81767941, -3.67354727},
-    {-24.3660622, -4.71108675, -3.56853986},
-    {-24.8248234, -5.24409819, -3.46353388},
-    {-24.3608418, -4.74663305, -3.74348927},
-    {-25.1447258, -4.6044755, -3.98849845},
-    {-24.7767887, -4.8176918, -3.67351556},
-    {-24.0515118, -5.03089905, -4.19841719},
-    {-23.8865089, -4.60452461, -4.19836378},
-    {-23.635603, -4.10704517, -4.37337208},
-    {-23.8383675, -3.96492147, -4.72329903},
-    {-23.3263111, -3.60958099, -5.00327063},
-    {-24.3643951, -3.39635944, -5.21327543},
-    {-24.0567417, -3.00548744, -5.24827957},
-    {-23.5927029, -3.11208677, -5.87818146},
-    {-23.8383732, -2.47253275, -5.77312756},
-    {-23.7353134, -2.25933409, -5.98309326},
-    {-24.0567131, -1.72628498, -6.40310049},
-    {-24.1476879, -0.980146289, -6.61298895},
-    {-23.5256329, -0.482698917, -6.68295527},
-    {-23.7422581, 0.0858871713, -7.17294693},
-    {-23.3365917, 0.228058666, -7.17299271},
-    {-22.6596355, 1.25847518, -7.03296709},
-    {-23.6425285, 2.00470543, -7.17296934},
-    {-23.3229103, 2.64423037, -6.96293163},
-    {-22.8176193, 3.49710464, -6.4730773},
-    {-23.4397354, 4.492064, -6.19314289},
-    {-23.2266541, 5.55800486, -6.05312061},
-    {-22.9241257, 6.48193502, -5.4932518},
-    {-23.0306816, 7.26370955, -4.86336565},
-    {-22.7213421, 7.90331125, -4.3734417},
-    {-22.202322, 8.61393929, -3.95348883},
-    {-22.5082932, 9.53776741, -3.04361296},
-    {-22.9275417, 10.3195887, -2.13377929},
-    {-22.7178612, 10.6748791, -1.01394033},
-    {-22.6181698, 11.1723909, -0.244065568},
-    {-22.7179089, 11.1012783, 0.595811903},
-    {-21.8963413, 11.598794, 0.945756316},
-    {-22.312151, 11.9541769, 2.34553981},
-    {-22.102541, 12.3805294, 3.32539392},
-    {-21.9994144, 12.4515991, 4.23525667},
-    {-21.5902653, 12.5227137, 4.72518682},
-    {-21.0746174, 12.6648474, 5.35509443},
-    {-21.0846176, 12.7360611, 6.05501842},
-    {-20.974884, 12.7359638, 6.89487123},
-    {-20.8650379, 12.8779955, 7.52475977},
-    {-20.6620731, 12.6648474, 8.36464405},
-    {-20.3428783, 12.6646967, 8.99450397},
-    {-20.3396339, 12.6646471, 9.90434551},
-    {-19.8369827, 12.6648493, 10.5343218},
-    {-19.2150211, 12.6647987, 11.304183},
-    {-19.6211224, 12.0250998, 12.4939575},
-    {-19.5212593, 11.2434101, 13.4038448},
-    {-19.3182335, 10.6038561, 14.1737518},
-    {-18.6930618, 9.89310074, 14.8735867},
-    {-18.6930752, 8.68496799, 16.0634022},
-    {-18.6962528, 7.69007063, 16.9732933},
-    {-18.5994167, 6.19773579, 17.8132381},
-    {-18.2900639, 4.63426447, 18.7930889},
-    {-18.2869473, 2.71542382, 19.4929447},
-    {-18.0838318, 0.867693961, 19.7729454},
-    {-17.7775803, -1.406425, 19.7729874},
-    {-17.3649578, -3.32524896, 19.6330051},
-    {-17.4711895, -5.59939814, 19.563055},
-    {-17.571228, -7.80248404, 18.7231426},
-    {-17.9775372, -9.65023041, 17.9531784},
-    {-17.5681648, -11.2137127, 17.0433502},
-    {-18.0900822, -12.5640087, 15.5736322},
-    {-18.1963482, -13.9143057, 14.3138428},
-    {-18.0900822, -14.7671003, 12.9840069},
-    {-18.4058247, -15.4778109, 11.7242298},
-    {-18.9279594, -15.9042559, 10.6744175},
-    {-19.2342453, -16.2595768, 9.34458065},
-    {-19.2342453, -16.3306446, 8.29472351},
-    {-19.2310524, -16.1884899, 7.45482683},
-    {-19.3374043, -16.1174412, 6.40498209},
-    {-20.05299, -15.6909962, 5.63507366},
-    {-19.8499546, -15.8331518, 5.07515717},
-    {-20.7815819, -15.6199646, 4.72521162},
-    {-21.3939419, -15.4067287, 4.37525225},
-    {-20.5654602, -15.1224375, 3.81532645},
-    {-20.7750549, -14.7671185, 3.11543083},
-    {-20.6686287, -14.3406954, 2.69548988},
-    {-20.9813538, -14.553915, 2.27554893},
-    {-20.8815098, -14.2696571, 1.85560691},
-    {-21.4005394, -14.1986055, 1.08571386},
-    {-21.3972721, -14.3407259, 0.525792599},
-    {-22.1260662, -13.9854155, -0.174122751},
-    {-21.2908688, -13.6300354, -0.594043851},
-    {-20.9813538, -13.7721701, -1.01398444},
-    {-20.8848534, -13.6300602, -1.99386978},
-    {-21.2974663, -13.345789, -2.69377089},
-    {-20.8847771, -13.5589952, -2.97373343},
-    {-20.6784935, -13.8432655, -3.67363596},
-    {-20.5654831, -13.7721558, -3.88356137},
-    {-20.2560577, -13.9142904, -4.51347065},
-    {-20.0530033, -14.0564413, -4.7934494},
-    {-19.5308723, -14.1985455, -4.65343285},
-    {-19.8467388, -14.3407106, -4.58347797},
-    {-19.3374043, -14.5539465, -4.44353151},
-    {-19.537281, -15.1224537, -4.30351686},
-    {-18.8152351, -15.1935225, -3.74359727},
-    {-19.1278896, -15.8331499, -3.53364062},
-    {-19.1247311, -16.3306046, -2.62375641},
-    {-18.7089653, -16.6859207, -1.78386343},
-    {-18.6121616, -17.0413036, -0.734026968},
-    {-19.0247631, -17.4677086, 0.385810405},
-    {-18.708931, -17.7519341, 1.85561097},
-    {-18.8120766, -17.8940697, 3.39538884},
-    {-18.4026318, -17.6098213, 5.0751524},
-    {-18.8057156, -17.396553, 6.47492552},
-    {-18.605772, -16.97019, 7.73476553},
-    {-18.6057911, -16.1884499, 9.13456154},
-    {-18.3931503, -15.9752083, 10.7442894},
-    {-18.2963486, -15.5488453, 11.7941761},
-    {-18.6026459, -14.9802856, 12.564044},
-    {-18.8057537, -14.1274633, 13.4038935},
-    {-18.6057911, -13.9142904, 13.7538948},
-    {-17.8837929, -13.9142904, 13.9638643},
-    {-18.1932182, -13.7010889, 14.3838043},
-    {-17.5743732, -13.4878864, 14.5237846},
-    {-17.5837631, -13.7721987, 14.6638517},
-    {-17.8963223, -14.127552, 14.3139277},
-    {-17.271143, -14.4828615, 14.6638212},
-    {-17.0648251, -14.4828615, 14.3838596},
-    {-17.3804722, -14.6960974, 13.8239908},
-    {-17.0709953, -15.193574, 13.4040499},
-    {-16.9677982, -15.9753246, 13.1940775},
-    {-17.2772789, -16.0463924, 12.9141169},
-    {-16.9678268, -16.5438709, 12.42418},
-    {-16.6583443, -16.6149387, 11.934247},
-    {-17.0647907, -16.8280983, 11.5842514},
-    {-16.9524746, -16.8991032, 11.2342377},
-    {-16.7584305, -17.0413284, 11.0243473},
-    {-16.6644287, -17.1835289, 10.7444477},
-    {-17.2772789, -17.2545528, 10.5344343},
-    {-17.1741543, -17.3966885, 10.2544727},
-    {-17.5836926, -17.1834602, 10.2544546},
-    {-17.6899529, -17.3256207, 10.4644451},
-    {-17.6868362, -17.3255959, 10.464426},
-    {-17.9900494, -17.1834164, 10.1844282},
-    {-18.0901299, -16.8280582, 10.1844101},
-    {-18.4089737, -16.7570534, 10.0444832},
-    {-18.3058147, -16.6149178, 9.83451176},
-    {-17.8900433, -16.0463543, 9.90448475},
-    {-17.8900337, -16.4727612, 9.97447681},
-    {-18.0994587, -16.6149178, 9.27458858},
-    {-18.3057766, -16.4727802, 8.85464954},
-    {-18.4058285, -16.543829, 8.43469048},
-    {-18.7216511, -16.6860065, 8.08476543},
-    {-19.3406048, -17.1124134, 7.66482258},
-    {-19.0311432, -16.8281422, 6.89492655},
-    {-18.7152729, -16.4727612, 6.05502176},
-    {-18.6089687, -16.6859417, 5.28512383},
-    {-18.8120708, -17.0412598, 4.23526764},
-    {-18.7152729, -16.9702339, 2.90545964},
-    {-19.024683, -17.1123714, 1.99558783},
-    {-19.2342453, -17.0413246, 0.455797017},
-    {-19.5373135, -16.6859436, -1.08397222},
-    {-18.7184315, -16.1885071, -2.27382946},
-    {-19.3374043, -15.6910334, -3.74362779},
-    {-19.537262, -14.7671165, -5.07340765},
-    {-19.021553, -13.7721701, -6.47320747},
-    {-19.3310146, -12.8482885, -7.66304255},
-    {-19.5373135, -12.1376143, -8.57291126},
-    {-19.4276905, -10.5030479, -9.55271244},
-    {-20.0530605, -9.29490566, -10.672617},
-    {-19.5373001, -7.58928394, -11.6524744},
-    {-19.4405632, -5.74151421, -12.7024002},
-    {-19.1247959, -3.8937645, -12.9822865},
-    {-19.124712, -1.97494113, -13.262248},
-    {-19.124712, 0.157092884, -13.4022274},
-    {-19.4405632, 2.14703703, -13.1223421},
-    {-19.1342869, 4.77657986, -12.7024355},
-    {-19.2374611, 7.05075359, -11.5825911},
-    {-19.3309956, 9.11161518, -10.5326357},
-    {-19.3406048, 11.0305862, -8.92294121},
-    {-19.4405632, 12.6650953, -7.38313246},
-    {-19.1279278, 13.8731995, -5.42337799},
-    {-19.1343498, 15.1525345, -3.74363923},
-    {-19.2342834, 15.64995, -1.8538909},
-    {-18.6152916, 16.3606339, -0.0341333486},
-    {-18.20578, 16.716032, 1.78561556},
-    {-17.8963032, 16.9292374, 3.32540464},
-    {-18.4089737, 16.6449051, 4.58523178},
-    {-18.0994968, 16.9291763, 5.56509733},
-    {-17.9932079, 16.6448479, 6.61494303},
-    {-17.158741, 16.3603973, 7.2448225},
-    {-16.7492352, 16.4315243, 8.01472282},
-    {-16.7522926, 16.7869225, 8.43467617},
-    {-17.2680225, 17.0001278, 8.71463776},
-    {-16.6522083, 17.2133904, 9.06460285},
-    {-16.3427353, 17.000185, 9.34456348},
-    {-16.5460415, 16.8579865, 8.99459648},
-    {-16.2365646, 17.0711899, 9.13457775},
-    {-16.2395725, 17.0712509, 9.20458508},
-    {-16.0393333, 17.2135086, 9.13462543},
-    {-16.6491489, 17.4975986, 8.99459743},
-    {-16.4427986, 17.2133255, 9.27455997},
-    {-16.7553196, 17.0712528, 9.13459206},
-    {-16.8615665, 16.715971, 8.99462795},
-    {-17.177227, 16.6450233, 8.99465847},
-    {-17.0679169, 16.8581085, 9.13460732},
-    {-16.8616028, 16.5738373, 9.0646162},
-    {-16.8462181, 16.3603382, 9.48447704},
-    {-17.0555859, 16.2182617, 9.34451389},
-    {-17.368084, 15.5787163, 9.62449074},
-    {-17.8900433, 15.2945566, 9.76450443},
-    {-17.990097, 14.9391623, 10.0444469},
-    {-17.6837444, 14.79708, 9.97447586},
-    {-18.0963326, 14.7260113, 9.62452412},
-    {-18.0994968, 14.2285938, 9.62454128},
-    {-18.8184166, 14.1574717, 9.62452412},
-    {-19.3373661, 14.1575251, 9.48456001},
-    {-19.1310863, 14.0153894, 9.34458065},
-    {-19.4437447, 13.944375, 8.99464226},
-    {-19.4372807, 13.8021317, 8.43469334},
-    {-19.956358, 14.0153894, 7.734797},
-    {-19.8532448, 14.0864573, 7.10488701},
-    {-20.0563049, 14.1574717, 6.54495287},
-    {-20.152956, 14.3705664, 5.98501778},
-    {-20.1496754, 14.5126467, 4.65520048},
-    {-19.9466381, 14.7259045, 3.46537876},
-    {-20.1529751, 14.6548367, 2.48551869},
-    {-20.6784744, 14.0864573, 1.15570128},
-    {-20.5655251, 14.086297, -0.174093366},
-    {-20.4590988, 13.6598396, -1.50389636},
-    {-21.0877991, 12.8782511, -2.76375008},
-    {-21.0911102, 11.8122816, -4.02358961},
-    {-20.4623661, 10.8882599, -5.28335714},
-    {-21.2940788, 9.68019962, -6.26325989},
-    {-22.0027676, 8.75615501, -6.96307087},
-    {-21.8996372, 7.69014692, -7.59297752},
-    {-21.9029865, 6.48204231, -7.94295025},
-    {-21.7965317, 5.34493446, -8.22288322},
-    {-22.3054428, 4.06566048, -8.22282982},
-    {-22.5251884, 2.64443254, -8.5028944},
-    {-23.2403145, 1.36517298, -8.57283115},
-    {-22.7179089, 0.156993628, -8.29282093},
-    {-22.7179089, -1.40647984, -7.8028965},
-    {-23.1303444, -2.68568039, -7.94287348},
-    {-23.2369137, -3.8938055, -7.10302687},
-    {-23.1371555, -4.67553663, -6.61312389},
-    {-23.2437153, -5.81260061, -6.19320869},
-    {-22.7246532, -6.87861776, -5.00336218},
-    {-22.8243637, -8.01568794, -4.30345201},
-    {-23.130373, -8.93955898, -3.25359344},
-    {-23.2437344, -10.0055761, -2.20379186},
-    {-23.0374775, -10.7162466, -1.36391568},
-    {-22.8346176, -11.4979963, 0.105863243},
-    {-23.0409508, -11.7822676, 0.805763304},
-    {-23.1406612, -12.0665264, 1.85560954},
-    {-22.5150433, -12.0665073, 2.97544694},
-    {-21.5835819, -12.1375628, 3.95529509},
-    {-21.6967487, -12.1375942, 5.0051527},
-    {-21.9993763, -12.4218416, 5.84501028},
-    {-21.8929405, -12.6350317, 6.33492804},
-    {-21.3740387, -12.777154, 7.31476736},
-    {-21.3773403, -12.8482313, 7.87469196},
-    {-21.2775402, -12.6350431, 8.78456402},
-    {-21.2775402, -12.8482456, 9.41447258},
-    {-20.8749123, -12.9193459, 9.90445042},
-    {-20.7717686, -12.5640087, 10.8143187},
-    {-20.462347, -12.4929409, 11.6541977},
-    {-20.5654869, -12.2086716, 12.4240866},
-    {-20.6751881, -11.5690794, 12.774085},
-    {-20.0628033, -11.1426897, 13.474041},
-    {-19.5437222, -10.2898655, 14.3838892},
-    {-19.7532883, -9.2238493, 15.2238045},
-    {-19.9596062, -8.655303, 15.993701},
-    {-19.8564472, -7.66035128, 16.4836349},
-    {-20.0562859, -6.31006384, 16.9735012},
-    {-19.7467804, -4.95976973, 17.4634323},
-    {-19.3406048, -3.82266712, 18.0934162},
-    {-19.8629303, -2.25914216, 18.2334766},
-    {-19.437418, -1.05104196, 18.3033142},
-    {-19.7467899, 0.299244881, 18.0933437},
-    {-19.3438263, 1.57853734, 18.0934544},
-    {-19.8629112, 2.71565413, 18.3034649},
-    {-19.8629112, 3.21313429, 18.0934925},
-    {-19.7564983, 4.27913237, 17.5335312},
-    {-19.7532692, 4.70551157, 17.0435581},
-    {-19.9563293, 5.06081915, 17.1135139},
-    {-19.4404774, 5.55829716, 16.6935711},
-    {-19.5501537, 5.98477507, 16.6936417},
-    {-19.7532692, 5.55832863, 16.8335876},
-    {-19.8596764, 5.41622543, 16.9736042},
-    {-19.5469513, 5.55832863, 16.9035778},
-    {-19.6533585, 5.48729372, 17.0435944},
-    {-19.9047775, 5.41616106, 17.0085297},
-    {-19.7435131, 5.2028923, 17.1834373},
-    {-19.6468811, 4.70548153, 17.183506},
-    {-19.4373512, 4.63438416, 17.5334206},
-    {-19.5405254, 4.63438272, 17.8133812},
-    {-19.4438305, 3.92375922, 18.09342},
-    {-19.7533073, 3.63948917, 18.3033905},
-    {-19.2246399, 3.28403926, 18.2332478},
-    {-19.2214432, 2.78654075, 18.4431801},
-    {-19.2858238, 2.00489783, 18.4783287},
-    {-19.237442, 1.79171729, 18.8633156},
-    {-19.4501572, 1.8628329, 18.7934036},
-    {-18.7216511, 1.50744557, 18.8633156},
-    {-18.2026558, 1.08101332, 19.0032558},
-    {-18.3573933, 0.938877702, 19.108242},
-    {-18.8216286, 0.37033245, 19.3532085},
-    {-18.508955, 0.0860406309, 19.563139},
-    {-17.5883617, -0.233717635, 19.6332302},
-    {-18.3573933, -1.08656025, 19.8431416},
-    {-18.4089737, -1.19316173, 19.8431396},
-    {-17.79002, -1.26422977, 19.4231987},
-    {-19.1310863, -1.72617233, 19.8431416},
-    {-18.2995262, -2.25921106, 19.9130478},
-    {-17.9963379, -2.4723866, 19.493187},
-    {-18.3573933, -2.89879394, 19.9481277},
-    {-17.8931255, -2.79219174, 19.7381573},
-    {-17.8932304, -2.68558836, 19.8431396},
-    {-18.5026474, -2.68562913, 19.7030373},
-    {-18.0431709, -2.79221058, 19.7380924},
-    {-18.3479595, -3.11203337, 19.4230785},
-    {-18.6716118, -3.00537634, 19.6332321},
-    {-18.5184727, -2.47236037, 19.1433201},
-    {-18.6247959, -1.90379751, 19.2833405},
-    {-19.3002357, -1.93931019, 19.4233837},
-    {-18.9810886, -1.93935406, 19.0033169},
-    {-19.4501534, -1.40631664, 19.2133484},
-    {-19.4453316, -0.76672703, 19.1083012},
-    {-19.600174, -0.233717635, 18.7933445},
-    {-19.7451992, 0.299230874, 18.8982124},
-    {-19.5533829, 1.15214837, 18.6534214},
-    {-19.6000977, 1.36531854, 18.478384},
-    {-19.3470325, 2.50244856, 18.373457},
-    {-19.0375023, 3.35527182, 18.3034668},
-    {-19.4502048, 3.92382002, 17.9535103},
-    {-19.4599228, 4.91887188, 17.3936901},
-    {-19.3502617, 5.70056581, 17.2536392},
-    {-19.65979, 6.83766651, 16.6237183},
-    {-19.556612, 7.61942005, 16.2737617},
-    {-19.3438358, 8.4010973, 15.9937334},
-    {-18.8279648, 8.96964455, 15.1538439},
-    {-18.5153141, 9.82241821, 14.7338705},
-    {-19.0343342, 10.4620762, 14.2439651},
-    {-19.0343208, 10.9595556, 13.9640007},
-    {-18.6216183, 11.5991707, 13.7540293},
-    {-18.831152, 11.8834944, 13.3341103},
-    {-18.631155, 12.096796, 13.0541983},
-    {-18.6279736, 12.5231571, 12.8441992},
-    {-18.7311516, 12.523159, 12.774209},
-    {-18.7247906, 12.3809223, 12.5641861},
-    {-19.2406712, 12.2387857, 12.6341772},
-    {-19.1469784, 12.0257254, 12.9142151},
-    {-19.2406578, 11.7413073, 13.1241121},
-    {-18.9279499, 11.243784, 13.6140194},
-    {-19.031105, 10.9595079, 13.8239927},
-    {-19.5533638, 10.6042604, 13.9640293},
-    {-20.0725117, 10.3200283, 13.964057},
-    {-19.5469322, 9.89348793, 14.1039553},
-    {-19.5469513, 9.53814602, 13.8939829},
-    {-19.8564472, 9.18280602, 14.0339651},
-    {-19.9628735, 8.89857578, 13.8940115},
-    {-20.3755245, 9.11178017, 13.5440559},
-    {-20.3755245, 9.25391674, 13.4040756},
-    {-20.7881451, 9.18284893, 13.3340845},
-    {-20.5851421, 8.82754707, 13.194129},
-    {-20.9978542, 8.89861488, 12.5642099},
-    {-20.9978638, 9.25396061, 12.1442642},
-    {-21.2973747, 9.82237625, 12.0742044},
-    {-21.0844975, 9.89336014, 12.0741596},
-    {-21.2008095, 9.46712112, 11.5143194},
-    {-21.816576, 9.96455574, 11.444314},
-    {-21.3007107, 10.177763, 11.3043318},
-    {-20.9912148, 10.6041689, 10.8143988},
-    {-21.4038887, 10.8884439, 10.6044264},
-    {-21.2008705, 10.9595566, 10.4644642},
-    {-21.6069088, 11.0305319, 10.3244457},
-    {-21.6102543, 11.243784, 9.9745121},
-    {-20.9912338, 11.5280561, 9.34459686},
-    {-20.6751919, 11.8122339, 9.20458126},
-    {-20.7848969, 12.0255327, 9.06463337},
-    {-21.0977077, 11.9545135, 8.92466831},
-    {-20.3755436, 12.2387857, 8.92466831},
-    {-20.4655972, 12.4517937, 8.29469681},
-    {-20.5753288, 12.6650934, 7.87478065},
-    {-20.7849541, 12.8072805, 7.87479305},
-    {-20.7816658, 12.5229616, 7.52482891},
-    {-20.7783699, 12.7361155, 7.03488636},
-    {-20.9879837, 12.8782997, 6.12502003},
-    {-21.5170498, 12.8785019, 5.63511658},
-    {-21.3073788, 13.304862, 5.21516514},
-    {-21.2907963, 13.1624727, 4.79519272},
-    {-21.5070953, 12.665144, 4.23528194},
-    {-21.7133846, 12.7362127, 3.04544497},
-    {-22.3324375, 12.5940762, 2.20555592},
-    {-22.1294403, 12.3809233, 1.50564873},
-    {-21.8199062, 11.9545135, 1.01571226},
-    {-22.2325802, 11.5281029, 0.0358430557},
-    {-23.1679497, 11.3860588, -0.73407191},
-    {-23.0613747, 10.6042585, -1.43397331},
-    {-22.9581928, 9.53822994, -2.2038734},
-    {-23.2711411, 8.9697237, -2.76381469},
-    {-23.2642918, 7.97468853, -3.46369457},
-    {-23.4706383, 7.33507109, -4.02362204},
-    {-23.4672279, 6.34007883, -4.37355804},
-    {-24.0931206, 5.55839348, -5.07350111},
-    {-24.5024281, 4.56341076, -5.4934268},
-    {-23.9795456, 3.14198351, -5.70336056},
-    {-23.9795647, 2.28916883, -5.63336754},
-    {-24.3922005, 1.64955735, -5.84333897},
-    {-23.7732468, 0.44140175, -6.05331087},
-    {-24.0862427, -0.695669949, -6.33329344},
-    {-24.2960148, -1.33526623, -6.26332521},
-    {-23.6632347, -2.04600501, -5.91329241},
-    {-24.3852463, -3.04095483, -5.91328812},
-    {-24.2890453, -3.68054199, -5.77334881},
-    {-23.7801342, -4.32013655, -5.56341696},
-    {-23.6839008, -4.95973825, -5.28349352},
-    {-23.3743668, -5.52828598, -5.6334486},
-    {-23.4706383, -5.95470762, -5.6334095},
-    {-23.2677212, -6.02577162, -5.70341921},
-    {-23.1610947, -6.73645926, -5.84338093},
-    {-23.0511017, -6.94967079, -6.19329309},
-    {-22.9547577, -7.0207324, -6.40330648},
-    {-22.7586536, -6.80751991, -6.96330357},
-    {-22.2393951, -7.23393345, -7.17325163},
-    {-21.8132267, -6.80753279, -7.4531188},
-    {-22.1260853, -6.3811202, -7.5931263},
-    {-21.8199062, -6.52325535, -7.87310982},
-    {-21.6135597, -6.16791296, -8.71300316},
-    {-21.5137348, -5.5282917, -9.06298447},
-    {-21.6202469, -4.7465291, -9.06301212},
-    {-21.5104294, -3.89372849, -9.48289585},
-    {-21.5103951, -2.96983552, -9.97283649},
-    {-21.9231033, -1.90381277, -10.1828079},
-    {-21.3073788, -0.979909956, -10.4628029},
-    {-21.4039021, 0.370353162, -10.5327301},
-    {-22.3324032, 1.50744498, -10.5327301},
-    {-22.3324032, 2.57346916, -9.97280407},
-    {-21.7134457, 3.99482965, -9.62285233},
-    {-21.2974281, 5.3450942, -9.06289959},
-    {-22.022913, 6.55328321, -8.22304058},
-    {-22.2360191, 7.90365934, -7.38319683},
-    {-21.9299088, 9.11185932, -6.47334194},
-    {-21.5104294, 10.1067352, -5.35344744},
-    {-21.7302265, 10.7465343, -4.37364054},
-    {-21.8300037, 11.3150368, -3.25376987},
-    {-21.5137253, 11.9545593, -2.34385514},
-    {-21.3073788, 12.3099041, -1.50396442},
-    {-20.9978542, 12.380971, -1.0140276},
-    {-21.0977459, 12.8783998, -0.454093456},
-    {-21.3073788, 13.0205898, 0.175817907},
-    {-21.5204029, 12.9496212, 0.245796561},
-    {-21.4139099, 13.2338428, 0.315793067},
-    {-20.8880596, 13.5179634, 0.245819807},
-    {-20.5884342, 13.9445353, -0.0341630355},
-    {-20.4852715, 14.1577425, -0.384116739},
-    {-20.2723885, 13.8733606, -0.73405695},
-    {-20.0660515, 14.3708344, -1.08400941},
-    {-19.7565365, 14.5129728, -1.85390794},
-    {-19.3405952, 14.8682594, -2.41382146},
-    {-19.8629303, 14.8683691, -2.9037838},
-    {-18.8312664, 14.7262335, -3.18374753},
-    {-18.6216602, 14.9393816, -3.32371473},
-    {-18.9343243, 15.2947807, -4.09362936},
-    {-18.6248474, 15.0815763, -4.44358158},
-    {-18.6248531, 14.7262335, -4.8635273},
-    {-18.6217041, 14.8683186, -5.14347267},
-    {-18.4153194, 14.9393864, -5.07348347},
-    {-18.6311035, 14.7263432, -5.28351212},
-    {-18.4215889, 14.7262897, -5.21350145},
-    {-18.6279926, 14.7973576, -5.49346685},
-    {-18.4153004, 14.797245, -5.21346474},
-    {-18.6216469, 14.7261772, -5.0034914},
-    {-18.7279682, 14.9394379, -4.79353666},
-    {-18.3152485, 15.0105085, -4.58356524},
-    {-18.5216217, 15.0105085, -4.51357508},
-    {-18.7248249, 15.152586, -4.16360235},
-    {-19.2374611, 15.1525326, -3.60366225},
-    {-18.8310509, 14.9394398, -3.39371657},
-    {-19.6501293, 14.9393282, -3.04373765},
-    {-19.5501347, 14.8683138, -2.90377045},
-    {-19.4502048, 14.5130262, -2.973773},
-    {-19.6437073, 14.5128126, -2.69375896},
-    {-19.9596062, 14.5129166, -2.6237936},
-    {-20.1724415, 14.0866184, -2.76380038},
-    {-19.9724503, 14.2999325, -2.97379994},
-    {-20.4787159, 13.5890827, -3.25372314},
-    {-20.1724415, 13.5891342, -3.32372856},
-    {-20.588459, 13.4470491, -3.60370803},
-    {-20.7980957, 13.0917597, -4.65359068},
-    {-20.1789532, 12.8785534, -5.00354815},
-    {-19.7661991, 12.381073, -5.35350323},
-    {-20.5818462, 11.8834429, -5.98336077},
-    {-20.7849159, 11.3148499, -6.54326582},
-    {-20.4721889, 10.5330572, -7.24314928},
-    {-21.2008858, 9.96459866, -8.29305649},
-    {-21.1976032, 9.04067135, -8.78296471},
-    {-21.0944309, 8.11678505, -8.99293613},
-    {-20.9912338, 7.1218276, -9.55286121},
-    {-20.7881794, 5.98477507, -9.83285332},
-    {-20.9879456, 5.06082153, -10.4627066},
-    {-20.9978161, 4.1370244, -10.8827467},
-    {-20.6915894, 2.71568346, -11.3027258},
-    {-21.4139004, 1.22323716, -11.442709},
-    {-21.8165627, 0.0150188291, -11.4426088},
-    {-21.5037117, -1.19316542, -11.1626091},
-    {-21.2974281, -2.54345417, -11.0926228},
-    {-21.3007488, -4.17801094, -10.3927479},
-    {-21.0944309, -5.10189486, -9.41288185},
-    {-21.2940788, -6.4521966, -8.64292812},
-    {-21.9163818, -7.37607813, -8.15302372},
-    {-21.4072609, -8.08675957, -7.17320108},
-    {-21.9263992, -9.15278339, -5.91339588},
-    {-22.2292252, -10.0766687, -4.72350979},
-    {-22.1294498, -10.8584242, -4.02362108},
-    {-22.5387173, -11.2848253, -2.7637763},
-    {-22.3222866, -11.7112083, -1.6438942},
-    {-22.2258625, -11.5690899, -0.594059169},
-    {-22.1126347, -11.6401291, 0.175851196},
-    {-22.0128098, -12.0665483, 0.945739508},
-    {-22.5421028, -12.6351318, 1.64562964},
-    {-22.7450771, -12.5640526, 2.20555639},
-    {-21.7133942, -12.9904613, 2.69549084},
-    {-21.6069088, -12.9904499, 3.18542314},
-    {-22.2258625, -13.1325855, 3.39539456},
-    {-22.1160069, -13.3457623, 3.81533098},
-    {-22.0161915, -13.7011166, 4.09529495},
-    {-21.3906078, -13.7010889, 4.09528828},
-    {-21.7033138, -14.1275091, 3.95531321},
-    {-20.9945488, -14.1275673, 4.0953064},
-    {-21.1909389, -14.2696562, 4.09529686},
-    {-21.1975842, -14.6250296, 4.16529274},
-    {-20.478754, -14.909318, 4.16529655},
-    {-20.6784744, -14.7671499, 4.37526035},
-    {-20.7817001, -15.0514202, 4.16528988},
-    {-20.4656448, -14.7671165, 4.30526257},
-    {-20.7816277, -15.0514212, 4.72521257},
-    {-20.472086, -15.1935587, 4.51524019},
-    {-20.678442, -14.8382196, 4.58523035},
-    {-21.1909733, -14.9092693, 4.86518812},
-    {-21.194273, -15.0514221, 4.86519289},
-    {-21.2907963, -14.7671165, 5.1451416},
-    {-21.3973293, -14.696064, 5.28512859},
-    {-21.0877991, -14.3407259, 5.35511971},
-    {-21.8098736, -14.1275225, 5.70507002},
-    {-21.8198967, -13.7011557, 5.7750845},
-    {-20.7849293, -13.2747345, 5.98504829},
-    {-20.6784744, -13.2747211, 6.05502987},
-    {-21.1909542, -13.6300488, 6.26499271},
-    {-22.2191982, -13.1325617, 6.12500429},
-    {-22.4288273, -12.9193687, 6.40497398},
-    {-22.022913, -12.7772551, 6.05503798},
-    {-22.0196075, -12.4929724, 6.19501066},
-    {-22.126152, -12.6351204, 5.98504686},
-    {-22.6452675, -12.7061996, 5.42512941},
-    {-22.4355431, -12.421916, 5.56510401},
-    {-22.5386925, -12.6351204, 5.28514099},
-    {-22.3257065, -12.7772331, 4.72520876},
-    {-22.1193371, -13.0615053, 4.30526447},
-    {-22.0262432, -12.7062006, 4.23528767},
-    {-22.0295963, -12.5640755, 3.46538854},
-    {-22.2359142, -12.7772808, 2.8354733},
-    {-21.9264317, -12.9194164, 2.69549084},
-    {-22.4456997, -12.7772913, 2.13556242},
-    {-22.3324032, -12.6351204, 1.36567056},
-    {-22.4390202, -12.9194059, 0.875730395},
-    {-22.3256741, -12.6350994, 0.525791705},
-    {-22.4322281, -12.4929724, -0.38408795},
-    {-22.0161877, -12.5640297, -0.594051361},
-    {-22.0228882, -12.2797794, -1.22398233},
-    {-22.2258625, -12.2797699, -1.36395371},
-    {-22.0228882, -12.0665751, -1.78390634},
-    {-22.2292118, -11.9955063, -1.78390634},
-    {-22.0296249, -11.9955263, -2.13388157},
-    {-22.2426872, -11.8534079, -2.13390541},
-    {-21.9264317, -11.6401834, -2.55382705},
-    {-22.2359619, -11.6401834, -2.90378261},
-    {-22.0296059, -11.4980469, -3.18374586},
-    {-22.0329781, -11.2848501, -3.32374287},
-    {-21.9331341, -11.6402016, -3.04379225},
-    {-21.8299847, -11.2848568, -2.97380114},
-    {-22.0296059, -11.3559093, -3.04376411},
-    {-22.0195446, -11.2137489, -3.18370485},
-    {-22.2326927, -11.2137632, -3.46369576},
-    {-22.4457092, -11.355917, -2.76381111},
-    {-22.4322281, -11.0716143, -2.62378097},
-    {-22.3357849, -10.929492, -2.62380624},
-    {-22.1260815, -11.0716209, -2.62379289},
-    {-22.5420761, -10.8584232, -2.62380743},
-    {-22.538702, -10.9294844, -2.20385027},
-    {-22.744978, -11.071619, -2.06386924},
-    {-22.9513283, -11.4980307, -2.13386011},
-    {-22.5387554, -11.5690985, -1.78390753},
-    {-22.325655, -11.3558769, -1.36394322},
-    {-22.5421124, -11.7112436, -1.15400052},
-    {-22.3324032, -11.9955044, -0.594066918},
-    {-22.4389305, -11.8533802, -0.384103537},
-    {-22.7450771, -11.7823029, -0.244114146},
-    {-23.2711411, -12.1376734, -0.0341606364},
-    {-22.7450924, -12.4929838, 0.315809846},
-    {-22.2292252, -12.4929848, 0.595773518},
-    {-22.332365, -12.4219141, 1.01571596},
-    {-22.2258434, -12.7061777, 1.78561807},
-    {-22.3357754, -12.7772684, 1.92559326},
-    {-22.2258911, -12.9904499, 2.13556719},
-    {-22.0229263, -13.0615301, 2.4155283},
-    {-21.8232403, -13.061554, 3.11543846},
-    {-22.0195446, -12.9904499, 3.53537393},
-    {-22.1226997, -13.0615177, 4.02530861},
-    {-22.0761223, -13.2392054, 4.09530449},
-    {-21.7033997, -13.1325598, 4.30526209},
-    {-21.8098545, -13.4879131, 4.37525558},
-    {-21.7466469, -13.4523325, 4.41023636},
-    {-21.7666683, -13.5590134, 4.51524639},
-    {-22.0761223, -13.345808, 4.72522068},
-    {-21.75667, -13.5589752, 4.93517447},
-    {-21.0910759, -13.4879255, 5.28513575},
-    {-21.3007774, -13.9143467, 5.42512274},
-    {-21.6119308, -13.7722178, 5.7750802},
-    {-20.8381386, -13.8788214, 5.5651083},
-    {-21.2940979, -13.914319, 5.70507097},
-    {-21.606905, -13.6655951, 5.880054},
-    {-21.4571152, -13.5590143, 6.19502306},
-    {-22.2225094, -13.8432522, 6.26499271},
-    {-22.3906517, -13.985445, 6.50999546},
-    {-21.4139004, -13.4879789, 6.61499166},
-    {-21.462141, -13.985445, 6.82495499},
-    {-20.6735535, -13.7721777, 7.03487968},
-    {-21.3073788, -13.4524307, 6.82495499},
-    {-22.3806019, -13.5589933, 6.71993923},
-    {-21.4472218, -13.5589743, 6.9298954},
-    {-21.1426144, -13.6655979, 6.9299078},
-    {-20.9929008, -13.7722197, 6.61496878},
-    {-21.6019306, -13.8787794, 6.61493921},
-    {-21.2974281, -13.6655951, 6.71993876},
-    {-21.7067432, -13.8432522, 6.05502176},
-    {-21.4039021, -13.6300735, 5.49511337},
-    {-21.2042542, -13.9143782, 5.21516275},
-    {-21.771698, -13.7722445, 4.93519878},
-    {-21.462141, -13.8788424, 4.83021402},
-    {-21.6119022, -13.7722178, 3.88533187},
-    {-22.1227512, -13.7721987, 3.53537583},
-    {-21.6168041, -13.6656351, 2.9404552},
-    {-22.0862007, -13.665657, 2.41552711},
-    {-22.07617, -13.665616, 1.47065437},
-    {-22.0295963, -13.2036896, 0.385787904},
-    {-22.0295963, -13.061554, -0.734063268},
-    {-21.7134457, -12.7772579, -1.5039444},
-    {-21.8199253, -11.924448, -2.13387179},
-    {-21.8199062, -11.2137642, -2.69379735},
-    {-22.2224617, -10.7162666, -4.09356117},
-    {-22.8380146, -10.0766506, -4.72345924},
-    {-22.5421124, -9.08171368, -5.63340855},
-    {-22.0195446, -7.94462204, -6.47325373},
-    {-22.0195446, -6.73646879, -7.17315769},
-    {-22.1260662, -5.7415061, -7.73310709},
-    {-22.339159, -4.24906206, -8.15310097},
-    {-22.2225609, -2.54346991, -8.43295956},
-    {-22.4355812, -1.19314408, -8.57299423},
-    {-22.7450924, 0.583559871, -8.92294598},
-    {-23.1577282, 2.21812391, -8.43301392},
-    {-22.6486359, 3.85275316, -7.73315525},
-    {-22.1294022, 5.34515715, -6.96323395},
-    {-22.6350975, 6.48214579, -6.12328196},
-    {-22.7450924, 8.18785763, -5.14345503},
-    {-22.5353355, 9.53810406, -4.02358961},
-    {-22.2225094, 10.4619446, -2.48378801},
-    {-22.0195446, 11.2437363, -0.944011033},
-    {-21.8132267, 11.5990753, -0.0341378488},
-    {-21.7067146, 11.9543676, 1.2956847},
-    {-21.7100639, 12.5229597, 2.90546513},
-    {-21.4072037, 12.8073339, 4.23528719},
-    {-20.8913898, 12.9494705, 5.07517767},
-    {-20.8914223, 13.0205383, 5.98505545},
-    {-20.6850681, 13.1626749, 6.68496323},
-    {-20.7881985, 13.3048105, 7.6648345},
-    {-20.1724415, 13.3759298, 8.22477341},
-    {-19.5533504, 13.7312727, 8.71470833},
-    {-19.5405102, 13.8021317, 9.13459396},
-    {-19.5437737, 13.8021851, 9.34457874},
-    {-19.4534054, 13.7313261, 9.4146347},
-    {-19.5437222, 13.8021851, 9.7645216},
-    {-19.2342453, 13.9443216, 10.2544546},
-    {-18.9215908, 13.7310638, 10.5343981},
-    {-18.9216232, 13.3757257, 10.954339},
-    {-18.831152, 13.4470005, 10.9544182},
-    {-18.8312035, 13.3759327, 11.1643915},
-    {-19.0279274, 13.0204363, 11.5142822},
-    {-19.1343155, 12.8072805, 11.7942648},
-    {-19.65979, 12.3810205, 12.2142801},
-    {-19.6630211, 12.0257282, 12.7742319},
-    {-19.3502617, 11.599267, 13.1241627},
-    {-19.3438015, 11.0306244, 13.6140471},
-    {-19.0375214, 10.5331907, 13.8940392},
-    {-19.2438202, 9.89357853, 14.5239553},
-    {-19.5469513, 9.3960104, 14.8038626},
-    {-19.5565643, 8.47224236, 15.2239008},
-    {-19.6597424, 8.0458374, 15.7138329},
-    {-19.3438168, 6.83759212, 16.3436871},
-    {-19.9628353, 6.05584049, 16.6936398},
-    {-19.5533829, 5.62946367, 17.1836109},
-    {-19.2471447, 4.84774065, 17.743576},
-    {-19.553421, 4.06596088, 17.9535122},
-    {-19.2438488, 3.28420377, 18.0934925},
-    {-19.3438549, 2.64456058, 18.443409},
-    {-19.1374798, 1.93387663, 19.003334},
-    {-18.8279648, 1.00998902, 18.9333439},
-    {-18.6184692, 0.299285084, 19.2132683},
-    {-18.5184727, -0.0560358576, 19.2832985},
-    {-18.5247631, -0.482411474, 19.563343},
-    {-18.4215889, -0.908822417, 19.563343},
-    {-18.1026497, -1.26421273, 19.6332111},
-    {-17.7931442, -1.76169121, 19.563221},
-    {-17.8994389, -2.18808746, 19.7032433},
-    {-17.7931271, -2.33023715, 19.9131737},
-    {-17.58992, -2.47235918, 19.9132156},
-    {-17.8057137, -2.33018041, 20.0533237},
-    {-17.3804722, -2.47237253, 20.1231461},
-    {-17.7994537, -2.54341388, 20.12323},
-    {-18.1120739, -2.96981215, 20.0532818},
-    {-17.5930309, -3.04089451, 19.9132576},
-    {-17.7931271, -3.18305492, 19.8431816},
-    {-18.0026264, -3.53838348, 19.7032433},
-    {-17.8994293, -4.03586245, 19.7732334},
-    {-17.6930637, -4.60440874, 19.3532906},
-    {-18.1089115, -5.38615513, 19.4233208},
-    {-17.8024464, -6.23897219, 19.0734062},
-    {-18.2121029, -6.94966173, 18.513443},
-    {-18.2089634, -7.58928108, 18.0934544},
-    {-18.3184261, -7.94462204, 17.8135643},
-    {-18.6343002, -8.65531158, 17.1837177},
-    {-19.0470791, -9.57920837, 17.0437355},
-    {-19.2502327, -10.0766869, 16.0638237},
-    {-18.9343204, -10.4320192, 15.7837915},
-    {-18.6311607, -11.4980659, 15.7138643},
-    {-18.6374874, -11.7112885, 14.80404},
-    {-18.8374786, -11.853406, 14.3840322},
-    {-18.7311516, -12.848361, 13.8240747},
-    {-19.1502705, -13.4880047, 13.1242151},
-    {-19.4598522, -13.7722816, 12.4942923},
-    {-19.0470791, -14.1986952, 11.9343605},
-    {-19.0470791, -14.7672472, 11.0244722},
-    {-19.4631004, -15.1226101, 10.3945675},
-    {-19.6759205, -15.4069223, 9.69468594},
-    {-19.0471458, -15.4779377, 9.20469379},
-    {-19.9726009, -15.5489893, 8.85472202},
-    {-20.1952114, -15.7622881, 7.94489717},
-    {-20.0855656, -15.7622499, 7.24496031},
-    {-20.2788677, -15.4779005, 7.03493881},
-    {-19.7726822, -15.1936779, 6.89498663},
-    {-19.5662937, -15.2647486, 6.82499599},
-    {-19.9790897, -15.1226101, 6.82499599},
-    {-20.5081654, -14.9805384, 6.61505938},
-    {-20.914341, -15.0515747, 6.61504078},
-    {-20.9078255, -14.9094019, 6.54502964},
-    {-20.4950504, -14.4829874, 6.61502123},
-    {-20.7113495, -14.4119644, 6.47506523},
-    {-21.1241894, -14.1987562, 6.40507221},
-    {-21.1241894, -14.4119635, 6.40507364},
-    {-21.4305019, -14.1276703, 6.40506458},
-    {-21.4371281, -14.1276999, 6.40508318},
-    {-20.9177513, -14.1987553, 6.61504984},
-    {-20.8178234, -14.2698402, 6.54506731},
-    {-20.8112259, -14.0566015, 6.96499872},
-    {-20.8079376, -13.9144478, 6.82500553},
-    {-20.8112392, -14.0566034, 6.82501411},
-    {-21.2174587, -13.8433638, 7.52491188},
-    {-21.1208687, -13.7723236, 7.52493572},
-    {-20.8112392, -14.0565996, 8.22485542},
-    {-20.7113113, -13.8434067, 8.43484497},
-    {-20.3983994, -13.8433924, 9.0647583},
-    {-20.5047932, -13.5591288, 9.97467232},
-    {-20.4917889, -13.2037306, 10.6045218},
-    {-20.6949234, -12.6351652, 11.2344255},
-    {-20.39184, -12.4219809, 12.1443596},
-    {-20.3951321, -12.2798519, 13.2642479},
-    {-20.3918781, -11.4270105, 13.8941469},
-    {-20.0855122, -10.5741863, 14.384119},
-    {-20.0790291, -10.0766926, 15.2239571},
-    {-20.0757656, -9.22385883, 15.8538485},
-    {-20.1854458, -8.79745007, 16.0638866},
-    {-19.9855881, -8.22889709, 16.4139137},
-    {-20.3049736, -7.58926964, 16.9739494},
-    {-20.201786, -7.66033888, 16.9739513},
-    {-19.7921047, -7.66033888, 17.1839638},
-    {-19.7953434, -7.51819706, 17.1839981},
-    {-20.4180069, -7.51819611, 16.9740543},
-    {-19.7921371, -7.94462013, 16.9739857},
-    {-19.7985401, -8.37104225, 16.6240902},
-    {-19.6952972, -8.79746628, 16.5540981},
-    {-20.2180691, -9.1528244, 16.064209},
-    {-20.3343143, -9.29497814, 15.4343977},
-    {-20.1212654, -9.79247093, 15.0843658},
-    {-20.53438, -10.1478271, 14.80439},
-    {-20.2212887, -10.4321098, 14.3844013},
-    {-20.4278259, -10.6453228, 13.7544584},
-    {-21.5704308, -10.7164011, 13.054575},
-    {-21.4771328, -10.6453514, 12.8446684},
-    {-21.1705856, -11.00072, 12.6347103},
-    {-20.8507595, -10.5031967, 12.4946499},
-    {-21.2671795, -10.7164164, 12.0047159},
-    {-21.7903423, -10.645359, 11.584794},
-    {-21.7869701, -10.4321365, 11.5147762},
-    {-22.3033619, -10.4321356, 11.3747883},
-    {-22.1966705, -10.4321299, 11.3047733},
-    {-21.5803757, -9.86356068, 11.2348003},
-    {-22.0901585, -9.43712234, 11.3747463},
-    {-22.1001511, -9.43713284, 11.3748083},
-    {-22.3169518, -9.43713951, 11.3048782},
-    {-22.3135319, -9.50821209, 11.4448471},
-    {-22.1035614, -9.57928085, 11.0948524},
-    {-22.3034191, -9.7924881, 11.2348003},
-    {-22.2034817, -10.0057077, 11.0248365},
-    {-21.896883, -9.79249668, 11.1648455},
-    {-21.8935394, -10.1478529, 11.1648273},
-    {-21.9969025, -10.2899981, 11.1648264},
-    {-21.7869549, -10.3610649, 11.1648064},
-    {-21.7869511, -10.8585672, 11.0248175},
-    {-21.8869076, -10.9296331, 10.4648438},
-    {-21.8901997, -11.1428585, 10.5348568},
-    {-21.7902431, -11.7825117, 10.6748638},
-    {-21.58041, -11.7114325, 10.184886},
-    {-21.4771519, -11.6403599, 10.1848869},
-    {-21.5803947, -11.9957199, 9.62492943},
-    {-21.4771137, -12.5642939, 9.48494339},
-    {-21.2671566, -12.5642834, 9.13495636},
-    {-21.7935715, -12.4932442, 9.13500118},
-    {-21.7835922, -12.5642824, 9.13495445},
-    {-21.0573235, -12.7064161, 8.92495728},
-    {-21.0639648, -12.7775126, 8.99498177},
-    {-20.8607006, -12.7064514, 8.78501415},
-    {-21.3704433, -12.7774982, 8.50500774},
-    {-21.8835506, -12.6353445, 8.43499947},
-    {-21.367157, -12.4221296, 8.29501152},
-    {-21.3605061, -12.4221077, 8.29498386},
-    {-21.9734135, -12.2088747, 8.50493622},
-    {-21.8735237, -11.9956722, 8.64493656},
-    {-22.3965378, -11.9246197, 8.78495407},
-    {-21.9801121, -11.5692539, 8.9249258},
-    {-21.9835415, -11.4271164, 9.20491791},
-    {-21.9733658, -11.6403074, 9.27486229},
-    {-22.0732861, -11.2138739, 9.83479023},
-    {-22.2899017, -10.8585396, 10.1848125},
-    {-21.9834747, -10.7164049, 10.3948126},
-    {-21.9801121, -10.2188988, 11.0247374},
-    {-22.0833549, -10.1478281, 11.8646584},
-    {-21.976738, -9.65032291, 12.0046253},
-    {-21.8835506, -9.22390747, 12.4946499},
-    {-21.6736546, -8.86854744, 12.9845819},
-    {-21.776947, -8.37104511, 13.4745388},
-    {-21.4604454, -7.66033459, 14.1744223},
-    {-21.4671288, -7.23390436, 14.3844585},
-    {-21.4737396, -7.02068472, 14.6644907},
-    {-21.3804321, -6.59424353, 15.084548},
-    {-21.1738014, -6.52317238, 15.5745106},
-    {-20.9639454, -6.02567053, 15.6444731},
-    {-20.8639069, -5.67030382, 15.9244833},
-    {-21.4737587, -5.31496334, 16.1343689},
-    {-21.0705147, -5.03065348, 16.414444},
-    {-21.1804428, -4.67527628, 16.4145145},
-    {-21.0837612, -4.74633312, 16.5545731},
-    {-20.9738483, -4.46205807, 16.3445168},
-    {-21.0704765, -4.46207476, 16.9044056},
-    {-20.7639294, -4.24884892, 16.694458},
-    {-20.5507774, -4.24886799, 16.6943874},
-    {-20.4508057, -3.8934958, 16.8344116},
-    {-20.4540825, -3.68026972, 16.7644539},
-    {-20.8672791, -3.46705127, 16.8344479},
-    {-20.8738441, -3.11166668, 16.7645206},
-    {-20.4572792, -2.6141696, 16.7644882},
-    {-21.0671902, -2.32992101, 16.6243973},
-    {-21.2705097, -2.11671805, 16.414381},
-    {-20.8606434, -1.83241522, 16.2044296},
-    {-21.0739288, -1.40594947, 16.3444843},
-    {-20.8573189, -1.26385534, 16.764349},
-    {-20.7540989, -0.126703858, 16.624361},
-    {-20.5508289, 1.15261483, 16.4144096},
-    {-20.86726, 1.8633821, 16.5544701},
-    {-20.9639454, 2.71620107, 16.6943913},
-    {-20.8606434, 3.78228307, 16.2744236},
-    {-20.6540546, 4.7062192, 15.9244518},
-    {-20.3441601, 5.91444731, 15.6444731},
-    {-19.9212646, 7.05148935, 15.1544247},
-    {-19.9147758, 7.54891586, 14.4544239},
-    {-19.8179722, 8.61506462, 14.3144932},
-    {-20.1343174, 9.82336998, 13.4746161},
-    {-19.5178013, 10.1787739, 12.984683},
-    {-19.7211361, 10.6051617, 12.7046824},
-    {-19.201479, 11.7422667, 12.2146969},
-    {-19.511322, 12.3819122, 11.794733},
-    {-19.3047619, 12.9504862, 11.3747683},
-    {-19.2045727, 13.2348242, 11.2347994},
-    {-18.794611, 13.0216637, 10.8148537},
-    {-18.5849304, 13.5191107, 10.9548225},
-    {-18.4785118, 13.6612034, 10.8848085},
-    {-18.3752155, 13.732276, 10.7448206},
-    {-18.4816666, 13.8744707, 11.0948114},
-    {-17.9683552, 14.0166702, 11.5147991},
-    {-18.0684986, 13.8744707, 11.6547661},
-    {-18.3688927, 13.8032398, 11.8646812},
-    {-18.1717911, 13.3058949, 12.3547096},
-    {-18.1686554, 13.021554, 12.9846315},
-    {-17.9652538, 12.737318, 13.8245926},
-    {-17.7587185, 12.3108883, 14.7345171},
-    {-17.1388988, 12.0976725, 15.1544819},
-    {-17.4518719, 11.387002, 15.6444731},
-    {-17.4518909, 10.6052055, 16.6943913},
-    {-16.9323635, 10.17873, 17.1843147},
-    {-16.4127979, 9.53903866, 17.6042442},
-    {-15.9540825, 8.61518669, 18.6892319},
-    {-15.8903389, 7.97538424, 19.0040493},
-    {-15.6837978, 6.76716709, 19.6339931},
-    {-15.7840586, 6.05641937, 20.1239052},
-    {-15.471262, 4.99031973, 20.7538071},
-    {-15.4802723, 3.3557651, 21.1039085},
-    {-14.8516912, 2.21854782, 21.943697},
-    {-15.1585073, 1.57888627, 22.0836353},
-    {-14.6422052, 0.0153220911, 22.6435833},
-    {-14.4445171, -0.979620099, 22.9237022},
-    {-13.6168423, -2.36551905, 22.7836895},
-    {-13.4146767, -3.25389218, 22.783762},
-    {-13.7273922, -3.96459937, 22.6438236},
-    {-13.1077166, -4.88853025, 22.9238014},
-    {-12.7950344, -6.02568245, 22.9237518},
-    {-12.8424006, -6.41658401, 22.7836895},
-    {-13.0044203, -6.80746984, 22.6438236},
-    {-13.4175358, -7.16282797, 22.7138176},
-    {-12.9011192, -7.51818752, 22.5738297},
-    {-13.010149, -7.80247355, 22.7139149},
-    {-12.9125757, -7.37603664, 22.854002},
-    {-12.8121052, -7.09174585, 22.9940414},
-    {-12.545311, -6.73639154, 22.7839108},
-    {-12.6026335, -6.52316809, 22.7840099},
-    {-13.0230255, -5.77689314, 22.9941158},
-    {-12.4993696, -5.74136972, 23.3439617},
-    {-12.7002869, -5.03065872, 23.3438663},
-    {-12.3960209, -3.82241464, 23.2739716},
-    {-12.9154873, -3.04060388, 23.4840107},
-    {-13.0144091, -2.25882792, 23.6239223},
-    {-12.8637609, -1.40593421, 24.1489582},
-    {-12.8595238, -0.446477354, 23.6239223},
-    {-12.5580368, 0.406448066, 23.624073},
-    {-12.3945818, 1.7923013, 23.203949},
-    {-12.3945818, 2.75177765, 23.5189266},
-    {-12.0931273, 4.03116655, 23.2041016},
-    {-12.8235292, 5.843606, 23.1342297},
-    {-12.295536, 7.19385433, 22.7140598},
-    {-11.7789726, 8.33101654, 22.0141106},
-    {-11.314064, 9.25496006, 21.7341309},
-    {-11.5667744, 10.2498903, 20.9640961},
-    {-11.4690304, 11.3871403, 20.7891979},
-    {-11.1549263, 12.559763, 20.1591797},
-    {-11.314064, 12.8796663, 19.9492588},
-    {-11.3684597, 13.66152, 19.5643291},
-    {-11.1645927, 14.0880089, 19.0744038},
-    {-11.468997, 14.1589746, 19.1443176},
-    {-11.4717607, 14.2300987, 19.0743618},
-    {-11.2651491, 14.0168848, 18.7243881},
-    {-11.3629408, 13.5903397, 18.7243061},
-    {-11.8766975, 13.3770704, 19.1442375},
-    {-12.0804787, 12.5241556, 19.2141895},
-    {-12.0748596, 12.0976238, 19.4940891},
-    {-12.9039688, 11.7423124, 19.7741051},
-    {-13.4146433, 11.0315056, 19.7040272},
-    {-14.0401897, 9.96551323, 20.1240807},
-    {-14.3559074, 9.53916836, 20.4041405},
-    {-14.5536709, 8.68618107, 20.6139927},
-    {-14.8664675, 8.33086014, 20.7540245},
-    {-15.0760679, 7.69124937, 20.5440845},
-    {-14.9638605, 6.83827543, 20.4739609},
-    {-15.4832697, 5.98544836, 20.4040127},
-    {-15.6928606, 5.55905342, 20.3340588},
-    {-16.1060467, 5.41690874, 20.3340588},
-    {-16.9384613, 4.70624876, 20.1241608},
-    {-16.9353981, 4.13764286, 20.4040985},
-    {-17.3455124, 3.6401093, 20.6840305},
-    {-16.722702, 3.28472376, 20.6139946},
-    {-16.5099945, 1.86324084, 20.473917},
-    {-16.8198662, 0.79716599, 20.6838989},
-    {-16.9322968, -0.26884672, 20.7540264},
-    {-16.3064899, -1.5481739, 21.0339127},
-    {-16.4128494, -3.18280888, 21.2439404},
-    {-17.0325241, -4.60424423, 20.8239765},
-    {-16.8259277, -6.16782522, 20.3340168},
-    {-16.5191765, -7.6603303, 20.1240749},
-    {-17.0386944, -9.65034866, 19.2141933},
-    {-16.829071, -11.4982157, 17.8842583},
-    {-16.4189339, -12.9196672, 16.7643814},
-    {-16.7349186, -14.2700682, 15.4345503},
-    {-17.0448742, -15.6915159, 13.68468},
-    {-17.1450939, -16.4732914, 11.8647957},
-    {-17.4518719, -17.3261375, 10.0449142},
-    {-18.1844063, -17.539423, 7.66513586},
-    {-18.384697, -17.4683037, 5.42528868},
-    {-18.3878117, -17.6104717, 3.32544684},
-    {-19.3176441, -16.7576027, 1.08561027},
-    {-20.0505486, -15.4783516, -0.944263816},
-    {-20.4637966, -14.3411846, -2.27417326},
-    {-21.2869968, -12.8486423, -3.95403886},
-    {-21.8936062, -11.2139359, -5.63384867},
-    {-22.0002975, -9.08177376, -6.33381462},
-    {-22.5134716, -7.09174967, -7.03373861},
-    {-23.3500576, -5.17278433, -7.24379349},
-    {-23.0401001, -2.82739019, -7.03380775},
-    {-23.6600285, -0.837350607, -6.68383217},
-    {-23.9733849, 0.441974789, -5.98390436},
-    {-24.5898113, 1.86340714, -5.00395346},
-    {-24.6861362, 2.71622658, -3.74401522},
-    {-24.4795227, 3.42695236, -2.69409299},
-    {-24.6896305, 4.35091782, -2.13414884},
-    {-24.7823887, 4.84833479, -1.08419895},
-    {-24.785902, 5.20372534, -0.38426277},
-    {-24.8891907, 5.77230263, -0.38426277},
-    {-24.7894268, 5.55911779, -0.244280264},
-    {-24.3657532, 5.48794746, -0.104271382},
-    {-24.0593452, 5.98548651, -0.524245262},
-    {-24.1730576, 5.98558617, -0.944234729},
-    {-24.2764111, 5.91451311, -1.29420888},
-    {-24.2694187, 5.91444731, -1.99413574},
-    {-23.8562336, 5.70122957, -2.69408035},
-    {-23.2330284, 5.34583712, -3.67398739},
-    {-23.7460346, 5.13258886, -4.02394295},
-    {-23.742609, 4.8482728, -4.58387852},
-    {-23.5360126, 4.35077047, -5.49380398},
-    {-23.6392937, 3.7111249, -5.77377558},
-    {-23.3329277, 3.28472257, -6.33375025},
-    {-23.4292908, 2.71609616, -6.75366831},
-    {-23.1228962, 2.50290775, -7.10366154},
-    {-22.9163418, 2.21862078, -7.59361935},
-    {-23.226141, 1.2236172, -8.43354511},
-    {-22.7098141, 0.370759934, -8.57353401},
-    {-22.8096714, -0.126760483, -8.57350826},
-    {-22.7030315, -0.553209782, -8.85345554},
-    {-23.2227688, -1.26390398, -8.50351334},
-    {-22.4964848, -1.40606272, -8.0835247},
-    {-22.9095383, -1.69034719, -8.01353264},
-    {-23.012764, -2.54320264, -7.73355818},
-    {-23.5395317, -3.04066825, -7.10368538},
-    {-23.7495155, -3.46708393, -6.68374491},
-    {-23.3226204, -3.68034315, -6.19369698},
-    {-23.8354702, -3.75142455, -5.77371502},
-    {-23.6255188, -3.89357638, -4.72379589},
-    {-23.7322083, -4.1778512, -4.23385954},
-    {-23.8424587, -3.96461821, -4.0939045},
-    {-23.9456882, -3.75140262, -3.81392765},
-    {-24.4724846, -3.53815603, -3.18402815},
-    {-24.7788391, -3.32495284, -3.04402566},
-    {-24.6685886, -2.40104747, -2.83401632},
-    {-24.9713497, -1.9035759, -2.83398986},
-    {-24.9713497, -1.40607858, -2.83398986},
-    {-24.7577839, -0.766474307, -2.83396363},
-    {-25.0710793, -0.126817733, -2.90397143},
-    {-24.6579628, 0.512821198, -2.97396493},
-    {-24.2449722, 1.08138835, -2.97396374},
-    {-24.6580353, 1.86316538, -3.25393653},
-    {-24.7612991, 2.71602082, -3.32393074},
-    {-24.2485008, 3.49782562, -3.11396384},
-    {-24.0419922, 4.56389332, -3.04397035},
-    {-24.0419922, 5.55888796, -2.55401659},
-    {-23.9352722, 6.41170597, -2.41401577},
-    {-23.8285503, 7.2645216, -1.78406465},
-    {-23.6289444, 8.1174469, -1.08415341},
-    {-23.0128174, 9.11248302, -0.874181271},
-    {-22.6995869, 9.82315445, -0.0342514962},
-    {-22.5929565, 10.7470312, 0.455707341},
-    {-22.2831707, 11.1023884, 1.29562879},
-    {-22.5895081, 11.6709061, 2.4855125},
-    {-22.1731777, 11.8130007, 3.60540128},
-    {-21.3506279, 12.097332, 5.07526207},
-    {-21.3605442, 12.2396202, 6.33516312},
-    {-20.8376579, 12.3816624, 8.01498032},
-    {-20.5343285, 11.8131924, 9.83484268},
-    {-20.6310654, 10.7470312, 11.7946215},
-    {-20.0050526, 9.39660072, 13.4744062},
-    {-20.0050297, 8.33054066, 14.4543085},
-    {-19.905077, 6.48274136, 15.7842073},
-    {-19.4888077, 4.7770133, 16.8340702},
-    {-19.8017941, 3.35562849, 17.6040287},
-    {-19.8082542, 1.43676531, 18.1640491},
-    {-19.5985317, -0.553243876, 18.234005},
-    {-19.8082542, -2.11678982, 18.4440212},
-    {-19.7017555, -3.11179471, 18.1640091},
-    {-19.5920525, -4.67537308, 17.8139706},
-    {-19.9050388, -6.23892164, 17.4640408},
-    {-19.5984783, -6.73641348, 17.2540989},
-    {-19.9147434, -7.37604856, 16.6942196},
-    {-20.0180206, -7.9446187, 15.9242887},
-    {-20.3343525, -8.22890282, 15.5743847},
-    {-20.4310837, -8.93961811, 15.3643408},
-    {-20.537653, -9.36604691, 14.8044224},
-    {-21.0474052, -9.36604023, 14.4543943},
-    {-20.8408794, -9.36604023, 14.4543943},
-    {-20.7442322, -9.7924757, 13.9644947},
-    {-20.8507786, -10.0056934, 13.4045744},
-    {-20.847477, -10.3610468, 12.844594},
-    {-20.8540649, -10.2899876, 12.7046566},
-    {-20.7474804, -10.1478376, 12.4246559},
-    {-20.9540405, -10.7164106, 11.9346972},
-    {-21.3671513, -11.0717688, 11.7947092},
-    {-21.2704868, -11.0717831, 11.3747883},
-    {-20.9639454, -11.4982243, 11.5847931},
-    {-21.2671795, -11.7824945, 11.4447651},
-    {-21.1605968, -11.8535576, 11.0247755},
-    {-20.7507687, -11.9246378, 11.1647844},
-    {-20.6474915, -12.2089243, 11.2347794},
-    {-20.8540649, -12.4932117, 11.1647844},
-    {-20.9573574, -12.3510695, 11.3747663},
-    {-20.3278389, -11.9956799, 11.7246714},
-    {-20.1180401, -11.7824574, 12.5645714},
-    {-19.7146759, -11.5692711, 13.1945906},
-    {-19.6210976, -11.0717916, 14.1045942},
-    {-19.9277439, -10.14785, 15.4344568},
-    {-19.711504, -9.29497623, 16.3442841},
-    {-19.0950394, -7.73140049, 17.324234},
-    {-19.1982975, -6.02568483, 17.9541779},
-    {-18.5786209, -4.39103842, 19.1440773},
-    {-18.5754528, -2.61426091, 19.4940052},
-    {-18.0622292, -0.908528924, 19.7040272},
-    {-18.1686554, 0.655066967, 19.844059},
-    {-18.0622292, 2.36076427, 19.7740211},
-    {-17.6491184, 3.7111249, 20.193985},
-    {-17.1357841, 4.99044657, 19.9140511},
-    {-16.5222111, 5.91444492, 19.844141},
-    {-16.4066696, 6.62502718, 19.8439732},
-    {-16.5099621, 6.62502575, 19.9139652},
-    {-16.3126068, 6.69620371, 19.7741051},
-    {-15.8903999, 6.55395412, 19.913969},
-    {-16.1941433, 6.19852972, 20.2638493},
-    {-16.5039158, 5.41674423, 20.4738312},
-    {-16.7196007, 4.56398201, 20.5439548},
-    {-16.5160599, 3.64007998, 21.2439423},
-    {-16.3125744, 2.71617413, 21.3139801},
-    {-16.3095531, 1.72114491, 21.2439423},
-    {-16.3095341, 0.726137519, 21.5239182},
-    {-16.3064899, -0.055669874, 21.1739044},
-    {-16.819828, -0.411046833, 21.1038647},
-    {-17.2328968, -1.19283223, 20.8938808},
-    {-17.4425526, -1.76138854, 20.6139488},
-    {-17.3362122, -1.76140308, 20.6139069},
-    {-17.3393269, -1.83246148, 20.4039669},
-    {-17.6553497, -2.32993388, 20.0540829},
-    {-17.9621048, -2.4720912, 20.1940308},
-    {-17.9620724, -2.75637698, 19.7740688},
-    {-18.5723515, -2.96963096, 19.3539772},
-    {-18.5786209, -3.4671073, 19.2840633},
-    {-19.0950203, -3.89353681, 18.9340935},
-    {-18.8852577, -3.96462011, 18.6540794},
-    {-18.4753437, -4.39103842, 18.5141296},
-    {-18.7883644, -4.81746054, 18.6541576},
-    {-18.5849667, -5.45709848, 18.2342319},
-    {-18.5786209, -6.16782808, 17.9541779},
-    {-18.7915363, -6.80746794, 17.9542542},
-    {-18.4879742, -7.37603951, 18.1643124},
-    {-18.7009602, -7.94461727, 17.954401},
-    {-18.9012222, -8.72641182, 17.4643669},
-    {-18.9107742, -9.36607456, 17.254488},
-    {-18.391037, -9.65036011, 17.3244495},
-    {-18.3878651, -10.0767918, 17.1144257},
-    {-18.3910179, -10.1478691, 17.0444679},
-    {-18.2845058, -10.1478634, 17.1144276},
-    {-18.5975456, -10.503232, 17.2544537},
-    {-18.0872517, -10.3610992, 17.46451},
-    {-17.3764572, -10.076828, 17.8846283},
-    {-17.6771851, -9.86359215, 17.8845177},
-    {-17.570734, -9.08178616, 18.164463},
-    {-17.7836075, -8.58427525, 18.5845127},
-    {-17.5894489, -7.66032028, 18.8646526},
-    {-17.3796349, -6.94958162, 19.3545856},
-    {-17.8995571, -6.38098669, 19.7046089},
-    {-17.8086243, -5.7412982, 19.6347752},
-    {-17.4922791, -4.88841915, 19.7746887},
-    {-17.3826847, -4.39091539, 19.9145985},
-    {-17.3858242, -4.03553486, 20.3346195},
-    {-17.2793541, -3.46695256, 20.0545902},
-    {-18.0091248, -3.04048395, 19.9146824},
-    {-17.5956631, -3.11155844, 19.9146805},
-    {-18.0123253, -3.11154604, 19.9147243},
-    {-18.2221966, -3.04046035, 19.6347752},
-    {-18.2190762, -3.46691847, 19.4247437},
-    {-18.73592, -3.6801424, 19.2147541},
-    {-18.9394875, -3.82230353, 18.9347267},
-    {-19.2624588, -4.67516375, 18.7248936},
-    {-19.8828049, -5.38591385, 18.3049088},
-    {-19.6760063, -5.45698881, 18.0949173},
-    {-19.8827858, -6.5231123, 17.3249474},
-    {-19.6825047, -6.87848425, 16.8350334},
-    {-20.3028545, -7.44708586, 16.2050552},
-    {-20.5064468, -8.15784168, 15.6450405},
-    {-20.5064468, -8.9396677, 15.0850611},
-    {-20.8232193, -9.72150421, 14.3151445},
-    {-20.7165451, -10.5033283, 13.3351498},
-    {-20.609848, -11.4983759, 12.4951534},
-    {-20.8166599, -12.0669785, 11.655179},
-    {-21.1301537, -12.2802143, 10.3252487},
-    {-21.3336372, -12.77773, 8.57529068},
-    {-21.6472168, -13.0620441, 7.31534481},
-    {-22.2743702, -13.2042198, 5.77541208},
-    {-22.0641651, -13.0620546, 3.95546269},
-    {-22.3710442, -12.7777414, 2.48550296},
-    {-22.7846737, -12.5645151, 0.805561066},
-    {-22.7812634, -11.853756, -0.594384193},
-    {-22.6812572, -10.5033264, -1.4343698},
-    {-23.4050713, -9.50827503, -2.20434022},
-    {-23.1913815, -8.44214153, -3.18427944},
-    {-23.3981838, -7.44708872, -3.88425469},
-    {-23.7049141, -6.52311659, -4.2342248},
-    {-23.9323597, -5.24372911, -3.81433439},
-    {-24.2253208, -4.31978941, -3.95425177},
-    {-24.2218494, -3.3247478, -4.02423334},
-    {-24.9419899, -3.04046249, -3.4642427},
-    {-24.72822, -2.25866652, -3.18422556},
-    {-24.7388115, -1.90325069, -3.39425874},
-    {-24.5284958, -1.33466697, -3.11425591},
-    {-24.524971, -0.979310751, -3.1142416},
-    {-24.2183475, -0.9792943, -2.97426128},
-    {-24.5284805, -0.766068161, -3.11425543},
-    {-24.5459843, -0.410604119, -3.25432348},
-    {-24.6388359, -0.766031623, -3.46427274},
-    {-24.1114616, -0.837160587, -3.53422356},
-    {-24.425108, -0.90821892, -3.67423224},
-    {-23.9047394, -0.979310751, -4.16419268},
-    {-24.6214218, -1.26364279, -4.44414759},
-    {-24.2148762, -1.97435343, -4.58417606},
-    {-24.1045265, -2.18760586, -4.44414806},
-    {-24.213171, -1.9388243, -4.9341507},
-    {-24.4181442, -2.54296279, -5.21412897},
-    {-24.5179882, -2.89834809, -5.21411037},
-    {-23.8909035, -2.89837313, -5.35406399},
-    {-23.7944889, -3.39586735, -5.35410309},
-    {-24.108017, -4.03552532, -5.56411266},
-    {-23.7979221, -4.24874878, -6.19408083},
-    {-23.3740826, -4.81736374, -6.12402105},
-    {-23.0605774, -5.74133348, -6.12400055},
-    {-23.2707138, -5.88347435, -5.70404625},
-    {-23.1639729, -6.23884821, -5.63402843},
-    {-23.4740105, -6.52314281, -5.35404491},
-    {-23.4773407, -6.80743599, -5.00408125},
-    {-23.4274845, -7.48263502, -4.19913387},
-    {-23.5773602, -7.69585848, -3.88412809},
-    {-23.6841717, -7.87354326, -3.534163},
-    {-23.2741432, -8.5132103, -2.90421081},
-    {-23.5772648, -8.8685751, -2.34422016},
-    {-23.8822346, -8.44212914, -1.57424581},
-    {-23.5704632, -8.65534973, -1.22426093},
-    {-23.367218, -8.58427811, -0.594306529},
-    {-23.8874073, -8.442132, -0.104344249},
-    {-24.3524666, -8.01568985, 0.000649897614},
-    {-24.7071686, -7.66032314, 0.595624328},
-    {-24.496994, -7.48264122, 0.525635004},
-    {-24.491745, -7.16281605, 0.525642693},
-    {-24.4864998, -6.84299135, -0.314289361},
-    {-25.1169262, -6.62976265, -0.314313948},
-    {-24.651989, -6.30993414, -0.209317699},
-    {-25.1169777, -5.45705605, -0.839277208},
-    {-24.9566288, -5.03062868, -1.15424252},
-    {-25.223856, -4.24880362, -1.78422666},
-    {-24.651989, -3.96451974, -2.2041893},
-    {-24.9067974, -3.11165357, -2.76414037},
-    {-24.9103508, -2.18769097, -3.04413366},
-    {-24.3901634, -1.61912084, -3.53408933},
-    {-24.347271, -0.97942096, -4.30408001},
-    {-24.3866673, -0.0555352941, -4.1640296},
-    {-24.0215874, 0.726244688, -4.61898088},
-    {-24.4812813, 1.25925648, -4.82894039},
-    {-24.0215874, 1.68572533, -5.14394331},
-    {-23.2467079, 3.00056958, -5.70390272},
-    {-23.243288, 3.99555802, -5.7738781},
-    {-22.8403416, 4.91959429, -6.05392122},
-    {-23.2638836, 5.98578835, -6.12397957},
-    {-23.0367222, 6.98059797, -5.91386843},
-    {-22.7267532, 7.83347225, -5.77387762},
-    {-22.3203335, 9.04178524, -5.49393845},
-    {-21.9036713, 9.68139648, -4.86396313},
-    {-21.9003258, 10.6763697, -4.37398148},
-    {-21.5837402, 11.8134317, -3.53401661},
-    {-21.4937325, 12.3111362, -2.06416965},
-    {-21.3904133, 13.1640043, -0.874260426},
-    {-20.7672081, 13.6614666, 0.52565074},
-    {-20.5540447, 13.8745785, 2.13554001},
-    {-20.347456, 14.2299385, 4.37536335},
-    {-20.2472992, 14.1589212, 6.05525303},
-    {-19.7437973, 13.803771, 7.73516798},
-    {-19.6243324, 13.0217123, 8.99501133},
-    {-19.7308502, 12.3110352, 11.0948753},
-    {-19.6275864, 11.4581671, 12.4247742},
-    {-20.0407867, 10.6763697, 13.4746952},
-    {-19.6275196, 9.53921223, 14.3146334},
-    {-19.6275387, 8.54419327, 15.3645582},
-    {-19.0044708, 8.11772346, 16.1344662},
-    {-19.4144859, 7.12267303, 16.7643833},
-    {-18.8041725, 6.5542016, 17.3244495},
-    {-18.1843967, 5.91454744, 17.4644356},
-    {-18.6007996, 6.05672741, 17.6044636},
-    {-18.187542, 6.05672741, 17.8144493},
-    {-18.0810814, 6.1277647, 18.3043766},
-    {-17.984045, 6.12783337, 18.164463},
-    {-17.7680187, 6.26987553, 18.1643467},
-    {-18.181242, 6.69630957, 17.8843708},
-    {-17.8681946, 7.33592701, 17.7443447},
-    {-18.3910179, 7.83350754, 17.6744213},
-    {-18.0810814, 8.33101654, 17.4644375},
-    {-18.0811138, 9.04174519, 17.1144638},
-    {-17.5613861, 9.6102829, 16.8344479},
-    {-17.3578911, 9.75247002, 16.4845085},
-    {-17.5582714, 10.2498903, 16.1344681},
-    {-17.4705448, 10.818697, 15.9246435},
-    {-17.5645313, 11.1739206, 15.7145634},
-    {-17.3485813, 11.6712894, 15.3644953},
-    {-17.2483673, 11.884553, 15.084547},
-    {-17.1419868, 11.8134317, 15.2245064},
-    {-17.1481953, 11.8846016, 15.1545734},
-    {-17.2484379, 12.0266972, 15.084547},
-    {-17.670948, 12.0268412, 15.2946234},
-    {-17.4611816, 11.7425041, 15.5045776},
-    {-17.8681087, 11.8845539, 15.3645267},
-    {-17.2607632, 12.1690378, 15.2946539},
-    {-17.4580479, 11.8846045, 15.0145826},
-    {-16.8259373, 11.9554806, 15.2944393},
-    {-16.7319069, 12.1688433, 15.2945318},
-    {-16.9476871, 12.1689892, 15.574604},
-    {-17.3546848, 12.2399645, 15.1545715},
-    {-17.3485813, 12.3820095, 15.4344893},
-    {-17.0417976, 12.4531317, 15.4345207},
-    {-17.1512585, 12.097868, 15.6445675},
-    {-17.0418491, 12.1688433, 15.5745087},
-    {-16.8321342, 11.7423592, 15.7844629},
-    {-16.5222111, 11.6002169, 15.9944448},
-    {-16.7318878, 11.4581194, 16.1344681},
-    {-17.1419868, 10.8894958, 16.4844074},
-    {-17.0417404, 10.1788177, 16.8344154},
-    {-17.0479145, 9.53925323, 17.5344315},
-    {-17.148138, 8.68633938, 17.8143749},
-    {-17.3485813, 8.47304058, 18.3042603},
-    {-17.4487896, 7.47799397, 18.5842018},
-    {-17.3485813, 6.5540967, 18.8642178},
-    {-17.3454742, 5.77226734, 19.2141514},
-    {-17.4488277, 4.91940784, 19.7741051},
-    {-17.2391129, 3.99543858, 19.4940853},
-    {-17.1450939, 3.07158899, 19.5642052},
-    {-17.4518719, 2.28976822, 19.9841309},
-    {-17.4518719, 2.00548005, 20.1241188},
-    {-17.6584663, 1.436903, 20.1241188},
-    {-17.5582619, 0.726200819, 20.5441303},
-    {-17.5551167, -0.055611413, 20.4740906},
-    {-17.9683552, 0.157605633, 20.1241188},
-    {-18.0685024, -0.126701415, 20.1240749},
-    {-17.4487476, -0.197774976, 19.9840889},
-    {-17.5489368, -0.339936733, 19.9840469},
-    {-18.0622959, -0.339955002, 20.193985},
-    {-17.9652405, -0.268847317, 19.914093},
-    {-17.868185, 0.086552158, 19.774189},
-    {-17.855669, 0.299686998, 19.914011},
-    {-18.0716, 0.584038496, 19.914135},
-    {-17.9683037, 1.22368538, 20.1941128},
-    {-18.3783894, 1.29473639, 19.914093},
-    {-18.3815422, 1.57904708, 19.774147},
-    {-17.8619232, 1.86331213, 19.704113},
-    {-17.6616249, 2.21872067, 19.5642033},
-    {-18.0748062, 2.28979254, 19.2842255},
-    {-17.5613956, 2.64518046, 19.4242573},
-    {-18.0747871, 2.57408428, 19.4942093},
-    {-18.384697, 2.43193722, 19.4942093},
-    {-18.4848385, 2.28976679, 19.2141895},
-    {-18.4848385, 1.86333406, 19.2841854},
-    {-18.694582, 1.57907081, 19.3542213},
-    {-19.1078205, 1.43692553, 19.5642052},
-    {-18.7947235, 0.868325412, 19.1441975},
-    {-19.2079105, 0.0154597163, 19.2141933},
-    {-18.4848385, -0.624188364, 19.2141933},
-    {-18.2813625, -1.05060601, 19.3542213},
-    {-18.588131, -1.97455931, 19.4241753},
-    {-19.0045052, -2.68526864, 19.3542194},
-    {-18.8010979, -3.680269, 18.8642979},
-    {-18.7979259, -4.46207714, 18.4442902},
-    {-18.7009602, -6.02565622, 18.0243969},
-    {-19.3273048, -6.73637724, 17.8844814},
-    {-19.7437973, -8.01568985, 17.4645443},
-    {-19.537138, -9.57929897, 16.4846077},
-    {-19.1205692, -10.7875338, 15.3646498},
-    {-19.4337692, -11.8536406, 14.3847437},
-    {-19.0300407, -12.777627, 13.5448751},
-    {-19.3304596, -13.5593958, 12.5648642},
-    {-19.4337692, -13.9147644, 11.1649475},
-    {-19.0269012, -14.4833784, 9.9050684},
-    {-19.5339127, -14.767622, 8.9250803},
-    {-19.9504776, -15.1940775, 8.0851469},
-    {-20.4736576, -15.0519667, 7.31522083},
-    {-20.5737667, -15.1940966, 6.545259},
-    {-20.8869629, -14.696599, 6.4752717},
-    {-21.4003448, -14.6255093, 6.19527721},
-    {-20.883728, -14.5544367, 5.7753067},
-    {-21.1937504, -14.3412161, 5.9152956},
-    {-21.6104145, -13.772645, 5.56532526},
-    {-21.8170738, -13.488349, 5.4253335},
-    {-21.4004059, -13.1329699, 5.28533554},
-    {-21.9171085, -13.275116, 5.21533966},
-    {-22.0137024, -13.132946, 4.58536959},
-    {-22.1170177, -12.7065067, 4.37538481},
-    {-22.6370068, -12.7065182, 4.23539925},
-    {-22.327055, -12.7775917, 3.74542785},
-    {-21.6037407, -12.8486643, 3.1154685},
-    {-21.8170929, -12.7065401, 1.9955374},
-    {-21.5104294, -12.3511848, 1.50556493},
-    {-21.5037403, -12.7776022, 0.525630951},
-    {-21.8171272, -12.9908352, -0.594310164},
-    {-21.8137646, -12.7065296, -1.01427472},
-    {-21.6070518, -12.7776022, -1.7142334},
-    {-21.3037167, -12.777626, -2.62420011},
-    {-21.2970486, -12.8486767, -3.25413513},
-    {-21.1904221, -12.422226, -3.60409951},
-    {-20.6803551, -12.2090263, -4.30408955},
-    {-20.6705284, -12.4222136, -4.72401047},
-    {-20.8738098, -12.1379128, -4.93397713},
-    {-20.8870487, -12.1379528, -5.28403044},
-    {-21.1937275, -12.4222364, -5.21401501},
-    {-21.0936756, -12.2800999, -5.2840271},
-    {-20.773819, -12.1379223, -5.49395752},
-    {-20.7705326, -12.3511314, -5.28395128},
-    {-20.8772259, -12.2800684, -5.42395973},
-    {-21.2036839, -12.1379728, -4.86409092},
-    {-21.4070606, -12.0668888, -4.51409245},
-    {-21.7104397, -11.9957972, -4.16408014},
-    {-21.4004059, -11.8536501, -3.8141005},
-    {-21.4070988, -11.7115221, -3.39415622},
-    {-22.0271301, -11.8536682, -3.60414338},
-    {-22.1271019, -11.640439, -3.25415134},
-    {-22.5337391, -11.2850552, -2.76415229},
-    {-22.4236317, -10.9296751, -2.83412313},
-    {-22.6404419, -10.7164764, -2.97415328},
-    {-22.7437668, -10.5032568, -2.834162},
-    {-23.0572243, -10.0768204, -2.97416711},
-    {-22.9538994, -9.86359978, -3.25415015},
-    {-22.9504642, -9.08178997, -3.53411794},
-    {-22.7403755, -8.79749489, -4.09406805},
-    {-22.733593, -8.37105465, -4.51400423},
-    {-23.3501225, -7.589252, -5.00395346},
-    {-23.0469208, -6.80744839, -5.49395895},
-    {-22.8368988, -6.09672403, -5.77391911},
-    {-23.3569355, -5.45706177, -5.98392582},
-    {-23.2570343, -5.10169029, -6.47391462},
-    {-23.4671383, -4.24880362, -6.82391548},
-    {-23.2536144, -3.75130916, -7.38383055},
-    {-22.9538651, -2.89839745, -8.01386738},
-    {-22.64048, -2.54304552, -8.64379692},
-    {-22.320282, -1.61913788, -9.27367687},
-    {-22.4270134, -0.12658754, -9.5536871},
-    {-21.8170929, 0.726354897, -9.9037571},
-    {-21.8103867, 1.86347711, -10.3236666},
-    {-21.3870869, 2.85842371, -10.4635649},
-    {-20.9738293, 4.20880604, -10.3235741},
-    {-20.8705368, 5.63025808, -10.3235722},
-    {-20.5671597, 6.76749086, -10.1836433},
-    {-20.0440788, 7.97565222, -9.90360451},
-    {-19.5242367, 9.32599449, -9.62359238},
-    {-19.5275288, 10.60534, -8.92367268},
-    {-19.3208923, 11.6714325, -8.15372658},
-    {-19.1238079, 12.7376738, -7.03387499},
-    {-19.2238998, 13.6615715, -5.91393137},
-    {-19.0204639, 14.3723545, -4.93401384},
-    {-18.9203415, 14.7277756, -3.81410408},
-    {-18.7136612, 15.0831423, -2.48418188},
-    {-18.8106136, 15.4383955, -1.64421558},
-    {-19.4209175, 15.4382219, -0.874240935},
-    {-19.3208351, 15.7936459, -0.104304366},
-    {-18.8105946, 16.006979, 0.315653473},
-    {-19.2238998, 15.7226868, 0.595635593},
-    {-18.5976639, 15.6514997, 0.875625312},
-    {-19.2207451, 15.9358473, 0.735631287},
-    {-19.5274677, 15.7225723, 0.73563534},
-    {-19.6339836, 15.2961912, 0.38565582},
-    {-19.6307774, 15.6514997, -0.104304366},
-    {-19.5274677, 15.2961349, -0.524274349},
-    {-19.5307961, 15.0119019, -1.15423656},
-    {-19.6308632, 14.6564827, -1.85418022},
-    {-20.353941, 14.4432669, -2.41413879},
-    {-19.9407158, 14.0878992, -3.25407863},
-    {-20.3605003, 13.5194225, -4.09405327},
-    {-20.1538773, 13.2351313, -5.00399065},
-    {-20.0375576, 12.8084965, -5.35389042},
-    {-20.2441406, 12.4531317, -6.1238308},
-    {-20.2441597, 11.9556246, -6.40380907},
-    {-20.250658, 11.3871403, -6.47384787},
-    {-20.1473427, 11.3871403, -6.6138382},
-    {-20.3506966, 10.960659, -6.82380104},
-    {-20.8672123, 10.6763697, -7.03378582},
-    {-20.8606491, 10.9605665, -6.68376637},
-    {-20.7606621, 10.9606123, -6.1238308},
-    {-20.6606522, 11.0317307, -5.91386843},
-    {-20.7573566, 11.3159266, -5.56385469},
-    {-21.2671986, 11.4579782, -5.07385588},
-    {-21.183733, 11.7425489, -4.79398298},
-    {-20.87714, 11.9558191, -4.02405739},
-    {-20.9804707, 12.1690388, -3.60408449},
-    {-20.9705238, 12.3110352, -3.25406361},
-    {-20.9672318, 12.6663504, -2.62409997},
-    {-20.8639164, 13.2349262, -1.92415214},
-    {-20.6507683, 13.5191135, -1.85413587},
-    {-20.547472, 13.5191107, -1.29418004},
-    {-20.5540829, 13.8745785, -0.524259686},
-    {-20.8639164, 14.4431543, 0.0356946252},
-    {-20.4441547, 14.5851908, 0.665659189},
-    {-20.137558, 14.6563148, 1.22561181},
-    {-20.1440315, 15.1539326, 2.41551399},
-    {-20.0310917, 15.0826941, 3.46543217},
-    {-19.9374523, 15.1539354, 4.65535116},
-    {-19.7340946, 15.0829182, 5.70527935},
-    {-19.3176441, 14.8696432, 6.475214},
-    {-19.0109119, 14.7986288, 7.73513699},
-    {-19.1142464, 14.3721914, 8.85505486},
-    {-19.3208351, 13.9457588, 10.1149616},
-    {-19.220726, 13.3061552, 11.374896},
-    {-18.3878841, 12.6664009, 12.2847824},
-    {-18.6914272, 12.0266495, 13.1246738},
-    {-19.2143192, 11.2449493, 13.6846838},
-    {-19.1046104, 10.7473507, 14.2445841},
-    {-18.5881119, 10.178772, 15.0145226},
-    {-18.4943295, 9.46817875, 15.4345818},
-    {-18.5912857, 9.11273575, 15.7844925},
-    {-19.7308502, 8.757411, 15.9945107},
-    {-19.2175293, 8.54423523, 15.8545523},
-    {-19.6339836, 8.47320271, 15.644598},
-    {-19.0141048, 8.61534595, 15.2946234},
-    {-19.1110039, 8.54419518, 15.1545715},
-    {-19.2079105, 8.47304249, 14.8745337},
-    {-20.3441601, 8.82840443, 14.5245619},
-    {-19.6179066, 8.97050381, 14.2445555},
-    {-19.927763, 9.25479317, 13.7545948},
-    {-20.2505684, 9.18388748, 13.334733},
-    {-20.3506107, 9.1127739, 13.1247225},
-    {-20.6540031, 9.18376446, 13.054677},
-    {-20.7672215, 9.18388844, 12.7047787},
-    {-21.5936089, 9.18388844, 12.7747717},
-    {-20.6605721, 9.39706326, 12.4247742},
-    {-21.1771355, 9.53920937, 12.7047548},
-    {-21.277235, 8.97058964, 12.7747231},
-    {-20.6573658, 9.04166222, 12.5647383},
-    {-20.6606331, 9.04170227, 12.8447428},
-    {-20.5573177, 8.89955616, 12.7047529},
-    {-21.2271481, 8.93507385, 12.9147272},
-    {-20.7672215, 9.25496197, 12.8447676},
-    {-20.4474621, 9.39698124, 12.984683},
-    {-20.4474945, 9.11269188, 13.1946669},
-    {-20.9738483, 9.32603359, 13.0547523},
-    {-20.4540119, 9.82349968, 12.8447447},
-    {-20.2506905, 9.68139839, 13.1947422},
-    {-19.6276436, 9.7524271, 13.4047003},
-    {-20.2925148, 10.2143097, 13.4396477},
-    {-19.8422108, 10.21451, 13.6497526},
-    {-18.9075832, 10.427659, 13.8596945},
-    {-18.9043961, 10.5342245, 14.3146334},
-    {-18.907568, 10.3921261, 14.5246477},
-    {-19.1078205, 10.3920355, 14.5945845},
-    {-18.5913181, 10.3920355, 15.154542},
-    {-18.1780987, 9.82345772, 15.4345207},
-    {-18.8980217, 9.46805286, 15.749465},
-    {-18.1327362, 8.93513489, 16.064537},
-    {-18.8980217, 8.61518669, 16.6943913},
-    {-18.3815422, 8.18875408, 17.044363},
-    {-18.5976448, 6.90956497, 17.849411},
-    {-18.7947617, 6.4119482, 17.8143024},
-    {-19.2175255, 5.84347439, 17.954401},
-    {-18.4379711, 5.20377254, 17.9543476},
-    {-19.067318, 4.45760393, 18.3744297},
-    {-19.0577984, 3.92447162, 18.5842991},
-    {-18.5929146, 3.1782105, 19.0042667},
-    {-18.7883129, 2.57400632, 18.8641396},
-    {-18.9012089, 1.57906711, 19.0042458},
-    {-18.9011898, 1.15263617, 19.0742416},
-    {-19.2143517, 0.299785644, 19.0742836},
-    {-19.377327, -0.446426183, 19.0043869},
-    {-19.9923763, -1.08610713, 18.899334},
-    {-19.1142101, -1.9034431, 18.8643379},
-    {-18.4379425, -2.47204447, 19.0042686},
-    {-19.0673656, -3.2182672, 18.7944012},
-    {-18.7525883, -4.28437376, 18.6893501},
-    {-19.0044861, -5.17280006, 18.3742943},
-    {-18.592886, -6.30995178, 18.3743153},
-    {-19.2175255, -6.80745506, 18.1643887},
-    {-18.9012222, -7.73140049, 18.0943165},
-    {-18.6946011, -8.37105274, 17.9543266},
-    {-18.3847866, -8.86855602, 18.0243225},
-    {-18.3848343, -9.22391891, 17.8843327},
-    {-18.0779266, -9.2949934, 17.8143749},
-    {-18.1780796, -9.22391891, 17.6743507},
-    {-18.1843777, -9.15285015, 17.7444191},
-    {-17.9809189, -8.93963623, 18.0244331},
-    {-17.8744545, -9.08177948, 18.5843563},
-    {-18.0873566, -8.3710537, 18.8644142},
-    {-17.670948, -7.73139811, 19.0743618},
-    {-17.054203, -7.16281843, 19.1443958},
-    {-16.4310837, -6.66530704, 19.5643291},
-    {-16.5435867, -6.16778469, 19.9844265},
-    {-17.1544323, -5.52814198, 20.1942825},
-    {-16.7318935, -4.67529106, 20.4741344},
-    {-16.9446316, -4.39098549, 20.4042244},
-    {-16.8382206, -3.89348674, 20.6841621},
-    {-16.8473911, -3.75131011, 21.1042671},
-    {-16.32481, -3.53811312, 20.9641857},
-    {-16.3277874, -3.46702957, 21.0342255},
-    {-16.2214088, -3.4670403, 21.2441692},
-    {-16.4280682, -3.82240415, 21.3841553},
-    {-16.9476967, -4.31990433, 21.384201},
-    {-16.3308411, -4.53311348, 21.244257},
-    {-16.2184258, -4.74635696, 21.0341377},
-    {-16.3247528, -5.31492996, 21.1741714},
-    {-16.1150913, -5.81244326, 20.8941479},
-    {-16.4280682, -6.38101912, 20.7542019},
-    {-16.5405521, -6.73637295, 20.47435},
-    {-16.9538803, -7.30495834, 20.2643661},
-    {-16.8505459, -7.6603241, 19.9843845},
-    {-16.8566875, -8.37105942, 19.704483},
-    {-17.0602875, -8.72642326, 19.2144718},
-    {-17.3765106, -9.29501629, 18.3746014},
-    {-17.2762337, -9.86361122, 18.16465},
-    {-17.5831184, -10.5032673, 17.3946609},
-    {-17.7898483, -11.3561544, 16.7646923},
-    {-17.8900909, -12.2090263, 16.134697},
-    {-17.6833973, -12.7065411, 15.3647404},
-    {-17.8963699, -13.4173079, 14.524848},
-    {-18.1062222, -14.6966457, 13.9649086},
-    {-18.0936451, -15.2651701, 12.6348829},
-    {-18.0936832, -15.6916103, 11.2349644},
-    {-18.5133095, -16.4734573, 9.97507858},
-    {-18.2095814, -17.0420895, 8.99516773},
-    {-17.7899055, -17.1841946, 7.66521502},
-    {-17.6865711, -17.5395622, 6.40528584},
-    {-17.9965744, -17.6106358, 5.07535839},
-    {-18.2064075, -17.5395851, 4.305408},
-    {-18.6166821, -17.6106358, 3.39545608},
-    {-18.81703, -17.5395164, 2.62550044},
-    {-18.1969452, -17.3973713, 2.13552952},
-    {-18.6198883, -17.4685097, 2.06553078},
-    {-19.1366291, -17.1842155, 1.9255389},
-    {-18.926796, -17.5395603, 1.71555185},
-    {-18.4005051, -17.6105652, 1.85554898},
-    {-18.1969795, -17.3262959, 2.27552247},
-    {-18.4036388, -17.2552223, 2.55550456},
-    {-18.5069923, -17.1841507, 2.97547841},
-    {-19.0300732, -17.113121, 3.67544055},
-    {-18.6135292, -17.1130981, 3.88542652},
-    {-18.6294117, -16.8999844, 4.58540726},
-    {-19.2399254, -17.1842155, 4.65538931},
-    {-19.136591, -17.113142, 4.44540024},
-    {-18.7232189, -16.9709949, 4.30540848},
-    {-19.2368336, -17.113121, 4.30540419},
-    {-19.0301399, -17.3263397, 4.23540831},
-    {-18.6166821, -17.6817093, 3.95542407},
-    {-18.8201847, -17.8238335, 3.67543745},
-    {-18.9203796, -17.6816616, 3.39545298},
-    {-18.716835, -17.6816864, 3.39545345},
-    {-18.4067936, -17.7527599, 2.76548934},
-    {-18.5101757, -17.8949051, 2.41551256},
-    {-18.19384, -17.7527122, 1.85554945},
-    {-18.0936642, -17.8238087, 1.22558701},
-    {-18.5069828, -17.8948822, 1.08559608},
-    {-18.9235477, -17.3973904, 0.455627888},
-    {-19.0268822, -17.3263168, 0.10564974},
-    {-19.1302452, -17.3973904, -0.0343420543},
-    {-19.5435696, -17.0420246, -0.314326555},
-    {-19.3369236, -16.9709511, -0.594308019},
-    {-19.0332851, -16.7577705, -0.524327159},
-    {-18.9299316, -16.1891823, -0.594323933},
-    {-19.4402199, -16.0469952, -0.874291301},
-    {-19.8536167, -15.6916275, -1.15427577},
-    {-20.0602379, -15.2651873, -1.22427106},
-    {-21.1937275, -14.8387299, -1.08427},
-    {-20.9870872, -14.199069, -1.50424421},
-    {-20.983757, -13.5593958, -1.85421205},
-    {-21.6104488, -13.0619078, -1.85423267},
-    {-21.3037167, -12.7065525, -1.99423623},
-    {-21.6070843, -12.2090168, -2.414186},
-    {-21.7070751, -11.4982748, -2.76415348},
-    {-22.3304367, -10.929697, -2.9041574},
-    {-22.8437042, -10.2900314, -3.25412178},
-    {-23.0537605, -9.65037632, -3.39412856},
-    {-22.8504829, -9.08179379, -3.53413367},
-    {-23.4602413, -8.22890854, -3.60408449},
-    {-23.4671383, -7.87354326, -3.67410874},
-    {-23.2604771, -7.37603092, -3.67410874},
-    {-23.5739117, -6.59421968, -4.09409952},
-    {-24.0871315, -6.02563715, -3.88409638},
-    {-24.0767097, -5.67028713, -4.37401295},
-    {-23.9803391, -5.24383688, -4.30405378},
-    {-24.1835022, -4.39096737, -4.65401411},
-    {-23.9838104, -3.82236362, -5.00402832},
-    {-23.9768753, -3.25379968, -5.00399065},
-    {-24.0905704, -2.75624919, -5.0740447},
-    {-23.6703548, -2.47198343, -5.14400053},
-    {-23.766758, -1.47699261, -5.56393242},
-    {-23.5532017, -0.908444881, -6.05385685},
-    {-24.0767097, 0.0155400988, -5.8439126},
-    {-23.8700638, 0.797337115, -6.26388359},
-    {-23.5635757, 1.3659445, -6.54388571},
-    {-23.5704346, 2.07671857, -6.19395494},
-    {-23.5601082, 3.2138176, -6.33387947},
-    {-23.1537514, 4.13781977, -6.33392143},
-    {-23.3638363, 4.77750921, -6.05396175},
-    {-23.3603401, 5.91464472, -5.70396519},
-    {-23.6599903, 6.9806366, -5.00395393},
-    {-23.3500195, 7.76243782, -4.09401798},
-    {-22.8437042, 8.47328281, -3.46410847},
-    {-23.1468353, 8.97071075, -2.55414319},
-    {-22.9367981, 9.46817875, -1.71418929},
-    {-22.4304237, 9.96582127, -0.594289124},
-    {-22.9435635, 10.534358, 0.315651536},
-    {-22.6201077, 10.676322, 1.0856154},
-    {-22.7336731, 10.9607506, 1.85555553},
-    {-22.7369461, 10.9607973, 2.34551907},
-    {-22.4270039, 11.174017, 2.97547698},
-    {-22.6268616, 11.1739244, 3.25545478},
-    {-22.8403893, 10.9607925, 3.53544235},
-    {-22.8539791, 10.8188324, 3.88542819},
-    {-22.7404137, 10.9608431, 2.97548151},
-    {-22.7336025, 10.889677, 1.15559959},
-    {-22.8437042, 10.179039, -0.244315356},
-    {-23.0434875, 9.61036777, -1.29422748},
-    {-23.1502171, 8.75753403, -2.34416866},
-    {-23.4567776, 8.18891144, -2.97411299},
-    {-23.4568157, 7.62032747, -3.39408302},
-    {-23.6669006, 7.33607483, -3.46409273},
-    {-23.3602886, 7.97577238, -2.76414585},
-    {-23.1570816, 8.75761127, -1.01428044},
-    {-23.5531826, 9.75242615, 0.0356919281},
-    {-22.5269222, 10.6764593, 1.08560777},
-    {-21.8204384, 11.3874264, 1.64555538},
-    {-21.1971474, 12.2402573, 1.01559746},
-    {-20.5605621, 13.3771725, -0.594264269},
-    {-20.1472607, 13.8036098, -2.34414554},
-    {-19.5274143, 14.1589775, -3.53406167},
-    {-18.3942108, 14.7276096, -4.0940361},
-    {-17.8838501, 15.5095243, -3.60409665},
-    {-17.5707245, 16.0780487, -2.5541575},
-    {-17.1543503, 16.9308681, -1.43421984},
-    {-17.0448608, 17.6414738, -0.244285673},
-    {-16.5344296, 18.2101765, 1.64556813},
-    {-16.3247528, 18.4944038, 3.4654398},
-    {-16.1151295, 18.4943428, 5.07531643},
-    {-15.4038887, 18.2813797, 6.82523918},
-    {-15.8201771, 17.7839317, 8.7151165},
-    {-15.49228, 17.0728321, 10.604887},
-    {-15.79914, 16.1488323, 11.9347658},
-    {-15.2915678, 16.1490059, 12.4247999},
-    {-14.7691278, 15.8646011, 12.8447189},
-    {-14.3588238, 15.7935896, 13.1247225},
-    {-14.9816818, 15.6514997, 13.4747219},
-    {-15.0879803, 15.7937012, 13.6147394},
-    {-14.6717396, 16.291153, 13.2647381},
-    {-14.9816818, 16.788662, 12.2848082},
-    {-14.9816818, 17.3572426, 11.6548529},
-    {-14.8813019, 17.9258881, 10.674942},
-    {-14.7809877, 18.1391678, 10.1849947},
-    {-15.0849457, 18.4233303, 10.1849585},
-    {-14.9906025, 17.9970856, 9.90503216},
-    {-14.884304, 18.2102432, 9.5550375},
-    {-14.6747227, 18.7787609, 9.27503967},
-    {-14.2643576, 18.6366806, 9.13506413},
-    {-14.5773306, 18.7788868, 8.71510792},
-    {-14.8961029, 18.7790852, 8.57516193},
-    {-15.1943598, 18.9920425, 8.71509075},
-    {-14.9846649, 18.8498287, 8.57508659},
-    {-15.1942415, 18.7788219, 8.64509773},
-    {-14.9846601, 18.8498363, 8.43509865},
-    {-15.2975855, 18.8498974, 8.435112},
-    {-14.8813543, 18.9209042, 7.87513781},
-    {-14.8783712, 19.0629864, 7.31516409},
-    {-14.884304, 19.205265, 6.96520996},
-    {-14.5713978, 19.3473415, 6.54522943},
-    {-14.7721062, 19.1339912, 6.26523066},
-    {-14.7661781, 19.4181499, 5.91524076},
-    {-14.6658449, 19.4182148, 6.19522667},
-    {-14.5625486, 19.5603619, 6.40521097},
-    {-14.9757347, 19.3471413, 6.54519987},
-    {-14.6658306, 19.4892883, 6.6151948},
-    {-14.7720919, 19.2761383, 6.61520529},
-    {-14.258544, 19.5604935, 6.75520372},
-    {-14.987648, 19.4895554, 6.82521915},
-    {-15.0880136, 19.5605602, 6.54522943},
-    {-14.5654507, 19.5604286, 6.75519371},
-    {-15.2916193, 19.2762012, 6.9651885},
-    {-14.7868872, 19.631834, 6.61525249},
-    {-14.6717205, 19.5604935, 6.40522909},
-    {-14.5683813, 19.8447838, 6.40522814},
-    {-14.7809601, 19.5606289, 6.47524023},
-    {-14.5743284, 19.5606289, 6.33525085},
-    {-14.3618069, 19.4183521, 6.40522909},
-    {-14.568429, 19.7026386, 6.33523417},
-    {-14.5655317, 19.9157925, 6.33522463},
-    {-14.4621687, 19.6315002, 6.19523668},
-    {-14.6628809, 19.4892254, 5.84524632},
-    {-14.3529959, 20.0578003, 5.98523569},
-    {-14.459219, 19.9157238, 6.05523825},
-    {-14.0373106, 19.7023029, 5.91522551},
-    {-13.7274256, 19.9155216, 5.84523058},
-    {-14.1523018, 19.844717, 5.8452611},
-    {-14.1551762, 19.7737122, 5.77527428},
-    {-14.0489483, 19.5604286, 5.63527775},
-    {-14.0460176, 19.6314335, 5.21530247},
-    {-13.5353003, 19.7737122, 5.07532644},
-    {-14.0460558, 19.6314316, 5.14530802},
-    {-14.4680443, 19.915926, 5.42530632},
-    {-14.1551762, 19.8447838, 5.35530472},
-    {-14.3588715, 19.9157887, 5.00532341},
-    {-14.5684338, 20.0580025, 5.28530931},
-    {-14.4621544, 19.7736454, 5.21530771},
-    {-14.6687756, 19.9157925, 5.14531279},
-    {-14.9757681, 19.9157238, 5.07531261},
-    {-14.7721109, 19.4182835, 5.07531929},
-    {-14.4621687, 19.4182835, 5.00532389},
-    {-14.6658449, 19.702507, 5.07531261},
-    {-14.6569672, 19.7023048, 5.07529497},
-    {-14.3558884, 19.5603619, 5.07531404},
-    {-14.8782997, 19.4183464, 5.21531439},
-    {-15.2826519, 19.4181499, 5.07530689},
-    {-15.1763906, 19.4180832, 4.86531878},
-    {-14.7720108, 19.4893532, 4.65534925},
-    {-15.0760632, 19.4892254, 4.79532909},
-    {-14.8753977, 19.5604286, 5.07531881},
-    {-15.1853209, 19.2761383, 5.14531422},
-    {-14.7691612, 19.2760715, 5.35529184},
-    {-14.9757166, 19.4182148, 4.93532372},
-    {-15.0819769, 19.2050648, 5.14531326},
-    {-15.3889503, 19.2760715, 5.07531261},
-    {-15.1823759, 19.4182167, 5.07531261},
-    {-15.1823759, 19.1339283, 5.28529644},
-    {-15.2826567, 19.1338596, 5.21529579},
-    {-15.2886229, 19.1339912, 5.35529757},
-    {-14.8753977, 19.347208, 5.28530312},
-    {-14.8724241, 19.6314335, 5.28529596},
-    {-15.2856731, 19.4182148, 5.49528122},
-    {-15.185359, 19.1339931, 5.56528234},
-    {-14.8694887, 19.2049332, 5.63525963},
-    {-14.8665247, 19.4891567, 5.49526548},
-    {-14.775075, 19.5604935, 5.56529045},
-    {-14.9757872, 19.5603619, 5.63527107},
-    {-15.185359, 19.4893532, 5.42529297},
-    {-14.7750559, 19.4183464, 5.70527935},
-    {-14.3530102, 19.4892197, 5.77525377},
-    {-14.659955, 19.4891567, 5.70525026},
-    {-14.4621544, 19.6315002, 5.8452611},
-    {-14.4621687, 19.7025757, 5.84526205},
-    {-14.4533567, 19.4891567, 6.12521553},
-    {-14.7721109, 19.4893532, 5.77526379},
-    {-14.1523018, 19.3472099, 5.42529249},
-    {-13.9427586, 19.5603619, 5.56527519},
-    {-14.6687946, 19.6315002, 5.70527124},
-    {-14.565484, 19.5604286, 5.8452611},
-    {-14.8753691, 19.7025757, 5.8452611},
-    {-14.6687469, 19.7736454, 5.70527124},
-    {-14.7278509, 19.7027378, 5.77528524},
-    {-14.5713596, 19.7027073, 5.63529062},
-    {-14.5625486, 19.4892883, 5.42528677},
-    {-14.462182, 19.7736454, 5.21530819},
-    {-14.6746941, 19.6316338, 5.42530537},
-    {-14.2556086, 19.5604286, 5.28530264},
-    {-14.3589239, 19.70257, 5.42529297},
-    {-14.4621868, 19.2761383, 5.14531326},
-    {-14.2628136, 19.5961323, 4.83035135},
-    {-14.5742617, 19.4895554, 5.21532583},
-    {-14.9845839, 19.4184132, 5.49530172},
-    {-15.1883087, 19.3828125, 5.35530424},
-    {-15.3388338, 19.1694946, 5.04031801},
-    {-15.1823282, 19.3471413, 5.49528074},
-    {-14.7234001, 19.3828125, 5.04032707},
-    {-14.7691278, 19.3471413, 5.00531816},
-    {-14.6598845, 19.6312981, 5.21528912},
-    {-14.8665056, 19.6313019, 5.21528864},
-    {-15.028863, 19.3827133, 4.93532562},
-    {-15.1793547, 19.1338596, 5.35528469},
-    {-15.0790129, 19.2050018, 5.21530151},
-    {-15.6441975, 19.4892216, 5.04030943},
-    {-15.1823282, 19.4892883, 4.86532927},
-    {-15.0244169, 19.382616, 5.25029325},
-    {-15.1838102, 19.7025394, 5.1453104},
-    {-14.4046421, 19.2760067, 5.25029325},
-    {-15.1838341, 19.0628872, 5.04031849},
-    {-15.3522806, 19.3830109, 5.25033188},
-    {-15.3432798, 19.3828106, 5.25031185},
-    {-14.7691231, 19.2760715, 5.14530659},
-    {-14.8694744, 19.595829, 5.67025995},
-    {-14.8783188, 19.3828106, 5.35530472},
-    {-14.7691612, 19.4892883, 5.42528582},
-    {-14.8739491, 19.4893188, 5.46028614},
-    {-14.4133863, 19.3828106, 5.46029615},
-    {-14.5728273, 19.3829117, 4.93534231},
-    {-14.7721252, 19.4893532, 5.28530312},
-    {-14.7322493, 19.4896202, 5.35532427},
-    {-14.2613745, 19.7737827, 5.35531187},
-    {-14.5684338, 19.809248, 5.35530424},
-    {-14.8649712, 19.4891205, 5.25028372},
-    {-15.1822577, 19.7735806, 5.35529041},
-    {-14.7690563, 19.5603619, 5.35529089},
-    {-14.2614031, 19.4894886, 5.35531139},
-    {-14.4621687, 19.70257, 5.07531881},
-    {-14.8724337, 19.702507, 4.93532372},
-    {-14.7720394, 19.6315022, 5.07531786},
-    {-14.7661781, 19.4892197, 5.63526249},
-    {-14.5595989, 19.4892254, 5.56526756},
-    {-14.4563112, 19.7024403, 5.35528374},
-    {-14.4651699, 19.5604935, 5.5652895},
-    {-14.459219, 19.5603638, 5.49528027},
-    {-15.082015, 19.70257, 5.28530264},
-    {-14.9698267, 19.844511, 5.35527658},
-    {-14.9787178, 19.844717, 5.63527775},
-    {-14.671711, 19.4894199, 5.42529821},
-    {-14.3588381, 19.9157887, 5.28530264},
-    {-14.4651318, 20.0580025, 5.35530329},
-    {-14.7780199, 19.6316338, 5.21532059},
-    {-14.6717396, 19.6315689, 5.35530424},
-    {-14.8813543, 19.915926, 5.14532423},
-    {-14.778038, 19.6316338, 5.00533438},
-    {-14.6658115, 19.8446484, 5.00531721},
-    {-14.56252, 19.9157238, 5.21530151},
-    {-14.56252, 19.5603619, 5.35529041},
-    {-14.3529911, 19.6313667, 5.21529579},
-    {-14.2497139, 19.915657, 5.1453023},
-    {-14.4650993, 19.8447838, 5.28530979},
-    {-14.2526636, 19.6314335, 4.93532276},
-    {-14.152297, 19.5604286, 5.14531374},
-    {-14.4651318, 19.4894218, 5.4253006},
-    {-14.4592943, 19.8446522, 5.07531166},
-    {-14.5713978, 19.7027073, 5.00533533},
-    {-14.6687946, 19.4182835, 5.21530867},
-    {-14.87251, 19.7735748, 5.28529692},
-    {-14.763299, 19.7734413, 4.86531734},
-    {-14.4503927, 19.8444481, 4.86531258},
-    {-14.5655127, 19.70257, 5.07531929},
-    {-14.2555799, 19.6315002, 4.93532991},
-    {-13.9339809, 19.6312351, 5.14528751},
-    {-14.2466688, 19.6313019, 5.14529324},
-    {-13.739006, 19.9157887, 5.00532341},
-    {-14.6628475, 19.5602932, 4.8653245},
-    {-14.3559122, 19.702507, 4.51535559},
-    {-14.0519028, 19.7737122, 4.5853591},
-    {-13.9427214, 19.9157238, 4.79533482},
-    {-13.8394289, 19.9157238, 4.93532372},
-    {-14.1522636, 19.9868622, 4.79534006},
-    {-14.1434717, 19.8445168, 4.72532892},
-    {-14.5596037, 20.1999454, 4.58534479},
-    {-14.6658258, 20.2000122, 4.58535051},
-    {-14.4621687, 19.9157925, 4.51536036},
-    {-14.1493473, 20.2710838, 4.58534956},
-    {-14.4562922, 20.2710152, 4.65533972},
-    {-13.8423071, 19.70257, 4.58535576},
-    {-13.6298523, 19.9867249, 4.79532957},
-    {-14.2438707, 20.413023, 4.51534176},
-    {-14.4504261, 20.1287346, 4.51534176},
-    {-14.6599169, 19.7734432, 4.51534605},
-    {-14.043087, 20.1999397, 4.79532957},
-    {-13.9456043, 19.9868622, 4.79533958},
-    {-13.9427023, 19.9867935, 5.00531721},
-    {-13.8395338, 19.8446484, 4.72533894},
-    {-14.3530293, 19.7024384, 4.58534479},
-    {-14.4503927, 19.9865894, 4.86531258},
-    {-14.4475002, 19.9865208, 4.72531843},
-    {-14.5566349, 19.7734432, 4.51534605},
-    {-14.3529911, 19.9867249, 4.65533972},
-    {-13.934, 20.2708759, 4.51534176},
-    {-14.1405935, 20.1998024, 4.44534636},
-    {-13.5237112, 20.2709465, 4.7253294},
-    {-14.0401611, 20.2709465, 4.79532385},
-    {-14.1434908, 20.1288033, 4.51534891},
-    {-14.3529434, 20.0577984, 4.65534019},
-    {-14.0401754, 20.3420143, 4.7253294},
-    {-14.0402794, 20.2709446, 4.79532433},
-    {-14.5566587, 19.9866581, 4.79532528},
-    {-13.9398613, 19.9867249, 4.86532402},
-    {-13.7332678, 20.0577984, 4.58534431},
-    {-14.1464024, 20.1288719, 4.58534431},
-    {-14.3559408, 20.0578671, 4.30537176},
-    {-14.7721109, 19.9868622, 4.23538113},
-    {-14.4593039, 20.3421516, 4.58534861},
-    {-13.9427214, 20.27108, 4.58534956},
-    {-13.8365459, 20.1999454, 4.23537445},
-    {-13.4175692, 20.1998081, 4.51534128},
-    {-13.4175882, 20.1287327, 4.72532368},
-    {-14.143486, 20.1998768, 4.37535906},
-    {-14.0372782, 19.7733746, 4.37535429},
-    {-14.1405745, 19.8444481, 4.72532511},
-    {-14.2497139, 20.0577984, 4.51535034},
-    {-14.2526064, 20.5553761, 4.30537081},
-    {-13.8394289, 20.6264458, 4.02539301},
-    {-13.6270409, 20.4130898, 4.16537523},
-    {-13.8306704, 19.7733727, 4.16537142},
-    {-14.1463881, 20.0577984, 4.37536287},
-    {-13.9456377, 20.2000809, 4.58535528},
-    {-13.9397573, 20.1999454, 4.5153513},
-    {-14.143486, 20.4130898, 4.51534748},
-    {-13.7273922, 20.057663, 4.16537142},
-    {-13.7303038, 20.3420181, 4.09538078},
-    {-13.9340143, 20.057663, 4.09537697},
-    {-14.1434717, 20.1288013, 4.02538633},
-    {-13.7273922, 19.9865932, 4.58533525},
-    {-13.5236635, 20.0577335, 4.5853405},
-    {-14.0489674, 20.1290073, 4.16538572},
-    {-14.1610088, 20.2713585, 4.44538021},
-    {-13.9427023, 19.9157219, 4.37536621},
-    {-13.9486017, 19.9869308, 4.51536179},
-    {-14.2555943, 20.0579357, 4.30537367},
-    {-13.9455662, 19.9868622, 4.16538477},
-    {-13.7360802, 20.1289406, 4.09538603},
-    {-13.7303228, 20.2709465, 4.23536873},
-    {-14.1376295, 19.9865208, 4.44534302},
-    {-14.3500462, 20.1288033, 4.5853405},
-    {-14.1434717, 20.1998768, 4.37535858},
-    {-14.7602501, 20.3419495, 4.23536634},
-    {-14.6569529, 20.1998024, 4.16537094},
-    {-14.0431061, 19.9867249, 4.23537302},
-    {-13.8336153, 20.1998711, 4.23536968},
-    {-13.8278246, 20.4129543, 4.23536253},
-    {-14.0343847, 20.3418808, 4.0253787},
-    {-13.8307037, 20.1998081, 4.025383},
-    {-14.1405411, 20.3419495, 4.44534683},
-    {-14.0430346, 20.1999454, 4.58534384},
-    {-14.143486, 20.3420181, 4.30536318},
-    {-13.6298857, 20.12887, 4.30536699},
-    {-14.0431061, 19.77351, 4.30536604},
-    {-13.9369307, 19.9155865, 4.58533907},
-    {-13.6357803, 20.2000809, 4.44536304},
-    {-13.9456758, 20.2711506, 4.16538572},
-    {-13.9427395, 20.2000122, 4.44536114},
-    {-14.0402088, 20.3420181, 4.515347},
-    {-14.2496948, 20.0577984, 4.65533972},
-    {-14.1434717, 20.1998768, 4.37535715},
-    {-13.7303562, 20.3420181, 4.30536366},
-    {-13.7274256, 20.413023, 4.37535429},
-    {-14.3441849, 20.128664, 4.09537315},
-    {-14.6598978, 20.1998768, 4.16537476},
-    {-14.0489292, 20.342226, 4.37537193},
-    {-14.0431061, 20.5553036, 4.30536747},
-    {-14.0372782, 20.2708778, 4.44534826},
-    {-14.0343513, 20.3418808, 4.2353611},
-    {-14.0460558, 20.4132271, 4.30537176},
-    {-14.1493521, 20.2000122, 4.37536621},
-    {-13.9398088, 19.9156551, 4.23537302},
-    {-14.0431061, 20.3420906, 4.51535082},
-    {-14.0431061, 20.2710171, 4.51535082},
-    {-14.1463976, 20.1999454, 4.51535082},
-    {-14.2467642, 20.1998768, 4.30536366},
-    {-14.2467356, 20.3420181, 4.30536556},
-    {-14.0401611, 20.4841633, 4.51534748},
-    {-13.8394289, 20.1289368, 4.23537683},
-    {-13.9456377, 20.0579357, 4.23538065},
-    {-13.9427214, 20.2710838, 4.30537081},
-    {-14.0489292, 20.2000809, 4.23538017},
-    {-13.8365126, 20.4842319, 4.09538412},
-    {-14.1464024, 20.2710171, 3.88540053},
-    {-14.5625486, 20.1289406, 4.30537176},
-    {-14.0460701, 20.2710838, 4.30537176},
-    {-13.6240959, 19.9865894, 4.16537142},
-    {-14.0401754, 20.0577297, 4.0953784},
-    {-14.0343657, 20.1286678, 4.23536062},
-    {-14.1405745, 20.2708817, 4.09537697},
-    {-14.3471155, 20.3419495, 4.23536539},
-    {-14.2467499, 20.1998711, 4.02538538},
-    {-13.3143053, 19.9865894, 3.95538783},
-    {-13.3113937, 19.9865208, 4.37534904},
-    {-13.7302666, 20.1998711, 4.16537428},
-    {-13.8335485, 20.1998711, 4.23536825},
-    {-14.4503927, 20.1287327, 4.30535984},
-    {-14.0518646, 20.1290741, 4.37537336},
-    {-14.0459986, 20.2710838, 4.37536621},
-    {-14.2497988, 20.2710152, 4.65534019},
-    {-14.1435909, 20.1288013, 4.51534748},
-    {-13.7303181, 20.2709465, 4.37535667},
-    {-13.4233637, 20.1999454, 4.37536192},
-    {-13.7390108, 20.0579357, 4.5153594},
-    {-13.833601, 20.1998711, 4.44535351},
-    {-13.9398088, 20.1999454, 4.23537302},
-    {-13.9398088, 19.8445854, 4.23537302},
-    {-14.2467499, 19.9155865, 4.30536413},
-    {-14.0489292, 20.2711544, 4.72534466},
-    {-13.951499, 20.0580673, 4.5853653},
-    {-14.5713787, 19.9869957, 4.51537037},
-    {-14.4563112, 19.9867249, 4.30536699},
-    {-14.2438564, 20.1287346, 4.37535334},
-    {-14.143486, 20.2709465, 4.09538031},
-    {-14.1434717, 19.9155865, 4.09538031},
-    {-14.2438192, 19.9155197, 4.23536491},
-    {-14.0459557, 20.200016, 4.51535559},
-    {-14.0431061, 20.2710152, 4.44535637},
-    {-14.1434526, 19.9866581, 4.4453516},
-    {-13.8365126, 20.1999454, 4.16537857},
-    {-13.8307228, 20.1287327, 4.65532875},
-    {-14.1405411, 19.9155197, 4.93530607},
-    {-14.0401611, 20.0577297, 4.515347},
-    {-14.3441849, 20.128664, 4.02537918},
-    {-13.7303038, 20.3420181, 4.30536366},
-    {-13.7332163, 19.9156551, 4.09538412},
-    {-14.3530102, 19.9867249, 4.30536652},
-    {-14.3442564, 20.3418789, 4.51533318},
-    {-14.5536709, 20.2708759, 4.30535984},
-    {-14.5536709, 20.2708778, 4.23536491},
-    {-14.3500128, 20.1288033, 4.30536413},
-    {-13.9398088, 20.3420849, 4.37536192},
-    {-14.0401421, 20.2709465, 4.30536222},
-    {-14.2468395, 19.9866619, 4.09537935},
-    {-14.4651556, 20.0580025, 4.30537987},
-    {-14.1465073, 20.3420849, 4.44535732},
-    {-14.0285044, 20.1285286, 4.02537203},
-    {-13.9281244, 20.1285973, 4.16536427},
-    {-14.1405554, 20.057663, 4.37535381},
-    {-14.0343466, 20.0575943, 4.51533699},
-    {-13.9281578, 20.0575256, 4.44533873},
-    {-14.547781, 20.199667, 4.37534475},
-    {-14.2321196, 20.2706032, 4.44532967},
-    {-13.7187243, 20.1995983, 3.95537925},
-    {-13.9281769, 20.0575275, 4.30535221},
-    {-13.9252415, 20.1995983, 4.44533682},
-    {-14.1347132, 20.6261005, 4.51533222},
-    {-14.243824, 20.4840908, 4.44534636},
-    {-14.3559027, 20.2710838, 4.02539349},
-    {-14.4562922, 20.3420849, 4.16537857},
-    {-13.9368973, 20.1288033, 4.30536366},
-    {-14.0343332, 20.1997356, 4.37534904},
-    {-14.3500462, 20.1998711, 4.23537016},
-    {-13.9397898, 19.9867249, 4.30536842},
-    {-13.7390251, 19.9157925, 4.58535576},
-    {-13.6299381, 19.9867249, 4.44535685},
-    {-13.7245092, 20.128664, 4.58533096},
-    {-14.2468395, 20.1998711, 4.44535017},
-    {-13.8277731, 20.2708111, 4.1653657},
-    {-13.6328354, 20.413229, 4.09538841},
-    {-13.7303371, 20.2709465, 4.23537016},
-    {-14.1493807, 20.2000122, 4.16538143},
-    {-14.0460367, 20.4843006, 4.02539253},
-    {-13.9398088, 20.4131584, 4.16537905},
-    {-13.6357145, 20.3422222, 4.44536495},
-    {-13.8365507, 20.1999454, 4.58534479},
-    {-13.9281769, 20.0575256, 4.44533634},
-    {-13.9252796, 20.1285286, 4.58532095},
-    {-13.7215643, 20.1285992, 4.30535126},
-    {-13.8248606, 20.199667, 4.16536379},
-    {-14.0372782, 20.3419495, 4.09537745},
-    {-13.9252415, 20.3417416, 4.16535902},
-    {-13.5179539, 20.128664, 4.16536713},
-    {-13.8336153, 20.1288033, 4.44535303},
-    {-13.9398088, 20.0577984, 4.51535082},
-    {-14.3559408, 20.1289406, 4.23537636},
-    {-14.046051, 20.2000122, 4.30537081},
-    {-14.4504118, 19.7733746, 4.44534779},
-    {-14.3471298, 19.7733746, 3.95538807},
-    {-14.2467642, 20.0577297, 4.09538031},
-    {-14.1434669, 20.3420219, 4.16537476},
-    {-14.2409115, 20.2708111, 4.58533001},
-    {-14.1317873, 20.1285305, 4.44533443},
-    {-14.0343142, 20.2708073, 4.58533144},
-    {-14.1405411, 20.3419495, 4.51534176},
-    {-14.3529911, 20.1288719, 4.37536192},
-    {-14.5595846, 19.7735119, 4.44535637},
-    {-14.6628809, 20.0577984, 4.58534622},
-    {-13.830718, 20.2708759, 4.30535841},
-    {-13.6212368, 20.128664, 4.30535507},
-    {-14.1347132, 20.199667, 4.30534983},
-    {-14.1346989, 20.2707405, 4.23535728},
-    {-14.2350645, 20.199604, 4.5853219},
-    {-14.2379951, 19.9153824, 4.51533222},
-    {-14.2438192, 19.9865894, 4.37535381},
-    {-14.1435242, 19.8445168, 4.23536968},
-    {-14.2409401, 19.8443832, 4.37535},
-    {-14.6599312, 20.1998768, 4.37535667},
-    {-13.7762308, 20.2352772, 4.20036364},
-    {-14.1434717, 20.3420181, 4.44535112},
-    {-13.9281769, 20.0575256, 4.44533873},
-    {-13.7245283, 20.0575943, 4.51533699},
-    {-13.7245092, 20.2708111, 4.37534904},
-    {-13.7302666, 19.9155865, 4.30536413},
-    {-13.2224798, 20.2000809, 4.5153594},
-    {-13.7848663, 20.2354813, 4.41035938},
-    {-14.3870335, 20.1284599, 4.20035362},
-    {-14.4002485, 20.128767, 4.51534319},
-    {-13.8219967, 20.199604, 4.37534142},
-    {-13.8306894, 20.1287346, 4.44534826},
-    {-14.5595894, 20.3420887, 4.20037508},
-    {-14.0431395, 20.12887, 4.37536097},
-    {-13.9310694, 20.128664, 4.30535507},
-    {-13.8219681, 20.4838848, 4.5853219},
-    {-13.4706593, 20.4485931, 4.51534414},
-    {-13.5266228, 20.1288719, 4.72533417},
-    {-13.6169662, 19.9153481, 4.20035982},
-    {-13.9368973, 19.9155865, 4.5853405},
-    {-13.8335819, 20.1288013, 4.37535763},
-    {-13.6299191, 20.1288719, 4.51535082},
-    {-13.7849426, 20.0222626, 4.20037508},
-    {-14.085988, 20.128664, 4.30535507},
-    {-14.7056637, 19.915451, 4.20036411},
-    {-13.457654, 20.2350693, 4.62031364},
-    {-14.1405554, 19.8444481, 4.58533669},
-    {-14.2409067, 20.128664, 4.72532034},
-    {-14.085988, 20.0220585, 4.62032795},
-    {-14.8561602, 20.2351685, 4.72531128},
-    {-14.1376295, 20.0575943, 4.37534857},
-    {-13.4706879, 19.7023373, 4.20037031},
-    {-13.4706879, 20.0221596, 4.41035223},
-    {-13.8306704, 19.9865894, 4.37535381},
-    {-14.3383093, 20.057457, 4.44533443},
-    {-14.5478001, 20.1996727, 4.23535728},
-    {-13.7761555, 20.0220585, 4.30535507},
-    {-13.9441795, 20.1289711, 4.51535845},
-    {-14.2409067, 19.8088436, 3.99038243},
-    {-14.3441849, 20.128664, 4.30535507},
-    {-14.2379761, 20.1996727, 4.30535126},
-    {-14.0255785, 20.0573902, 4.23535013},
-    {-14.0373487, 20.057663, 4.37535381},
-    {-14.0401754, 19.8445168, 4.51534796},
-    {-13.6183386, 19.9864521, 4.3053503},
-    {-14.2380142, 20.199667, 4.37534475},
-    {-14.2438383, 20.2708759, 4.23536444},
-    {-14.0431061, 20.0577984, 4.30536747},
-    {-14.3412018, 20.0575256, 4.30535173},
-    {-14.2321196, 19.9863205, 4.30534267},
-    {-14.0344038, 20.128664, 4.58533144},
-    {-13.8336535, 19.8445168, 4.37535763},
-    {-13.9339809, 20.1287327, 4.37535286},
-    {-13.9311409, 20.1286678, 4.30535555},
-    {-13.5121641, 20.1285305, 4.09536695},
-    {-13.8336344, 20.2709465, 4.515347},
-    {-13.8277731, 20.2708111, 4.44534349},
-    {-14.3442039, 20.2708111, 4.1653657},
-    {-14.0372639, 20.2708778, 4.37535381},
-    {-14.2409067, 20.2708111, 4.30535507},
-    {-14.0343466, 19.915451, 3.95538521},
-    {-13.830718, 20.1287346, 4.025383},
-    {-13.5179539, 20.2708073, 4.2353611},
-    {-13.7186527, 20.6260262, 4.23535299},
-    {-14.1200733, 20.4125366, 4.30533075},
-    {-13.8248796, 20.199667, 4.30535126},
-    {-14.0255928, 20.4838181, 4.3053422},
-    {-14.2321196, 20.1995354, 4.09536266},
-    {-13.715807, 20.2706051, 4.09536266},
-    {-13.8219872, 20.1995983, 4.16535997},
-    {-14.1288376, 20.1284599, 4.37533617},
-    {-14.1317682, 20.4838848, 4.23535299},
-    {-14.0255594, 20.0573921, 4.2353487},
-    {-14.4444847, 19.8443146, 4.51533222},
-    {-13.7274256, 19.9865894, 4.02538347},
-    {-13.7245092, 20.0575943, 4.09537315},
-    {-13.7274399, 20.2708778, 4.51534176},
-    {-13.830718, 20.3419495, 4.51534176},
-    {-14.0372782, 20.413023, 4.44534779},
-    {-13.9368973, 20.3420219, 4.30536318},
-    {-13.830718, 20.1998024, 4.23536491},
-    {-13.8277922, 20.4840221, 4.30535507},
-    {-14.2409067, 20.128664, 4.37534904},
-    {-14.6481323, 20.057457, 4.51532698},
-    {-14.4415722, 19.9863853, 4.445333},
-    {-14.3471298, 20.2708778, 4.37535286},
-    {-14.0343466, 20.3418808, 4.30535507},
-    {-13.715826, 20.0573921, 4.23534966},
-    {-13.8191233, 20.1995354, 4.16535616},
-    {-14.1318016, 20.1995983, 4.09536648},
-    {-13.9339523, 20.057663, 4.37535524},
-    {-13.9339619, 20.1998024, 4.44534922},
-    {-13.8306513, 20.1998024, 4.16536903},
-    {-13.7302666, 20.3420143, 4.2353673},
-    {-13.7245092, 20.4129486, 4.37534904},
-    {-13.5237484, 20.1998711, 4.30536413},
-    {-13.7303038, 19.9866543, 4.37535858},
-    {-13.2081165, 20.0575943, 4.16536713},
-    {-14.2438564, 20.1287327, 4.09537649},
-    {-14.4474106, 20.1997395, 4.37534904},
-    {-14.0313549, 20.1285992, 4.4453392},
-    {-13.9310026, 20.1997395, 4.37534857},
-    {-13.5178823, 20.4129543, 4.09537268},
-    {-14.1347132, 20.2707405, 4.16536331},
-    {-14.3471298, 20.1998081, 4.44534779},
-    {-14.0373487, 20.2708778, 4.44534588},
-    {-13.6183577, 20.1285973, 4.3753438},
-    {-13.7216167, 20.199667, 4.37534523},
-    {-14.3500462, 20.1998711, 4.30536222},
-    {-14.4445362, 19.9864521, 4.09536886},
-    {-14.0314207, 20.1285992, 4.30535126},
-    {-14.4475002, 19.915451, 4.37534857},
-    {-14.0314398, 20.0575256, 4.16536331},
-    {-13.8307037, 19.9865894, 4.23536587},
-    {-14.3500462, 20.1288013, 4.02538729},
-    {-14.0401611, 19.9866581, 4.09538126},
-    {-13.7274256, 20.1287327, 4.51534128},
-    {-13.934, 20.2708759, 4.72532415},
-    {-14.4503927, 20.1998081, 4.58533621},
-    {-14.0285234, 20.4128132, 4.44533491},
-    {-13.7129002, 20.0573215, 4.51531935},
-    {-14.6511631, 19.9153843, 4.3053503},
-    {-14.5566206, 19.9866581, 4.3053627},
-    {-14.3441849, 19.915451, 4.09537315},
-    {-14.0285091, 19.9863853, 4.16535854},
-    {-14.7513771, 20.057457, 4.44533539},
-    {-13.9310694, 20.128664, 4.72531891},
-    {-13.7215977, 20.2707405, 4.02537632},
-    {-13.7303371, 20.2709465, 4.02538681},
-    {-14.2437859, 19.9865971, 4.23536491},
-    {-14.3324671, 20.0573235, 4.16535187},
-    {-13.9253836, 20.2706718, 4.30534697},
-    {-14.2379761, 20.2707405, 4.51533365},
-    {-14.1464357, 20.2710152, 4.37535906},
-    {-13.8336868, 20.0577297, 4.2353673},
-    {-14.1317539, 19.9153137, 4.65531492},
-    {-14.3353834, 20.1284618, 4.58531666},
-    {-13.7158117, 20.1995354, 4.09536266},
-    {-13.9281769, 20.1285973, 4.23535776},
-    {-14.3412733, 20.1285973, 4.37534523},
-    {-13.9281578, 20.199667, 4.44533873},
-    {-13.9339666, 19.9155197, 4.44534779},
-    {-14.1376295, 20.1997356, 4.51533699},
-    {-14.544836, 20.057457, 4.44533491},
-    {-14.5448551, 20.057457, 4.16535997},
-    {-14.0343332, 19.8443794, 4.09537172},
-    {-13.7274065, 20.057663, 4.09537601},
-    {-14.2379761, 20.1285973, 4.4453392},
-    {-14.1346846, 19.7021675, 4.58532572},
-    {-14.0314016, 20.0575275, 4.72531414},
-    {-13.8277922, 19.915451, 4.51533699},
-    {-14.0372448, 20.1998081, 4.58533573},
-    {-13.7216167, 19.9864521, 4.51533318},
-    {-13.9281435, 20.0575256, 4.44533873},
-    {-13.9311695, 20.0575943, 4.37535},
-    {-14.6569672, 20.1287327, 4.30535984},
-    {-14.1405554, 20.1287327, 4.16537094},
-    {-13.934, 20.1287327, 4.30535889},
-    {-14.1288424, 20.0573902, 4.23534918},
-    {-14.0255928, 20.1995354, 4.23534966},
-    {-14.2379951, 20.4839554, 4.09537029},
-    {-13.6183529, 20.2707424, 4.37534475},
-    {-14.0314589, 20.0575275, 4.30535126},
-    {-14.6451683, 19.9863205, 4.23534966},
-    {-14.2321196, 20.1284618, 4.23534966},
-    {-14.3353834, 19.9863205, 4.44532967},
-    {-14.3412733, 20.1285992, 4.58532572},
-    {-14.1347132, 20.0575256, 4.30535173},
-    {-14.2321196, 20.1995354, 4.09536266},
-    {-14.0227003, 20.3416061, 4.4453249},
-    {-14.2321529, 20.1284618, 4.65531015},
-    {-14.2408934, 20.1997395, 4.51533461},
-    {-14.4386463, 20.1284599, 4.58531666},
-    {-14.4415913, 19.9153137, 4.44533348},
-    {-14.4327517, 20.1993942, 4.65530109},
-    {-14.2379103, 19.9864521, 4.44533873},
-    {-13.9310694, 20.0575943, 4.58533096},
-    {-14.146265, 20.1999397, 4.65533876},
-    {-14.1318064, 20.0574608, 4.51532841},
-    {-13.6125488, 19.8441772, 4.23534966},
-    {-13.9164915, 19.9151115, 4.30533552},
-    {-13.9164915, 20.2704678, 4.09535503},
-    {-13.9252462, 19.9863853, 4.44533491},
-    {-13.8248606, 19.9153824, 4.65532017},
-    {-14.0343466, 19.9865208, 4.37534904},
-    {-14.6480999, 20.1995983, 4.51532745},
-    {-14.4386415, 20.1284618, 4.44532967},
-    {-14.1288567, 20.1284618, 4.16535473},
-    {-14.3324528, 20.1283951, 4.51531839},
-    {-14.1288614, 20.3416748, 4.58531666},
-    {-14.3324337, 20.1283913, 4.58531189},
-    {-14.2350311, 20.2706738, 4.23535347},
-    {-13.8219872, 20.3417416, 4.23535347},
-    {-14.0285044, 20.199604, 4.30534697},
-    {-14.0285044, 20.0574608, 4.23535347},
-    {-13.6125488, 19.9152489, 4.44532967},
-    {-14.1258926, 20.1994629, 4.37533236},
-    {-13.9252129, 20.1285286, 4.58532047},
-    {-14.1230278, 19.9861851, 4.58530807},
-    {-14.1288424, 20.1284599, 4.09536314},
-    {-14.0314207, 19.9864578, 4.02537537},
-    {-13.7273922, 20.1998081, 4.23536301},
-    {-13.5121641, 20.199604, 4.23535156},
-    {-14.0227194, 20.2705345, 4.3753314},
-    {-13.8190708, 20.1995354, 4.51532316},
-    {-13.8190708, 20.2706051, 4.23534966},
-    {-14.5419054, 20.1995296, 4.23534966},
-    {-14.536025, 19.9151096, 4.5153141},
-    {-13.494936, 19.772768, 4.09534502},
-    {-14.0256643, 20.1995296, 4.23534918},
-    {-14.1288614, 20.3416748, 4.30534315},
-    {-14.1347322, 20.2707424, 4.09536982},
-    {-14.2409067, 20.128664, 4.37534904},
-    {-14.0284901, 20.1285286, 4.30534792},
-    {-13.6125488, 20.1284618, 4.16535616},
-    {-14.1288567, 20.1995354, 4.51532316},
-    {-14.3353834, 19.9863205, 4.23534966},
-    {-13.6067581, 19.9861794, 4.30533314},
-    {-13.9077425, 20.3413296, 4.44530821},
-    {-14.1229286, 20.1283245, 4.2353425},
-    {-14.0256119, 20.1995296, 4.37533617},
-    {-14.1405792, 20.057663, 4.30535889},
-    {-13.8161592, 20.1994629, 4.16535139},
-    {-13.7129335, 20.1283913, 3.95537233},
-    {-13.7100363, 20.2704678, 4.16534853},
-    {-14.1346512, 20.1996727, 4.30535126},
-    {-14.1317539, 20.199604, 4.58532238},
-    {-13.9310884, 20.2708111, 4.30535555},
-    {-14.2350121, 20.4128132, 4.37533903},
-    {-14.3353834, 19.8441772, 4.37533617},
-    {-14.5536947, 20.057663, 4.02538347},
-    {-13.9281578, 20.3418102, 4.16536427},
-    {-13.9194746, 20.3416061, 4.02536726},
-    {-13.9136515, 20.0571842, 4.30533266},
-    {-14.3324718, 20.4126759, 4.51531887},
-    {-14.0226812, 19.9151783, 4.30533838},
-    {-13.9194221, 20.1283951, 4.16535282},
-    {-13.7100029, 20.1993942, 4.30533552},
-    {-14.2262249, 20.0572548, 4.37532711},
-    {-14.0138941, 20.1992569, 4.30532598},
-    {-13.6067772, 20.2704678, 4.02536249},
-    {-14.1318064, 20.1285286, 4.02537203},
-    {-13.9252796, 19.9863853, 4.30534601},
-    {-13.9194221, 20.0573215, 4.58531189},
-    {-13.8248796, 20.0575256, 4.37534428},
-    {-14.0343466, 20.0575943, 4.16536713},
-    {-14.0284948, 20.057457, 4.09536695},
-    {-14.1259966, 20.1283951, 4.09536219},
-    {-13.6009684, 20.0571194, 4.09534931},
-    {-14.4358158, 19.9151783, 4.16535091},
-    {-14.3324528, 19.9862537, 4.23534632},
-    {-13.8190708, 20.1284618, 4.58531666},
-    {-13.7128763, 20.1994629, 4.44532537},
-    {-13.9223347, 19.9152451, 4.51532364},
-    {-13.7216358, 20.1996727, 4.23535728},
-    {-14.1317682, 20.412817, 4.44533396},
-    {-13.9281578, 20.199667, 4.4453392},
-    {-13.8219681, 20.2706718, 4.02537584},
-    {-13.8103504, 20.0571842, 3.88537312},
-    {-14.0197554, 19.9151115, 4.44532156},
-    {-14.0226336, 20.1994629, 4.44532394},
-    {-13.5121832, 20.1285305, 3.95537925},
-    {-13.8219681, 20.199604, 4.16536045},
-    {-13.9310694, 20.2708073, 4.30535507},
-    {-13.8190899, 20.1284599, 4.02537012},
-    {-14.0197172, 19.9861851, 4.5853076},
-    {-14.3295269, 20.1993942, 4.44532061},
-    {-13.8277063, 19.9865208, 4.3053565},
-    {-13.9281244, 19.9153824, 4.09537029},
-    {-13.8248425, 20.1285973, 4.23535776},
-    {-14.3324528, 20.1283913, 4.30533791},
-    {-13.7215023, 20.0575256, 4.30534935},
-    {-14.0314207, 20.2707405, 4.44533873},
-    {-14.3412399, 19.9864521, 4.51533222},
-    {-14.2350502, 20.1285305, 4.44533396},
-    {-13.9281578, 20.199667, 4.37534523},
-    {-14.1346989, 19.7732391, 4.58532619},
-    {-14.6481323, 19.844244, 4.37534094},
-    {-13.9193897, 20.0573235, 4.23534536},
-    {-14.0285234, 19.9863853, 4.30534649},
-    {-14.2292223, 19.9862537, 4.1653533},
-    {-14.3383093, 20.2706738, 4.30534697},
-    {-13.9223347, 19.8441772, 4.30534315},
-    {-14.4415722, 20.057457, 4.23535347},
-    {-14.3412209, 20.1285973, 4.16536379},
-    {-14.1376295, 19.9865208, 4.37534904},
-    {-14.3441849, 20.128664, 4.44534302},
-    {-14.2350645, 20.1285286, 4.72530937},
-    {-14.3383141, 20.2706738, 4.23535299},
-    {-14.2409067, 20.1286678, 4.02538013},
-    {-14.8545885, 20.0574608, 4.16535997},
-    {-14.1287851, 19.9863205, 4.30534363},
-    {-14.0284853, 20.4838848, 4.16536188},
-    {-14.1317205, 20.3417454, 4.09536839},
-    {-13.6269884, 20.1288033, 4.16537476},
-    {-14.2321196, 19.8441753, 4.09536266},
-    {-13.9310884, 19.7022381, 4.23536301},
-    {-13.9253502, 19.9863853, 4.51532936},
-    {-14.1288567, 19.8441772, 4.65531015},
-    {-14.0343513, 20.1286678, 4.44534159},
-    {-13.8277922, 19.915453, 4.1653676},
-    {-14.2320671, 20.1995354, 4.37533712},
-    {-14.4385757, 20.1284618, 4.09536171},
-    {-14.1317539, 20.4128132, 4.30534744},
-    {-14.1346798, 20.2707405, 4.58532715},
-    {-14.0343142, 20.128664, 4.37535},
-    {-14.2379103, 20.4128799, 3.95538378},
-    {-14.851696, 20.5548878, 4.16535616},
-    {-14.2379761, 20.3418102, 4.30535316},
-    {-14.0255451, 20.1995296, 4.02536917},
-    {-13.9281578, 20.1996727, 4.37534475},
-    {-14.0343466, 20.128664, 4.37534904},
-    {-14.4444981, 20.0575256, 4.16536283},
-    {-14.5536709, 20.3419495, 4.51534224},
-    {-14.3441849, 20.4129543, 4.51533842},
-    {-14.2350693, 19.9863853, 4.72530842},
-    {-13.5092897, 19.7731075, 4.44532967},
-    {-13.618372, 19.7732391, 4.16536379},
-    {-13.715807, 20.1284599, 4.16535664},
-    {-14.6511154, 19.9153824, 4.23535776},
-    {-14.5390596, 20.1283913, 4.16535282},
-    {-14.0904102, 20.4485931, 4.09537792},
-    {-13.9252319, 20.1285286, 4.30534697},
-    {-13.9194031, 20.1283951, 4.30533886},
-    {-14.016839, 20.3414688, 4.44531631},
-    {-14.085988, 20.128664, 4.09537315},
-    {-14.6480999, 20.4128094, 4.23535299},
-    {-14.2365131, 20.2351723, 4.3053484},
-    {-14.4415913, 20.412817, 4.30534697},
-    {-14.4445362, 20.3418102, 4.23535872},
-    {-13.9266758, 20.2351685, 4.3053484},
-    {-14.0816469, 20.3417759, 3.9903779},
-    {-13.76752, 20.2350674, 3.67540026},
-    {-14.3412018, 20.0575256, 4.30535126},
-    {-14.2278023, 20.0217533, 4.30533695},
-    {-14.550745, 20.128664, 4.51533699},
-    {-14.7100859, 20.2353764, 3.78040338},
-    {-13.4706593, 20.2353764, 4.30536222},
-    {-13.621232, 20.4484901, 4.30535555},
-    {-13.9222822, 20.2350674, 4.41033411},
-    {-14.3383474, 20.1285286, 4.44533443},
-    {-13.6168613, 20.3417778, 4.30534887},
-    {-13.9281912, 20.0575256, 4.37534666},
-    {-13.7187386, 20.199604, 4.37534094},
-    {-14.4533567, 20.3420181, 4.3053627},
-    {-13.7805729, 20.1287689, 4.20036936},
-    {-13.928196, 20.0575256, 4.44533873},
-    {-13.8307419, 20.1998081, 4.30535889},
-    {-14.0314541, 20.3418121, 4.3753438},
-    {-13.9310694, 20.1997356, 4.30535507},
-    {-13.7245092, 19.915451, 4.44534302},
-    {-13.8219681, 19.9153137, 4.37534094},
-    {-14.0343332, 20.2708111, 3.8853898},
-    {-14.0343466, 20.2708111, 3.88539004},
-    {-14.0285044, 20.2706738, 4.23535299},
-    {-14.341259, 20.1996727, 4.37534571},
-    {-14.0284901, 19.844244, 4.23535442},
-    {-14.0255928, 19.9152489, 4.37533617},
-    {-14.3412781, 20.0575256, 4.44533873},
-    {-14.2379475, 20.3418102, 4.37534714},
-    {-13.1020317, 20.0575275, 4.30535316},
-    {-13.8220015, 20.1995983, 4.37534046},
-    {-13.8249321, 20.0575256, 4.44533873},
-    {-13.5179539, 20.128664, 4.58533096},
-    {-13.7186909, 20.199604, 4.23535442},
-    {-13.8161783, 19.9151802, 4.16535282},
-    {-13.9223347, 20.4838181, 4.37533617},
-    {-14.1288567, 20.5548878, 4.37533617},
-    {-14.2379618, 20.2707405, 4.37534428},
-    {-14.237957, 19.9864521, 4.30535173},
-    {-14.2379475, 19.8443127, 4.30535221},
-    {-13.7215643, 20.0575256, 4.51533365},
-    {-14.0284567, 20.2706738, 4.30534792},
-    {-14.1288567, 20.0573921, 4.37533617},
-    {-14.4386415, 20.1995354, 4.51532316},
-    {-14.2291889, 20.1994629, 4.51531839},
-    {-14.3295078, 20.4126072, 4.44532061},
-    {-14.0255976, 20.5548878, 4.51532316},
-    {-13.8191042, 19.9863167, 4.44532967},
-    {-13.7187519, 20.0574608, 4.23535299},
-    {-14.1259069, 20.1994629, 4.7952919},
-    {-14.0226669, 20.1994629, 4.65530396},
-    {-14.125926, 20.2705345, 4.4453249},
-    {-13.5064068, 20.412674, 4.58531189},
-    {-13.7129622, 20.1994629, 4.4453249},
-    {-14.2409782, 20.2708111, 4.23536062},
-    {-14.1347895, 20.2707424, 4.44533682},
-    {-13.7100601, 20.3415375, 4.37532902},
-    {-13.5064783, 20.2705383, 4.09535933},
-    {-13.8190708, 20.1995354, 4.09536266},
-    {-14.4357347, 20.2705345, 4.37533188},
-    {-13.6154413, 20.1995983, 4.51532841},
-    {-13.19664, 20.1283913, 4.23534632},
-    {-14.0226526, 20.1994629, 4.51531935},
-    {-13.9194221, 20.5548172, 4.51531792},
-    {-13.8190708, 20.1995354, 4.30534267},
-    {-13.3973722, 20.1993256, 4.23533773},
-    {-14.0227194, 20.2705345, 4.23534536},
-    {-14.2321196, 20.2706051, 4.44532967},
-    {-14.5478716, 20.2707424, 4.44533825},
-    {-14.335516, 20.1284618, 4.30534267},
-    {-13.5092516, 20.4127445, 4.37533617},
-    {-14.0314398, 20.0575256, 4.37534475},
-    {-14.2320862, 19.9152451, 4.16535568},
-    {-14.2291698, 19.8441105, 4.09535933},
-    {-13.6096182, 20.1283913, 4.30534077},
-    {-13.9222775, 20.0573902, 4.44533157},
-    {-13.9223347, 20.0573921, 4.23534966},
-    {-13.8161783, 20.1994667, 4.44532537},
-    {-14.2321196, 20.5548878, 4.51532316},
-    {-14.1230707, 20.1283245, 4.09535551},
-    {-13.8161783, 20.0573215, 4.23534584},
-    {-13.9223156, 20.2706032, 4.44532871},
-    {-14.2350836, 20.3417416, 4.58532095},
-    {-14.4445744, 20.199667, 4.30535126},
-    {-14.1347322, 20.1285973, 4.30535126},
-    {-14.1346989, 20.3418102, 4.37534523},
-    {-14.0227528, 20.1994629, 4.30533838},
-    {-14.3353977, 19.9863167, 4.09536123},
-    {-14.016839, 19.7729034, 4.23533773},
-    {-13.9164915, 20.3415375, 4.09535456},
-    {-14.1230001, 20.1993942, 4.30533457},
-    {-13.715807, 20.1284618, 4.09536266},
-    {-13.6096182, 20.0573235, 4.30533838},
-    {-14.0226669, 20.0573235, 4.58531189},
-    {-13.922349, 19.9152489, 4.23535061},
-    {-14.0255737, 20.1284599, 4.30534267},
-    {-14.2262726, 20.2704678, 4.58530807},
-    {-13.7129145, 19.9151802, 4.58531332},
-    {-13.9194031, 19.9862537, 4.51531887},
-    {-13.7128954, 20.0573215, 4.37533188},
-    {-14.1289082, 20.3416748, 4.37533665},
-    {-14.5301542, 20.1281891, 4.30532646},
-    {-14.7395401, 20.1282578, 4.16534424},
-    {-14.1200829, 19.9861164, 4.02535915},
-    {-14.019784, 20.0572529, 4.16534901},
-    {-13.9252415, 20.1285305, 4.44533443},
-    {-13.8190708, 20.1284618, 4.23534966},
-    {-13.7158117, 20.1995354, 4.37533617},
-    {-13.9252462, 20.057457, 4.23535252},
-    {-14.2291889, 20.0573215, 4.51531887},
-    {-13.8190708, 19.8441772, 4.30534315},
-    {-13.7129145, 19.9862537, 4.23534489},
-    {-14.0255451, 19.9863167, 4.09536219},
-    {-13.9339666, 20.1287346, 4.37535238},
-    {-14.0255928, 20.3416767, 4.51532316},
-    {-13.8190708, 20.1995296, 4.65531015},
-    {-14.1347179, 20.1285973, 4.44533968},
-    {-14.0431776, 20.0578003, 4.58534431},
-    {-14.2350502, 20.2706738, 4.51532793},
-    {-14.1200829, 20.4836121, 4.72528887},
-    {-13.8074236, 19.9860439, 4.51530457},
-    {-13.8132477, 19.9151115, 4.37532806},
-    {-13.9194031, 20.0573235, 4.23534536},
-    {-14.0197363, 19.9151115, 4.2353425},
-    {-13.8104019, 20.1282558, 4.23533869},
-    {-14.3294888, 20.1283245, 4.37532806},
-    {-14.0138988, 20.2703304, 4.4453125},
-    {-14.0167913, 20.1282578, 4.44531727},
-    {-14.0197363, 20.2704678, 4.44532156},
-    {-13.9135942, 20.5546761, 4.44531631},
-    {-13.8161736, 20.2705307, 4.44532585},
-    {-14.3265724, 20.3414669, 4.37532377},
-    {-14.1229811, 19.9861794, 4.51531458},
-    {-14.0197554, 20.1993942, 4.51531315},
-    {-14.4475002, 20.1997356, 4.37535095},
-    {-14.5389795, 20.2705345, 4.44532776},
-    {-14.4298162, 20.2703991, 4.58530235},
-    {-13.9165106, 20.0572548, 4.37532806},
-    {-14.2203875, 19.9860477, 4.51530457},
-    {-13.807457, 20.1281872, 4.44531202},
-    {-13.7071056, 20.2703934, 4.51530981},
-    {-14.4327183, 20.0572529, 4.51531363},
-    {-13.9135942, 19.9150429, 4.65529537},
-    {-13.7041798, 20.1281872, 4.51530504},
-    {-14.2174759, 20.1281185, 4.58529282},
-    {-13.9107018, 19.9149761, 4.72528315},
-    {-14.1230278, 20.1283245, 4.65530062},
-    {-14.1259451, 20.4837494, 4.51531935},
-    {-14.5330324, 20.3414688, 4.51530886},
-    {-14.530097, 19.9860477, 4.58529758},
-    {-14.016839, 20.1282558, 4.37532377},
-    {-13.6067209, 19.9151115, 4.44532108},
-    {-14.2203827, 19.9860477, 4.44531202},
-    {-14.016839, 20.1993256, 4.16534472},
-    {-14.1142502, 19.8438396, 4.16533756},
-    {-13.710041, 20.0572548, 4.44532156},
-    {-14.2262297, 19.9151115, 4.44532061},
-    {-13.7012682, 20.2702618, 4.58529234},
-    {-13.7071056, 20.1993256, 4.44531631},
-    {-13.7041798, 19.8439083, 4.51530504},
-    {-14.226263, 19.9861851, 4.44531918},
-    {-15.0434027, 20.1281185, 4.37531757},
-    {-14.6392078, 20.0572529, 4.16534805},
-    {-14.1229811, 20.2704678, 4.16534805},
-    {-13.9136324, 19.9150429, 4.23533821},
-    {-14.3265438, 20.0571842, 4.44531584},
-    {-14.1200552, 20.4836082, 4.72528791},
-    {-14.1200361, 20.057188, 4.44531727},
-    {-14.2203636, 19.9860439, 4.37531948},
-    {-13.9135942, 20.0571842, 4.65529585},
-    {-14.0139275, 20.2703304, 4.4453125},
-    {-14.1201401, 20.2703991, 4.37532377},
-    {-14.3295412, 20.1283245, 4.30533457},
-    {-14.0197554, 20.2704678, 4.37532806},
-    {-13.8161402, 20.1283951, 4.4453249},
-    {-13.60674, 20.1993942, 4.58530617},
-    {-14.016839, 20.1282558, 4.65529537},
-    {-14.2262535, 19.9861851, 4.58530712},
-    {-13.9106827, 20.199255, 4.65529108},
-    {-13.7071056, 20.3414688, 4.44531679},
-    {-13.403162, 20.4126759, 4.58531189},
-    {-13.6009493, 20.1281891, 4.37532043},
-    {-13.8103504, 20.1993256, 4.44531631},
-    {-14.1259451, 19.986248, 4.37533283},
-    {-13.807457, 20.1281872, 4.23533297},
-    {-13.7042131, 19.9860477, 4.4453125},
-    {-13.6038609, 20.1282558, 4.65529537},
-    {-13.9223528, 20.4127445, 4.44532967},
-    {-13.9194031, 20.3416061, 4.44532633},
-    {-13.9106684, 20.4124699, 4.4453125},
-    {-13.600935, 20.2703304, 4.37531996},
-    {-13.8133135, 19.9861794, 4.44532156},
-    {-14.0139132, 20.2703304, 4.37531948},
-    {-14.1171103, 20.4835396, 4.44531155},
-    {-14.019722, 20.1993942, 4.72529364},
-    {-14.0226622, 20.1283913, 4.51531982},
-    {-14.016839, 19.9861126, 4.23533773},
-    {-13.60674, 20.2704678, 4.30533552},
-    {-13.9165392, 20.3415356, 4.5853076},
-    {-14.0226669, 20.0573235, 4.65530682},
-    {-14.1171188, 20.2703304, 4.23533392},
-    {-13.8103685, 20.5546818, 4.58530331},
-    {-14.0110197, 20.2702579, 4.44530773},
-    {-13.4947834, 20.1281223, 4.58529377},
-    {-14.0081463, 20.1280499, 4.44530296},
-    {-13.8074379, 20.1281872, 4.65529108},
-    {-13.9107018, 20.1992569, 4.51530552},
-    {-13.9077759, 20.4124012, 4.58529234},
-    {-14.1171761, 20.2703304, 4.58529568},
-    {-13.9165106, 20.1283264, 4.4453187},
-    {-13.6096706, 20.5548191, 4.30533886},
-    {-13.9076948, 20.5545444, 4.37531519},
-    {-13.7071629, 20.1993256, 4.23533869},
-    {-14.016839, 20.3414669, 4.23533773},
-    {-13.8074236, 20.3413982, 4.51530552},
-    {-14.2204018, 20.1281872, 4.4453125},
-    {-13.8045502, 19.8438396, 4.37531471},
-    {-13.7013197, 20.0570507, 4.5152998},
-    {-14.3206825, 19.985981, 4.2353301},
-    {-13.8045311, 19.985981, 4.37531567},
-    {-13.90485, 20.1280499, 4.72527266},
-    {-14.2233276, 20.1282558, 4.58530235},
-    {-14.1171761, 20.0571194, 4.58529758},
-    {-14.1171713, 20.1992569, 4.58529758},
-    {-13.8103504, 20.0571842, 4.44531631},
-    {-14.9430513, 20.1992569, 4.37531948},
-    {-14.7365618, 20.1281872, 4.51530552},
-    {-14.8427944, 20.1282558, 4.44531631},
-    {-14.0197554, 20.270462, 4.23534203},
-    {-13.8045692, 19.8438396, 4.58529091},
-    {-13.9077759, 19.7017002, 4.51529932},
-    {-13.7071056, 19.9150429, 4.44531631},
-    {-14.1200876, 20.1282558, 4.44531727},
-    {-14.2262535, 20.1993942, 4.44532156},
-    {-14.2203827, 19.9860439, 4.58529806},
-    {-14.0109682, 19.985981, 4.51530027},
-    {-13.8103504, 20.1282558, 4.44531679},
-    {-14.4298162, 20.2703991, 4.16534472},
-    {-14.3236609, 19.9860477, 4.30532646},
-    {-14.533061, 20.0571842, 4.23533773},
-    {-14.4327898, 20.1283245, 4.23534393},
-    {-14.7484322, 20.1284599, 4.51532316},
-    {-14.424036, 19.985981, 4.30532408},
-    {-14.633379, 20.1281872, 4.2353344},
-    {-14.6363058, 19.9150429, 4.37532377},
-    {-13.9165106, 19.9151115, 4.30533457},
-    {-14.1287899, 20.1284599, 4.02536964},
-    {-14.0255451, 19.9152489, 4.30534267},
-    {-14.3265724, 19.9861164, 4.37532377},
-    {-14.2174759, 20.2702579, 4.30532312},
-    {-14.4239645, 20.199194, 4.37531757},
-    {-14.3148298, 20.0569153, 4.16533136},
-    {-14.4180555, 19.9147758, 4.09533787},
-    {-14.4269047, 19.7728367, 4.37531948},
-    {-14.633379, 19.9149761, 4.4453125},
-    {-14.6363058, 19.7729034, 4.44531631},
-    {-14.848732, 19.7019653, 4.65530539},
-    {-14.0197744, 19.8440418, 4.65530252},
-    {-14.0197363, 19.7019024, 4.86528015},
-    {-14.3324528, 19.6308956, 4.51531887},
-    {-15.2647352, 20.0573902, 4.37533617},
-    {-14.5331182, 19.8439732, 4.37532234},
-    {-14.3324337, 19.7730389, 4.65530491},
-    {-14.226263, 19.8440418, 4.65530109},
-    {-14.6392689, 19.9151115, 4.37532806},
-    {-14.7366428, 19.8439083, 4.58529758},
-    {-14.630434, 19.772768, 4.51530123},
-    {-14.8368759, 19.7016983, 4.44530821},
-    {-14.2204399, 19.8439045, 4.58529758},
-    {-14.5271902, 19.8438396, 4.58529282},
-    {-14.934145, 19.4883575, 4.58528233},
-    {-14.8338642, 19.9148464, 4.7252717},
-    {-14.7306862, 19.9148445, 4.3753109},
-    {-14.9431028, 19.6306934, 4.37531996},
-    {-14.7366524, 19.6306934, 4.65529013},
-    {-14.83395, 19.4884186, 4.30531693},
-    {-15.0463095, 19.701767, 4.23533297},
-    {-14.8368807, 19.772768, 4.51530075},
-    {-14.630434, 19.8438377, 4.23532963},
-    {-14.5212717, 19.4883575, 4.30531454},
-    {-14.7306862, 19.5594883, 4.16533375},
-    {-14.6304064, 19.772768, 4.09534502},
-    {-14.7366142, 19.9860477, 4.02535391},
-    {-14.2291698, 19.8441105, 3.95537233},
-    {-14.533061, 19.8439732, 4.16534472},
-    {-14.3236322, 19.9149761, 4.09534883},
-    {-14.4298067, 19.9150429, 4.0953536},
-    {-14.4327517, 19.8440399, 4.2353425},
-    {-14.5301065, 20.0571194, 3.815377},
-    {-14.1141739, 19.772768, 3.74538207},
-    {-14.6790686, 19.9148407, 4.09534121},
-    {-14.2203636, 19.701767, 4.02535534},
-    {-14.2204018, 19.9860439, 4.02535582},
-    {-14.6273899, 20.270195, 4.16533375},
-    {-15.0432606, 19.985981, 4.44530869},
-    {-14.4298162, 19.8439732, 4.30533075},
-    {-14.9932194, 19.8083363, 3.99035788},
-    {-14.6363058, 19.9861164, 4.0953517},
-    {-14.4298162, 20.0571842, 4.23533773},
-    {-14.6363058, 19.8439732, 3.88537288},
-    {-14.5241833, 19.9148407, 3.99035192},
-    {-14.4268808, 19.7728348, 3.81537747},
-    {-14.3177748, 19.9148388, 3.81537151},
-    {-14.3737812, 20.1281528, 3.88536763},
-    {-14.8472738, 20.0217533, 3.57040787},
-    {-15.1465616, 19.7727718, 3.95535684},
-    {-14.5330515, 19.8439732, 4.23533821},
-    {-14.0168772, 19.9150429, 4.30533218},
-    {-14.1142693, 19.9149075, 3.88536906},
-    {-14.683486, 19.9149437, 3.8853693},
-    {-13.4490757, 19.7018318, 3.88537145},
-    {-14.3781986, 19.4886208, 3.99036241},
-    {-14.4268808, 19.5596237, 3.81537747},
-    {-14.3236647, 19.9149761, 3.74538445},
-    {-14.3738098, 20.1281528, 3.78037906},
-    {-14.21455, 19.8082371, 3.57039785},
-    {-14.6879606, 19.7018356, 3.6753974},
-    {-14.687932, 20.2348633, 3.57040477},
-    {-14.3207388, 20.0570488, 3.18544149},
-    {-14.5271902, 19.9149132, 3.32542586},
-    {-14.6835146, 19.9149437, 3.25543427},
-    {-14.6789932, 20.2346573, 3.57039714},
-    {-14.5271425, 20.0570507, 3.25543308},
-    {-14.2277498, 20.4481792, 3.25543952},
-    {-14.2174759, 20.1281185, 3.25543237},
-    {-13.4490757, 20.3414688, 3.46541381},
-    {-14.5330706, 20.4125366, 3.32542849},
-    {-14.2321196, 20.1284618, 3.15045094},
-    {-14.6333513, 19.9149761, 3.25543547},
-    {-14.4239454, 19.9149132, 3.18544054},
-    {-14.2204399, 20.1992569, 3.18544149},
-    {-14.0110064, 20.1991901, 3.25543404},
-    {-14.839859, 20.2703304, 2.83547831},
-    {-14.2262249, 20.1283245, 3.18544555},
-    {-14.2234182, 20.1282578, 3.39542198},
-    {-13.4919529, 20.270195, 3.32542443},
-    {-13.5980949, 20.4124012, 3.25543332},
-    {-13.9048643, 20.1280537, 3.32542443},
-    {-14.6304531, 20.1991901, 3.18544054},
-    {-14.8398399, 20.1281872, 3.39542031},
-    {-14.5271711, 20.1991901, 3.53540373},
-    {-14.3236465, 20.1281872, 3.46541262},
-    {-13.9078093, 20.0570507, 3.25543332},
-    {-13.9048643, 20.1280499, 3.04545474},
-    {-13.8045502, 19.9149132, 2.83547783},
-    {-14.3324337, 20.2705307, 3.18544769},
-    {-14.4297924, 20.2703991, 3.39542294},
-    {-14.2116432, 20.1990528, 3.325423},
-    {-14.1055012, 20.3411255, 3.04545116},
-    {-13.9993496, 20.4121284, 3.39541125},
-    {-14.1113529, 20.270195, 3.115448},
-    {-14.1171713, 20.4835396, 3.39542031},
-    {-14.833931, 20.4123325, 3.18543744},
-    {-14.6274281, 20.3412628, 3.3954165},
-    {-14.117157, 20.0571175, 3.18544149},
-    {-14.1200829, 20.0571842, 3.11545062},
-    {-14.2204399, 20.1281872, 3.53540611},
-    {-13.907795, 20.1991901, 3.39541793},
-    {-14.4298449, 19.9150429, 3.60540032},
-    {-14.5301256, 20.1992569, 3.46541429},
-    {-14.2116385, 20.4122639, 3.18543696},
-    {-14.1113243, 20.056982, 2.83547735},
-    {-13.8016386, 20.1991215, 3.25543189},
-    {-13.9049025, 20.4123325, 3.39541841},
-    {-14.0110197, 20.1281223, 3.67538929},
-    {-13.90485, 19.9148445, 3.18543959},
-    {-13.8074236, 20.0571175, 3.18544197},
-    {-14.2204018, 20.1281872, 3.46541333},
-    {-14.6303921, 20.4124012, 3.32542944},
-    {-14.6274662, 19.9859123, 2.97546315},
-    {-14.5359964, 20.1283245, 3.32543159},
-    {-14.3295078, 20.1283245, 3.32543039},
-    {-14.2233276, 19.8439732, 3.46541524},
-    {-14.4268522, 20.2703304, 3.11545014},
-    {-14.7306862, 20.1991215, 3.25543189},
-    {-14.4326811, 20.1283264, 3.18544245},
-    {-14.6421337, 19.9862537, 3.11545157},
-    {-14.8368759, 19.985981, 3.32542586},
-    {-14.217495, 20.4124012, 3.25543332},
-    {-14.3207197, 20.1991901, 3.18544102},
-    {-14.0081081, 20.1280499, 3.04545569},
-    {-14.0138941, 19.7728348, 3.25543451},
-    {-13.7987652, 19.9147758, 3.39541435},
-    {-14.3236837, 20.0571194, 3.04545665},
-    {-14.7336597, 20.4124012, 3.11544752},
-    {-14.836895, 20.1991901, 3.04545569},
-    {-14.3178272, 20.270195, 3.18543839},
-    {-14.1083984, 19.9147758, 3.39541483},
-    {-13.9077902, 20.0570507, 3.25543308},
-    {-14.1142311, 20.1281185, 3.18544054},
-    {-14.1171761, 20.2703304, 3.32542849},
-    {-13.9077568, 20.1991901, 3.32542586},
-    {-14.2174759, 20.2702618, 3.25543189},
-    {-14.2204018, 20.2703304, 3.04545617},
-    {-14.7336884, 20.1281185, 3.115448},
-    {-14.1142263, 19.985981, 3.25543332},
-    {-14.2204018, 20.0571194, 3.18544197},
-    {-14.2115908, 20.3411942, 3.5353992},
-    {-14.7336359, 19.9859753, 3.04545259},
-    {-14.3178082, 20.056982, 2.97546077},
-    {-13.592309, 20.1279831, 2.97546124},
-    {-14.6216087, 20.0568466, 3.18543696},
-    {-14.3118572, 20.2700577, 3.25542831},
-    {-14.2144976, 20.1280499, 3.11544657},
-    {-15.4442968, 19.9857101, 3.25542736},
-    {-14.836771, 19.9149075, 3.39541936},
-    {-14.1113052, 19.9148388, 3.32542491},
-    {-14.3148489, 20.3411961, 3.325423},
-    {-14.5242262, 20.1280499, 3.39541674},
-    {-14.21455, 20.3412628, 3.46540928},
-    {-14.4239264, 20.1991901, 3.32542586},
-    {-14.1142645, 20.1991901, 3.32542634},
-    {-14.2086792, 20.1279163, 3.25542879},
-    {-14.3148117, 20.127985, 3.325423},
-    {-14.1142311, 19.985981, 3.18544102},
-    {-14.0110016, 19.8438396, 3.32542586},
-    {-14.2174759, 19.8438435, 3.25543332},
-    {-14.1113529, 20.4123344, 3.25543237},
-    {-14.2174377, 20.3413296, 3.39541793},
-    {-14.0109873, 20.1281185, 3.115448},
-    {-14.2174377, 20.1991901, 3.25543404},
-    {-14.6303682, 20.1281185, 3.32542586},
-    {-14.0110016, 20.1281185, 3.25543332},
-    {-14.5242262, 20.056982, 3.39541674},
-    {-14.4180555, 20.1279831, 3.32542396},
-    {-14.2086601, 20.0568485, 3.04545522},
-    {-14.6156855, 19.843504, 3.18543506},
-    {-14.5183125, 20.0568466, 2.76548433},
-    {-14.114212, 20.0570507, 3.115448},
-    {-14.0139322, 20.2703304, 3.11544895},
-    {-13.899045, 19.9857788, 3.46540475},
-    {-14.4180937, 19.9147758, 3.325423},
-    {-14.1142454, 20.2702618, 3.18544102},
-    {-14.2174759, 20.1281223, 3.39541626},
-    {-14.0052013, 19.9147758, 3.3954134},
-    {-14.0051823, 19.9858437, 3.11544514},
-    {-14.2087126, 20.1989841, 3.11544466},
-    {-13.9964428, 20.3409901, 3.32541728},
-    {-13.79002, 20.3409901, 3.11544156},
-    {-14.1084127, 20.2701206, 2.76548386},
-    {-14.3148298, 20.1990509, 3.11544347},
-    {-14.0051489, 20.3411942, 3.39541531},
-    {-14.0080938, 20.3412628, 3.46540928},
-    {-13.8016386, 20.4834042, 3.39541674},
-    {-13.6926279, 20.1279144, 3.32542133},
-    {-13.7986984, 20.1279831, 3.25543094},
-    {-14.5212908, 20.1990528, 3.25543094},
-    {-14.3207197, 20.2702618, 3.25543451},
-    {-14.1142645, 20.1281185, 3.46541166},
-    {-14.2086792, 20.2700577, 3.18543696},
-};
\ No newline at end of file
diff --git a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_imu_data.h b/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_imu_data.h
deleted file mode 100644
index 079f707f1..000000000
--- a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_imu_data.h
+++ /dev/null
@@ -1,35 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Authors: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-/**
- * BMX160 IMU data from Lynx flight test in Roccaraso.
- * Sampled at 50 Hz (20 ms period).
- * Each sample here is the result of an average over an entire FIFO, corrected
- * using calibration parameters and rotated in body frame.
- */
-static constexpr unsigned IMU_DATA_SIZE      = 6463;
-static const unsigned MOTION_SENSOR_AXIS_NUM = 3;
-extern const float ACCEL_DATA[IMU_DATA_SIZE][MOTION_SENSOR_AXIS_NUM];
-extern const float GYRO_DATA[IMU_DATA_SIZE][MOTION_SENSOR_AXIS_NUM];
-extern const float MAG_DATA[IMU_DATA_SIZE][MOTION_SENSOR_AXIS_NUM];
\ No newline at end of file
diff --git a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_press_data.cpp b/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_press_data.cpp
deleted file mode 100644
index b54217a83..000000000
--- a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_press_data.cpp
+++ /dev/null
@@ -1,1462 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Authors: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include "lynx_press_data.h"
-
-const float PRESSURE_DATA[PRESSURE_DATA_SIZE] = {
-    85681.5859, 85698.3438, 85687.0234, 85687.0234, 85691.8984, 85689.7891,
-    85679.3672, 85687.6406, 85658.8281, 85658.8281, 85693.375,  85661.5625,
-    85640.5078, 85654.0156, 85677.2656, 85677.2656, 85665.3359, 85671.7031,
-    85668.2969, 85655.8828, 85637.4609, 85637.4609, 85639.6328, 85638.8203,
-    85649.6172, 85636.3047, 85630.0156, 85630.0156, 85606.6719, 85610.6094,
-    85601.1562, 85597.9531, 85590.9688, 85590.9688, 85577.1172, 85567.0547,
-    85565.1484, 85550.4531, 85547.7422, 85547.7422, 85532.4766, 85533.8203,
-    85526.1484, 85521.8906, 85503.7109, 85503.7109, 85492.7422, 85484.7891,
-    85473.0234, 85466.2109, 85461.0547, 85461.0547, 85436.4297, 85428.7266,
-    85420.1641, 85413.1016, 85395.6094, 85395.6094, 85385.2734, 85372.5703,
-    85358.6094, 85355.4844, 85335.2812, 85335.2812, 85315.7969, 85306.2656,
-    85291.3672, 85279.0781, 85275.0156, 85275.0156, 85259.2578, 85241.9375,
-    85226.7969, 85224.0391, 85206.7578, 85206.7578, 85179.4844, 85177.8594,
-    85163.0078, 85148.2422, 85141.9531, 85141.9531, 85108.5078, 85096.4922,
-    85085.1328, 85073.5312, 85057.5859, 85057.5859, 85029.0547, 85018.0547,
-    84997.4844, 84993.875,  84980.0781, 84980.0781, 84952.2109, 84934.6797,
-    84912.1172, 84896.4922, 84873.7344, 84873.7344, 84841.3281, 84807.6094,
-    84794.6641, 84781.7188, 84765.125,  84765.125,  84728,      84712.2109,
-    84706.5312, 84681.8984, 84673.3828, 84673.3828, 84630.875,  84627.1797,
-    84609.4062, 84592.2031, 84573.6562, 84573.6562, 84553.8203, 84524.5234,
-    84510.4844, 84487.9219, 84475.8281, 84475.8281, 84446.8906, 84426.9219,
-    84397.9062, 84382.9766, 84357.8984, 84357.8984, 84322.3906, 84301.8984,
-    84270.9375, 84255.5547, 84236.8516, 84236.8516, 84195.9531, 84167.7109,
-    84145.7969, 84128.0234, 84103.9219, 84103.9219, 84058.6406, 84045.6562,
-    84019.3594, 83991.4844, 83959.2266, 83959.2266, 83925.0234, 83889.2344,
-    83874.8281, 83841.0625, 83812.5,    83812.5,    83743.5938, 83727.4844,
-    83702.9766, 83681.1484, 83667.0625, 83667.0625, 83617.6719, 83594.9453,
-    83559.3203, 83518.1328, 83481.0469, 83481.0469, 83413.1016, 83385.875,
-    83334.6641, 83295.0625, 83252.1719, 83252.1719, 83111.3203, 83017.3438,
-    82931.3984, 82853.4922, 82807.1094, 82807.1094, 82746.8438, 82717.2266,
-    82675.5078, 82637.8594, 82601.6641, 82601.6641, 82548.4688, 82512.3984,
-    82488.0078, 82459.6094, 82445.1172, 82445.1172, 82419.4219, 82411.4297,
-    82396.0469, 82400.2656, 82385.7812, 82385.7812, 82372.8516, 82361.3672,
-    82335.0781, 82328.7031, 82314.9922, 82314.9922, 82266.3281, 82259.0703,
-    82233.1797, 82217.1484, 82426.2109, 82426.2109, 82174.4531, 82181.1094,
-    82168.2422, 82152.4609, 82124.9844, 82124.9844, 82087.1094, 82083.4609,
-    82087.9609, 82073.3516, 82036.75,   82036.75,   81990.3516, 82028.0078,
-    82166.7812, 82374.9922, 82661.5938, 82661.5938, 82926.8203, 82911.0703,
-    82905.5938, 82946.6562, 82929.5781, 82929.5781, 82861.9062, 82825.5469,
-    82792.8438, 82768.5781, 82750.3594, 82750.3594, 82693.7031, 82676.5391,
-    82650.8125, 82620.3438, 82601.1875, 82601.1875, 82598.1953, 83182.0703,
-    83905.9766, 84545.0391, 85008.8828, 85008.8828, 84617.6016, 84202.5391,
-    83485.0938, 82799.0938, 82273.2969, 82273.2969, 81184.7656, 80662.8906,
-    80304.0234, 80237.0312, 80070.7031, 80070.7031, 79558.0234, 79448.6641,
-    79200.8906, 79283.1016, 79164.0078, 79164.0078, 79298.0234, 79158.4766,
-    79020.7188, 79005.1328, 78936.2344, 78936.2344, 78760.0625, 78817.2422,
-    78801.4531, 78811.4766, 78749.0703, 78749.0703, 78757.3594, 78631.0391,
-    78798.0938, 78727.3672, 78719.7422, 78719.7422, 78686.6875, 78595.9609,
-    78542.9688, 78618.1562, 78591.8984, 78591.8984, 78640.7578, 78639.9922,
-    78600.0625, 78581.0312, 78498.1328, 78498.1328, 78516.1797, 78517.6797,
-    78570.5469, 78475.9609, 78454.2109, 78454.2109, 78486.2969, 78428.6406,
-    78442.6016, 78405.5078, 78357.4688, 78357.4688, 78448.3828, 78395.1406,
-    78310.3359, 78410.3984, 78320.2344, 78320.2344, 78287.1484, 78263.7734,
-    78224.6172, 78309.3047, 78216.7031, 78216.7031, 78049.0234, 78213.2422,
-    78121.375,  78126.9297, 78064.3984, 78064.3984, 77966.7578, 77888.6484,
-    78027.0547, 78012.4453, 78030.3047, 78030.3047, 77973.9219, 78054.0625,
-    77885.3438, 77930.9922, 77941.9844, 77941.9844, 78051.9141, 77881,
-    77892.6875, 77977.7734, 77869.7969, 77869.7969, 77665.3672, 77635.9844,
-    77689.9922, 77747.7344, 77792.6562, 77792.6562, 77735.6797, 77660.0781,
-    77692.1328, 77636.1016, 77558.1875, 77558.1875, 77669.9453, 77666.2578,
-    77650.7578, 77532.4297, 77572.3594, 77572.3594, 77460.7812, 77520.75,
-    77537.6719, 77431.3594, 77473.9219, 77473.9219, 77550.9219, 77449.8828,
-    77436.2109, 77363.9844, 77488.7188, 77488.7188, 77370.8125, 77348.1719,
-    77352.4688, 77305.5234, 77301.625,  77301.625,  77302.5078, 77266.4375,
-    77277.3125, 77180.5,    77173.4766, 77173.4766, 77155.9609, 77066.2422,
-    77218.9297, 77158.0312, 77066.6484, 77066.6484, 77085.1797, 77159.1484,
-    77129.2891, 77107.9062, 77075.0781, 77075.0781, 77001.0156, 77123.3125,
-    76997.3281, 76983.0469, 77057.8672, 77057.8672, 77101.7969, 76957.7188,
-    77014.5625, 76967.8203, 76940.4766, 76940.4766, 76871.0547, 76872.0312,
-    76830.0391, 76765.9688, 76765.1562, 76765.1562, 76857.3672, 76710.6562,
-    76797.6406, 76734.0625, 76759.2188, 76759.2188, 76640.125,  76708.7422,
-    76697.0938, 76612.1719, 76672.8281, 76672.8281, 76683.5703, 76613.1328,
-    76710.875,  76580.1484, 76504.1094, 76504.1094, 76495.6953, 76546.7734,
-    76563.4062, 76568.6406, 76532.6953, 76532.6953, 76563.3906, 76437.8984,
-    76466.3047, 76435.1406, 76395.8281, 76395.8281, 76349.8828, 76358.5234,
-    76356.7422, 76359.2969, 76315.6016, 76315.6016, 76427.1016, 76530.7266,
-    76523.2969, 76643.6875, 76762.1172, 76762.1172, 76837.0312, 76818.5703,
-    76893.5469, 76898.2969, 76800.1875, 76800.1875, 76772.8203, 76785.1562,
-    76778.2188, 76748.4375, 76765.0703, 76765.0703, 76754.0547, 76725.5312,
-    76729.3906, 76703.4609, 76737.3359, 76737.3359, 76684.6953, 76655.9297,
-    76605.4922, 76624.1953, 76581.2344, 76581.2344, 76579.7188, 76566.8984,
-    76513.4609, 76471.3125, 76449.5625, 76449.5625, 76415.3594, 76482.1797,
-    76420.9609, 76448.3438, 76395.0312, 76395.0312, 76385.2188, 76390.3359,
-    76348.9062, 76338.5234, 76333.0469, 76333.0469, 76363.9688, 76354.1953,
-    76262.3828, 76247.7734, 76250.2109, 76250.2109, 76268.7422, 76272.7188,
-    76204.2734, 76175.1016, 76140.2891, 76140.2891, 76082.25,   76095.0312,
-    76114.8359, 76071.2969, 76101.6094, 76101.6094, 76004.3906, 75997.5391,
-    75959.3594, 76010.7656, 76029.3828, 76029.3828, 75982.7578, 75915.0391,
-    75959.4688, 75984.7422, 75913.4141, 75913.4141, 75877.8438, 75935.125,
-    75912.7734, 75908.2656, 75833.9375, 75833.9375, 75791.7891, 75782.2969,
-    75795.3203, 75801.6484, 75748.0156, 75748.0156, 75735.2812, 75757.0625,
-    75739.2578, 75691.7891, 75716.9375, 75716.9375, 75659.2188, 75632.4062,
-    75624.2891, 75609.5234, 75575.4375, 75575.4375, 75600.9141, 75559.2109,
-    75573.7734, 75546.1484, 75571.2188, 75571.2188, 75473.1094, 75483.4141,
-    75543.2109, 75492.0547, 75473.1484, 75473.1484, 75395.5078, 75404.6797,
-    75374.1719, 75360.3359, 75365.3281, 75365.3281, 75347.5469, 75329.7344,
-    75297.7266, 75292.8984, 75285.1484, 75285.1484, 75267.5938, 75253.6406,
-    75250.7578, 75232.5469, 75265.4062, 75265.4062, 75237.6875, 75210.1016,
-    75235.625,  75158.5391, 75169.125,  75169.125,  75131.5312, 75113.0312,
-    75124.2734, 75095.0234, 75088.5703, 75088.5703, 75065.2969, 75049.4688,
-    75025.3359, 75025.25,   75010.6484, 75010.6484, 75021.1406, 75004.875,
-    75007.3906, 74961.1797, 74952.9453, 74952.9453, 74921.6016, 74917.2969,
-    74905.1719, 74895.1094, 74886.9922, 74886.9922, 74877.6719, 74840.5938,
-    74797.4688, 74832.6406, 74784.6875, 74784.6875, 74783.8672, 74772.9531,
-    74795.625,  74768.0859, 74758.4688, 74758.4688, 74725.4453, 74691.8125,
-    74708.0391, 74694.9766, 74694.0859, 74694.0859, 74647.4141, 74660.8438,
-    74680.3594, 74656.7891, 74634.7188, 74634.7188, 74654.75,   74613.2109,
-    74630.6172, 74581.2031, 74590.5312, 74590.5312, 74678.9141, 74700.8203,
-    74778.3438, 74814.125,  74906.0469, 74906.0469, 75025.7266, 75106.8984,
-    75175.6172, 75213.1484, 75192.9453, 75192.9453, 74854.5938, 74636.1016,
-    74468.6016, 74422.6406, 74413.1875, 74413.1875, 74397.5938, 74383.9219,
-    74380.9609, 74369.3203, 74353.2578, 74353.2578, 74337.8359, 74319.0938,
-    74308.1797, 74300.875,  74289.1562, 74289.1562, 74269.6094, 74260.6094,
-    74251.2734, 74238.5,    74230.5859, 74230.5859, 74215.3125, 74208.375,
-    74196.6953, 74184.6875, 74176.8516, 74176.8516, 74162.5703, 74155.3125,
-    74140.3438, 74135.3516, 74122.0859, 74122.0859, 74108.8516, 74099.3203,
-    74092.3828, 74079.9297, 74072.0625, 74072.0625, 74054.1094, 74036.8281,
-    74027.5,    74016.1406, 74003.4453, 74003.4453, 73987.0156, 73973.4609,
-    73962.6328, 73955.1719, 73948.0703, 73948.0703, 73930.1562, 73923.9453,
-    73913.7656, 73907.5156, 73891.8203, 73891.8203, 73879,      73868.375,
-    73858.5156, 73850.3203, 73846.0625, 73846.0625, 73827.3047, 73818.375,
-    73808.4766, 73796.5156, 73786.6953, 73786.6953, 73774.1406, 73763.2734,
-    73754.75,   73745.1797, 73732.6406, 73732.6406, 73716.4219, 73708.4766,
-    73697.9297, 73683.5234, 73678.4922, 73678.4922, 73671.7656, 73652.5391,
-    73641.9922, 73638.1406, 73625.1562, 73625.1562, 73614.1172, 73604.7891,
-    73588.3594, 73586.2109, 73573.3906, 73573.3906, 73557.9922, 73548.4219,
-    73539.4531, 73532.3516, 73525.4609, 73525.4609, 73509.0469, 73499.2344,
-    73496.8828, 73488.9297, 73480.1719, 73480.1719, 73470.1719, 73459.5,
-    73449.5625, 73443.8828, 73435.2422, 73435.2422, 73421.7344, 73416.1797,
-    73405.0625, 73395.6562, 73387.4141, 73387.4141, 73371.5781, 73364.1172,
-    73350,      73338.4766, 73339.7734, 73339.7734, 73322.3906, 73310.7109,
-    73299.1875, 73295.7422, 73286.0859, 73286.0859, 73276.6328, 73263.6094,
-    73256.5078, 73246.25,   73234.2422, 73234.2422, 73228.8672, 73219.8203,
-    73208.5078, 73205.4219, 73196.1719, 73196.1719, 73178.2891, 73174.7188,
-    73168.1094, 73157.1562, 73148.8359, 73148.8359, 73140.4141, 73133.2344,
-    73128.6875, 73122.0391, 73120.25,   73120.25,   73100.1328, 73091.6094,
-    73084.0234, 73079.5625, 73072.3047, 73072.3047, 73059.8516, 73054.625,
-    73048.8594, 73036.6094, 73034.9453, 73034.9453, 73021.6406, 73013.8906,
-    73001.7188, 72995.7969, 72993.125,  72993.125,  72980.1016, 72970.0469,
-    72964.5703, 72960.875,  72944.4844, 72944.4844, 72937.9609, 72929.2422,
-    72916.9062, 72913.9062, 72911.3906, 72911.3906, 72902.7422, 72888.2266,
-    72874.1094, 72876.9062, 72867.0469, 72867.0469, 72853.6094, 72847.6875,
-    72840.1016, 72834.1406, 72831.4219, 72831.4219, 72818.375,  72814.5234,
-    72804.1797, 72797.0781, 72785.8047, 72785.8047, 72780.8438, 72772.5703,
-    72766.2422, 72762.4688, 72755.0078, 72755.0078, 72746.9844, 72741.9531,
-    72728.0781, 72729.5,    72721.4297, 72721.4297, 72707.6719, 72705.6094,
-    72700.4531, 72695.2656, 72688.125,  72688.125,  72677.4141, 72671.6172,
-    72666.1406, 72656.3203, 72652.0625, 72652.0625, 72641.0078, 72634.1484,
-    72632.3203, 72627.9844, 72619.2188, 72619.2188, 72612.5781, 72603.1641,
-    72600.7734, 72590.8359, 72583.9375, 72583.9375, 72578.9219, 72567.0781,
-    72568.5391, 72558.5156, 72555.5938, 72555.5938, 72546.0078, 72540.6172,
-    72538.6641, 72530.1875, 72523.8203, 72523.8203, 72517.3594, 72513.3438,
-    72505.6406, 72497.1172, 72489.2109, 72489.2109, 72487.5469, 72477.3203,
-    72474.3203, 72467.0625, 72463.0078, 72463.0078, 72457.8516, 72449.1641,
-    72445.5156, 72438.9453, 72435.2109, 72435.2109, 72425.2188, 72419.2188,
-    72414.9531, 72412.3594, 72407.4531, 72407.4531, 72394.8203, 72392.4688,
-    72384.8359, 72382,      72376.3594, 72376.3594, 72369.3672, 72363.2422,
-    72352.5781, 72353.875,  72346.25,   72346.25,   72341.8906, 72333.7031,
-    72331.0234, 72325.0156, 72322.3047, 72322.3047, 72316.2031, 72310.0391,
-    72302.5312, 72302.4922, 72292.5156, 72292.5156, 72289.0391, 72282.4297,
-    72280.3984, 72277.1953, 72269.9766, 72269.9766, 72256.6094, 72257.9141,
-    72252.8828, 72251.1406, 72243.7969, 72243.7969, 72237.1484, 72233.25,
-    72228.9141, 72227.3281, 72224.4531, 72224.4531, 72215.9062, 72210.3438,
-    72207.625,  72205.1562, 72202.3125, 72202.3125, 72193.1406, 72188.1875,
-    72179.1797, 72181.4531, 72175.6562, 72175.6562, 72172.4609, 72164.1875,
-    72162.3594, 72157.25,   72156.1172, 72156.1172, 72149.5703, 72142.9609,
-    72137.7266, 72138.4141, 72134.3203, 72134.3203, 72130.6719, 72127.0625,
-    72125.6016, 72119.1562, 72114.7344, 72114.7344, 72109.2891, 72105.1094,
-    72100.2422, 72097.8516, 72095.8203, 72095.8203, 72086.0078, 72084.1406,
-    72076.0312, 72073.6797, 72070.7969, 72070.7969, 72072.0391, 72067.6641,
-    72063.4844, 72056.0625, 72058.4531, 72058.4531, 72054.2734, 72049.0859,
-    72047.8672, 72040,      72040.5625, 72040.5625, 72033.1484, 72032.0938,
-    72031.3672, 72026.0078, 72022.3203, 72022.3203, 72020.9688, 72017.0312,
-    72009.6484, 72010.4219, 72006.1562, 72006.1562, 72003.1797, 72000.3828,
-    71996.2031, 71995.9141, 71992.2656, 71992.2656, 71982.5547, 71982.7969,
-    71985.3906, 71974.5625, 71978.9453, 71978.9453, 71973.4609, 71971.3125,
-    71968.875,  71965.2656, 71964.1719, 71964.1719, 71954.9062, 71958.0703,
-    71952.3516, 71957.3828, 71950.8906, 71950.8906, 71947.3438, 71939.3125,
-    71942.5547, 71940.6484, 71936.0703, 71936.0703, 71934.375,  71930.6484,
-    71926.1797, 71927.9297, 71921.5547, 71921.5547, 71921.7109, 71915.8281,
-    71917.4141, 71916.4766, 71911.7734, 71911.7734, 71907.0938, 71907.0469,
-    71905.4688, 71902.2266, 71892.4062, 71892.4062, 71906.5547, 71897.2266,
-    71896.3359, 71893.4141, 71889.9688, 71889.9688, 71891.6719, 71886.6406,
-    71888.6328, 71882.1797, 71881.6953, 71881.6953, 71878.4688, 71874.125,
-    71877.0469, 71875.9141, 71876.5625, 71876.5625, 71867.3828, 71871.1172,
-    71871.1562, 71866.5312, 71867.2266, 71867.2266, 71866.4141, 71860.3672,
-    71860.7344, 71859.4375, 71856.8438, 71856.8438, 71853.2969, 71855.3672,
-    71856.1797, 71854.5547, 71853.0938, 71853.0938, 71851.0312, 71851.2734,
-    71847.625,  71846.8984, 71845.8828, 71845.8828, 71844.7656, 71842.125,
-    71840.1797, 71838.0312, 71836.125,  71836.125,  71837.5312, 71830.1094,
-    71834.4922, 71834.0469, 71830.3516, 71830.3516, 71836.625,  71833.3438,
-    71833.1406, 71830.0938, 71830.8672, 71830.8672, 71834.6719, 71828.3828,
-    71827.6953, 71826.2734, 71827.4062, 71827.4062, 71829.25,   71824.1406,
-    71827.4688, 71821.0625, 71823.5781, 71823.5781, 71822.7969, 71824.4609,
-    71821.2578, 71822.8359, 71819.5547, 71819.5547, 71824.8438, 71817.0938,
-    71817.0156, 71815.5547, 71821.4766, 71821.4766, 71820.0938, 71812.7109,
-    71815.1484, 71817.3359, 71817.5781, 71817.5781, 71817.9922, 71818.3516,
-    71823.4219, 71817.2188, 71816.0859, 71816.0859, 71815.8047, 71820.1016,
-    71816.6562, 71819.0078, 71816.7344, 71816.7344, 71829.9766, 71818.4141,
-    71817.6484, 71820.9297, 71816.9922, 71816.9922, 71821.5391, 71821.9453,
-    71820.7656, 71819.1875, 71820.0781, 71820.0781, 71824.0703, 71827.6406,
-    71823.5391, 71825.6953, 71842.5703, 71842.5703, 71900.9219, 71825.3438,
-    71816.5391, 71817.2734, 71823.7266, 71823.7266, 71828.8594, 71835.5547,
-    71836.5703, 71833.8906, 71830.4062, 71830.4062, 71831.1875, 71833.5,
-    71830.2969, 71834.6797, 71833.4609, 71833.4609, 71841.1406, 71839.8438,
-    71838.9922, 71838.5859, 71840.6094, 71840.6094, 71844.4141, 71846.2031,
-    71844.2969, 71837.1094, 71830.9844, 71830.9844, 71809.6484, 71807.9062,
-    71787.0547, 71793.0156, 71802.2656, 71802.2656, 71851.1953, 71851.3594,
-    71842.6406, 71831.3594, 71826.25,   71826.25,   71823.875,  71818.1484,
-    71806.2266, 71792.1094, 71811.1719, 71811.1719, 71818.4531, 71805.2734,
-    71796.9531, 71796.5469, 71796.3047, 71796.3047, 71791.2734, 71789.6094,
-    71766.1172, 71770.7812, 71768.5156, 71768.5156, 71800.2812, 71764.8672,
-    71773.5078, 71752.5703, 71731.9219, 71731.9219, 71737.7891, 71742.1719,
-    71745.2891, 71752.4766, 71750.4453, 71750.4453, 71772.0156, 71791.6094,
-    71770.875,  71785.5625, 71789.1719, 71789.1719, 71829.6797, 71836.25,
-    71850.5703, 71860.7891, 71844.9297, 71844.9297, 71878.1406, 71900.4922,
-    71909.8203, 71919.5625, 71920.6172, 71920.6172, 71929.4531, 71928.3594,
-    71935.8594, 71935.0547, 71929.7344, 71929.7344, 71930.8984, 71935.8047,
-    71922.1719, 71914.2188, 71919.7812, 71919.7812, 71907.4375, 71897.0078,
-    71895.6719, 71885.4062, 71890.6406, 71890.6406, 71891.0391, 71883.2109,
-    71884.9531, 71889.2969, 71880.4531, 71880.4531, 71875.3984, 71887.2812,
-    71897.9531, 71883.7109, 71889.1094, 71889.1094, 71908.6641, 71900.3906,
-    71908.8672, 71920.1094, 71917.3906, 71917.3906, 71927.9844, 71945.7578,
-    71952.4062, 71956.4219, 71966.6484, 71966.6484, 72007.8047, 72006.0234,
-    72015.5547, 72012.4688, 72022.0078, 72022.0078, 72029.875,  72035.1094,
-    72020.3438, 72018.2344, 72002.6562, 72002.6562, 71998.4141, 71997.9688,
-    71996.3047, 71993.1875, 71982.6406, 71982.6406, 71992.1875, 71994.1797,
-    71995.1484, 72003.4297, 71997.2578, 71997.2578, 72009.9453, 72016.7266,
-    72025.7734, 72026.7422, 72036.0703, 72036.0703, 72038.8906, 72043.7656,
-    72036.9453, 72035.6094, 72048.5469, 72048.5469, 72047.9844, 72049.3281,
-    72072.6094, 72079.5938, 72075.25,   72075.25,   72085.8906, 72084.7109,
-    72087.5938, 72086.4922, 72094.7734, 72094.7734, 72103.7344, 72102.5625,
-    72109.6641, 72115.8281, 72116.3125, 72116.3125, 72092.125,  72090.8281,
-    72098.25,   72106.125,  72091.9688, 72091.9688, 72114.0312, 72110.3438,
-    72120.8125, 72118.1328, 72112.9375, 72112.9375, 72120.8359, 72115.1953,
-    72107.8594, 72094.0625, 72104.9375, 72104.9375, 72094.0156, 72112.6797,
-    72112.5547, 72103.9141, 72110.4062, 72110.4062, 72128.1406, 72118.2422,
-    72120.6797, 72118.8906, 72119.5391, 72119.5391, 72130.1406, 72129.6172,
-    72136.1016, 72161.7031, 72164.2969, 72164.2969, 72192.2734, 72196.9375,
-    72204.4375, 72198.9609, 72207.7656, 72207.7656, 72210.0703, 72224.9219,
-    72222.7734, 72232.9141, 72235.3047, 72235.3047, 72238.3359, 72249.4141,
-    72257.6094, 72257.2812, 72258.5859, 72258.5859, 72271.5234, 72271.8047,
-    72265.7656, 72275.2578, 72278.3828, 72278.3828, 72288.1875, 72289.5234,
-    72290.1328, 72291.1484, 72296.625,  72296.625,  72301.3828, 72309.0938,
-    72307.3047, 72312.9453, 72320.8125, 72320.8125, 72328.75,   72330.6562,
-    72335.4844, 72322.8281, 72330.8203, 72330.8203, 72339.2891, 72343.7109,
-    72343.6719, 72345.0078, 72356.6172, 72356.6172, 72354.7656, 72353.9922,
-    72355.6562, 72358.0938, 72359.9609, 72359.9609, 72355.8906, 72361.6562,
-    72368.0234, 72366.9297, 72362.1406, 72362.1406, 72367.5938, 72374.8125,
-    72374.8906, 72364.5078, 72386.9062, 72386.9062, 72362.5156, 72362.6797,
-    72361.0547, 72368.9297, 72365.5625, 72365.5625, 72372.2969, 72360.9766,
-    72366.8203, 72376.1094, 72380.25,   72380.25,   72389.5703, 72397.6016,
-    72410.2578, 72392.5312, 72406.7344, 72406.7344, 72418.9453, 72436.3906,
-    72432.1719, 72427.0625, 72429.0859, 72429.0859, 72448.7422, 72440.5078,
-    72451.7812, 72453.0391, 72462.0469, 72462.0469, 72476.875,  72481.6641,
-    72491.6484, 72500.2422, 72506.125,  72506.125,  72516.1172, 72518.6719,
-    72525.6953, 72527.5234, 72541.3984, 72541.3984, 72541.6797, 72545.25,
-    72544.6016, 72551.25,   72561.6406, 72561.6406, 72573.1328, 72571.4688,
-    72571.3828, 72577.1875, 72582.7422, 72582.7422, 72583.3828, 72581.8828,
-    72594.3359, 72596.2891, 72601.8828, 72601.8828, 72612.1406, 72615.875,
-    72608.8984, 72609.2656, 72618.6719, 72618.6719, 72620.8828, 72610.6172,
-    72611.0234, 72622.7422, 72621.7734, 72621.7734, 72627.5234, 72627.5625,
-    72627.2812, 72630.8516, 72625.6953, 72625.6953, 72627.0938, 72635.6484,
-    72637.2344, 72642.8359, 72642.6719, 72642.6719, 72649.2969, 72648.9297,
-    72648.3984, 72652.6172, 72658.8281, 72658.8281, 72664.9297, 72657.9141,
-    72667.3672, 72679.5391, 72688.3828, 72688.3828, 72689.25,   72690.9141,
-    72699.3125, 72699.875,  72683.2422, 72683.2422, 72680.8906, 72691.5547,
-    72703.8125, 72697.6875, 72698.4531, 72698.4531, 72707.6641, 72714.9688,
-    72714.1562, 72720.4844, 72718.3359, 72718.3359, 72740.9844, 72737.3672,
-    72742.0391, 72755.5469, 72755.0625, 72755.0625, 72736.1953, 72748.3281,
-    72753.8438, 72757.7812, 72746.6641, 72746.6641, 72751.4375, 72778.4141,
-    72770.6641, 72773.625,  72777.7266, 72777.7266, 72774.875,  72774.5078,
-    72770.1328, 72773.9453, 72778.9766, 72778.9766, 72781.9844, 72770.0156,
-    72765.8359, 72756.2656, 72745.7109, 72745.7109, 72772.0312, 72751.5,
-    72763.0625, 72760.2656, 72763.0234, 72763.0234, 72779.9531, 72782.625,
-    72798.3672, 72808.9609, 72806.3203, 72806.3203, 72810.1953, 72820.5859,
-    72817.625,  72819.125,  72822.6953, 72822.6953, 72845.5938, 72831.0234,
-    72848.6797, 72855.0469, 72869.5703, 72869.5703, 72859.2344, 72857.2422,
-    72856.2344, 72869.0938, 72873.1094, 72873.1094, 72884.0469, 72885.625,
-    72894.5547, 72904.3281, 72914.3125, 72914.3125, 72922.8672, 72940.6797,
-    72948.7109, 72949,      72965.6328, 72965.6328, 72958.1328, 72963.1562,
-    72957.6016, 72984.4609, 72975.1719, 72975.1719, 72987.1484, 72982.2422,
-    73005.5703, 72994.8984, 73007.8438, 73007.8438, 73021.7578, 73033.8828,
-    73042.8125, 73040.3359, 73038.3516, 73038.3516, 73069.7969, 73074.5078,
-    73073.9766, 73076.6172, 73085.5781, 73085.5781, 73086.375,  73099.6406,
-    73093.6406, 73103.7422, 73097.4922, 73097.4922, 73124.5547, 73128.6094,
-    73122.1172, 73136.8906, 73129.9141, 73129.9141, 73135.4688, 73133.6016,
-    73128.4141, 73130.2812, 73126.8281, 73126.8281, 73134.5234, 73125.1094,
-    73140.2031, 73132.5391, 73121.9453, 73121.9453, 73137.2031, 73131.8516,
-    73140.3281, 73135.6641, 73139.6016, 73139.6016, 73128.3047, 73123.8438,
-    73142.4609, 73144.8125, 73153.1328, 73153.1328, 73144.7656, 73151.2969,
-    73166.3125, 73160.875,  73175.9688, 73175.9688, 73177.6484, 73184.3438,
-    73198.0156, 73198.9062, 73203.125,  73203.125,  73213.2266, 73204.7109,
-    73198.9844, 73198.5781, 73216.5156, 73216.5156, 73219.7188, 73232.6562,
-    73243,      73246.3281, 73242.3125, 73242.3125, 73252.4062, 73256.5469,
-    73260.8906, 73252.8984, 73256.875,  73256.875,  73278.5938, 73279.0781,
-    73285.3672, 73288.3672, 73308.6953, 73308.6953, 73325.0234, 73323.7656,
-    73320.6016, 73341.4531, 73338.6094, 73338.6094, 73345.0391, 73350.3203,
-    73351.6562, 73353.5234, 73354.2109, 73354.2109, 73360.9609, 73363.1094,
-    73365.5859, 73366.1953, 73368.1016, 73368.1016, 73377.5703, 73383.7422,
-    73386.9062, 73389.5391, 73388.2812, 73388.2812, 73405.2578, 73411.9062,
-    73417.5859, 73424.8516, 73417.9922, 73417.9922, 73437.9688, 73436.2266,
-    73442.3516, 73431.7266, 73439.6719, 73439.6719, 73446.7578, 73440.8281,
-    73447.7266, 73439.6953, 73440.4219, 73440.4219, 73440.0781, 73443.8438,
-    73435.9375, 73438.9766, 73433.1406, 73433.1406, 73429.1953, 73422.8672,
-    73428.7891, 73441.6484, 73434.5078, 73434.5078, 73438.3516, 73442.2031,
-    73438.1016, 73443.8672, 73440.7031, 73440.7031, 73447.6016, 73456.8125,
-    73463.625,  73475.7578, 73490.8047, 73490.8047, 73514.9688, 73516.2656,
-    73537.1172, 73537,      73551.2812, 73551.2812, 73580.4375, 73594.1094,
-    73587.0078, 73605.4688, 73605.1484, 73605.1484, 73620.2422, 73628.7656,
-    73637,      73629.8594, 73637.3281, 73637.3281, 73644.1484, 73649.8672,
-    73650.8438, 73651.3672, 73647.2734, 73647.2734, 73649.3672, 73656.7891,
-    73655.7344, 73660.1562, 73667.9062, 73667.9062, 73678.3203, 73677.4688,
-    73682.8672, 73691.6719, 73696.2578, 73696.2578, 73705.8828, 73706.4531,
-    73712.4531, 73717.4844, 73718.2578, 73718.2578, 73728.7656, 73726.4141,
-    73732.0938, 73731.7266, 73736.7188, 73736.7188, 73742.125,  73748.2891,
-    73746.5469, 73746.4688, 73748.1328, 73748.1328, 73746.5859, 73745.6562,
-    73761.6797, 73759.3672, 73763.3828, 73763.3828, 73778.3516, 73785.6172,
-    73780.3438, 73791.9453, 73794.7812, 73794.7812, 73803.2344, 73807.3672,
-    73812.2422, 73815.9297, 73817.6797, 73817.6797, 73827.6562, 73831.7109,
-    73834.3906, 73830.8203, 73833.6172, 73833.6172, 73838.4766, 73832.3906,
-    73833.4062, 73843.5078, 73831.8203, 73831.8203, 73835.6328, 73838.3125,
-    73835.2266, 73837.9062, 73838.0234, 73838.0234, 73865.8594, 73867.6484,
-    73875.6406, 73882.0469, 73881.8047, 73881.8047, 73902.5859, 73902.7422,
-    73903.7578, 73910.0859, 73904.9766, 73904.9766, 73922.2578, 73905.0156,
-    73907.4141, 73915.2422, 73916.5391, 73916.5391, 73938.0625, 73938.3438,
-    73946.375,  73955.3047, 73962.2422, 73962.2422, 73979.2812, 73988.6562,
-    73987.2734, 73986.3047, 73992.1875, 73992.1875, 73988.4062, 73986.0938,
-    73998.2656, 73993.9609, 73993.5547, 73993.5547, 73993.0625, 73996.1484,
-    73970.75,   73967.625,  73981.6641, 73981.6641, 73979.2031, 73990.9688,
-    73997.0547, 73981.9219, 73990.5234, 73990.5234, 73994.7578, 74004.375,
-    74003.3594, 74027.625,  74032.9844, 74032.9844, 74025.0703, 74039.9609,
-    74052.9062, 74071.7734, 74076.7266, 74076.7266, 74080.2188, 74084.6016,
-    74083.2969, 74090.5625, 74081.8359, 74081.8359, 74087.9688, 74091.4219,
-    74102.0938, 74118.8047, 74127.5703, 74127.5703, 74152.7344, 74152.4922,
-    74147.3828, 74143.8516, 74142.6719, 74142.6719, 74159.0234, 74166.2891,
-    74168.0781, 74179.5156, 74174.2031, 74174.2031, 74190.8359, 74203.9453,
-    74206.0156, 74208.7734, 74221.2266, 74221.2266, 74233.6953, 74229.7969,
-    74225.5,    74239.5781, 74237.1797, 74237.1797, 74251.9922, 74245.2969,
-    74251.7891, 74254.0625, 74251.7891, 74251.7891, 74258.75,   74249.9062,
-    74251.5312, 74253.1094, 74249.3828, 74249.3828, 74246.75,   74246.6719,
-    74252.2734, 74256.8125, 74262.4531, 74262.4531, 74279.0078, 74277.3828,
-    74277.7891, 74287.6484, 74284.5625, 74284.5625, 74287.8203, 74292.4062,
-    74305.1875, 74303.0391, 74311.2734, 74311.2734, 74324.5625, 74346.3906,
-    74353.9453, 74348.9922, 74362.5469, 74362.5469, 74360.3438, 74363.6719,
-    74368.7422, 74375.3984, 74387.0391, 74387.0391, 74396.4297, 74395.4219,
-    74396.9219, 74397.6484, 74394.4844, 74394.4844, 74400.6797, 74401.125,
-    74403.9297, 74404.8594, 74419.6719, 74419.6719, 74414.5703, 74418.2578,
-    74414.9375, 74420.2109, 74418.1797, 74418.1797, 74416.2109, 74416.9766,
-    74413.7734, 74417.6719, 74422.0938, 74422.0938, 74423.375,  74443.0156,
-    74432.3438, 74429.8281, 74443.8672, 74443.8672, 74466.5547, 74468.625,
-    74463.0234, 74471.5859, 74492.2734, 74492.2734, 74498.2734, 74504.8047,
-    74500.0547, 74512.1484, 74531.2188, 74531.2188, 74549.1484, 74549.3125,
-    74556.0938, 74560.2734, 74567.2891, 74567.2891, 74582.6016, 74584.2266,
-    74578.1797, 74586.1328, 74582.9688, 74582.9688, 74574.1328, 74593.8516,
-    74584.0312, 74596.0781, 74607.2812, 74607.2812, 74623.5391, 74623.9844,
-    74643.0547, 74636.4766, 74640.2969, 74640.2969, 74646.6562, 74659.1172,
-    74653.5938, 74652.0938, 74659.1953, 74659.1953, 74657.2266, 74645.9922,
-    74646.1953, 74634.7891, 74620.6328, 74620.6328, 74607.3828, 74627.5469,
-    74619.3125, 74617,      74610.2656, 74610.2656, 74629.1719, 74629.0469,
-    74641.9141, 74646.1719, 74675.3828, 74675.3828, 74685.5,    74698.1641,
-    74722.3828, 74734.4375, 74742.5078, 74742.5078, 74744.7344, 74750.8984,
-    74744.1641, 74748.625,  74753.5781, 74753.5781, 74746.8594, 74757.4062,
-    74761.3047, 74770.5938, 74768.9766, 74768.9766, 74799.875,  74808.4766,
-    74802.3438, 74811.1484, 74818.7812, 74818.7812, 74822.1016, 74830.0547,
-    74833.0625, 74840.6484, 74841.0078, 74841.0078, 74846.2109, 74845.4844,
-    74848.8906, 74847.3906, 74852.4609, 74852.4609, 74859.5547, 74858.375,
-    74865.9219, 74867.7109, 74873.4688, 74873.4688, 74873.4062, 74861.5234,
-    74876.8203, 74869.6328, 74881.8906, 74881.8906, 74876.9922, 74875.3672,
-    74880.9297, 74884.3359, 74881.9844, 74881.9844, 74885.4297, 74891.7578,
-    74884.8594, 74891.8828, 74900.7656, 74900.7656, 74921.6562, 74918.6094,
-    74926.9297, 74935.125,  74941.6953, 74941.6953, 74934.9766, 74948.2031,
-    74949.7031, 74956.1172, 74965.5703, 74965.5703, 74969.25,   74983.3281,
-    74999.6797, 74992.375,  74996.8047, 74996.8047, 75006.1719, 75013.2734,
-    75014.0469, 75013.0312, 75026.2188, 75026.2188, 75029.5312, 75028.7578,
-    75027.7891, 75032.4922, 75039.2266, 75039.2266, 75045.6797, 75036.5547,
-    75045.6406, 75051.6484, 75051.6094, 75051.6094, 75059.3828, 75065.3438,
-    75058.4844, 75051.8359, 75052.8906, 75052.8906, 75024.0391, 75043.875,
-    75050.8125, 75065.5781, 75075.9297, 75075.9297, 75094.9609, 75100.6406,
-    75108.4375, 75111.5547, 75116.75,   75116.75,   75143.6172, 75143.9375,
-    75147.9141, 75156.6406, 75155.9922, 75155.9922, 75159.3438, 75159.2188,
-    75166.6875, 75176.9531, 75172.6094, 75172.6094, 75201.125,  75193.2969,
-    75184.8516, 75193.0938, 75199.4219, 75199.4219, 75172.7578, 75155.3047,
-    75146.8672, 75151.7812, 75152.2656, 75152.2656, 75150.2109, 75151.9141,
-    75154.5547, 75181.4141, 75177.8438, 75177.8438, 75176.625,  75180.3516,
-    75171.6719, 75178.7734, 75171.5078, 75171.5078, 75171.9219, 75189.0859,
-    75193.6719, 75209.8203, 75232.0078, 75232.0078, 75222.2188, 75246.1562,
-    75246.0312, 75253.4219, 75271.4766, 75271.4766, 75290.1719, 75292.2422,
-    75291.875,  75289.8828, 75292.3203, 75292.3203, 75299.9297, 75297.9062,
-    75285.5312, 75299.6875, 75301.2344, 75301.2344, 75286.3672, 75289.2031,
-    75303.8516, 75275.3281, 75281.375,  75281.375,  75315.3594, 75296.8203,
-    75279.6562, 75290.1641, 75290.7344, 75290.7344, 75296.1875, 75308.5234,
-    75319.1094, 75316.1094, 75332.5,    75332.5,    75366.2969, 75350.5547,
-    75338.3438, 75359.8516, 75375.3047, 75375.3047, 75391.125,  75388.4844,
-    75393.2734, 75410.4375, 75409.625,  75409.625,  75408.7812, 75428.5859,
-    75421.5625, 75437.7578, 75454.5938, 75454.5938, 75436.0781, 75440.0078,
-    75454.0938, 75457.5391, 75476.8906, 75476.8906, 75489.8359, 75487.2031,
-    75497.5078, 75501.3984, 75502.4141, 75502.4141, 75521.4453, 75519.7812,
-    75517.3906, 75527.0469, 75532.1953, 75532.1953, 75547.9141, 75553.7969,
-    75556.1484, 75557.4062, 75559.2734, 75559.2734, 75564.0312, 75565.3672,
-    75570.7656, 75577.4609, 75593.5312, 75593.5312, 75591.375,  75595.3906,
-    75601.0312, 75597.1328, 75614.3438, 75614.3438, 75622.9141, 75619.0547,
-    75612.2031, 75617.9609, 75627.4609, 75627.4609, 75641.0547, 75641.4141,
-    75637.8047, 75651.9688, 75639.5469, 75639.5469, 75661.9531, 75664.5547,
-    75665.1641, 75671.1641, 75673.0703, 75673.0703, 75690.2109, 75691.5938,
-    75682.3828, 75684.0078, 75694.7578, 75694.7578, 75683.1875, 75678.4375,
-    75688.0938, 75686.6719, 75700.2266, 75700.2266, 75717.1797, 75724.8906,
-    75715.5547, 75709.6719, 75692.1016, 75692.1016, 75707.2344, 75701.7188,
-    75708.7344, 75717.2969, 75733.125,  75733.125,  75755.875,  75749.9062,
-    75756.3984, 75769.1016, 75768.2891, 75768.2891, 75788,      75787.6016,
-    75795.3438, 75808.4531, 75799.3672, 75799.3672, 75800.5391, 75800.0547,
-    75807.4766, 75805.4922, 75804.3906, 75804.3906, 75803.6953, 75794.0391,
-    75766.2031, 75775.1719, 75779.9609, 75779.9609, 75808.8359, 75796.1328,
-    75760.1484, 75757.0625, 75781.0859, 75781.0859, 75821.0859, 75828.0625,
-    75840.9219, 75867.2578, 75859.7891, 75859.7891, 75863.4922, 75886.1328,
-    75884.3906, 75893.1484, 75903.6172, 75903.6172, 75931.4844, 75927.7109,
-    75931.4453, 75940.8594, 75950.6797, 75950.6797, 75956.1797, 75948.3438,
-    75959.625,  75962.5859, 75973.0938, 75973.0938, 75973.8047, 75978.1875,
-    75976.1172, 75981.2266, 75983.2188, 75983.2188, 75996.2812, 76001.3516,
-    76000.5859, 76007.6406, 76007.7656, 76007.7656, 76018.75,   76021.5859,
-    76032.0547, 76032.3828, 76038.75,   76038.75,   76053.0234, 76054.2812,
-    76063.3281, 76060.2031, 76071.4062, 76071.4062, 76079.5938, 76073.7109,
-    76079.5938, 76081.2969, 76090.3906, 76090.3906, 76095.3047, 76094.4141,
-    76097.7812, 76099.6484, 76095.3047, 76095.3047, 76109.1797, 76117.2109,
-    76121.6797, 76118.4688, 76132.875,  76132.875,  76145.8672, 76140.6328,
-    76145.9922, 76145.1328, 76148.4609, 76148.4609, 76142.1094, 76142.8828,
-    76161.9141, 76156.1484, 76165.0781, 76165.0781, 76161.0156, 76169.6172,
-    76175.9062, 76174.1641, 76175.5859, 76175.5859, 76184.6953, 76182.2969,
-    76181.8906, 76178.4453, 76180.0703, 76180.0703, 76192.2344, 76191.9531,
-    76199.0078, 76205.5391, 76212.4375, 76212.4375, 76225.1562, 76227.7109,
-    76230.4766, 76238.5078, 76240.6953, 76240.6953, 76258.6094, 76264.4531,
-    76262.6641, 76262.1016, 76269.1953, 76269.1953, 76282.0234, 76284.6641,
-    76291.7656, 76284.2188, 76287.5391, 76287.5391, 76285.8125, 76289.0625,
-    76292.2656, 76298.3125, 76292.2656, 76292.2656, 76316.7656, 76312.1797,
-    76317.4141, 76323.8672, 76321.2734, 76321.2734, 76334.8359, 76330.6562,
-    76335.1562, 76343.8359, 76344.6953, 76344.6953, 76343.0781, 76351.8828,
-    76340.3594, 76339.4688, 76335.0078, 76335.0078, 76323.7812, 76329.4688,
-    76335.5547, 76356.0781, 76373.4062, 76373.4062, 76368.75,   76377.4766,
-    76378.6094, 76386.0391, 76391.1094, 76391.1094, 76411.7969, 76408.4688,
-    76401.3672, 76394.9609, 76412.2031, 76412.2031, 76398.0703, 76407.9297,
-    76418.5625, 76390.8906, 76385.1719, 76385.1719, 76383.4453, 76408.3594,
-    76387.75,   76365.6328, 76386.8984, 76386.8984, 76388.7109, 76397.6797,
-    76396.4219, 76408.1875, 76434.2734, 76434.2734, 76437.6797, 76461.6172,
-    76473.625,  76455.3672, 76465.4688, 76465.4688, 76480.7109, 76489.0703,
-    76492.7969, 76511.7891, 76520.5938, 76520.5938, 76517.6406, 76544.4609,
-    76538.25,   76568.1562, 76561.2969, 76561.2969, 76545.4219, 76537.5469,
-    76549.0312, 76568.1016, 76561.125,  76561.125,  76570.8672, 76569.2031,
-    76590.1797, 76594.8047, 76610.9531, 76610.9531, 76621.9688, 76624.1172,
-    76623.5859, 76629.2266, 76637.9922, 76637.9922, 76650.2734, 76650.3594,
-    76669.4219, 76666.1406, 76671.8203, 76671.8203, 76697.0938, 76691.7734,
-    76698.1484, 76703.4609, 76708.5312, 76708.5312, 76718.0625, 76716.1094,
-    76709.2109, 76711.6484, 76707.5938, 76707.5938, 76719.75,   76724.4922,
-    76733.1328, 76738.1641, 76739.875,  76739.875,  76745.5,    76755.9219,
-    76769.9219, 76763.6719, 76768.7891, 76768.7891, 76757.9453, 76745.0469,
-    76738.1875, 76744.7656, 76748.8984, 76748.8984, 76727.8984, 76731.1484,
-    76742.3047, 76734.2266, 76735.1641, 76735.1641, 76703.7734, 76717.1172,
-    76714.9297, 76710.3047, 76722.9609, 76722.9609, 76716.3594, 76700.1719,
-    76691.3672, 76694.4922, 76709.5469, 76709.5469, 76718.0859, 76733.8672,
-    76756.3047, 76752.375,  76731.8047, 76731.8047, 76773.3594, 76756.0391,
-    76773.8125, 76786.1016, 76803.1875, 76803.1875, 76807.6797, 76805.2891,
-    76819.6953, 76825.4922, 76845.6562, 76845.6562, 76834.5625, 76830.2656,
-    76849.25,   76825.4766, 76827.75,   76827.75,   76841.1875, 76817.2109,
-    76861.3516, 76876.6094, 76866.625,  76866.625,  76875.0547, 76900.7422,
-    76899.6016, 76902.5625, 76918.4688, 76918.4688, 76919.1562, 76931.8125,
-    76939.4375, 76955.1797, 76973.4375, 76973.4375, 76988.5703, 76984.7578,
-    76988.125,  77008.0859, 77006.9531, 77006.9531, 77021.2969, 77015.8594,
-    77020.5234, 77024.1406, 77036.2656, 77036.2656, 77038.0469, 77041.5781,
-    77049.9766, 77051.6797, 77059.7109, 77059.7109, 77059.5391, 77062.5391,
-    77060.1484, 77070.6562, 77071.8281, 77071.8281, 77081.2031, 77071.9141,
-    77085.4219, 77094.6328, 77097.8359, 77097.8359, 77101.2031, 77103.6406,
-    77106.5156, 77110.3359, 77111.1016, 77111.1016, 77127,      77116.3281,
-    77121.6094, 77127.8516, 77125.7031, 77125.7031, 77141.0234, 77132.0156,
-    77140.4922, 77131.4453, 77140.0078, 77140.0078, 77146.1562, 77144.1719,
-    77150.7812, 77161.25,   77163.3203, 77163.3203, 77179.5,    77179.6641,
-    77172.4375, 77171.5078, 77177.0234, 77177.0234, 77197,      77202.3203,
-    77209.7812, 77217.1641, 77230.5938, 77230.5938, 77219.1328, 77233.1328,
-    77232.8047, 77234.5469, 77243.2734, 77243.2734, 77245.1562, 77245.4453,
-    77256.2344, 77268.6094, 77269.9062, 77269.9062, 77272.9609, 77265.2109,
-    77275.7578, 77287.8906, 77285.2578, 77285.2578, 77286.0781, 77286.7344,
-    77274.3984, 77276.2266, 77291.5156, 77291.5156, 77316.3828, 77305.5078,
-    77303.8047, 77305.4688, 77298.4453, 77298.4453, 77285.5859, 77304.25,
-    77315.6953, 77321.7812, 77322.0625, 77322.0625, 77330.5,    77338.4922,
-    77361.0938, 77354.7656, 77355.8594, 77355.8594, 77338.3516, 77338.2266,
-    77333.1172, 77345.6094, 77340.5,    77340.5,    77328.0859, 77336.4062,
-    77350.8125, 77344.3203, 77380.1016, 77380.1016, 77356.4453, 77335.7109,
-    77336.8125, 77327.3125, 77350.6406, 77350.6406, 77346.6016, 77346.3594,
-    77366.7656, 77369.8906, 77366.2422, 77366.2422, 77398.6172, 77375.7344,
-    77368.8828, 77358.3281, 77396.3438, 77396.3438, 77383.0391, 77377.4375,
-    77374.9219, 77383.7266, 77381.0469, 77381.0469, 77410.6484, 77406.0234,
-    77411.5859, 77394.0156, 77421.3203, 77421.3203, 77440.7031, 77429.0156,
-    77412.625,  77441.5078, 77453.3984, 77453.3984, 77447.3906, 77469.9531,
-    77465.7734, 77435.0625, 77484.4375, 77484.4375, 77469.2969, 77467.5547,
-    77480.0547, 77480.8203, 77500.0547, 77500.0547, 77502.2031, 77524.2734,
-    77531.9375, 77528.0469, 77552.2266, 77552.2266, 77581.5938, 77578.2266,
-    77599.7734, 77602.9766, 77589.1875, 77589.1875, 77630.4688, 77629.25,
-    77638.8672, 77641.9453, 77646.5312, 77646.5312, 77650.5938, 77668.8906,
-    77681.6719, 77682.2812, 77671.8516, 77671.8516, 77691.6953, 77693.1172,
-    77690.8828, 77691.5312, 77702.4062, 77702.4062, 77702.7656, 77714.1641,
-    77710.6719, 77715.9531, 77722.2422, 77722.2422, 77721.7344, 77726.1172,
-    77739.5469, 77738.4453, 77747.1719, 77747.1719, 77750.6562, 77743.4375,
-    77755.4453, 77751.875,  77758.4062, 77758.4062, 77759.7266, 77772.3906,
-    77770.8438, 77770.8047, 77777.9453, 77777.9453, 77791.6797, 77793.0156,
-    77795.5312, 77802.3125, 77800.0391, 77800.0391, 77814.2344, 77821.4531,
-    77821.375,  77820.6406, 77818.3281, 77818.3281, 77835.9375, 77832.9766,
-    77834.4766, 77837.4453, 77843.3281, 77843.3281, 77857.3281, 77858.6641,
-    77858.1016, 77860.4922, 77863.7344, 77863.7344, 77860.3438, 77858.3984,
-    77867.7266, 77881.6797, 77885.2969, 77885.2969, 77906.7031, 77897.0078,
-    77913.8047, 77906.5391, 77913.6797, 77913.6797, 77912.3047, 77916.5703,
-    77916.6875, 77923.1406, 77924.0703, 77924.0703, 77929.7266, 77931.75,
-    77933.9844, 77928.3438, 77935.0781, 77935.0781, 77914.6641, 77931.8203,
-    77925.2891, 77934.1719, 77941.4375, 77941.4375, 77954.9219, 77951.6719,
-    77939.5,    77946.8047, 77950.0938, 77950.0938, 77961.2109, 77966.4453,
-    77971.7578, 77976.1406, 77988.3516, 77988.3516, 77989.2188, 77994.4141,
-    77999.6875, 78022.8125, 78013.9297, 78013.9297, 78027.9531, 78036.1484,
-    78037.8906, 78030.4688, 78025.6016, 78025.6016, 78028.75,   78041.2031,
-    78056.0156, 78056.3828, 78079.7109, 78079.7109, 78071.4375, 78090.9531,
-    78108.0781, 78116.5156, 78117.0391, 78117.0391, 78121.5781, 78127.0156,
-    78134.0312, 78132.3281, 78130.8281, 78130.8281, 78146.4375, 78147.375,
-    78149.9297, 78160.1562, 78164.3281, 78164.3281, 78171.1875, 78180.7578,
-    78182.3438, 78186.2812, 78197.5156, 78197.5156, 78198.1953, 78209.0312,
-    78218.1172, 78219.2109, 78235.7266, 78235.7266, 78233.2891, 78243.1484,
-    78231.1016, 78245.2578, 78247.6953, 78247.6953, 78259.2109, 78259.8984,
-    78258.4766, 78266.3516, 78275.5547, 78275.5547, 78270.4453, 78282.0469,
-    78275.4297, 78273.4844, 78262.8984, 78262.8984, 78267.0938, 78261.5,
-    78259.4297, 78251.9688, 78247.4609, 78247.4609, 78254.6953, 78258.7188,
-    78274.0469, 78275.875,  78277.4531, 78277.4531, 78319.4375, 78316.6797,
-    78317.2891, 78328.1172, 78325.9688, 78325.9688, 78333.8828, 78343.3828,
-    78360.1797, 78370.9688, 78373.4844, 78373.4844, 78379.3047, 78389.9375,
-    78393.7891, 78393.8281, 78398.1719, 78398.1719, 78386.3281, 78377.3594,
-    78371.5234, 78379.4297, 78377,      78377,      78432.1875, 78413.3203,
-    78409.1797, 78416.2031, 78411.0078, 78411.0078, 78434.3594, 78448.2734,
-    78447.0156, 78445.1875, 78458.4922, 78458.4922, 78452.6797, 78469.5625,
-    78470.4922, 78464.2422, 78491.9141, 78491.9141, 78485.6016, 78498.9062,
-    78506.4922, 78508.1953, 78511.7266, 78511.7266, 78516.3984, 78524.9531,
-    78519.3984, 78525.9688, 78544.8359, 78544.8359, 78538.7812, 78541.1328,
-    78541.5391, 78549.6094, 78556.3047, 78556.3047, 78569.4531, 78570.6328,
-    78571.9297, 78570.5469, 78580.5703, 78580.5703, 78593.4531, 78604.1641,
-    78605.2578, 78589.6406, 78595.9688, 78595.9688, 78589.6641, 78595.0938,
-    78601.5469, 78612.0547, 78620.4922, 78620.4922, 78639.8203, 78642.0078,
-    78647.2031, 78650.6484, 78642.25,   78642.25,   78658.7031, 78662.3125,
-    78661.9062, 78668.7656, 78681.1406, 78681.1406, 78680.4375, 78676.9922,
-    78697.2734, 78703.6484, 78703.8906, 78703.8906, 78710.9219, 78703.9844,
-    78712.7109, 78698.5938, 78708.3281, 78708.3281, 78723.0312, 78715.5625,
-    78726.4766, 78728.8281, 78733.9844, 78733.9844, 78715.9297, 78718.8516,
-    78729.8438, 78739.9922, 78753.7031, 78753.7031, 78790.8359, 78796.1094,
-    78809.9453, 78811.7656, 78810.1406, 78810.1406, 78810.4609, 78803.1953,
-    78807.375,  78806,      78802.0625, 78802.0625, 78820.8438, 78827.1719,
-    78831.6406, 78833.3047, 78840.0391, 78840.0391, 78851.9141, 78862.1797,
-    78865.5469, 78869.5234, 78882.5078, 78882.5078, 78900.4375, 78904.0938,
-    78898.9766, 78907.6172, 78901.8203, 78901.8203, 78921.1719, 78915.4922,
-    78921.8984, 78916.1406, 78915.0469, 78915.0469, 78926.0938, 78923.9844,
-    78911.6875, 78921.2188, 78932.9844, 78932.9844, 78929.8125, 78931.6016,
-    78940.4844, 78946.2031, 78942.9219, 78942.9219, 78950.1641, 78952.8828,
-    78962.6953, 78966.3516, 78962.2891, 78962.2891, 78968.125,  78988.6094,
-    78982.7266, 78983.9453, 78980.5,    78980.5,    78985.7031, 78998.1172,
-    79004.1641, 79006.1094, 79004.8906, 79004.8906, 79015.9297, 79010.8984,
-    78998.6094, 79012.2344, 79014.3906, 79014.3906, 79016.5938, 79017.8984,
-    79025.7656, 79050.3516, 79041.3828, 79041.3828, 79050.3906, 79068.1641,
-    79058.8281, 79070.5156, 79073.6406, 79073.6406, 79066.6641, 79084.5156,
-    79091.375,  79099.0781, 79106.1016, 79106.1016, 79105.2578, 79110.5703,
-    79108.1406, 79115.1172, 79127.9375, 79127.9375, 79148.6484, 79132.8281,
-    79138.75,   79153.9688, 79158.7109, 79158.7109, 79168.9531, 79173.0547,
-    79177.7969, 79170.1328, 79182.8672, 79182.8672, 79182.3438, 79194.3906,
-    79192.1641, 79192.8516, 79190.3359, 79190.3359, 79177.6328, 79158.4453,
-    79167,      79146.4375, 79184.6484, 79184.6484, 79139.7422, 79146.9219,
-    79171.9141, 79173.2891, 79155.8828, 79155.8828, 79155.0234, 79176.5703,
-    79177.8281, 79178.7578, 79209.7969, 79209.7969, 79208.1406, 79235.9297,
-    79248.1406, 79248.75,   79253.2109, 79253.2109, 79276.7031, 79277.4375,
-    79293.5,    79305.4688, 79307.6562, 79307.6562, 79333.2109, 79334.8359,
-    79325.5,    79335.9297, 79340.6328, 79340.6328, 79345.1484, 79355.25,
-    79354.4766, 79357.3594, 79368.875,  79368.875,  79369.6016, 79377.6328,
-    79378.6094, 79379.7422, 79375.8906, 79375.8906, 79380.2656, 79385.6562,
-    79372.1484, 79392.4766, 79409.3516, 79409.3516, 79429.75,   79441.1875,
-    79443.7031, 79444.0312, 79450.7188, 79450.7188, 79463.1406, 79463.8672,
-    79471.1328, 79473.4062, 79463.0547, 79463.0547, 79481.4062, 79485.5391,
-    79483.0703, 79491.0156, 79491.5859, 79491.5859, 79498.7266, 79514.2188,
-    79505.1328, 79511.3359, 79522.8203, 79522.8203, 79526.6953, 79525.6797,
-    79545.3203, 79538.4609, 79538.8281, 79538.8281, 79558.5078, 79554.5703,
-    79561.1875, 79558.2656, 79559.7266, 79559.7266, 79574.2656, 79566.3984,
-    79575.3984, 79581.5703, 79578.5234, 79578.5234, 79591.2266, 79595.4844,
-    79600.7188, 79592.5234, 79600.1953, 79600.1953, 79599.4219, 79592.6484,
-    79594.1094, 79589.3594, 79599.2188, 79599.2188, 79619.25,   79625.8203,
-    79618.8438, 79641.8828, 79644.3594, 79644.3594, 79665.0078, 79679.3281,
-    79677.7422, 79683.3828, 79678.4766, 79678.4766, 79696.7109, 79694.4844,
-    79715.8984, 79724.375,  79705.0703, 79705.0703, 79705.5234, 79692.2188,
-    79682.7266, 79657.9375, 79666.9453, 79666.9453, 79680.3047, 79695.5156,
-    79701.3594, 79711.375,  79710.5625, 79710.5625, 79693.2656, 79695.5781,
-    79694.0781, 79709.4531, 79690.7969, 79690.7969, 79716.3828, 79703.9297,
-    79740.3203, 79737.9609, 79729.0781, 79729.0781, 79709.3906, 79724.5625,
-    79735.7188, 79733.0781, 79751.7812, 79751.7812, 79755.7188, 79773.4453,
-    79773.125,  79755.3516, 79754.625,  79754.625,  79790.2578, 79791.7578,
-    79788.0625, 79799.9141, 79814.3516, 79814.3516, 79803.2656, 79821.3984,
-    79786.5938, 79821.7656, 79824.5234, 79824.5234, 79811.125,  79802.2031,
-    79822.9297, 79817.7812, 79837.0859, 79837.0859, 79855.2656, 79864.2656,
-    79876.1953, 79868.8125, 79892.3359, 79892.3359, 79918.2578, 79917.8516,
-    79921.3047, 79927.4688, 79932.5391, 79932.5391, 79937.7188, 79939.6328,
-    79934.9609, 79948.3516, 79970.7422, 79970.7422, 79961.2969, 79974.4375,
-    79974.1562, 79965.7188, 79975.0469, 79975.0469, 79979.9609, 79984.5078,
-    79989.5391, 79995.6641, 79996.0703, 79996.0703, 80000.4922, 80007.4297,
-    80010.1484, 80016.7188, 80018.0547, 80018.0547, 80039.0859, 80031.5859,
-    80021.5234, 80025.6641, 80030.2031, 80030.2031, 80038.9141, 80019.2344,
-    80027.9609, 80028.0781, 80034.3281, 80034.3281, 80045.8672, 80032.8438,
-    80033.4922, 80055.9297, 80079.5391, 80079.5391, 80098.6172, 80080.8906,
-    80092.9375, 80107.1328, 80126.9688, 80126.9688, 80132.5469, 80132.5078,
-    80120.4219, 80120.6641, 80127.7656, 80127.7656, 80132.8281, 80141.5469,
-    80141.9531, 80160.6953, 80150.5938, 80150.5938, 80160.9609, 80160.3906,
-    80174.0234, 80187.1641, 80174.1484, 80174.1484, 80189.875,  80190.6094,
-    80193.4453, 80178.6016, 80200.625,  80200.625,  80212.8203, 80204.3828,
-    80209.0078, 80214.1953, 80225.9219, 80225.9219, 80224.3047, 80224.0625,
-    80238.0938, 80239.0234, 80236.3906, 80236.3906, 80254.3281, 80261.0234,
-    80261.7109, 80284.3047, 80281.75,   80281.75,   80300.4688, 80296.7031,
-    80313.2109, 80303.5938, 80304.6484, 80304.6484, 80326.0391, 80339.5469,
-    80332.5234, 80337.0703, 80342.5469, 80342.5469, 80358.6641, 80354.6875,
-    80366.3281, 80367.8672, 80374.6797, 80374.6797, 80371.0938, 80374.5,
-    80373,      80391.4609, 80407.9688, 80407.9688, 80399.9766, 80411.5,
-    80416.5703, 80412.7578, 80421.1484, 80421.1484, 80430.3125, 80426.0469,
-    80423.1719, 80434.8516, 80427.9141, 80427.9141, 80449.3516, 80453.3672,
-    80463.9141, 80456.9766, 80466.5938, 80466.5938, 80481.3281, 80486.1953,
-    80494.7578, 80491.1875, 80499.5391, 80499.5391, 80499.9062, 80508.75,
-    80508.0234, 80505.5078, 80520.9219, 80520.9219, 80534.5156, 80533.3047,
-    80540.2344, 80536.75,   80525.3125, 80525.3125, 80552.0859, 80551.3125,
-    80542.0234, 80562.1797, 80568.7969, 80568.7969, 80576.7891, 80586.1562,
-    80580.5156, 80578.3281, 80601.6094, 80601.6094, 80599.5703, 80601.6406,
-    80608.0938, 80603.6328, 80606.3906, 80606.3906, 80607.7578, 80618.9141,
-    80614.0859, 80618.7109, 80608.6484, 80608.6484, 80639.3125, 80645.2344,
-    80643.7344, 80645.4766, 80638.7422, 80638.7422, 80636.0469, 80659.3672,
-    80664.6406, 80666.4297, 80675.0703, 80675.0703, 80679.8672, 80681.8906,
-    80672.9688, 80659.8281, 80651.5078, 80651.5078, 80666.9453, 80675.9531,
-    80655.0625, 80660.4531, 80692.625,  80692.625,  80709.3203, 80706.8906,
-    80698.9766, 80719.6641, 80731.2266, 80731.2266, 80740.2188, 80733.0859,
-    80737.1406, 80742.6953, 80754.3359, 80754.3359, 80758.8828, 80776.2031,
-    80778.5938, 80792.0234, 80794.1328, 80794.1328, 80805.5391, 80811.8672,
-    80821.2734, 80824.7656, 80830.7656, 80830.7656, 80837.6641, 80833.2031,
-    80844.0703, 80840.6641, 80842.6094, 80842.6094, 80834.8594, 80821.5156,
-    80831.9766, 80846.4609, 80839.9688, 80839.9688, 80827.5,    80831.9609,
-    80858.7266, 80860.3906, 80857.3906, 80857.3906, 80875.0625, 80866.9062,
-    80884.4688, 80904.6328, 80910.2266, 80910.2266, 80913.1953, 80923.2109,
-    80917.1328, 80922.6016, 80933.0312, 80933.0312, 80953.5547, 80944.8359,
-    80969.6172, 80957,      80966.125,  80966.125,  80970.2812, 80968.7812,
-    80972.3906, 80969.6797, 80976.5312, 80976.5312, 80989.0078, 80976.8359,
-    80985.0312, 80986.8594, 80997.3203, 80997.3203, 80988.5781, 80995.6797,
-    81014.4609, 81023.8281, 81017.4219, 81017.4219, 81041.875,  81055.7031,
-    81049.5391, 81073.875,  81072.9062, 81072.9062, 81072.0391, 81078.2891,
-    81083.1094, 81081.5703, 81092.6406, 81092.6406, 81102.75,   81102.5859,
-    81102.1406, 81107.6172, 81109.6016, 81109.6016, 81120.4688, 81125.4141,
-    81117.3828, 81116.9766, 81118.2344, 81118.2344, 81135.5078, 81134.9062,
-    81138.9609, 81127.3984, 81146.0547, 81146.0547, 81153.2812, 81139.5703,
-    81163.8281, 81168.2891, 81163.8281, 81163.8281, 81181.2188, 81181.7891,
-    81181.8672, 81189.8594, 81210.2578, 81210.2578, 81222.1328, 81225.9062,
-    81241.0781, 81241.3984, 81245.0078, 81245.0078, 81250.6641, 81252.125,
-    81264.1719, 81270.6172, 81271.2656, 81271.2656, 81267.4688, 81273.0312,
-    81265.3672, 81267.875,  81261.1875, 81261.1875, 81298.9531, 81287.5547,
-    81292.3047, 81292.1797, 81280.1797, 81280.1797, 81305.7578, 81305.5547,
-    81323.6016, 81322.6719, 81325.1406, 81325.1406, 81344.9531, 81351.2344,
-    81360.8906, 81357.3594, 81370.625,  81370.625,  81376.0938, 81373.9844,
-    81384.2422, 81389.0703, 81380.1875, 81380.1875, 81389.9609, 81383.1875,
-    81385.9922, 81386.0312, 81386.5938, 81386.5938, 81379.3125, 81363.5703,
-    81364.2188, 81356.5938, 81352.9844, 81352.9844, 81364.4531, 81348.8438,
-    81372.0391, 81408.5,    81399.0938, 81399.0938, 81408.9531, 81414.0703,
-    81449.7578, 81455.2734, 81462.0859, 81462.0859, 81485.8516, 81476.6875,
-    81482.1641, 81478.0234, 81482.1641, 81482.1641, 81495.1875, 81500.4219,
-    81503.9922, 81522.6094, 81526.0547, 81526.0547, 81544.3828, 81538.8672,
-    81540.6094, 81553.7109, 81555.4922, 81555.4922, 81570.2031, 81583.0234,
-    81578.5234, 81582.0469, 81588.3359, 81588.3359, 81583.8359, 81598.9609,
-    81601.8828, 81607.5156, 81611.0859, 81611.0859, 81613.75,   81618.4141,
-    81624.7422, 81625.1875, 81632.4922, 81632.4922, 81649.8984, 81633.2734,
-    81647.8359, 81653.1016, 81650.4297, 81650.4297, 81660.3516, 81644.9766,
-    81641.9375, 81640.9219, 81653.6562, 81653.6562, 81643.4844, 81646.4062,
-    81640.2031, 81647.1797, 81644.5391, 81644.5391, 81640.7031, 81643.6641,
-    81636.6875, 81654.2109, 81670.5156, 81670.5156, 81657.9609, 81661.8594,
-    81658.1641, 81671.3438, 81682.5,    81682.5,    81688.2891, 81711.1641,
-    81690.6406, 81704.9531, 81709.6562, 81709.6562, 81724.8047, 81742.9766,
-    81745.9375, 81743.5859, 81755.3906, 81755.3906, 81784.8594, 81779.75,
-    81792.4375, 81796.9453, 81802.9062, 81802.9062, 81818.1875, 81811.1328,
-    81822.3281, 81820.9922, 81835.5469, 81835.5469, 81842.4141, 81840.75,
-    81846.3125, 81837.9141, 81850,      81850,      81868.1016, 81870.4062,
-    81881.8438, 81872.6016, 81866.7578, 81866.7578, 81872.4844, 81890.7734,
-    81887.8125, 81881.6484, 81877.3516, 81877.3516, 81881.6172, 81884.6172,
-    81880.6016, 81900.0312, 81923.5938, 81923.5938, 81923.7734, 81941.9062,
-    81939.9141, 81948.2734, 81955.4062, 81955.4062, 81964.2734, 81962.9766,
-    81961.5938, 81944.8047, 81943.1406, 81943.1406, 81934.1328, 81921.8828,
-    81937.5781, 81962.2812, 81956.3203, 81956.3203, 81974.3125, 81992.3203,
-    82006.2344, 82020.0234, 82005.7031, 82005.7031, 81999.8828, 81969.9062,
-    81961.8359, 81956.7266, 81963.6641, 81963.6641, 81930.5469, 81898.3828,
-    81912.7031, 81899.0312, 81941.8203, 81941.8203, 81985.6875, 82049.4375,
-    82025.1094, 82031.9609, 82063.2734, 82063.2734, 82114.7812, 82108.375,
-    82105.9844, 82105.25,   82126.3828, 82126.3828, 82131.7969, 82135.1641,
-    82144.1641, 82141.6562, 82132.8906, 82132.8906, 82140.5859, 82144.2344,
-    82149.6719, 82156.9688, 82154.2891, 82154.2891, 82160.6406, 82145.6719,
-    82154.4375, 82151.8828, 82160.2344, 82160.2344, 82181.125,  82191.1406,
-    82184.8984, 82167.9062, 82169.5234, 82169.5234, 82197.9688, 82228.0156,
-    82235.1172, 82244.9688, 82239.4141, 82239.4141, 82222.2188, 82228.5859,
-    82227.2031, 82223.0234, 82234.3047, 82234.3047, 82237.3828, 82243.7891,
-    82254.375,  82252.2266, 82206.7656, 82206.7656, 82232.1719, 82268.6719,
-    82254.1172, 82273.0156, 82270.7812, 82270.7812, 82285.6172, 82271.4688,
-    82277.0625, 82275.1953, 82272.4766, 82272.4766, 82288,      82288.1641,
-    82294.4844, 82290.4766, 82288.3672, 82288.3672, 82288.7422, 82285.5312,
-    82293.6484, 82293.9297, 82296.8516, 82296.8516, 82292.9375, 82294.9297,
-    82294.7266, 82298.1328, 82307.6172, 82307.6172, 82307.6016, 82309.1016,
-    82310.4375, 82306.6641, 82310.3984, 82310.3984, 82311.2266, 82312.1953,
-    82312.9297, 82310.2891, 82313.0859, 82313.0859, 82317.3438, 82317.3828,
-    82316.4453, 82320.5859, 82324.5625, 82324.5625, 82324.3047, 82327.4688,
-    82325.0703, 82327.9531, 82327.6641, 82327.6641, 82330.5859, 82335.7344,
-    82333.4219, 82336.7109, 82336.3828, 82336.3828, 82343.7266, 82339.1797,
-    82337.1172, 82345.0234, 82342.3828, 82342.3828, 82346.2188, 82346.3438,
-    82351.5312, 82348.4922, 82352.2656, 82352.2656, 82356.0859, 82350.6562,
-    82355.2344, 82358.0781, 82350.8984, 82350.8984, 82361.1484, 82354.2969,
-    82357.375,  82356.8906, 82356.0781, 82356.0781, 82364.1484, 82367.0312,
-    82367.2734, 82367.9219, 82370.0312, 82370.0312, 82370.2109, 82369.8906,
-    82369.9688, 82366.3594, 82369.9688, 82369.9688, 82377.2969, 82375.7578,
-    82378.3516, 82377.0938, 82375.2266, 82375.2266, 82378.9922, 82381.9453,
-    82384.5469, 82384.9062, 82380.2422, 82380.2422, 82387.6953, 82386.3984,
-    82389.0781, 82387.4922, 82395.1562, 82395.1562, 82404.1641, 82396.2969,
-    82402.0547, 82395.8516, 82398.7734, 82398.7734, 82400.6719, 82406.7109,
-    82410.1172, 82407.0781, 82412.0234, 82412.0234, 82411.1016, 82412.9297,
-    82412.3203, 82407.4922, 82416.8594, 82416.8594, 82421.4297, 82423.3359,
-    82419.4844, 82422.2812, 82423.0156, 82423.0156, 82430.4297, 82436.5156,
-    82429.6172, 82427.9141, 82423.5391, 82423.5391, 82431.3203, 82428.8828,
-    82430.9141, 82431.3984, 82429.6172, 82429.6172, 82435.2031, 82440.4766,
-    82439.7891, 82440.6406, 82439.2188, 82439.2188, 82440.6719, 82440.5938,
-    82440.4688, 82440.4297, 82440.7969, 82440.7969, 82444.6328, 82443.0156,
-    82446.5391, 82446.5391, 82453.1094, 82453.1094, 82453.0312, 82461.1016,
-    82456.4766, 82458.875,  82465.3984, 82465.3984, 82464.3906, 82461.2266,
-    82469.2578, 82458.4297, 82466.375,  82466.375,  82467.6094, 82474.5469,
-    82469.3516, 82470.9375, 82472.9219, 82472.9219, 82475.0078, 82477.6016,
-    82480.4375, 82477.7578, 82479.4219, 82479.4219, 82479.2344, 82480.7734,
-    82473.8359, 82479.3516, 82478.7031, 82478.7031, 82483.7891, 82484.8438,
-    82483.3438, 82484.0781, 82488.7422, 82488.7422, 82494.5078, 82494.9141,
-    82491.0625, 82494.8359, 82489.3594, 82489.3594, 82495,      82496.7812,
-    82502.6641, 82498.8516, 82501.8516, 82501.8516, 82510.0625, 82509.4141,
-    82509.9453, 82506.4141, 82516.8359, 82516.8359, 82520.5312, 82519.9219,
-    82521.7109, 82522.2734, 82520.4531, 82520.4531, 82522.9141, 82522.6719,
-    82516.7891, 82515.6094, 82518.6953, 82518.6953, 82518.6953, 82515.2891,
-    82521.5703, 82522.625,  82521.4531, 82521.4531, 82532.3516, 82531.0547,
-    82530.5234, 82539,      82539.4062, 82539.4062, 82538.5625, 82533.4922,
-    82539.4922, 82542.2109, 82538.3125, 82538.3125, 82544.8203, 82545.7969,
-    82546.1641, 82546.7266, 82546.7266, 82546.7266, 82546.3281, 82546.7734,
-    82557.1484, 82551.8828, 82549.5703, 82549.5703, 82562.5938, 82557.7266,
-    82560.9297, 82564.9453, 82568.7578, 82568.7578, 82563.1484, 82565.25,
-    82565.4141, 82563.3047, 82566.5547, 82566.5547, 82571.2578, 82567.6875,
-    82571.2578, 82574.9922, 82574.0938, 82574.0938, 82576.3438, 82573.7109,
-    82583.6016, 82581.7812, 82574.1562, 82574.1562, 82581.2578, 82587.2188,
-    82582.0312, 82587.4609, 82582.7188, 82582.7188, 82587.1094, 82587.875,
-    82585.6094, 82589.2188, 82589.7031, 82589.7031, 82602.4453, 82600.4609,
-    82598.8359, 82601.4766, 82600.3828, 82600.3828, 82603.5078, 82604.1562,
-    82603.2656, 82604.9297, 82602.7812, 82602.7812, 82607.5859, 82607.5859,
-    82607.9141, 82611.5234, 82608.4375, 82608.4375, 82619.2031, 82617.2969,
-    82619.8125, 82619.0391, 82618.4297, 82618.4297, 82622.1172, 82621.75,
-    82625.8516, 82624.875,  82627.7578, 82627.7578, 82628.7812, 82632.0703,
-    82626.6328, 82629.7578, 82627.4453, 82627.4453, 82633.6484, 82640.2188,
-    82637.5391, 82635.1875, 82643.8672, 82643.8672, 82641.8828, 82637.6641,
-    82647.0312, 82646.2578, 82648.4531, 82648.4531, 82653.3125, 82646.1719,
-    82648.5703, 82645.5234, 82647.1094, 82647.1094, 82654.1875, 82658.9297,
-    82653.5,    82652.0391, 82652.1172, 82652.1172, 82662.125,  82663.2656,
-    82657.8281, 82664.8047, 82663.9141, 82663.9141, 82671.4609, 82660.5156,
-    82669.9219, 82664.125,  82667.1641, 82667.1641, 82672.0234, 82666.7891,
-    82674.3281, 82676.7266, 82674.4141, 82674.4141, 82681.3984, 82676.2031,
-    82677.625,  82679.7344, 82677.4219, 82677.4219, 82684.9531, 82690.2266,
-    82686.4922, 82691.2812, 82690.0234, 82690.0234, 82693.2734, 82693.5547,
-    82698.3359, 82692.8672, 82693.7188, 82693.7188, 82701.3672, 82707.6172,
-    82702.0625, 82701.9375, 82710.25,   82710.25,   82709.6406, 82705.5859,
-    82711.5469, 82706.6406, 82713.1719, 82713.1719, 82714.5078, 82713.9062,
-    82719.4609, 82716.9844, 82720.6719, 82720.6719, 82720.8203, 82721.1875,
-    82720.375,  82721.5938, 82719.9297, 82719.9297, 82726.4297, 82724.2422,
-    82729.1094, 82727.6094, 82728.7422, 82728.7422, 82731.5703, 82730.1484,
-    82733.9219, 82735.1328, 82732.0938, 82732.0938, 82744.0938, 82740.8516,
-    82741.4141, 82741.9844, 82738.5391, 82738.5391, 82746.2578, 82747.0312,
-    82744.7188, 82754.8984, 82754.0859, 82754.0859, 82751.8594, 82752.4688,
-    82753.6875, 82753.5625, 82753.9688, 82753.9688, 82754.4766, 82760.5625,
-    82761.375,  82759.3438, 82762.0625, 82762.0625, 82765.0938, 82756.2578,
-    82764.4062, 82770.0859, 82768.75,   82768.75,   82769.3984, 82775.7656,
-    82772.4766, 82771.8281, 82775.1562, 82775.1562, 82778.2969, 82776.7578,
-    82780.4453, 82779.8359, 82782.5547, 82782.5547, 82789.0859, 82783.4141,
-    82791.5234, 82788.2812, 82787.0234, 82787.0234, 82792.2266, 82789.9531,
-    82794.0078, 82792.4688, 82794.0469, 82794.0469, 82795.7656, 82793.1719,
-    82797.4297, 82794.75,   82799.2578, 82799.2578, 82799.6953, 82803.5859,
-    82804.0781, 82799.8594, 82803.6328, 82803.6328, 82804.5312, 82801.4062,
-    82804.8516, 82803.8359, 82804.7734, 82804.7734, 82815.5781, 82812.9453,
-    82810.1094, 82812.9844, 82820.3672, 82820.3672, 82814.8984, 82813.4375,
-    82820.4922, 82817.3672, 82817.8984, 82817.8984, 82825.9609, 82821.5391,
-    82823.2812, 82822.3906, 82823,      82823,      82829.0859, 82827.1406,
-    82833.2656, 82829.3281, 82828.3203, 82828.3203, 82836.8125, 82838.7188,
-    82837.3359, 82841.1875, 82840.2578, 82840.2578, 82844.5234, 82841.8828,
-    82845.5781, 82847.8438, 82848.0469, 82848.0469, 82848.0703, 82845.5547,
-    82851.3516, 82850.3047, 82854.0312, 82854.0312, 82852.8203, 82853.5469,
-    82855.6562, 82849.1719, 82860.5234, 82860.5234, 82857.7109, 82857.3906,
-    82863.0625, 82862.8594, 82864.2031, 82864.2031, 82866.2578, 82862.7734,
-    82860.8672, 82864.9219, 82865.5703, 82865.5703, 82865.5547, 82862.1094,
-    82870.4609, 82871.2734, 82865.6328, 82865.6328, 82874.3203, 82878.4219,
-    82878.4219, 82879.4297, 82881.9062, 82881.9062, 82883.3516, 82883.2734,
-    82881.125,  82884.5703, 82886.1094, 82886.1094, 82887.9375, 82891.1797,
-    82890.4141, 82886.0312, 82891.7109, 82891.7109, 82893.3672, 82896.5703,
-    82892.4766, 82896.4922, 82893.7344, 82893.7344, 82894.7031, 82895.9531,
-    82901.0234, 82901.2656, 82897.5391, 82897.5391, 82908.1875, 82898.7031,
-    82904.4609, 82904.375,  82905.0703, 82905.0703, 82907.9531, 82903.8516,
-    82913.8672, 82908.8828, 82911.0312, 82911.0312, 82915.6641, 82910.1484,
-    82909.1797, 82899.4453, 82888.0078, 82888.0078, 82894.3359, 82902.8906,
-    82904.4688, 82908.5625, 82911.5625, 82911.5625, 82920.6875, 82921.9844,
-    82921.3359, 82921.2891, 82927.4531, 82927.4531, 82933.9062, 82932.1641,
-    82933.4609, 82930.1328, 82932.4453, 82932.4453, 82937.5547, 82936.6641,
-    82942.75,   82940.6016, 82936.5469, 82936.5469, 82944.6094, 82944.6484,
-    82940.2344, 82941.8906, 82942.4609, 82942.4609, 82952.3203, 82948.3906,
-    82946.1562, 82947.8984, 82947.5391, 82947.5391, 82954.3281, 82954.125,
-    82955.1406, 82954.3672, 82955.8672, 82955.8672, 82960.875,  82962.5391,
-    82959.7422, 82959.4922, 82962.5,    82962.5,    82965.3125, 82958.9062,
-    82963.7266, 82967.3359, 82966.3281, 82966.3281, 82966.6094, 82963.6016,
-    82968.1094, 82968.0625, 82968.7578, 82968.7578, 82973.9531, 82972.25,
-    82975.4922, 82974.6016, 82972.8594, 82972.8594, 82978.5547, 82973.2422,
-    82976.5625, 82978.7969, 82978.1094, 82978.1094, 82977.7266, 82979.7109,
-    82981.4922, 82983.8438, 82985.1406, 82985.1406, 82986.875,  82988.0078,
-    82981.8438, 82988.7812, 82986.9141, 82986.9141, 82989.6016, 82989.1562,
-    82993.375,  82991.4688, 82992.5625, 82992.5625, 82994.5469, 82998.7578,
-    82992.0312, 82996.6562, 83000.9141, 83000.9141, 83004.5156, 83002.9688,
-    83006.2188, 83007.9609, 83008.5234, 83008.5234, 83013.9844, 83007.6172,
-    83012.2422, 83008.875,  83011.9141, 83011.9141, 83018.4531, 83020.3984,
-    83018.0469, 83015.0859, 83014.1172, 83014.1172, 83024.4766, 83020.4609,
-    83025.4922, 83026.1016, 83022.5312, 83022.5312, 83026.375,  83028.8125,
-    83029.2969, 83031.125,  83027.4766, 83027.4766, 83033.5312, 83036.4531,
-    83036.6172, 83035.0312, 83041.8047, 83041.8047, 83036.7422, 83041.4922,
-    83042.3828, 83041.125,  83045.9062, 83045.9062, 83052,      83049.0859,
-    83044.5391, 83049.2422, 83052.4062, 83052.4062, 83048.7188, 83055.0859,
-    83050.5859, 83054.0703, 83052,      83052,      83055.8594, 83051.7266,
-    83056.1875, 83062.7578, 83058.9453, 83058.9453, 83063.1875, 83058.7266,
-    83061.0391, 83061.4844, 83064.0391, 83064.0391, 83070.9844, 83069.8438,
-    83070.1328, 83069.4375, 83070.1719, 83070.1719, 83068.1875, 83075.6875,
-    83074.6328, 83072.0781, 83076.5781, 83076.5781, 83083.9766, 83077.7734,
-    83075.2969, 83083.2109, 83082.3125, 83082.3125, 83087.9375, 83082.1797,
-    83088.5469, 83085.3828, 83091.1016, 83091.1016, 83089.9688, 83095.2812,
-    83091.5938, 83091.3047, 83095.7656, 83095.7656, 83099.3203, 83098.1484,
-    83101.6797, 83099.1641, 83098.3516, 83098.3516, 83098.3594, 83101.6875,
-    83101.1562, 83102.0547, 83107.8125, 83107.8125, 83104.8516, 83108.8281,
-    83106.9219, 83104.9297, 83115.3984, 83115.3984, 83116.8125, 83114.1328,
-    83118.1484, 83116.6094, 83116.6875, 83116.6875, 83117.1172, 83115.5312,
-    83120.0781, 83120.8047, 83119.4297, 83119.4297, 83122.8125, 83122.9375,
-    83124.6797, 83124.9219, 83127.1562, 83127.1562, 83129.125,  83128.6797,
-    83132.7344, 83128.8828, 83130.1797, 83130.1797, 83140.6641, 83136.3672,
-    83136.9766, 83138.3125, 83140.4609, 83140.4609, 83137.7734, 83144.2188,
-    83145.1953, 83142.8438, 83146.0078, 83146.0078, 83154.125,  83149.2188,
-    83154.125,  83149.5781, 83153.8828, 83153.8828, 83158.4141, 83155.5,
-    83158.0547, 83157.3594, 83158.6172, 83158.6172, 83159.6484, 83160.9844,
-    83160.7422, 83165.3672, 83161.3906, 83161.3906, 83165.4219, 83164.0391,
-    83165.3828, 83165.2578, 83169.4375, 83169.4375, 83165.8594, 83165.4922,
-    83168.4531, 83171.125,  83170.2734, 83170.2734, 83171.6172, 83166.2266,
-    83166.6719, 83169.5938, 83168.0156, 83168.0156, 83170.3047, 83174.6797,
-    83179.7891, 83178.3281, 83179.1016, 83179.1016, 83184.8516, 83187.6094,
-    83188.0156, 83189.3984, 83187.6953, 83187.6953, 83193.6328, 83195.7812,
-    83194.1953, 83194.8047, 83194.6016, 83194.6016, 83196.5234, 83197.2969,
-    83200.6641, 83201.6328, 83202.0781, 83202.0781, 83203.7266, 83202.5547,
-    83208.9219, 83206.7266, 83209.6875, 83209.6875, 83207.4766, 83208.3281,
-    83208.6953, 83206.9062, 83213.8438, 83213.8438, 83213.1719, 83209.4453,
-    83206.6484, 83209.7266, 83204.0078, 83204.0078, 83196.3828, 83189.4922,
-    83189.125,  83188.2734, 83190.8281, 83190.8281, 83189.4531, 83190.1406,
-    83191.1953, 83193.5469, 83187.6719, 83187.6719, 83196.1953, 83197.6172,
-    83194.8203, 83199.2812, 83195.2266, 83195.2266, 83204.1797, 83203.1641,
-    83201.4219, 83203.7344, 83208.5156, 83208.5156, 83223.25,   83220.25,
-    83230.7109, 83232.7812, 83235.0078, 83235.0078, 83245.0078, 83243.3047,
-    83247.3984, 83248.6562, 83252.6719, 83252.6719, 83252.7109, 83256.7266,
-    83260.5391, 83257.8594, 83255.3828, 83255.3828, 83260.9688, 83257.4453,
-    83262.1016, 83262.1875, 83263.6484, 83263.6484, 83268.9219, 83270.0547,
-    83263.6875, 83270.9453, 83270.2188, 83270.2188, 83273.6641, 83277.7969,
-    83279.8672, 83278.3281, 83276.2188, 83276.2188, 83283.7734, 83281.5859,
-    83278.1797, 83282.5156, 83283.8125, 83283.8125, 83277.9062, 83283.5859,
-    83281.3125, 83286.5469, 83284.8828, 83284.8828, 83287.7891, 83288.1094,
-    83292.5703, 83292.7734, 83289.6562, 83289.6562, 83292.9453, 83297.125,
-    83299.3516, 83293.4688, 83299.0312, 83299.0312, 83303.4609, 83304.5547,
-    83303.9062, 83303.0156, 83304.5156, 83304.5156, 83310.1875, 83310.4297,
-    83307.1875, 83308.6875, 83310.1016, 83310.1016, 83312.4062, 83317.4375,
-    83318.125,  83314.5547, 83316.2188, 83316.2188, 83319.5156, 83321.8281,
-    83323,      83320.3672, 83326.0469, 83326.0469, 83325.9688, 83329.4141,
-    83327.1484, 83328.4062, 83329.4141, 83329.4141, 83328.9531, 83331.5469,
-    83333.0078, 83335.8047, 83332.4375, 83332.4375, 83337.0469, 83340.9375,
-    83338.1016, 83339.0312, 83334.8594, 83334.8594, 83343.6797, 83348.7891,
-    83349.6406, 83346.1562, 83344.8984, 83344.8984, 83347.5078, 83352.125,
-    83349.7734, 83351.7656, 83349.9375, 83349.9375, 83354.5391, 83358.5078,
-    83358.3516, 83355.3906, 83357.0078, 83357.0078, 83358.5312, 83365.0547,
-    83365.5859, 83362.7891, 83361.0391, 83361.0391, 83368.8906, 83363.7812,
-    83370.7969, 83365.8125, 83369.9453, 83369.9453, 83370.0391, 83375.1094,
-    83374.5469, 83372.6797, 83376.9375, 83376.9375, 83378.8906, 83380.1484,
-    83380.5938, 83384.2031, 83382.7422, 83382.7422, 83382.5078, 83386.8516,
-    83386.4844, 83388.3516, 83384.4531, 83384.4531, 83391.1328, 83395.1094,
-    83392.3516, 83394.1719, 83392.9609, 83392.9609, 83392.0625, 83396.2812,
-    83399.6875, 83397.375,  83403.1328, 83403.1328, 83409.9844, 83400.9062,
-    83402.8906, 83408.4062, 83408.2812, 83408.2812, 83411.1797, 83402.9922,
-    83406.6016, 83408.8672, 83417.9531, 83417.9531, 83413.2656, 83415.25,
-    83416.9531, 83414.2344, 83419.9141, 83419.9141, 83421.7422, 83419.1094,
-    83423.4062, 83420.2422, 83423.4844, 83423.4844, 83427.5391, 83424.7422,
-    83430.5391, 83428.7578, 83429.7266, 83429.7266, 83431.8516, 83428,
-    83432.1797, 83430.7969, 83434.8984, 83434.8984, 83436.5156, 83438.0547,
-    83439.9609, 83438.3359, 83444.7422, 83444.7422, 83444.7578, 83443.4609,
-    83441.9609, 83449.3438, 83446.0547, 83446.0547, 83450.1719, 83447.5,
-    83450.0156, 83454.4297, 83454.0312, 83454.0312, 83458.7266, 83457.2656,
-    83457.9609, 83458.5625, 83455.6094, 83455.6094, 83463,      83465.3047,
-    83464.1719, 83467.0547, 83468.875,  83468.875,  83465.8203, 83467.9219,
-    83472.5859, 83471.4531, 83469.2656, 83469.2656, 83473.4453, 83474.625,
-    83472.8359, 83476.9766, 83475.0703, 83475.0703, 83486.0469, 83481.0547,
-    83481.0156, 83483.0859, 83483.4062, 83483.4062, 83486.6172, 83489.2109,
-    83488.1172, 83488.4375, 83488.3594, 83488.3594, 83494.8672, 83490.0469,
-    83494.3047, 83491.2188, 83491.7109, 83491.7109, 83504.5078, 83502.9609,
-    83500.3672, 83504.625,  83507.8672, 83507.8672, 83505.6094, 83504.2656,
-    83505.0391, 83510.1875, 83507.1875, 83507.1875, 83512.9844, 83509.2109,
-    83511.5625, 83514.4453, 83516.7109, 83516.7109, 83518.1562, 83516.1719,
-    83521.4844, 83518.2812, 83521.7656, 83521.7656, 83526.0469, 83524.9531,
-    83523.9375, 83525.7656, 83524.1016, 83524.1016, 83527.4219, 83530.5469,
-    83528.7969, 83534.8438, 83532.2031, 83532.2031, 83535.0156, 83531.0859,
-    83539.0312, 83539.4375, 83540.4922, 83540.4922, 83539.7109, 83541.2891,
-    83541.6953, 83541.1641, 83545.4688, 83545.4688, 83548.1797, 83551.5859,
-    83545.625,  83552.8359, 83545.5,    83545.5,    83555.5859, 83556.6406,
-    83556.3125, 83557.7344, 83557.4922, 83557.4922, 83559.4844, 83562.3672,
-    83561.7969, 83563.375,  83565.6094, 83565.6094, 83564.8281, 83567.5,
-    83569.4453, 83571.1875, 83571.9219, 83571.9219, 83573.4609, 83573.5781,
-    83573.5781, 83573.5,    83579.4609, 83579.4609, 83577.2578, 83576.1641,
-    83585.3672, 83576.4062, 83577.3438, 83577.3438, 83588.8047, 83588.6016,
-    83582.3203, 83580.375,  83586.6953, 83586.6953, 83594.2188, 83586.8438,
-    83593.5312, 83589.1484, 83591.0547, 83591.0547, 83597.8828, 83594.5625,
-    83598.25,   83596.0625, 83602.1406, 83602.1406, 83604.0312, 83604.0703,
-    83598.7578, 83602.8594, 83599.8125, 83599.8125, 83612.4844, 83612.6094,
-    83604.7812, 83607.2578, 83611.0234, 83611.0234, 83613.5234, 83611.4141,
-    83613,      83615.6328, 83614.7812, 83614.7812, 83621.6016, 83617.3047,
-    83619.8984, 83620.0156, 83622.4531, 83622.4531, 83628.8594, 83623.6719,
-    83629.5547, 83630.2812, 83629.3906, 83629.3906, 83626.7969, 83630.4453,
-    83633.6484, 83635.4297, 83640.2969, 83640.2969, 83640.4688, 83635.1953,
-    83639.1719, 83639.8203, 83641.8047, 83641.8047, 83644.4688, 83645.4844,
-    83640.9375, 83643.2109, 83642.4844, 83642.4844, 83651.0625, 83650.0078,
-    83646.6484, 83651.875,  83650.9453, 83650.9453, 83655.4609, 83657.4531,
-    83653.4375, 83659.3125, 83658.3828, 83658.3828, 83662.1641, 83660.3438,
-    83663.2578, 83665.2891, 83666.4219, 83666.4219, 83665.3906, 83668.1484,
-    83669.2031, 83668.7188, 83675.2891, 83675.2891, 83675.3047, 83680.4531,
-    83676.7656, 83674.6094, 83674.4922, 83674.4922, 83676.3984, 83679.2344,
-    83678.3828, 83686.8203, 83678.9141, 83678.9141, 83684.3516, 83684.7188,
-    83685.4062, 83687.5938, 83687.4766, 83687.4766, 83687.3438, 83690.3438,
-    83687.0234, 83689.0469, 83689.4531, 83689.4531, 83694.3281, 83694.2891,
-    83699.8828, 83699.7969, 83698.4609, 83698.4609, 83702.3828, 83701.4453,
-    83706.1484, 83701.6484, 83700.1094, 83700.1094, 83705.0938, 83710.9297,
-    83704.5625, 83708.5781, 83711.0547, 83711.0547, 83709.9609, 83711.1797,
-    83715.8047, 83713.4531, 83713.0859, 83713.0859, 83714.9609, 83717.8438,
-    83721.9766, 83721.8984, 83717.8047, 83717.8047, 83718.8984, 83723.3984,
-    83720.5234, 83720.0703, 83725.75,   83725.75,   83726.9219, 83726.9609,
-    83725.5,    83727.125,  83729.7578, 83729.7578, 83735.75,   83735.5938,
-    83732.6719, 83732.3047, 83732.7969, 83732.7969, 83740.7109, 83740.875,
-    83743.6719, 83739.375,  83741.5625, 83741.5625, 83745.75,   83742.875,
-    83741.0859, 83741.8594, 83749.8828, 83749.8828, 83748.6484, 83746.6562,
-    83752.0469, 83743.0938, 83747.1016, 83747.1016, 83754.0625, 83751.9141,
-    83756.2969, 83753.375,  83760.2656, 83760.2656, 83761.0781, 83754.5469,
-    83758.6016, 83757.0234, 83757.2656, 83757.2656, 83761.3281, 83755.9766,
-    83766.1562, 83762.4219, 83770.0469, 83770.0469, 83767.6172, 83769.5625,
-    83772.8047, 83772.4844, 83770.4141, 83770.4141, 83780.0391, 83777.1641,
-    83777.125,  83778.7031, 83781.0938, 83781.0938, 83786.125,  83790.9062,
-    83785.8438, 83785.5547, 83788.6797, 83788.6797, 83793.2891, 83795.7188,
-    83796.9766, 83801.7188, 83799.4922, 83799.4922, 83802.4375, 83796.7266,
-    83796.3594, 83797.3359, 83801.3438, 83801.3438, 83802.875,  83807.5312,
-    83811.1406, 83805.9531, 83807.2891, 83807.2891, 83807.9453, 83812.7266,
-    83812.1562, 83812.4062, 83808.6719, 83808.6719, 83811.3125, 83814.1094,
-    83816.6641, 83819.625,  83814.7188, 83814.7188, 83819.4141, 83819.5391,
-    83817.9609, 83820.5938, 83823.6328, 83823.6328, 83826.8516, 83820.2422,
-    83829.3281, 83826,      83827.4219, 83827.4219, 83829.6953, 83828.4766,
-    83831.5234, 83829.8594, 83824.7891, 83824.7891, 83836.3203, 83834.5,
-    83830.3594, 83838.4688, 83840.0469, 83840.0469, 83843.5938, 83839.0078,
-    83843.5078, 83837.5547, 83843.3516, 83843.3516, 83850.4375, 83843.8281,
-    83850.7656, 83849.1406, 83849.8672, 83849.8672, 83851.1641, 83850.4375,
-    83853.0703, 83853.5156, 83853.2344, 83853.2344, 83861.1953, 83860.2578,
-    83857.4219, 83859.4922, 83868.3672, 83868.3672, 83870.7031, 83865.2734,
-    83863.1641, 83865.7578, 83871.7188, 83871.7188, 83867.3438, 83872.4141,
-    83871.5625, 83876.2188, 83875.8594, 83875.8594, 83874.8281, 83872.1094,
-    83879.2422, 83876.8125, 83876.4844, 83876.4844, 83886.2031, 83889.4062,
-    83885.4766, 83889.5312, 83890.0156, 83890.0156, 83893.4141, 83893.6562,
-    83895.6406, 83897.6328, 83901.4844, 83901.4844, 83900.1562, 83897.8438,
-    83896.1016, 83899.2266, 83899.1016, 83899.1016, 83904.4141, 83899.2578,
-    83899.3438, 83906.2734, 83900.0703, 83900.0703, 83907.0391, 83908.0547,
-    83909.4766, 83907.125,  83911.5859, 83911.5859, 83911.6328, 83914.3906,
-    83912.7656, 83912.9297, 83912.7656, 83912.7656, 83915.3594, 83921.0312,
-    83919.25,   83915.5625, 83916.125,  83916.125,  83921.4531, 83916.9922,
-    83919.5469, 83920.4375, 83922.8281, 83922.8281, 83922.0312, 83925.5938,
-    83925.9219, 83929.5312, 83925.8828, 83925.8828, 83929.5234, 83927.6172,
-    83931.6328, 83928.3828, 83925.2656, 83925.2656, 83927.9453, 83928.0312,
-    83925.5156, 83930.6641, 83932.8125, 83932.8125, 83924.0391, 83926.3047,
-    83936.6016, 83933.6016, 83935.0625, 83935.0625, 83944.7656, 83945.0547,
-    83944.4062, 83943.8359, 83950.9688, 83950.9688, 83953.4062, 83952.0625,
-    83956.9297, 83949.9531, 83961.4688, 83961.4688, 83963.0469, 83962.1484,
-    83964.9062, 83961.4219, 83965.7578, 83965.7578, 83968.1094, 83963.4453,
-    83972.0391, 83968.8359, 83970.9062, 83970.9062, 83977.3594, 83977.5156,
-    83976.9531, 83973.4219, 83978.9375, 83978.9375, 83977.1562, 83981.2969,
-    83978.5781, 83979.5078, 83984.9844, 83984.9844, 83991.2891, 83980.0625,
-    83983.9922, 83987.5625, 83988.0859, 83988.0859, 83986.8203, 83990.2656,
-    83987.9531, 83990.8359, 83988.4844, 83988.4844, 83993.1719, 83989.3594,
-    83995.8516, 83991.8359, 83996.5781, 83996.5781, 83997.625,  83997.9531,
-    83995.7188, 83994.2656, 83991.0156, 83991.0156, 83983.0703, 83965.3594,
-    83956.1094, 83960.2891, 83961.2578, 83961.2578, 83966.0547, 83969.6641,
-    83980.1172, 83984.7422, 83985.5078, 83985.5078, 83997.6875, 83998.9062,
-    83998.9062, 83994.2812, 83999.8359, 83999.8359, 84002.625,  84007.8125,
-    84003.4766, 84005.0938, 84001.0391, 84001.0391, 84004.0703, 84000.9453,
-    83995.9609, 83995.5156, 83987.6953, 83987.6953, 83979.8047, 83969.5078,
-    83973.0781, 83969.875,  83974.7422, 83974.7422, 83976.0234, 83999.3359,
-    84011.4531, 84020.5312, 84017.7344, 84017.7344, 84029.5625, 84027.2578,
-    84029.6094, 84031.5547, 84034.5078, 84034.5078, 84036.9922, 84039.6641,
-    84039.5859, 84039.3828, 84041.6094, 84041.6094, 84039.7344, 84045.2031,
-    84045.6094, 84040.5391, 84043.1797, 84043.1797, 84051.5781, 84049.1875,
-    84046.8359, 84047.8047, 84048.9062, 84048.9062, 84048.2578, 84049.875,
-    84044.4844, 84050.9688, 84054.5,    84054.5,    84050.9844, 84055.6484,
-    84053.3359, 84057.2656, 84055.0781, 84055.0781, 84061.3281, 84056.8281,
-    84060.9688, 84055.375,  84052.5312, 84052.5312, 84032.8047, 84030.7344,
-    84027.9375, 84029.7266, 84042.4141, 84042.4141, 84053.1562, 84052.1016,
-    84058.3828, 84061.9922, 84057.4141, 84057.4141, 84073.3203, 84068.9844,
-    84071.0156, 84070,      84079.4453, 84079.4453, 84078.0938, 84077.2812,
-    84079.2734, 84079.7969, 84083.5312, 84083.5312, 84077.0312, 84085.4609,
-    84086.1094, 84087.8125, 84091.1797, 84091.1797, 84091.2812, 84092.5391,
-    84089.7812, 84091.7266, 84090.3906, 84090.3906, 84094.0938, 84100.9453,
-    84098.5938, 84099.7734, 84097.9922, 84097.9922, 84101.9219, 84105.0781,
-    84107.9609, 84107.8359, 84107.3906, 84107.3906, 84113.0234, 84112.9844,
-    84106.6562, 84109.6172, 84111.3203, 84111.3203, 84112.7734, 84114.3984,
-    84116.7891, 84116.2188, 84115.3281, 84115.3281, 84117.7344, 84118.0156,
-    84113.1484, 84120.3281, 84116.5156, 84116.5156, 84121.4688, 84124.4688,
-    84117.2891, 84122.6406, 84115.4688, 84115.4688, 84124.875,  84124.4297,
-    84125.0781, 84129.0469, 84126.3359, 84126.3359, 84129.1797, 84126.6641,
-    84129.75,   84130.5156, 84129.5469, 84129.5469, 84135.8594, 84130.9141,
-    84133.9531, 84135.5312, 84140.3203, 84140.3203, 84141.9453, 84140.8516,
-    84140.9297, 84137.125,  84142.3906, 84142.3906, 84147.1406, 84140.7344,
-    84144.1016, 84146,      84149.7734, 84149.7734, 84145.0938, 84147.6875,
-    84149.9609, 84142.2188, 84147.1641, 84147.1641, 84149.3359, 84153.2266,
-    84153.6328, 84153.1875, 84154.2812, 84154.2812, 84153.9453, 84151.5938,
-    84155.1641, 84152.3281, 84155.8516, 84155.8516, 84155.5,    84158.8672,
-    84160.6562, 84162.1562, 84162.1953, 84162.1953, 84161.1094, 84163.6641,
-    84163.2578, 84158.1094, 84158.0625, 84158.0625, 84163.9219, 84165.9922,
-    84166.7188, 84163.8828, 84167.8125, 84167.8125, 84165.1094, 84165.0703,
-    84165.1484, 84170.8672, 84171.4766, 84171.4766, 84171.4297, 84172.0781,
-    84171.1484, 84173.6172, 84171.7578, 84171.7578, 84176.9297, 84178.5547,
-    84175.875,  84181.5156, 84178.4297, 84178.4297, 84183.2812, 84182.3047,
-    84182.3906, 84186.1172, 84191.3047, 84191.3047, 84189.1641, 84187.5469,
-    84185.1484, 84187.0938, 84191.0703, 84191.0703, 84191.3828, 84193.8125,
-    84188.7031, 84191.625,  84190.2891, 84190.2891, 84194.2656, 84193.6172,
-    84192.8047, 84197.0234, 84194.2266, 84194.2266, 84191.5156, 84195.3203,
-    84188.5156, 84190.2578, 84193.3359, 84193.3359, 84203.5703, 84199.7188,
-    84202.1172, 84202.9219, 84204.7109, 84204.7109, 84211.4062, 84209.7031,
-    84214.7734, 84212.9844, 84211.4062, 84211.4062, 84214.9453, 84217.3359,
-    84208.7812, 84212.5938, 84213,      84213,      84215.7266, 84212.0781,
-    84206.6797, 84205.1797, 84197.8047, 84197.8047, 84188.9219, 84189.5703,
-    84192.125,  84184.5859, 84186.1641, 84186.1641, 84194.6406, 84191.9297,
-    84189.5781, 84188.8047, 84194.7266, 84194.7266, 84196.7812, 84201.6484,
-    84201.1641, 84208.1719, 84204.7734, 84204.7734, 84225.1016, 84216.3906,
-    84220.6406, 84221.8984, 84223.4844, 84223.4844, 84233.4141, 84227.8594,
-    84232.0391, 84234.75,   84231.75,   84231.75,   84230.3047, 84227.9922,
-    84234.1953, 84233.625,  84235.9375, 84235.9375, 84236.6641, 84235.7734,
-    84239.7891, 84240.6406, 84235.4141, 84235.4141, 84235.0938, 84238.9453,
-    84235.0938, 84229.9062, 84224.1094, 84224.1094, 84215.4688, 84215.0703,
-    84216.8906, 84218.5547, 84212.4688, 84212.4688, 84218.1406, 84223.3281,
-    84223.6953, 84222.0312, 84224.1016, 84224.1016, 84235.4766, 84242.0469,
-    84248.0859, 84243.0625, 84249.5078, 84249.5078, 84257.5625, 84259.7969,
-    84262.5078, 84256.3516, 84260.1172, 84260.1172, 84262.0391, 84258.7109,
-    84266.6562, 84262.2422, 84262.8516, 84262.8516, 84272.1562, 84276.7344,
-    84275.5234, 84274.0625, 84277.4219, 84277.4219, 84276.7031, 84276.9062,
-    84279.4609, 84275.4062, 84274.8359, 84274.8359, 84280.2969, 84280.6953,
-    84280.8984, 84282.1172, 84283.3359, 84283.3359, 84283.8906, 84289.2031,
-    84284.0938, 84286.1641, 84282.9141, 84282.9141, 84287.5156, 84292.5781,
-    84292.8281, 84288.9766, 84291.5703, 84291.5703, 84298.4531, 84291.2734,
-    84295.7344, 84295.9375, 84295.1641, 84295.1641, 84294.5391, 84296.9297,
-    84294.4922, 84296.6875, 84297.1328, 84297.1328, 84299.7188, 84300.4531,
-    84303.6172, 84297.3672, 84299.5234, 84299.5234, 84300.75,   84308.6562,
-    84303.875,  84301.6016, 84306.6719, 84306.6719, 84307.8594, 84304.2969,
-    84311.6719, 84304.5,    84310.9844, 84310.9844, 84312.8203, 84308.1172,
-    84309.1328, 84311.7656, 84310.6328, 84310.6328, 84311.2812, 84315.2969,
-    84318.0078, 84318.0938, 84312.0938, 84312.0938, 84322.4609, 84318.3281,
-    84322.625,  84320.4766, 84325.4219, 84325.4219, 84321.7656, 84324.1953,
-    84330.1172, 84326.5859, 84327.1172, 84327.1172, 84331.5469, 84327.6953,
-    84335.5234, 84331.0234, 84328.9141, 84328.9141, 84332.4453, 84325.6328,
-    84330.0156, 84325.9609, 84341.4453, 84341.4453, 84338.9688, 84336.8203,
-    84339.2891, 84337.1797, 84334.5469, 84334.5469, 84344.75,   84344.7891,
-    84339.3594, 84344.1797, 84343.8203, 84343.8203, 84346.9609, 84345.7422,
-    84347.7266, 84347.2812, 84348.7422, 84348.7422, 84352.6875, 84352.3594,
-    84353.4141, 84352.2422, 84353.375,  84353.375,  84355.1953, 84352.2734,
-    84357.5469, 84356.3281, 84360.6641, 84360.6641, 84360.375,  84361.9609,
-    84357.9453, 84354.0156, 84359.2031, 84359.2031, 84362.3125, 84360.4922,
-    84365.5156, 84366.4531, 84363.4062, 84363.4062, 84365.2422, 84368.6484,
-    84363.9844, 84365.3203, 84367.8359, 84367.8359, 84373.7969, 84368.2422,
-    84374.8125, 84376.5547, 84368.0391, 84368.0391, 84376.8359, 84379.3047,
-    84374.1562, 84373.6719, 84378.0078, 84378.0078, 84381.9688, 84381.9688,
-    84378,      84378.1562, 84383.875,  84383.875,  84387.6719, 84385.4453,
-    84387.9609, 84382.3672, 84388.4844, 84388.4844, 84384.4766, 84385.8906,
-    84387.9609, 84382.3672, 84393.6406, 84393.6406, 84391.2812, 84391.7266,
-    84390.6719, 84392.3281, 84393.5859, 84393.5859, 84396.4219, 84391.1875,
-    84393.1328, 84393.8281, 84400.2734, 84400.2734, 84395.2734, 84395.0703,
-    84397.9453, 84401.5547, 84404.8438, 84404.8438, 84404.5391, 84402.4688,
-    84396.75,   84395.4531, 84389.5781, 84389.5781, 84383.3438, 84380.75,
-    84379.6562, 84376.8594, 84377.7891, 84377.7891, 84373.0781, 84372.7109,
-    84382.5234, 84380.0938, 84376.8906, 84376.8906, 84384.2656, 84387.0625,
-    84394.0391, 84391.6875, 84398.9062, 84398.9062, 84414.1328, 84409.4688,
-    84406.6328, 84406.9531, 84418.0625, 84418.0625, 84415.5859, 84414.4922,
-    84417.25,   84411.0859, 84410.5625, 84410.5625, 84399.0078, 84398.3203,
-    84396.5781, 84392.4844, 84393.8203, 84393.8203, 84387.4844, 84392.75,
-    84398.6328, 84407.2266, 84410.2656, 84410.2656, 84427.2812, 84420.3438,
-    84426.7109, 84426.6328, 84427.2812, 84427.2812, 84428.3438, 84435.2344,
-    84432.3125, 84434.1016, 84434.1406, 84434.1406, 84434.9609, 84437.3984,
-    84437.2344, 84436.9453, 84438.2031, 84438.2031, 84439.7344, 84434.7109,
-    84441.8828, 84447.4766, 84440.9531, 84440.9531, 84449.1406, 84449.625,
-    84440.5,    84448.3281, 84452.8281, 84452.8281, 84448.3594, 84453.9141,
-    84457.1172, 84450.9922, 84450.7891, 84450.7891, 84456.7891, 84451.3906,
-    84454.3125, 84456.0938, 84459.9844, 84459.9844, 84458.875,  84456.7266,
-    84462.4844, 84461.6328, 84452.1094, 84452.1094, 84464.6484, 84458.8125,
-    84458.7266, 84460.5547, 84463.9609, 84463.9609, 84466.4609, 84466.0938,
-    84464.1953, 84464.8438, 84466.7891, 84466.7891, 84472.5391, 84472.7031,
-    84468.5703, 84465.7344, 84474.125,  84474.125,  84474.9375, 84472.7109,
-    84470.2344, 84469.8359, 84472.0234, 84472.0234, 84473.9688, 84473.9219,
-    84474.5312, 84479.3203, 84475.9922, 84475.9922, 84479.7656, 84482.0312,
-    84477.2891, 84483.125,  84482.1953, 84482.1953, 84477.1016, 84479.2891,
-    84484.4766, 84484.0781, 84480.2656, 84480.2656, 84487.5,    84486.7734,
-    84486.5234, 84488.7188, 84482.0234, 84482.0234, 84493.3672, 84491.9062,
-    84489.6797, 84485.0547, 84497.8672, 84497.8672, 84492.75,   84499.4766,
-    84496.1953, 84494.3281, 84496.3125, 84496.3125, 84497.7812, 84494.8203,
-    84496.6016, 84499.3594, 84494.9062, 84494.9062, 84497.6797, 84506.2734,
-    84492.7734, 84502.0156, 84498.5312, 84498.5312, 84503.875,  84505.9453,
-    84506.8359, 84509.0703, 84511.6172, 84511.6172, 84513.4531, 84505.5859,
-    84507.8984, 84508.8672, 84508.4609, 84508.4609, 84515.4062, 84511.3516,
-    84512.3203, 84511.1094, 84510.9453, 84510.9453, 84518.2422, 84514.2266,
-    84515.2031, 84519.3359, 84520.3047, 84520.3047, 84518.3438, 84519.0312,
-    84518.0625, 84521.3828, 84518.75,   84518.75,   84521.2578, 84523.0781,
-    84520.7266, 84518.7031, 84514.6094, 84514.6094, 84522.4297, 84526.8906,
-    84530.7422, 84530.1328, 84528.1016, 84528.1016, 84526.4297, 84528.9453,
-    84530.6484, 84530.1641, 84533.5234, 84533.5234, 84528.8984, 84528.7734,
-    84530.4766, 84537.125,  84529.9922, 84529.9922, 84538.5703, 84538,
-    84533.4609, 84533.5469, 84540.2734, 84540.2734, 84544.4922, 84542.9141,
-    84531.8047, 84542.3047, 84544.0469, 84544.0469, 84542.3359, 84549.4688,
-    84544.9688, 84541.3672, 84541.8125, 84541.8125, 84544.5938, 84546.6172,
-    84545.6875, 84550.2656, 84548.6875, 84548.6875, 84550.7344, 84551.1406,
-    84555.9688, 84555.2812, 84549.0312, 84549.0312, 84559.9062, 84552.0469,
-    84557.7578, 84558.0859, 84559.5469, 84559.5469, 84562.8672, 84560.0703,
-    84558.3281, 84551.3594, 84558.3281, 84558.3281, 84560.4297, 84561.6016,
-    84561.0781, 84567.8906, 84568.2578, 84568.2578, 84573.2812, 84565.9062,
-    84570.1172, 84570.3594, 84568.0547, 84568.0547, 84567.2734, 84566.3828,
-    84570.1094, 84571.25,   84573.7188, 84573.7188, 84570.0938, 84578.7266,
-    84577.0234, 84578.2031, 84577.9141, 84577.9141, 84582.5625, 84579.6875,
-    84584.875,  84576.2422, 84584.6719, 84584.6719, 84583.0781, 84582.1406,
-    84585.5078, 84589.4375, 84585.5078, 84585.5078, 84587.7891, 84578.6719,
-    84585.1172, 84586.6953, 84582.2734, 84582.2734, 84589.1641, 84589.4453,
-    84589.1172, 84583.9297, 84585.0625, 84585.0625, 84584.0938, 84585.1875,
-    84583.9297, 84591.3906, 84592.3594, 84592.3594, 84594.2969, 84593.4453,
-    84596.2031, 84592.0703, 84591.6641, 84591.6641, 84600.8828, 84596.4219,
-    84595.8516, 84593.2188, 84595.0391, 84595.0391, 84595.5703, 84595.2031,
-    84606.6406, 84596.9062, 84598.8125, 84598.8125, 84603.5938, 84597.4297,
-    84600.1016, 84603.0234, 84602.3359, 84602.3359, 84602.6172, 84605.8203,
-    84603.7969, 84604.2422, 84608.5,    84608.5,    84605.0234, 84604.0859,
-    84601.4922, 84603.9297, 84605.4297, 84605.4297, 84606.1406, 84605.4531,
-    84603.3438, 84606.8281, 84604.5156, 84604.5156, 84613.2188, 84609.6875,
-    84616.4609, 84609.9766, 84613.4219, 84613.4219, 84616.5391, 84614.0703,
-    84619.0938, 84617.6328, 84619.2188, 84619.2188, 84628.375,  84624.5703,
-    84623.5938, 84626.2266, 84624.7656, 84624.7656, 84625.0859, 84629.8281,
-    84630.0703, 84632.1797, 84629.0938, 84629.0938, 84635.1562, 84627.6953,
-    84638.3594, 84629.1953, 84631.1875, 84631.1875, 84630.7656, 84635.3828,
-    84642.2344, 84639.1172, 84632.5078, 84632.5078, 84637.7109, 84640.9141,
-    84638.1562, 84634.3906, 84642.0078, 84642.0078, 84641.2891, 84638.6172,
-    84643.1953, 84639.2656, 84648.5078, 84648.5078, 84643.7266, 84645.3516,
-    84650.0547, 84642.6719, 84645.2734, 84645.2734, 84646.8281, 84650.6016,
-    84648.0078, 84647.7656, 84649.2266, 84649.2266, 84649.4297, 84648.2891,
-    84650.1562, 84651.6953, 84654.0859, 84654.0859, 84657.8828, 84655,
-    84657.9609, 84653.5,    84664.7344, 84664.7344, 84662.1562, 84663.0859,
-    84661.8359, 84664.9922, 84661.75,   84661.75,   84667.9609, 84673.1875,
-    84664.6797, 84667.5156, 84671.4453, 84671.4453, 84678.4922, 84671.1953,
-    84674.3984, 84675.1719, 84675.0938, 84675.0938, 84677.3281, 84676.7656,
-    84676.1172, 84674.9766, 84675.75,   84675.75,   84676.4844, 84678.7969,
-    84680.0938, 84678.5938, 84682.3984, 84682.3984, 84684.4766, 84688.6094,
-    84684.8828, 84686.2578, 84685.6953, 84685.6953, 84688.4844, 84689.7422,
-    84685.8047, 84688.1172, 84684.3438, 84684.3438, 84689.6016, 84693.9766,
-    84695.6016, 84694.0234, 84691.0625, 84691.0625, 84698.3906, 84696.0859,
-    84700.3828, 84695.8828, 84692.7188, 84692.7188, 84701.125,  84700.5547,
-    84699.6641, 84706.8359, 84698.0391, 84698.0391, 84707.1641, 84701,
-    84706.3984, 84705.2578, 84700.3516, 84700.3516, 84704.2969, 84715.1641,
-    84716.4219, 84707.7422, 84706.7734, 84706.7734, 84713.2266, 84713.7891,
-    84703.0469, 84693.9297, 84680.5469, 84680.5469, 84681.6953, 84689,
-    84738.2578, 84730.2266, 84545.8828, 84545.8828, 84734.9062, 84699.5547,
-    84558.2266, 84718.2031, 84706.5312, 84706.5312, 84715.0391, 84724.0781,
-    84722.6953, 84720.7969, 84722.2109, 84722.2109, 84724.7031, 84720.8906,
-    84730.2969, 84724.8672, 84727.7812, 84727.7812, 84726.5156, 84730.125,
-    84723.4375, 84718.3281, 84726.9688, 84726.9688, 84721.2422, 84735.1484,
-    84718.4453, 84728.3359, 84735.9141, 84735.9141, 84716.9609, 84720.9297,
-    84723.2031, 84744.9297, 84716.4297, 84716.4297, 84728.6641, 84722.8672,
-    84725.9141, 84723.7656, 84718.8984, 84718.8984, 84726.2031, 84720.5234,
-    84721.7031, 84722.6719, 84721.5391, 84721.5391, 84731.3594, 84724.9531,
-    84723.2891, 84719.1953, 84723.6562, 84723.6562, 84718.7188, 84724.0234,
-    84723.9844, 84726.2188, 84721.1484, 84721.1484, 84719.1094, 84718.7031,
-    84715.5859, 84719.1953, 84720.9375, 84720.9375, 84724,      84724.7734,
-    84725.625,  84724.2031, 84725.3359, 84725.3359, 84727.7344, 84726.3516,
-    84724.4453, 84723.6797, 84721.1641, 84721.1641, 84723.1172, 84722.7891,
-    84725.5859, 84718.9766, 84723.1172, 84723.1172, 84723.2734, 84721.4531,
-    84720.9219, 84726.6797, 84724.4531, 84724.4531, 84719.8438, 84719.5156,
-    84719.6016, 84721.3828, 84722.3203, 84722.3203, 84723.2109, 84725.2344,
-    84717.8203, 84722.6016, 84717.9844, 84717.9844, 84729.4688, 84725.1719,
-    84723.7109, 84721.6406, 84722.4531, 84722.4531, 84721.4609, 84718.9844,
-    84729.8906, 84723.4453, 84724.0938, 84724.0938, 84725.3672, 84723.4609,
-    84720.9062, 84724.0703, 84723.5391, 84723.5391, 84722.3516, 84724.9844,
-    84718.0938, 84724.2969, 84724.7812, 84724.7812, 84723.8281, 84722.9766,
-    84726.1016, 84723.7891, 84725.6953, 84725.6953, 84720.6641, 84723.625,
-    84725.8984, 84723.0938, 84722.2031, 84722.2031, 84722.6094, 84724.0234,
-    84722.5703, 84723.2969, 84718.0703, 84718.0703, 84724.8906, 84721.4062,
-    84722.625,  84722.5,    84719.2578, 84719.2578, 84724.0078, 84724.4609,
-    84724.7031, 84721.0078, 84716.3516, 84716.3516, 84725.7812, 84722.3359,
-    84721.6875, 84718.2422, 84723.6328, 84723.6328, 84721.1094, 84719.25,
-    84723.5859, 84719.5312, 84721.5156, 84721.5156, 84724.1719, 84722.3906,
-    84722.3047, 84717.6016, 84724.0938, 84724.0938, 84721.625,  84722.9609,
-    84722.0312, 84714.8516, 84720.2812, 84720.2812, 84721.5,    84721.7812,
-    84720.7734, 84717.9375, 84722.0312, 84722.0312, 84725.6953, 84724.6016,
-    84725.2109, 84725.9766, 84723.5469, 84723.5469, 84721.9531, 84715.75,
-    84722.5625, 84719.8047, 84718.1875, 84718.1875, 84723.6719, 84720.3047,
-    84713.0469, 84722.25,   84720.9141, 84720.9141, 84726.0938, 84719.2031,
-    84721.4375, 84717.9062, 84721.0703, 84721.0703, 84722.4922, 84724.3203,
-    84722.375,  84720.6719, 84723.0625, 84723.0625, 84729.8906, 84724.9453,
-    84722.1875, 84722.3047, 84723.0391, 84723.0391, 84721.2812, 84723.9609,
-    84727.4844, 84716.8281, 84722.0156, 84722.0156, 84719.2891, 84720.9453,
-    84720.7031, 84720.1797, 84719.7344, 84719.7344, 84721.6328, 84722.6016,
-    84723.6172, 84716.5625, 84720.1719, 84720.1719, 84719.3516, 84726.5312,
-    84724.5,    84722.9219, 84719.2734, 84719.2734, 84719.1328, 84723.3516,
-    84719.9844, 84718.5625, 84721.2031, 84721.2031, 84724.5859, 84720.7812,
-    84722.5234, 84720.7812, 84718.75,   84718.75,   84720.7422, 84725.7266,
-    84723.4141, 84714.7422, 84718.1875, 84718.1875, 84721.4844, 84722.8594,
-    84722.0078, 84723.9922, 84721.2812, 84721.2812, 84721.4609, 84716.1562,
-    84723.9375, 84717.3672, 84721.625,  84721.625,  84724.1562, 84727.5625,
-    84723.3047, 84719.8594, 84720.3047, 84720.3047, 84723.7578, 84720.7578,
-    84718.6094, 84724.1641, 84718.1641, 84718.1641, 84724.2109, 84724.0078,
-    84723.3594, 84722.5078, 84718.2109, 84718.2109, 84725.3203, 84723.1719,
-    84722.3984, 84727.9531, 84720.375,  84720.375,  84722.2891, 84713.5312,
-    84717.1797, 84718.1094, 84720.8281, 84720.8281, 84724.9453, 84723.9688,
-    84721.8594, 84722.5469, 84723.6016, 84723.6016, 84724.5781, 84721.7422,
-    84721.375,  84723.8516, 84716.1094, 84716.1094, 84720.7578, 84717.9609,
-    84721.0469, 84717.4375, 84718.25,   84718.25,   84724.5469, 84723.8594,
-    84724.1016, 84720.6172, 84720.8203, 84720.8203, 84718.8594, 84719.5078,
-    84723.6797, 84722.3828, 84718.0859, 84718.0859, 84724.0156, 84716.2344,
-    84714.4141, 84722.0312, 84719.8047, 84719.8047, 84719.7109, 84721.7422,
-    84721.1328, 84721.0547, 84720.2812, 84720.2812, 84722.5938, 84718.8281,
-    84718.7891, 84717.4453, 84721.6641, 84721.6641, 84721.8516, 84715.8906,
-    84723.4766, 84722.8281, 84717.9219, 84717.9219, 84721.7734, 84722.9844,
-    84723.0703, 84723.9219, 84721.7734, 84721.7734, 84721.1172, 84723.9141,
-    84723.1875, 84723.4297, 84719.0078, 84719.0078, 84720.0312, 84722.8281,
-    84722.2188, 84722.7891, 84724.2891, 84724.2891, 84719.9141, 84717.8125,
-    84722.7969, 84723.7656, 84715.375,  84715.375,  84724.7109, 84716.0781,
-    84721.4297, 84717.5312, 84718.9922, 84718.9922, 84724.0703, 84718.6328,
-    84722.6094, 84722.0781, 84719.2031, 84719.2031, 84720.4844, 84721.1719,
-    84715.4141, 84723.2422, 84721.0078, 84721.0078, 84722.8359, 84722.5547,
-    84721.2188, 84722.7969, 84720.4062, 84720.4062, 84719.3672, 84723.2578,
-    84724.2734, 84716.5234, 84716.0781, 84716.0781, 84723.0312, 84721.1719,
-    84717.4766, 84722.4219, 84719.1016, 84719.1016, 84720.7109, 84719.0078,
-    84720.3516, 84722.8203, 84725.7031, 84725.7031, 84716.1406, 84720.7188,
-    84724.7344, 84723.1562, 84725.9922, 84725.9922, 84724.8438, 84722.25,
-    84720.1016, 84720.3828, 84720.5859, 84720.5859, 84724.2969, 84723.8125,
-    84718.6641, 84718.2578, 84720.2422, 84720.2422, 84720.8906, 84722.4766,
-    84719.3516, 84721.2969, 84720.8125, 84720.8125, 84717.8516, 84720.8516,
-    84719.9609, 84727.4141, 84717.4453, 84717.4453, 84721.8906, 84718.0859,
-    84721.0391, 84720.8828, 84725.0547, 84725.0547, 84721.4844, 84721.5703,
-    84725.0938, 84718.7266, 84720.875,  84720.875,  84721.0859, 84717.9219,
-    84723.3984, 84719.7109, 84718.2891, 84718.2891, 84719.3906, 84722.4766,
-    84720.6094, 84723.5703, 84722.6406, 84722.6406, 84723.6797, 84724.6172,
-    84721.5781, 84722.1406, 84720.8828, 84720.8828, 84725.5,    84724.9688,
-    84723.75,   84718.4453, 84718.3203, 84718.3203, 84721.1562, 84721.7656,
-    84723.1875, 84718.8047, 84723.3438, 84723.3438, 84723.3516, 84723.2734,
-    84723.4766, 84723.6719, 84721.4453, 84721.4453, 84725.1406, 84722.5469,
-    84724.3281, 84721.0469, 84721.4453, 84721.4453, 84718.9844, 84721.0547,
-    84728.5938, 84717.6016, 84722.4297, 84722.4297, 84720.5156, 84722.7031,
-    84719.7422, 84720.8828, 84718.6484, 84718.6484, 84723.6797, 84718.4531,
-    84720.0312, 84720.1562, 84722.1016, 84722.1016, 84724.8594, 84724.7422,
-    84723.3984, 84722.0234, 84722.6328, 84722.6328, 84719.6797, 84727.8281,
-    84719.3984, 84719.2812, 84721.9922, 84721.9922, 84725.8516, 84721.5938,
-    84717.6172, 84720.5391, 84722.4453, 84722.4453, 84720.8281, 84719.1641,
-    84725.0078, 84719.4922, 84719.5703, 84719.5703, 84723.8359, 84721.9766,
-    84724.8516, 84724.6094, 84724.8906, 84724.8906, 84723.5938, 84725.2578,
-    84721.8125, 84720.9141, 84723.4688, 84723.4688, 84723.2266, 84719.8203,
-    84722.0859, 84724.6406, 84722.25,   84722.25,   84719.6094, 84725.1562,
-    84721.4297, 84719.9688, 84722.9297, 84722.9297, 84722.2969, 84729.0234,
-    84721.4062, 84720.8359, 84722.2969, 84722.2969, 84728.125,  84725.7734,
-    84720.75,   84720.3828, 84721.7266, 84721.7266, 84726.5547, 84719.2188,
-    84725.8281, 84722.625,  84724.2891, 84724.2891, 84723.2109, 84720.9375,
-    84722.8438, 84722.1953, 84722.1172, 84722.1172, 84727.4844, 84723.4766,
-    84724.9297, 84724.3672, 84723.5938, 84723.5938, 84721.7422, 84721.9844,
-    84725.4688, 84724.6953, 84723.1562, 84723.1562, 84725.8672, 84724.3672,
-    84716.2578, 84721.3672, 84724.5234, 84724.5234, 84723.8516, 84723.4453,
-    84718.8594, 84720.4453, 84721.5391, 84721.5391, 84724.625,  84720.6875,
-    84720.9766, 84724.5781, 84723.1641, 84723.1641, 84732.6953, 84725.6406,
-    84722.1562, 84720.9375, 84722.6016, 84722.6016, 84725.1797, 84724.8984,
-    84728.625,  84723.1953, 84722.9531, 84722.9531, 84723.3594, 84725.0625,
-    84728.7109, 84721.7344, 84719.3438, 84719.3438, 84724.9688, 84724.4453,
-    84721.1172, 84723.9531, 84720.3906, 84720.3906, 84727.8359, 84721.0234,
-    84722.3203, 84719.0391, 84721.9141, 84721.9141, 84720.5703, 84721.7891,
-    84720.0469, 84719.7188, 84720.0078, 84720.0078, 84724.3438, 84719.9219,
-    84725.3125, 84723.6094, 84723.6094, 84723.6094, 84727.3125, 84726.6172,
-    84716.7656, 84718.1484, 84716.4453, 84716.4453, 84723.0391, 84719.9531,
-    84720.0781, 84716.875,  84721.7344, 84721.7344, 84724.9219, 84722.6562,
-    84723.3047, 84724.0312, 84723.3438, 84723.3438, 84722.9688, 84720.125,
-    84720.2109, 84723.4922, 84718.2188, 84718.2188, 84725.1172, 84724.7969,
-    84722.0781, 84724.9922, 84722.8047, 84722.8047, 84724.6719, 84720.5781,
-    84724.75,   84722.0781, 84719.3594, 84719.3594, 84722.4609, 84720.5938,
-    84722.625,  84721.3672, 84722.9453, 84722.9453, 84724.2891, 84724.125,
-    84726.7188, 84718.8906, 84724.6094, 84724.6094, 84725.1406, 84724.25,
-    84723.7266, 84717.5625, 84721.3359, 84721.3359, 84727.9922, 84722.6406,
-    84718.9062, 84723.3281, 84721.9062, 84721.9062, 84723.4766, 84726.7188,
-    84726.4375, 84720.6797, 84727.0859, 84727.0859, 84726.3594, 84727.5781,
-    84717.6484, 84720.5625, 84722.75,   84722.75,   84725.5078, 84729.3203,
-    84723.8906, 84719.1484, 84725.1875, 84725.1875, 84725.0312, 84724.9062,
-    84722.2734, 84723.7734, 84721.7891, 84721.7891, 84724.5156, 84725.6094,
-    84724.0703, 84720.625,  84723.8281, 84723.8281, 84726.4766, 84720.2344,
-    84723.6797, 84723.9219, 84721,      84721,      84726.1484, 84724.9297,
-    84724.7656, 84722.6172, 84720.3906, 84720.3906, 84725.1562, 84726.125,
-    84727.1406, 84723.1641, 84719.4375, 84719.4375, 84717.5469, 84726.7422,
-    84719.5703, 84720.9922, 84719.1641, 84719.1641, 84725.6797, 84725.1484,
-    84724.9922, 84720.8125, 84723.4062, 84723.4062, 84725.8125, 84722.1641,
-    84726.4141, 84721.8359, 84721.9609, 84721.9609, 84724.2109, 84724.4531,
-    84722.8281, 84723.7656, 84721.8594, 84721.8594, 84724.3984, 84725.2891,
-    84721.7188, 84726.625,  84721.1953, 84721.1953, 84730.2578, 84727.1797,
-    84723.125,  84726.5312, 84724.5,    84724.5,    84722.8516, 84726.5781,
-    84725.3203, 84723.1719, 84725.5234, 84725.5234, 84723.8281, 84725.5781,
-    84725.4922, 84724.3203, 84722.4922, 84722.4922, 84729.2812, 84729.6406,
-    84720.6016, 84722.9922, 84722.4297, 84722.4297, 84726.6406, 84724.4922,
-    84727.5312, 84719.1016, 84721.5703, 84721.5703, 84724.1016, 84720.9375,
-    84726.125,  84723.5703, 84728.6406, 84728.6406, 84725.0781, 84723.8203,
-    84725.8906, 84722.7266, 84723.2969, 84723.2969, 84723.4531, 84725.3984,
-    84725.2734, 84727.1406, 84724.5469, 84724.5469, 84724.1172, 84727.3984,
-    84723.5469, 84721.9688, 84724.6016, 84724.6016, 84723.9219, 84721.8516,
-    84720.7188, 84725.6641, 84729.6797, 84729.6797, 84725.1953, 84725.5625,
-    84722.0312, 84721.8281, 84719.8047, 84719.8047, 84724.25,   84725.9453,
-    84727.3672, 84726.1953, 84724.9766, 84724.9766, 84728.5781, 84723.2656,
-    84725.5391, 84726.0234, 84722.5391, 84722.5391, 84724.2344, 84724.2734,
-    84724.7578, 84730.3125, 84727.7578, 84727.7578, 84723.1484, 84722.5,
-    84723.5547, 84725.2969, 84719.7891, 84719.7891, 84724.3438, 84726.6562,
-    84723.0469, 84724.625,  84725.2734, 84725.2734, 84728.875,  84722.9141,
-    84722.9531, 84723.6797, 84724.25,   84724.25,   84723.6016, 84728.1016,
-    84724.6562, 84719.5938, 84724.25,   84724.25,   84726.2578, 84724.3906,
-    84723.5781, 84721.3125, 84723.7031, 84723.7031, 84723.8203, 84719.7656,
-    84720.4531, 84721.3906, 84722.8906, 84722.8906, 84723.4219, 84722.125,
-    84724.4297, 84723.8672, 84725.6484, 84725.6484, 84724.0938, 84726.4453,
-    84730.4609, 84725.3516, 84720.0469, 84720.0469, 84725.9844, 84725.7812,
-    84725.3828, 84725.0938, 84726.3125, 84726.3125, 84723.5781, 84722.4062,
-    84731.3594, 84722,      84727.1484, 84727.1484, 84726.3359, 84725.2344,
-    84727.3438, 84724.7109, 84721.0234, 84721.0234, 84727.9688, 84722.1719,
-    84721,      84726.7188, 84723.4297, 84723.4297, 84726.3203, 84722.5078,
-    84723.6406, 84722.9531, 84722.3906, 84722.3906, 84729.0078, 84724.7969,
-    84724.1094, 84728.2812, 84726.0078, 84726.0078, 84728.0391, 84728.8125,
-    84719.3281, 84723.9922, 84726.0938, 84726.0938, 84724.8984, 84727.1719,
-    84722.3906, 84724.1719, 84723.7656, 84723.7656, 84722.0938, 84723.875,
-    84724.1641, 84724.8125, 84720.0312, 84720.0312, 84728.8594, 84723.4297,
-    84725.6172, 84723.9609, 84728.0938, 84728.0938, 84726.7422, 84721.9219,
-    84725.4062, 84724.7969, 84721.5547, 84721.5547, 84725.4297, 84725.3828,
-    84728.6328, 84728.3828, 84725.4688, 84725.4688, 84723.5078, 84727.4766,
-    84729.2656, 84719.4531, 84723.5859, 84723.5859, 84724.8594, 84724.4141,
-    84727.5781, 84723.7266, 84723.8906, 84723.8906, 84731.5156, 84729.1172,
-    84726.6484, 84723.3672, 84720.4844, 84720.4844, 84726.4141, 84728.2422,
-    84726.0469, 84719.6016, 84719.7266, 84719.7266, 84722.8203, 84725.6562,
-    84723.75,   84721.1562, 84720.3906, 84720.3906, 84734.4609, 84729.5156,
-    84724.7344, 84725.75,   84729.1094, 84729.1094, 84726.7266, 84724.1719,
-    84729.4453, 84721.5781, 84727.8594, 84727.8594, 84724.5391, 84729.1953,
-    84724.1719, 84730.7812, 84727.375,  84727.375,  84727.6562, 84727.0078,
-    84731.1016, 84723.6016, 84726.3984, 84726.3984, 84726.4375, 84725.4219,
-    84726.4375, 84723.1094, 84728.1797, 84728.1797, 84730.4922, 84725.1875,
-    84725.2656, 84724.375,  84728.3438, 84728.3438, 84724.0156, 84723.6094,
-    84726.0781, 84725.1875, 84725.4297, 84725.4297, 84724.2734, 84726.0156,
-    84727.2344, 84721.7969, 84724.9219, 84724.9219, 84728.4766, 84726.7344,
-    84729.9766, 84729.3672, 84722.0312, 84722.0312, 84725.3203, 84723.7812,
-    84722.2422, 84725.8906, 84721.875,  84721.875,  84725.7188, 84729.4062,
-    84722.3516, 84726.0469, 84721.3438, 84721.3438, 84727.8281, 84727.7422,
-    84728.0312, 84726.0391, 84729.125,  84729.125,  84729.8594, 84722.8828,
-    84720.1641, 84728.3125, 84724.75,   84724.75,   84725.5,    84727,
-    84730.2422, 84727,      84721.0391, 84721.0391, 84732.1562, 84726.5156,
-    84721.3281, 84726.7188, 84723.9219, 84723.9219, 84723.875,  84728.8984,
-    84723.1406, 84722.8203, 84723.6719, 84723.6719, 84726.9766, 84725.1094,
-    84723.4844, 84726.8125, 84725.9609, 84725.9609, 84723.9062, 84722.8906,
-    84724.5547, 84720.9453, 84722.8516, 84722.8516, 84726.8984, 84727.1797,
-    84726.25,   84723.125,  84721.1406, 84721.1406, 84723.4141, 84726.0469,
-    84720.6562, 84726.0938, 84722.9297, 84722.9297, 84725.4766, 84720.1641,
-    84726.1641, 84725.8828, 84724.8281, 84724.8281, 84724.625,  84730.6641,
-    84721.9531, 84721.3828, 84723.0859, 84723.0859, 84723.6719, 84717.4219,
-    84726.3828, 84725.4922, 84719.4922, 84719.4922, 84727.4141, 84727.6172,
-    84724.0078, 84726.4453, 84719.3516, 84719.3516, 84720.6875, 84725.1484,
-    84728.7188, 84723.8125, 84721.9844, 84721.9844, 84726.8672, 84726.4219,
-    84731.9766, 84720.7031, 84725.5703, 84725.5703, 84726.2656, 84726.5859,
-    84723.5078, 84720.625,  84721.4375, 84721.4375, 84724.6094, 84725.1406,
-    84722.7109, 84726.3594, 84721.8594, 84721.8594, 84725.8047, 84730.3828,
-    84724.9531, 84724.3438, 84723.6953, 84723.6953, 84725.0469, 84722.5312,
-    84730.3906, 84724.1484, 84725.8516, 84725.8516, 84725.8906, 84721.3906,
-    84726.2969, 84722.3203, 84723.3359, 84723.3359, 84722.9531, 84725.5469,
-    84724.3281, 84721.2891, 84724.4531, 84724.4531, 84728.0703, 84725.7188,
-    84726.6094, 84719.2734, 84721.625,  84721.625,  84725.9688, 84722.5625,
-    84723.8203, 84726.0938, 84718.9141, 84718.9141, 84727.3047, 84721.3438,
-    84723.2891, 84721.4688, 84725.8906, 84725.8906, 84725.8047, 84723.2109,
-    84722.4062, 84725.1172, 84721.3516, 84721.3516, 84728.3359, 84722.5,
-    84724.1562, 84719.0938, 84725.3359, 84725.3359, 84725.5938, 84722.0234,
-    84724.0078, 84724.0078, 84722.9531, 84722.9531, 84720.1406, 84724.7969,
-    84725.6484, 84725.7734, 84720.8281, 84720.8281, 84725.6172, 84725.5391,
-    84723.9141, 84722.7344, 84720.3906, 84720.3906, 84729.2109, 84725.6484,
-    84726.8203, 84725.8906, 84727.4297, 84727.4297, 84724.7578, 84721.6406,
-    84725.8984, 84718.3984, 84721.1953, 84721.1953, 84718.8828, 84725.9766,
-    84723.7891, 84720.1406, 84720.6719, 84720.6719, 84723.9219, 84719.9922,
-    84722.6641, 84722.2188, 84724.25,   84724.25,   84725.8047, 84725.3203,
-    84718.4297, 84723.4531, 84727.1406, 84727.1406, 84722.4219, 84722.5781,
-    84722.4609, 84722.8672, 84723.5156, 84723.5156, 84723.6875, 84725.4688,
-    84722.5547, 84719.2266, 84718.4609, 84718.4609, 84722.9219, 84721.875,
-    84721.875,  84717.2891, 84722.9219, 84722.9219, 84722.1172, 84718.8359,
-    84724.5938, 84720.5781, 84725.9688, 84725.9688, 84721.8047, 84719.6172,
-    84722.1719, 84722.8203, 84721.8047, 84721.8047, 84723.2188, 84720.8672,
-    84721.6016, 84721.6016, 84720.7891, 84720.7891, 84721.2969, 84722.875,
-    84723.5234, 84722.1875, 84724.0547, 84724.0547, 84721.5781, 84719.3906,
-    84727.0078, 84723.1953, 84722.7891, 84722.7891, 84724,      84719.0156,
-    84719.2188, 84720.8438, 84722.625,  84722.625,  84719.8672, 84721.5312,
-    84720.4375, 84718.1641, 84717.5547, 84717.5547, 84725.5469, 84726.4766,
-    84721.8984, 84719.0547, 84720.2344, 84720.2344, 84720.2422, 84722.2656,
-    84719.2656, 84720.2031, 84722.3125, 84722.3125, 84717.8125, 84727.75,
-    84720.25,   84721.3047, 84720.9375, 84720.9375, 84723.5,    84718.0703,
-    84717.8672, 84722.4453, 84716.4453, 84716.4453, 84720.7578, 84720.1094,
-    84719.3828, 84721.3281, 84718.8516, 84718.8516, 84724.6953, 84721.8203,
-    84721.1719, 84718.0859, 84721.0078, 84721.0078, 84721.7109, 84720.25,
-    84723.1328, 84724.8359, 84720.0938, 84720.0938, 84725.1406, 84721.125,
-    84720.5625, 84722.0625, 84718.2109, 84718.2109, 84717.3281, 84719.3125,
-    84722.6797, 84722.8828, 84723.6953, 84723.6953, 84715.8359, 84718.9609,
-    84724.8359, 84720.6172, 84722.4453, 84722.4453, 84718.7734, 84724.8125,
-    84719.5,    84719.0938, 84718.9297, 84718.9297, 84722.4219, 84723.3125,
-    84719.6641, 84723.1484, 84718.2031, 84718.2031, 84720.8906, 84720.4062,
-    84725.6406, 84717.7734, 84718.0938, 84718.0938, 84719.4453, 84721.5156,
-    84722.8516, 84721.5156, 84720.8672, 84720.8672, 84725.5781, 84723.1094,
-    84721.5234, 84719.7422, 84712.7266, 84712.7266, 84717.2812, 84717.125,
-    84718.8281, 84720.9766, 84715.8672, 84715.8672, 84719.9375, 84719.2891,
-    84719.3281, 84718.3594, 84717.5859, 84717.5859, 84716.6016, 84724.5078,
-    84719.3125, 84717.0078, 84718.0625, 84718.0625, 84727.8281, 84720.6562,
-    84722.0703, 84722.2734, 84724.1406, 84724.1406, 84717.8516, 84716.2344,
-    84718.2578, 84718.5859, 84718.9453, 84718.9453, 84723.7109, 84718.8438,
-    84723.1406, 84718.6016, 84718.4375, 84718.4375, 84723.2344, 84722.2969,
-    84724.8125, 84719.9453, 84721,      84721,      84720.4141, 84721.7109,
-    84718.0156, 84717.7344, 84718.9141, 84718.9141, 84721.1406, 84723.5312,
-    84725.2734, 84720.4922, 84715.75,   84715.75,   84721.875,  84718.3906,
-    84721.2656, 84721.4297, 84720.9062, 84720.9062, 84722.0469, 84720.4219,
-    84718.6406, 84718.4375, 84722.8203, 84722.8203, 84723.1094, 84723.4766,
-    84721.4453, 84718.2422, 84720.4375, 84720.4375, 84719.7344, 84720.2578,
-    84718.4375, 84715.3125, 84725.4922, 84725.4922, 84722.4531, 84716.5391,
-    84720.7969, 84723.7109, 84717.6328, 84717.6328, 84717.4141, 84721.8672,
-    84718.2188, 84713.1562, 84717.6172, 84717.6172, 84724.8281, 84722.4297,
-    84721.7812, 84720.7734, 84720.3672, 84720.3672, 84724.2188, 84718.7031,
-    84717.2031, 84717.2422, 84717.5703, 84717.5703, 84719.2031, 84718.6406,
-    84713.5312, 84719.6875, 84714.9062, 84714.9062, 84723.3047, 84722.0859,
-    84724.1953, 84718.2344, 84721.1953, 84721.1953, 84721.3125, 84719.5234,
-    84723.8203, 84718.9141, 84722.0781, 84722.0781, 84722.8906, 84718.2266,
-    84722.6094, 84715.5547, 84721.875,  84721.875,  84724.0078, 84719.9141,
-    84723.1953, 84719.5469, 84716.625,  84716.625,  84726.7109, 84720.875,
-    84716.375,  84717.9922, 84716.8203, 84716.8203, 84717.2578, 84718.8438,
-    84713.2891, 84717.0547, 84715.2734, 84715.2734, 84722.1719, 84726.1016,
-    84721.5234, 84716.8203, 84720.4688, 84720.4688, 84719.8516, 84723.0156,
-    84719.4922, 84715.6016, 84722.8984, 84722.8984, 84719.1562,
-};
\ No newline at end of file
diff --git a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_press_data.h b/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_press_data.h
deleted file mode 100644
index 282a02589..000000000
--- a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_press_data.h
+++ /dev/null
@@ -1,30 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Authors: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-/**
- * MS5803 pressure data from Lynx flight test in Roccaraso.
- * Sampled at 66 Hz (15 ms period).
- */
-static constexpr unsigned PRESSURE_DATA_SIZE = 8615;
-extern const float PRESSURE_DATA[PRESSURE_DATA_SIZE];
\ No newline at end of file
diff --git a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_pressure_static_data.cpp b/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_pressure_static_data.cpp
deleted file mode 100644
index 7b7641fab..000000000
--- a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_pressure_static_data.cpp
+++ /dev/null
@@ -1,924 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Authors: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include "lynx_pressure_static_data.h"
-
-const float PRESSURE_STATIC_DATA[PRESSURE_STATIC_DATA_SIZE] = {
-    88731.4141, 89149.5781, 88796.1328, 89030.1094, 89119.6953, 88875.7891,
-    88895.6875, 88746.3516, 88860.8438, 88915.6016, 88850.8906, 88855.8672,
-    88875.7891, 88930.5312, 88845.8984, 88935.5078, 88865.8203, 88920.5781,
-    88811.0547, 88830.9766, 88811.0547, 88850.8906, 88821.0156, 88796.1328,
-    88835.9609, 88791.1562, 88811.0547, 88786.1797, 88811.0547, 88746.3516,
-    88731.4141, 88771.2422, 88731.4141, 88751.3281, 88746.3516, 88696.5703,
-    88691.5938, 88636.8359, 88661.7188, 88671.6875, 88597.0078, 88606.9609,
-    88616.9219, 88621.8984, 88621.8984, 88502.4219, 88507.3984, 88587.0547,
-    88477.5391, 88552.2109, 88477.5391, 88527.3203, 88482.5156, 88437.7109,
-    88422.7734, 88377.9688, 88402.8594, 88387.9297, 88402.8594, 88397.8828,
-    88363.0391, 88263.4844, 88213.7031, 88188.8047, 88158.9453, 88213.7031,
-    88163.9141, 88099.2031, 88074.3125, 88168.8984, 88119.1094, 88089.2422,
-    87999.6328, 88019.5547, 87944.875,  88004.6172, 87910.0234, 87860.2578,
-    87845.3203, 87790.5547, 87845.3203, 87800.5156, 87720.8672, 87750.7344,
-    87715.8828, 87686.0234, 87636.2344, 87651.1797, 87616.3359, 87606.3672,
-    87526.7266, 87481.9141, 87566.5469, 87417.2031, 87417.2031, 87412.2266,
-    87317.6484, 87322.6172, 87347.5156, 87247.9375, 87158.3516, 87228.0391,
-    87252.9297, 87103.5859, 87073.7266, 86979.1328, 87113.5469, 87168.2969,
-    87058.7812, 87138.4375, 87013.9766, 87043.8516, 86889.5312, 86974.1484,
-    86859.6641, 86745.1641, 86760.1016, 86710.3203, 86511.2031, 86600.8047,
-    86451.4609, 86431.5469, 86421.5938, 86361.8516, 86312.0781, 86212.5156,
-    86207.5312, 86167.7109, 86222.4766, 85943.7031, 86053.2188, 86112.9453,
-    85943.7031, 85893.9219, 85874.0156, 85804.3047, 85774.4453, 85595.2266,
-    85605.1875, 85530.5156, 85580.2969, 85525.5391, 85485.7109, 85455.8516,
-    85406.0781, 85341.3516, 85261.7031, 85231.8359, 85196.9922, 85172.1016,
-    85057.6016, 85027.7344, 85152.1797, 85341.3516, 85401.0859, 85256.7188,
-    85196.9922, 85052.6328, 84818.6641, 84748.9609, 84893.3281, 84694.2031,
-    85142.2344, 85037.6875, 85072.5312, 84987.9062, 85142.2344, 85117.3438,
-    84609.5781, 84948.0859, 84808.7031, 84619.5391, 84629.4844, 84559.7891,
-    84604.6016, 84440.3281, 84390.5469, 84380.5859, 84091.8594, 84206.3594,
-    84246.1797, 84111.7734, 84191.4219, 84037.1016, 83967.3984, 84012.2109,
-    84007.2344, 83813.0859, 83837.9766, 83852.9062, 83862.8672, 83833,
-    83773.2656, 83633.8828, 83514.3984, 83604.0078, 83504.4453, 83549.25,
-    83335.1953, 83345.1484, 83399.9141, 83350.125,  83265.4922, 83365.0703,
-    83195.8047, 83250.5625, 83101.2266, 83026.5469, 83021.5781, 82936.9531,
-    82931.9766, 82936.9531, 82777.6562, 82757.7344, 82623.3281, 82772.6719,
-    82752.7656, 82722.8828, 82658.1719, 82638.2578, 82533.7188, 82483.9375,
-    82533.7188, 82379.3984, 82394.3438, 82404.2891, 82314.6875, 82284.8203,
-    82220.1094, 82205.1797, 82160.375,  82120.5469, 82030.9375, 82050.8516,
-    82030.9375, 81956.2578, 81941.3281, 81951.2969, 81911.4688, 81851.7266,
-    81796.9688, 81742.2109, 81801.9531, 81697.4219, 81657.5938, 81582.9062,
-    81577.9375, 81528.1562, 81508.2422, 81562.9922, 81433.5703, 81408.6875,
-    81443.5234, 81319.0859, 81338.9922, 81284.2344, 81274.2656, 81309.1172,
-    81134.8906, 81204.5859, 81090.0859, 81134.8906, 81060.2188, 80995.5156,
-    81010.4375, 80965.6328, 80876.0312, 80930.7891, 80900.9141, 80801.3594,
-    80806.3359, 80766.5078, 80746.5938, 80657,      80711.75,   80632.1016,
-    80647.0312, 80592.2812, 80572.3672, 80482.7656, 80467.8281, 80502.6719,
-    80482.7656, 80423.0234, 80313.5078, 80298.5703, 80154.2109, 80114.3906,
-    80139.2734, 80149.2344, 80074.5625, 80084.5234, 79989.9297, 79989.9297,
-    79999.8828, 79935.1797, 79945.1328, 79910.2812, 79840.5938, 79830.6328,
-    79855.5312, 79805.7422, 79770.8984, 79780.8516, 79691.2422, 79671.3438,
-    79631.5156, 79611.6016, 79616.5859, 79551.875,  79591.6797, 79467.2422,
-    79462.2656, 79422.4375, 79452.3125, 79397.5469, 79307.9453, 79367.6719,
-    79347.7734, 79312.9219, 79362.6953, 79307.9453, 79278.0781, 79208.375,
-    79203.3984, 79208.375,  79123.75,   79128.7344, 79083.9219, 79093.8828,
-    79044.1094, 79034.1484, 78984.3672, 78984.3672, 78954.5,    78904.7188,
-    78874.8438, 78864.8906, 78820.0859, 78825.0703, 78820.0859, 78770.3125,
-    78755.375,  78725.5078, 78705.5938, 78700.6172, 78630.9297, 78601.0547,
-    78611.0156, 78606.0312, 78606.0312, 78536.3359, 78491.5391, 78511.4531,
-    78451.7109, 78446.7422, 78476.6016, 78441.75,   78391.9766, 78342.1953,
-    78322.2891, 78327.2578, 78312.3281, 78297.3906, 78227.6953, 78202.8125,
-    78217.75,   78217.75,   78153.0234, 78133.1094, 78123.1641, 78093.2891,
-    78093.2891, 78063.4219, 78008.6641, 77998.7109, 77998.7109, 77963.8594,
-    77958.875,  77904.1328, 77869.2812, 77864.3047, 77864.3047, 77839.4062,
-    77829.4531, 77789.6328, 77799.5859, 77759.7578, 77744.8281, 77734.8672,
-    77685.0859, 77685.0859, 77660.2031, 77645.2656, 77630.3359, 77635.3047,
-    77595.4922, 77580.5547, 77620.375,  77540.7266, 77510.8594, 77495.9219,
-    77476.0156, 77441.1719, 77441.1719, 77421.25,   77431.2031, 77421.25,
-    77416.2656, 77406.3203, 77316.7188, 77301.7812, 77286.8438, 77266.9375,
-    77227.1094, 77217.1484, 77197.2344, 77182.2969, 77162.3984, 77152.4375,
-    77122.5703, 77107.6328, 77087.7266, 77077.7578, 77082.75,   77042.9219,
-    77032.9688, 77023,      77008.0703, 76978.2031, 76968.2578, 76943.3594,
-    76923.4453, 76908.5078, 76893.5781, 76873.6641, 76863.7109, 76848.7812,
-    76823.8828, 76808.9531, 76798.9922, 76794.0156, 76759.1719, 76749.2109,
-    76739.2578, 76714.3594, 76709.3906, 76694.4609, 76684.4922, 76654.6406,
-    76649.6484, 76634.7188, 76619.7891, 76594.8906, 76579.9609, 76565.0234,
-    76540.1406, 76535.1641, 76530.1797, 76510.2656, 76485.375,  76475.4219,
-    76450.5312, 76450.5312, 76440.5781, 76410.7031, 76395.7656, 76395.7656,
-    76370.8828, 76345.9922, 76345.9922, 76331.0625, 76301.1953, 76301.1953,
-    76276.2969, 76261.3672, 76251.4062, 76246.4297, 76241.4531, 76211.5859,
-    76196.6484, 76186.6953, 76166.7812, 76156.8125, 76141.8906, 76121.9766,
-    76117,      76102.0625, 76097.0938, 76062.2422, 76072.1953, 76052.2734,
-    76047.3047, 76032.3828, 76017.4375, 76002.5,    75977.6172, 75967.6484,
-    75962.6797, 75937.7891, 75932.8047, 75917.8828, 75907.9219, 75892.9844,
-    75883.0234, 75878.0547, 75858.1406, 75868.0938, 75848.1797, 75823.2969,
-    75818.3125, 75803.3828, 75783.4688, 75778.4844, 75768.5312, 75753.6016,
-    75748.6172, 75728.7109, 75713.7734, 75703.8281, 75698.8359, 75688.8828,
-    75683.9141, 75659.0156, 75649.0547, 75639.1094, 75629.1484, 75624.1797,
-    75619.1953, 75594.3047, 75589.3281, 75579.3672, 75554.4766, 75549.5,
-    75544.5156, 75524.6094, 75509.6797, 75509.6797, 75504.7031, 75489.7656,
-    75469.8594, 75469.8594, 75459.8906, 75449.9453, 75439.9766, 75430.0234,
-    75415.0938, 75405.1406, 75405.1406, 75385.2266, 75375.2656, 75375.2656,
-    75365.3203, 75350.375,  75340.4141, 75320.5,    75325.4922, 75310.5547,
-    75295.625,  75290.6484, 75280.6875, 75280.6875, 75255.7969, 75260.7734,
-    75240.8594, 75235.8828, 75235.8828, 75225.9219, 75210.9922, 75201.0391,
-    75191.0781, 75191.0781, 75181.125,  75171.1719, 75156.2344, 75151.25,
-    75146.2812, 75131.3438, 75131.3438, 75126.3672, 75111.4297, 75101.4766,
-    75101.4766, 75091.5234, 75076.5859, 75076.5859, 75061.6562, 75056.6797,
-    75051.6875, 75041.7422, 75036.7578, 75026.8047, 75016.8438, 75011.8672,
-    74996.9297, 74996.9297, 74986.9844, 74982,      74977.0312, 74967.0703,
-    74972.0469, 74957.1094, 74947.1484, 74942.1797, 74932.2188, 74932.2188,
-    74917.2812, 74917.2812, 74907.3203, 74897.3828, 74887.4219, 74887.4219,
-    74882.4375, 74872.4844, 74867.5078, 74857.5547, 74857.5547, 74847.5938,
-    74842.6094, 74837.6328, 74827.6797, 74827.6797, 74817.7188, 74812.7422,
-    74807.7734, 74792.8359, 74797.8047, 74787.8672, 74782.8828, 74782.8828,
-    74777.8984, 74772.9297, 74762.9609, 74753.0156, 74738.0781, 74738.0781,
-    74743.0547, 74738.0781, 74733.1016, 74728.1172, 74723.1406, 74713.1797,
-    74713.1797, 74708.2031, 74698.25,   74703.2344, 74688.3047, 74683.3203,
-    74683.3203, 74683.3203, 74678.3359, 74663.4141, 74673.3516, 74658.4219,
-    74658.4219, 74653.4531, 74643.4922, 74648.4688, 74638.5078, 74638.5078,
-    74628.5625, 74633.5391, 74623.5781, 74618.6016, 74618.6016, 74618.6016,
-    74608.6406, 74608.6406, 74603.6641, 74608.6406, 74603.6641, 74593.7109,
-    74593.7109, 74588.7344, 74583.7656, 74588.7344, 74578.7812, 74573.8047,
-    74573.8047, 74563.8438, 74558.8672, 74563.8438, 74563.8438, 74563.8438,
-    74553.8906, 74558.8672, 74553.8906, 74553.8906, 74543.9297, 74543.9297,
-    74533.9766, 74538.9531, 74533.9766, 74528.9922, 74528.9922, 74524.0156,
-    74528.9922, 74524.0156, 74524.0156, 74519.0469, 74519.0469, 74519.0469,
-    74519.0469, 74514.0625, 74514.0625, 74509.0859, 74504.1016, 74509.0859,
-    74504.1016, 74504.1016, 74499.1328, 74504.1016, 74499.1328, 74504.1016,
-    74504.1016, 74499.1328, 74494.1484, 74499.1328, 74494.1484, 74494.1484,
-    74484.1953, 74489.1641, 74489.1641, 74489.1641, 74484.1953, 74484.1953,
-    74489.1641, 74494.1484, 74489.1641, 74484.1953, 74484.1953, 74479.2109,
-    74484.1953, 74489.1641, 74489.1641, 74484.1953, 74484.1953, 74479.2109,
-    74489.1641, 74484.1953, 74489.1641, 74484.1953, 74479.2109, 74489.1641,
-    74489.1641, 74484.1953, 74484.1953, 74484.1953, 74494.1484, 74489.1641,
-    74489.1641, 74489.1641, 74494.1484, 74499.1328, 74474.2422, 74459.3047,
-    74484.1953, 74514.0625, 74509.0859, 74509.0859, 74479.2109, 74509.0859,
-    74504.1016, 74509.0859, 74489.1641, 74504.1016, 74509.0859, 74514.0625,
-    74514.0625, 74519.0469, 74519.0469, 74514.0625, 74514.0625, 74519.0469,
-    74504.1016, 74543.9297, 74543.9297, 74553.8906, 74528.9922, 74504.1016,
-    74484.1953, 74489.1641, 74494.1484, 74489.1641, 74504.1016, 74489.1641,
-    74499.1328, 74489.1641, 74528.9922, 74509.0859, 74484.1953, 74504.1016,
-    74484.1953, 74519.0469, 74469.2656, 74474.2422, 74484.1953, 74504.1016,
-    74499.1328, 74548.9141, 74489.1641, 74533.9766, 74489.1641, 74514.0625,
-    74543.9297, 74543.9297, 74543.9297, 74603.6641, 74568.8203, 74608.6406,
-    74568.8203, 74553.8906, 74499.1328, 74509.0859, 74509.0859, 74489.1641,
-    74429.4453, 74444.3672, 74444.3672, 74504.1016, 74499.1328, 74509.0859,
-    74524.0156, 74533.9766, 74563.8438, 74583.7656, 74593.7109, 74588.7344,
-    74618.6016, 74608.6406, 74608.6406, 74603.6641, 74603.6641, 74648.4688,
-    74653.4531, 74663.4141, 74673.3516, 74668.3906, 74683.3203, 74688.3047,
-    74693.2656, 74688.3047, 74678.3359, 74673.3516, 74668.3906, 74653.4531,
-    74643.4922, 74633.5391, 74583.7656, 74608.6406, 74598.6875, 74563.8438,
-    74603.6641, 74578.7812, 74623.5781, 74653.4531, 74593.7109, 74638.5078,
-    74678.3359, 74668.3906, 74678.3359, 74703.2344, 74688.3047, 74753.0156,
-    74767.9453, 74787.8672, 74782.8828, 74792.8359, 74797.8047, 74802.7891,
-    74792.8359, 74807.7734, 74812.7422, 74817.7188, 74817.7188, 74842.6094,
-    74832.6562, 74807.7734, 74827.6797, 74787.8672, 74832.6562, 74862.5312,
-    74857.5547, 74862.5312, 74842.6094, 74857.5547, 74832.6562, 74837.6328,
-    74837.6328, 74832.6562, 74872.4844, 74827.6797, 74867.5078, 74882.4375,
-    74907.3203, 74917.2812, 74917.2812, 74927.2422, 74932.2188, 74942.1797,
-    74937.2031, 74917.2812, 74917.2812, 74937.2031, 74937.2031, 74937.2031,
-    74952.1328, 74962.0859, 74977.0312, 74967.0703, 74982,      74996.9297,
-    74986.9844, 74991.9609, 75001.9141, 75016.8438, 75011.8672, 75011.8672,
-    75021.8281, 75021.8281, 75026.8047, 75041.7422, 75046.7109, 75041.7422,
-    75051.6875, 75066.625,  75071.6016, 75066.625,  75076.5859, 75071.6016,
-    75081.5625, 75071.6016, 75076.5859, 75091.5234, 75086.5391, 75061.6562,
-    75071.6016, 75081.5625, 75096.5078, 75116.3984, 75026.8047, 75006.8906,
-    75051.6875, 75136.3203, 75171.1719, 75141.2891, 75141.2891, 75161.2109,
-    75156.2344, 75196.0625, 75171.1719, 75156.2344, 75186.1016, 75191.0781,
-    75171.1719, 75196.0625, 75191.0781, 75225.9219, 75245.8359, 75240.8594,
-    75240.8594, 75245.8359, 75265.75,   75235.8828, 75265.75,   75265.75,
-    75280.6875, 75270.7266, 75275.7109, 75285.6562, 75300.6016, 75305.5703,
-    75315.5312, 75320.5,    75315.5312, 75320.5,    75320.5,    75325.4922,
-    75340.4141, 75330.4688, 75320.5,    75345.3984, 75350.375,  75360.3359,
-    75350.375,  75340.4141, 75385.2266, 75375.2656, 75375.2656, 75385.2266,
-    75380.25,   75390.2031, 75430.0234, 75410.1172, 75415.0938, 75425.0391,
-    75435.0078, 75435.0078, 75459.8906, 75435.0078, 75410.1172, 75430.0234,
-    75469.8594, 75479.8047, 75444.9609, 75484.7891, 75449.9453, 75474.8281,
-    75464.8672, 75459.8906, 75435.0078, 75420.0703, 75385.2266, 75410.1172,
-    75360.3359, 75395.1797, 75345.3984, 75305.5703, 75315.5312, 75410.1172,
-    75435.0078, 75474.8281, 75479.8047, 75509.6797, 75554.4766, 75484.7891,
-    75509.6797, 75464.8672, 75444.9609, 75435.0078, 75415.0938, 75400.1641,
-    75385.2266, 75405.1406, 75375.2656, 75410.1172, 75420.0703, 75479.8047,
-    75484.7891, 75484.7891, 75494.7422, 75514.6562, 75519.6328, 75519.6328,
-    75499.7188, 75489.7656, 75484.7891, 75489.7656, 75494.7422, 75524.6094,
-    75559.4609, 75514.6562, 75629.1484, 75639.1094, 75673.9531, 75678.9297,
-    75683.9141, 75768.5312, 75783.4688, 75753.6016, 75763.5547, 75783.4688,
-    75793.4375, 75798.4062, 75793.4375, 75798.4062, 75808.3594, 75803.3828,
-    75818.3125, 75833.25,   75818.3125, 75828.2812, 75833.25,   75838.2266,
-    75838.2266, 75843.2109, 75843.2109, 75848.1797, 75868.0938, 75883.0234,
-    75858.1406, 75878.0547, 75868.0938, 75888.0078, 75848.1797, 75863.1172,
-    75863.1172, 75838.2266, 75853.1562, 75868.0938, 75878.0547, 75858.1406,
-    75902.9453, 75922.8516, 75952.7266, 75972.6328, 75977.6172, 75972.6328,
-    75962.6797, 75947.7422, 75977.6172, 75972.6328, 76002.5,    76017.4375,
-    76002.5,    76017.4375, 76027.4062, 76022.4141, 76047.3047, 76047.3047,
-    76062.2422, 76052.2734, 76067.2188, 76067.2188, 76062.2422, 76072.1953,
-    76077.1797, 76087.125,  76092.1094, 76092.1094, 76102.0625, 76097.0938,
-    76107.0469, 76107.0469, 76117,      76131.9375, 76121.9766, 76141.8906,
-    76146.8672, 76166.7812, 76166.7812, 76166.7812, 76186.6953, 76191.6719,
-    76201.625,  76196.6484, 76191.6719, 76206.6016, 76211.5859, 76196.6484,
-    76221.5391, 76226.5234, 76201.625,  76196.6484, 76216.5625, 76211.5859,
-    76221.5391, 76236.4766, 76276.2969, 76281.2734, 76246.4297, 76271.3203,
-    76276.2969, 76271.3203, 76311.1484, 76321.1016, 76316.125,  76311.1484,
-    76316.125,  76350.9766, 76360.9141, 76360.9141, 76365.9062, 76375.8516,
-    76370.8828, 76385.8203, 76370.8828, 76400.75,   76400.75,   76400.75,
-    76405.7344, 76420.6719, 76415.6797, 76440.5781, 76445.5547, 76445.5547,
-    76440.5781, 76445.5547, 76455.5078, 76455.5078, 76470.4375, 76475.4219,
-    76480.3906, 76485.375,  76500.3125, 76485.375,  76495.3359, 76495.3359,
-    76510.2656, 76515.2422, 76525.2031, 76535.1641, 76535.1641, 76540.1406,
-    76545.1172, 76565.0234, 76570,      76570,      76560.0469, 76584.9375,
-    76579.9609, 76584.9375, 76579.9609, 76589.9141, 76594.8906, 76579.9609,
-    76584.9375, 76594.8906, 76579.9609, 76579.9609, 76570,      76570,
-    76589.9141, 76579.9609, 76589.9141, 76574.9844, 76599.875,  76634.7188,
-    76674.5391, 76689.4766, 76704.4062, 76704.4062, 76709.3906, 76709.3906,
-    76729.3125, 76724.3281, 76739.2578, 76729.3125, 76734.2812, 76749.2109,
-    76759.1719, 76764.1562, 76769.125,  76744.2422, 76749.2109, 76769.125,
-    76734.2812, 76784.0547, 76784.0547, 76769.125,  76823.8828, 76808.9531,
-    76808.9531, 76794.0156, 76764.1562, 76779.0859, 76784.0547, 76813.9375,
-    76754.1875, 76848.7812, 76868.6875, 76878.6406, 76848.7812, 76848.7812,
-    76858.7266, 76873.6641, 76903.5312, 76908.5078, 76913.4922, 76923.4453,
-    76913.4922, 76953.3125, 76943.3594, 76968.2578, 76963.2812, 76983.1797,
-    76973.2266, 76988.1484, 76983.1797, 76998.1172, 76993.1406, 77003.0938,
-    76993.1406, 76993.1406, 76998.1172, 76993.1406, 76998.1172, 76998.1172,
-    76978.2031, 76988.1484, 76983.1797, 77023,      77027.9844, 77042.9219,
-    77087.7266, 77067.8203, 77097.6719, 77097.6719, 77107.6328, 77107.6328,
-    77117.5938, 77122.5703, 77127.5469, 77127.5469, 77142.4766, 77147.4609,
-    77147.4609, 77152.4375, 77167.375,  77162.3984, 77167.375,  77182.2969,
-    77182.2969, 77182.2969, 77202.2188, 77187.2812, 77212.1719, 77217.1484,
-    77232.0859, 77242.0391, 77232.0859, 77232.0859, 77252,      77256.9766,
-    77256.9766, 77266.9375, 77271.9141, 77266.9375, 77286.8438, 77296.7969,
-    77291.8203, 77311.7266, 77316.7188, 77326.6641, 77321.6953, 77336.625,
-    77341.6094, 77351.5625, 77341.6094, 77351.5625, 77361.5156, 77361.5156,
-    77376.4531, 77361.5156, 77386.4062, 77386.4062, 77401.3359, 77401.3359,
-    77411.2969, 77406.3203, 77406.3203, 77401.3359, 77396.3594, 77391.3828,
-    77381.4297, 77361.5156, 77331.6406, 77286.8438, 77296.7969, 77346.5781,
-    77356.5469, 77391.3828, 77406.3203, 77406.3203, 77456.0938, 77480.9922,
-    77505.875,  77510.8594, 77540.7266, 77550.6875, 77535.75,   77565.6094,
-    77565.6094, 77580.5547, 77570.5938, 77585.5312, 77585.5312, 77585.5312,
-    77600.4531, 77610.4141, 77610.4141, 77615.3984, 77625.3516, 77635.3047,
-    77645.2656, 77635.3047, 77630.3359, 77645.2656, 77640.2891, 77630.3359,
-    77620.375,  77625.3516, 77630.3359, 77630.3359, 77595.4922, 77655.2188,
-    77655.2188, 77685.0859, 77700.0312, 77705,      77724.9062, 77734.8672,
-    77744.8281, 77749.8125, 77749.8125, 77764.7422, 77769.7188, 77779.6719,
-    77774.6953, 77779.6719, 77774.6953, 77799.5859, 77789.6328, 77789.6328,
-    77804.5547, 77799.5859, 77799.5859, 77804.5547, 77834.4375, 77849.3672,
-    77874.2578, 77864.3047, 77859.3203, 77884.2109, 77874.2578, 77889.1875,
-    77839.4062, 77839.4062, 77784.6641, 77779.6719, 77854.3438, 77859.3203,
-    77834.4375, 77859.3203, 77869.2812, 77864.3047, 77844.3828, 77854.3438,
-    77864.3047, 77854.3438, 77859.3203, 77844.3828, 77854.3438, 77879.2344,
-    77899.1484, 77958.875,  77953.9062, 77983.7812, 77988.7578, 78023.6016,
-    78028.5703, 77988.7578, 77968.8438, 77953.9062, 77988.7578, 78028.5703,
-    77938.9688, 77983.7812, 77998.7109, 77973.8125, 77953.9062, 77904.1328,
-    77884.2109, 77909.1016, 77919.0547, 77933.9922, 77963.8594, 77993.7266,
-    78073.3828, 78063.4219, 78093.2891, 78143.0703, 78113.2031, 78108.2344,
-    78187.875,  78123.1641, 78197.8281, 78187.875,  78167.9609, 78172.9453,
-    78113.2031, 78143.0703, 78138.0938, 78153.0234, 78177.9219, 78172.9453,
-    78212.7656, 78177.9219, 78242.6328, 78257.5703, 78252.5938, 78282.4531,
-    78282.4531, 78307.3516, 78292.4219, 78292.4219, 78307.3516, 78302.375,
-    78337.2188, 78312.3281, 78297.3906, 78327.2578, 78337.2188, 78327.2578,
-    78347.1719, 78352.1406, 78317.3047, 78342.1953, 78337.2188, 78372.0625,
-    78367.0781, 78372.0625, 78367.0781, 78372.0625, 78377.0469, 78391.9766,
-    78406.9141, 78396.9609, 78416.8672, 78396.9609, 78391.9766, 78406.9141,
-    78411.8984, 78411.8984, 78406.9141, 78411.8984, 78421.8438, 78426.8203,
-    78446.7422, 78456.6875, 78491.5391, 78521.4062, 78521.4062, 78526.3906,
-    78546.2891, 78541.3125, 78556.25,   78556.25,   78481.5859, 78516.4297,
-    78506.4688, 78491.5391, 78421.8438, 78391.9766, 78382.0156, 78421.8438,
-    78426.8203, 78426.8203, 78436.7734, 78431.7969, 78396.9609, 78416.8672,
-    78496.5156, 78581.1406, 78620.9609, 78660.7891, 78596.0781, 78635.8984,
-    78715.5547, 78625.9453, 78630.9297, 78630.9297, 78640.875,  78650.8359,
-    78685.6875, 78660.7891, 78675.7188, 78680.7109, 78700.6172, 78735.4688,
-    78720.5391, 78740.4297, 78750.3984, 78775.2812, 78770.3125, 78780.2578,
-    78780.2578, 78795.1953, 78820.0859, 78805.1641, 78825.0703, 78830.0469,
-    78835.0234, 78840.0078, 78844.9766, 78854.9297, 78854.9297, 78869.8672,
-    78869.8672, 78869.8672, 78874.8438, 78889.7812, 78894.7578, 78884.8047,
-    78904.7188, 78914.6797, 78919.6562, 78924.6328, 78929.6016, 78934.5859,
-    78939.5703, 78939.5703, 78944.5391, 78959.4688, 78949.5156, 78964.4531,
-    78969.4297, 78974.4062, 78979.3828, 78999.2969, 78994.3203, 79004.2812,
-    78999.2969, 79004.2812, 78999.2969, 78964.4531, 78979.3828, 78939.5703,
-    78939.5703, 78914.6797, 78959.4688, 78969.4297, 78984.3672, 79024.1953,
-    79024.1953, 79049.0781, 79064.0078, 79068.9844, 79093.8828, 79103.8359,
-    79118.7734, 79118.7734, 79123.75,   79138.6875, 79143.6641, 79128.7344,
-    79133.7031, 79143.6641, 79133.7031, 79113.7969, 79113.7969, 79128.7344,
-    79143.6641, 79153.6172, 79188.4688, 79178.5078, 79198.4219, 79178.5078,
-    79168.5469, 79168.5469, 79143.6641, 79158.5938, 79108.8203, 79073.9766,
-    79059.0391, 79103.8359, 79093.8828, 79133.7031, 79153.6172, 79193.4453,
-    79233.2656, 79258.1562, 79278.0781, 79238.25,   79273.0938, 79302.9531,
-    79297.9844, 79283.0391, 79278.0781, 79268.1094, 79283.0391, 79322.8672,
-    79268.1094, 79317.8906, 79352.7422, 79372.6484, 79372.6484, 79407.4922,
-    79392.5625, 79412.4766, 79422.4375, 79407.4922, 79402.5156, 79437.3672,
-    79417.4609, 79442.3438, 79407.4922, 79432.3984, 79447.3281, 79427.4141,
-    79452.3125, 79507.0625, 79497.1016, 79512.0469, 79507.0625, 79512.0469,
-    79521.9922, 79531.9531, 79541.9141, 79546.8906, 79551.875,  79556.8359,
-    79566.8047, 79556.8359, 79586.7109, 79591.6797, 79576.75,   79586.7109,
-    79591.6797, 79606.6172, 79596.6641, 79616.5859, 79606.6172, 79611.6016,
-    79591.6797, 79586.7109, 79536.9297, 79596.6641, 79541.9141, 79581.7344,
-    79606.6172, 79611.6016, 79586.7109, 79566.8047, 79596.6641, 79616.5859,
-    79606.6172, 79611.6016, 79606.6172, 79651.4297, 79601.6406, 79636.4922,
-    79641.4609, 79636.4922, 79616.5859, 79636.4922, 79666.3672, 79656.4141,
-    79656.4141, 79716.1328, 79701.2109, 79741.0391, 79760.9453, 79775.875,
-    79755.9688, 79775.875,  79765.9219, 79755.9688, 79765.9219, 79775.875,
-    79790.8125, 79790.8125, 79805.7422, 79780.8516, 79840.5938, 79845.5703,
-    79855.5312, 79865.4844, 79875.4375, 79880.4141, 79895.3438, 79900.3281,
-    79905.3047, 79905.3047, 79920.2422, 79910.2812, 79930.1953, 79940.1562,
-    79945.1328, 79950.1016, 79960.0703, 79979.9844, 79979.9844, 79994.9141,
-    79999.8828, 79994.9141, 80004.8672, 80004.8672, 79999.8828, 80009.8516,
-    80014.8203, 80019.8047, 80029.7578, 80034.7344, 80049.6719, 80049.6719,
-    80059.625,  80064.6094, 80064.6094, 80074.5625, 80084.5234, 80074.5625,
-    80079.5469, 80074.5625, 80084.5234, 80084.5234, 80084.5234, 80099.4453,
-    80109.3984, 80129.3203, 80134.2969, 80129.3203, 80149.2344, 80139.2734,
-    80134.2969, 80114.3906, 80099.4453, 80094.4766, 80134.2969, 80174.125,
-    80194.0312, 80174.125,  80139.2734, 80124.3438, 80129.3203, 80104.4219,
-    80099.4453, 80119.3594, 80119.3594, 80134.2969, 80164.1719, 80203.9922,
-    80208.9688, 80174.125,  80258.75,   80268.7109, 80268.7109, 80318.4922,
-    80278.6641, 80273.6797, 80238.8359, 80308.5234, 80263.7266, 80288.6172,
-    80313.5078, 80308.5234, 80308.5234, 80308.5234, 80343.3672, 80263.7266,
-    80218.9141, 80228.8828, 80288.6172, 80343.3672, 80323.4609, 80348.3594,
-    80288.6172, 80238.8359, 80393.1562, 80388.1875, 80442.9375, 80383.2031,
-    80358.3125, 80363.2891, 80338.3906, 80363.2891, 80432.9766, 80432.9766,
-    80408.0859, 80408.0859, 80452.8906, 80447.9141, 80482.7656, 80517.6094,
-    80517.6094, 80497.6953, 80522.5859, 80527.5703, 80552.4609, 80552.4609,
-    80572.3672, 80557.4375, 80552.4609, 80562.4141, 80552.4609, 80582.3281,
-    80562.4141, 80587.3047, 80592.2812, 80617.1719, 80627.1172, 80612.1797,
-    80627.1172, 80632.1016, 80637.0859, 80637.0859, 80652.0156, 80657,
-    80657,      80671.9375, 80676.9141, 80681.8828, 80696.8203, 80696.8203,
-    80691.8438, 80686.8594, 80701.7969, 80686.8594, 80647.0312, 80661.9688,
-    80671.9375, 80647.0312, 80681.8828, 80696.8203, 80691.8438, 80731.6562,
-    80806.3359, 80776.4688, 80796.3906, 80776.4688, 80746.5938, 80731.6562,
-    80746.5938, 80771.4844, 80776.4688, 80791.4062, 80786.4297, 80806.3359,
-    80746.5938, 80761.5469, 80776.4688, 80756.5547, 80736.6406, 80786.4297,
-    80801.3594, 80826.25,   80826.25,   80851.1406, 80846.1562, 80861.0938,
-    80871.0547, 80871.0547, 80856.1172, 80915.8516, 80935.7578, 80925.8047,
-    80900.9141, 80915.8516, 80930.7891, 80930.7891, 80920.8281, 80876.0312,
-    80890.9688, 80905.9062, 80920.8281, 80975.5938, 80950.6953, 80960.6562,
-    81005.4531, 80985.5469, 80975.5938, 81005.4531, 81005.4531, 81015.4219,
-    81045.2812, 81065.2031, 81080.125,  81095.0625, 81095.0625, 81100.0469,
-    81100.0469, 81110,      81124.9297, 81144.8438, 81129.9062, 81144.8438,
-    81149.8203, 81159.7734, 81159.7734, 81164.7578, 81164.7578, 81159.7734,
-    81164.7578, 81149.8203, 81174.7109, 81204.5859, 81184.6719, 81184.6719,
-    81224.4922, 81234.4453, 81259.3359, 81244.4062, 81244.4062, 81254.3672,
-    81209.5625, 81194.625,  81184.6719, 81184.6719, 81194.625,  81194.625,
-    81184.6719, 81224.4922, 81209.5625, 81289.2109, 81294.1875, 81324.0547,
-    81348.9375, 81309.1172, 81304.1484, 81289.2109, 81324.0547, 81264.3203,
-    81279.25,   81343.9609, 81358.8984, 81378.8125, 81393.7422, 81398.7266,
-    81433.5703, 81433.5703, 81433.5703, 81423.625,  81428.5938, 81438.5469,
-    81438.5469, 81428.5938, 81403.7031, 81423.625,  81433.5703, 81423.625,
-    81433.5703, 81423.625,  81423.625,  81413.6641, 81423.625,  81458.4688,
-    81488.3359, 81508.2422, 81538.1172, 81548.0625, 81558.0234, 81558.0234,
-    81558.0234, 81567.9844, 81567.9844, 81572.9609, 81587.8906, 81597.8438,
-    81587.8906, 81597.8438, 81602.8281, 81592.875,  81592.875,  81572.9609,
-    81567.9844, 81587.8906, 81612.7891, 81627.7188, 81677.5,    81632.6953,
-    81597.8438, 81597.8438, 81617.7578, 81627.7188, 81677.5,    81692.4375,
-    81717.3203, 81717.3203, 81752.1641, 81742.2109, 81742.2109, 81757.1406,
-    81762.125,  81757.1406, 81772.0781, 81777.0547, 81782.0391, 81791.9922,
-    81811.9062, 81811.9062, 81806.9297, 81826.8438, 81826.8438, 81836.7969,
-    81831.8203, 81836.7969, 81841.7812, 81846.7578, 81866.6641, 81861.6797,
-    81851.7266, 81866.6641, 81871.6406, 81871.6406, 81881.6016, 81906.4844,
-    81911.4688, 81931.3906, 81921.4219, 81926.4062, 81931.3906, 81936.3594,
-    81911.4688, 81916.4453, 81901.5078, 81871.6406, 81866.6641, 81866.6641,
-    81896.5312, 81861.6797, 81901.5078, 81846.7578, 81911.4688, 81926.4062,
-    81936.3594, 81966.2266, 82016.0078, 81971.2031, 82006.0469, 81976.1719,
-    81986.1406, 82006.0469, 82016.0078, 81991.1094, 82011.0312, 82006.0469,
-    82011.0312, 82001.0781, 81961.25,   81951.2969, 81951.2969, 82006.0469,
-    82040.8984, 82080.7188, 82095.6484, 82140.4609, 82140.4609, 82170.3203,
-    82100.6328, 82155.3984, 82085.7031, 82175.2969, 82125.5312, 82130.5,
-    82160.375,  82160.375,  82170.3203, 82180.2812, 82225.0859, 82230.0625,
-    82259.9297, 82254.9531, 82264.9062, 82259.9297, 82245,      82245,
-    82249.9766, 82245,      82245,      82254.9531, 82274.8672, 82289.7969,
-    82319.6719, 82319.6719, 82314.6875, 82289.7969, 82264.9062, 82269.8906,
-    82284.8203, 82334.6016, 82344.5625, 82349.5391, 82374.4297, 82374.4297,
-    82399.3203, 82379.3984, 82409.2734, 82429.1953, 82424.2031, 82444.1172,
-    82454.0781, 82454.0781, 82469.0156, 82464.0312, 82464.0312, 82488.9141,
-    82488.9141, 82488.9141, 82493.8984, 82493.8984, 82498.875,  82493.8984,
-    82478.9688, 82478.9688, 82473.9844, 82473.9844, 82483.9375, 82493.8984,
-    82543.6875, 82533.7188, 82543.6875, 82533.7188, 82513.8125, 82488.9141,
-    82488.9141, 82508.8359, 82493.8984, 82518.7891, 82558.6172, 82598.4375,
-    82623.3281, 82623.3281, 82643.2422, 82663.1641, 82643.2422, 82613.375,
-    82553.6406, 82598.4375, 82658.1719, 82648.2266, 82638.2578, 82678.0859,
-    82732.8516, 82678.0859, 82663.1641, 82698.0078, 82693.0156, 82693.0156,
-    82702.9766, 82688.0391, 82717.9141, 82668.1328, 82673.1172, 82693.0156,
-    82707.9531, 82722.8828, 82678.0859, 82807.5156, 82802.5391, 82822.4531,
-    82787.6016, 82777.6562, 82837.3828, 82807.5156, 82847.3438, 82792.5781,
-    82852.3203, 82842.3672, 82857.2969, 82867.2656, 82897.125,  82887.1719,
-    82912.0547, 82887.1719, 82897.125,  82907.0781, 82926.9844, 82941.9219,
-    82966.8203, 82946.9062, 82951.8828, 82926.9844, 82941.9219, 82951.8828,
-    82966.8203, 82966.8203, 82986.7422, 83006.6406, 83006.6406, 82996.6797,
-    82991.7031, 83011.6172, 82986.7422, 82996.6797, 83006.6406, 83061.3984,
-    83011.6172, 83021.5781, 83001.6641, 82991.7031, 83026.5469, 83031.5234,
-    83006.6406, 83016.5938, 82996.6797, 83061.3984, 83086.2891, 83106.1953,
-    83106.1953, 83141.0547, 83131.0938, 83146.0234, 83165.9453, 83180.875,
-    83165.9453, 83151,      83141.0547, 83165.9453, 83136.0703, 83151,
-    83131.0938, 83175.8984, 83205.7656, 83205.7656, 83245.5938, 83235.6328,
-    83215.7188, 83230.6484, 83250.5625, 83300.3438, 83290.3984, 83290.3984,
-    83300.3438, 83285.4141, 83305.3203, 83315.2734, 83320.25,   83325.2422,
-    83330.2188, 83315.2734, 83305.3203, 83300.3438, 83320.25,   83340.1641,
-    83355.1016, 83380,      83389.9531, 83394.9297, 83384.9688, 83399.9141,
-    83419.8125, 83399.9141, 83365.0703, 83399.9141, 83370.0391, 83414.8516,
-    83429.7734, 83429.7734, 83444.7109, 83474.5781, 83479.5625, 83494.4922,
-    83484.5391, 83509.4297, 83499.4688, 83524.3594, 83519.375,  83514.3984,
-    83534.3125, 83514.3984, 83529.3359, 83564.1875, 83549.25,   83559.2109,
-    83574.1328, 83569.1719, 83569.1719, 83584.1016, 83579.1172, 83599.0391,
-    83584.1016, 83569.1719, 83559.2109, 83549.25,   83514.3984, 83509.4297,
-    83494.4922, 83484.5391, 83519.375,  83534.3125, 83574.1328, 83574.1328,
-    83599.0391, 83643.8281, 83658.7578, 83663.7422, 83678.6797, 83708.5469,
-    83728.4609, 83678.6797, 83718.5078, 83733.4297, 83738.4219, 83713.5312,
-    83728.4609, 83733.4297, 83733.4297, 83728.4609, 83703.5781, 83703.5781,
-    83718.5078, 83723.4766, 83728.4609, 83733.4297, 83718.5078, 83713.5312,
-    83743.3906, 83768.2812, 83788.1953, 83803.1406, 83783.2188, 83837.9766,
-    83837.9766, 83867.8516, 83887.7578, 83902.6953, 83912.6484, 83922.6172,
-    83932.5547, 83937.5391, 83937.5391, 83942.5156, 83937.5391, 83962.4297,
-    83942.5156, 83922.6172, 83932.5547, 83937.5391, 83952.4766, 83972.3906,
-    83972.3906, 83982.3359, 83992.3047, 83982.3359, 83962.4297, 83962.4297,
-    83967.3984, 84012.2109, 83982.3359, 84022.1641, 84061.9922, 84057.0078,
-    84086.875,  84081.8984, 84081.8984, 84076.9297, 84076.9297, 84071.9453,
-    84081.8984, 84076.9297, 84091.8594, 84106.7969, 84091.8594, 84116.7578,
-    84116.7578, 84111.7734, 84121.7266, 84146.6172, 84146.6172, 84181.4688,
-    84186.4453, 84196.4062, 84206.3594, 84216.3125, 84211.3359, 84211.3359,
-    84201.3672, 84216.3125, 84221.2891, 84241.1953, 84226.2734, 84206.3594,
-    84176.4844, 84216.3125, 84276.0469, 84290.9766, 84295.9609, 84276.0469,
-    84281.0234, 84281.0234, 84276.0469, 84310.8984, 84310.8984, 84340.7656,
-    84335.7891, 84330.8125, 84335.7891, 84325.8281, 84320.8438, 84310.8984,
-    84300.9453, 84310.8984, 84320.8438, 84365.6562, 84370.625,  84370.625,
-    84390.5469, 84385.5703, 84420.4141, 84395.5156, 84365.6562, 84425.3906,
-    84415.4375, 84460.2344, 84470.1953, 84415.4375, 84465.2109, 84480.1484,
-    84500.0625, 84500.0625, 84510.0156, 84524.9453, 84534.9141, 84544.8672,
-    84544.8672, 84559.7891, 84564.7734, 84564.7734, 84569.75,   84574.7266,
-    84589.6641, 84594.6328, 84584.6953, 84589.6641, 84579.7109, 84609.5781,
-    84594.6328, 84614.5547, 84634.4688, 84634.4688, 84654.3828, 84659.3516,
-    84694.2031, 84669.3125, 84674.2969, 84674.2969, 84659.3516, 84704.1641,
-    84694.2031, 84654.3828, 84719.0938, 84758.9219, 84694.2031, 84694.2031,
-    84758.9219, 84739.0156, 84724.0781, 84768.875,  84753.9453, 84763.8906,
-    84753.9453, 84798.7422, 84778.8359, 84813.6797, 84798.7422, 84783.8047,
-    84788.7812, 84788.7812, 84798.7422, 84808.7031, 84803.7188, 84868.4297,
-    84848.5234, 84873.4141, 84873.4141, 84883.3672, 84878.3906, 84843.5547,
-    84913.2422, 84908.2656, 84903.2812, 84928.1797, 84908.2656, 84893.3281,
-    84878.3906, 84843.5547, 84848.5234, 84893.3281, 84913.2422, 84928.1797,
-    84943.1094, 84948.0859, 84963.0312, 84943.1094, 84863.4453, 84813.6797,
-    84753.9453, 84694.2031, 84773.8516, 84768.875,  84793.7656, 84858.4922,
-    84868.4297, 84868.4297, 84972.9766, 84997.8672, 85017.7734, 85067.5625,
-    85122.3203, 85097.4219, 85097.4219, 85102.3984, 85147.2109, 85157.1719,
-    85157.1719, 85172.1016, 85147.2109, 85157.1719, 85167.125,  85177.0703,
-    85192.0078, 85201.9688, 85231.8359, 85231.8359, 85226.8594, 85206.9453,
-    85201.9688, 85206.9453, 85226.8594, 85231.8359, 85226.8594, 85231.8359,
-    85251.75,   85266.6875, 85276.6328, 85276.6328, 85291.5625, 85276.6328,
-    85291.5625, 85286.6016, 85286.6016, 85286.6016, 85291.5625, 85286.6016,
-    85291.5625, 85296.5469, 85296.5469, 85296.5469, 85301.5312, 85296.5469,
-    85301.5312, 85306.5,    85296.5469, 85296.5469, 85306.5,    85306.5,
-    85306.5,    85306.5,    85311.4844, 85306.5,    85316.4688, 85316.4688,
-    85311.4844, 85321.4453, 85321.4453, 85321.4453, 85326.4219, 85321.4453,
-    85326.4219, 85326.4219, 85331.3906, 85336.375,  85331.3906, 85341.3516,
-    85341.3516, 85346.3281, 85346.3281, 85346.3281, 85351.3125, 85351.3125,
-    85346.3281, 85351.3125, 85346.3281, 85356.2891, 85351.3125, 85351.3125,
-    85366.25,   85356.2891, 85356.2891, 85361.2656, 85361.2656, 85361.2656,
-    85361.2656, 85361.2656, 85366.25,   85356.2891, 85356.2891, 85361.2656,
-    85366.25,   85371.2266, 85371.2266, 85376.2031, 85381.1719, 85386.1562,
-    85381.1719, 85391.1328, 85391.1328, 85396.1094, 85406.0781, 85406.0781,
-    85406.0781, 85396.1094, 85406.0781, 85406.0781, 85411.0391, 85421,
-    85425.9766, 85416.0234, 85425.9766, 85416.0234, 85425.9766, 85430.9609,
-    85430.9609, 85430.9609, 85440.9219, 85421,      85430.9609, 85425.9766,
-    85440.9219, 85435.9375, 85440.9219, 85445.8984, 85440.9219, 85450.8672,
-    85445.8984, 85455.8516, 85445.8984, 85460.8281, 85450.8672, 85460.8281,
-    85455.8516, 85455.8516, 85455.8516, 85460.8281, 85465.8047, 85460.8281,
-    85465.8047, 85460.8281, 85470.7891, 85465.8047, 85475.7578, 85465.8047,
-    85470.7891, 85470.7891, 85475.7578, 85470.7891, 85480.75,   85480.75,
-    85480.75,   85485.7109, 85485.7109, 85495.6719, 85490.6875, 85490.6875,
-    85495.6719, 85505.625,  85500.6484, 85505.625,  85510.6016, 85505.625,
-    85505.625,  85505.625,  85515.5859, 85510.6016, 85515.5859, 85515.5859,
-    85515.5859, 85510.6016, 85520.5703, 85520.5703, 85520.5703, 85520.5703,
-    85525.5391, 85530.5156, 85530.5156, 85530.5156, 85535.5,    85540.4766,
-    85545.4531, 85540.4766, 85545.4531, 85545.4531, 85540.4766, 85545.4531,
-    85550.4375, 85550.4375, 85550.4375, 85555.4141, 85560.3906, 85550.4375,
-    85550.4375, 85560.3906, 85565.3594, 85565.3594, 85560.3906, 85565.3594,
-    85560.3906, 85575.3281, 85575.3281, 85570.3438, 85575.3281, 85575.3281,
-    85570.3438, 85580.2969, 85580.2969, 85575.3281, 85585.2812, 85585.2812,
-    85595.2266, 85590.2578, 85590.2578, 85590.2578, 85595.2266, 85600.2109,
-    85600.2109, 85605.1875, 85600.2109, 85600.2109, 85600.2109, 85610.1719,
-    85600.2109, 85610.1719, 85615.1406, 85620.125,  85615.1406, 85620.125,
-    85620.125,  85620.125,  85620.125,  85625.1094, 85635.0547, 85625.1094,
-    85625.1094, 85625.1094, 85635.0547, 85635.0547, 85640.0469, 85635.0547,
-    85645.0156, 85645.0156, 85640.0469, 85645.0156, 85645.0156, 85649.9922,
-    85654.9688, 85649.9922, 85645.0156, 85645.0156, 85649.9922, 85659.9531,
-    85664.9297, 85669.9062, 85669.9062, 85669.9062, 85669.9062, 85674.8906,
-    85679.8672, 85679.8672, 85674.8906, 85684.8359, 85674.8906, 85684.8359,
-    85684.8359, 85674.8906, 85689.8203, 85689.8203, 85689.8203, 85684.8359,
-    85689.8203, 85699.7656, 85689.8203, 85694.7969, 85694.7969, 85699.7656,
-    85709.7344, 85709.7344, 85704.75,   85704.75,   85714.7109, 85714.7109,
-    85714.7109, 85724.6562, 85729.6484, 85729.6484, 85719.6797, 85724.6562,
-    85724.6562, 85734.6172, 85734.6172, 85739.5938, 85739.5938, 85734.6172,
-    85739.5938, 85744.5781, 85744.5781, 85744.5781, 85749.5547, 85744.5781,
-    85749.5547, 85749.5547, 85754.5391, 85759.5078, 85759.5078, 85759.5078,
-    85764.4844, 85754.5391, 85769.4688, 85764.4844, 85774.4453, 85769.4688,
-    85764.4844, 85774.4453, 85774.4453, 85779.4297, 85779.4297, 85784.4062,
-    85784.4062, 85784.4062, 85789.3828, 85784.4062, 85789.3828, 85789.3828,
-    85799.3281, 85799.3281, 85799.3281, 85799.3281, 85799.3281, 85809.2891,
-    85804.3047, 85804.3047, 85804.3047, 85804.3047, 85814.2656, 85809.2891,
-    85814.2656, 85814.2656, 85819.25,   85819.25,   85824.2266, 85824.2266,
-    85824.2266, 85829.2031, 85829.2031, 85824.2266, 85829.2031, 85834.1797,
-    85834.1797, 85834.1797, 85829.2031, 85839.1562, 85829.2031, 85844.1406,
-    85839.1562, 85849.1172, 85839.1562, 85844.1406, 85849.1172, 85849.1172,
-    85854.0938, 85854.0938, 85854.0938, 85854.0938, 85859.0781, 85859.0781,
-    85854.0938, 85854.0938, 85859.0781, 85864.0547, 85869.0234, 85864.0547,
-    85869.0234, 85869.0234, 85874.0156, 85878.9844, 85878.9844, 85878.9844,
-    85874.0156, 85883.9609, 85878.9844, 85878.9844, 85883.9609, 85883.9609,
-    85888.9375, 85893.9219, 85893.9219, 85893.9219, 85893.9219, 85893.9219,
-    85898.8984, 85893.9219, 85893.9219, 85898.8984, 85903.8672, 85898.8984,
-    85903.8672, 85908.8516, 85908.8516, 85908.8516, 85913.8359, 85923.7812,
-    85908.8516, 85918.7969, 85918.7969, 85928.7656, 85923.7812, 85923.7812,
-    85923.7812, 85923.7812, 85923.7812, 85938.7188, 85938.7188, 85933.7422,
-    85928.7656, 85933.7422, 85933.7422, 85933.7422, 85938.7188, 85938.7188,
-    85948.6875, 85943.7031, 85943.7031, 85943.7031, 85948.6875, 85948.6875,
-    85953.6484, 85948.6875, 85943.7031, 85958.625,  85948.6875, 85958.625,
-    85963.6172, 85963.6172, 85963.6172, 85963.6172, 85963.6172, 85968.5859,
-    85968.5859, 85963.6172, 85963.6172, 85973.5625, 85973.5625, 85978.5469,
-    85983.5312, 85988.5078, 85983.5312, 85978.5469, 85983.5312, 85983.5312,
-    85988.5078, 85988.5078, 85988.5078, 85983.5312, 85988.5078, 85988.5078,
-    85993.4766, 85993.4766, 85993.4766, 85998.4609, 85998.4609, 85998.4609,
-    85998.4609, 86003.4297, 86003.4297, 86013.3906, 86003.4297, 86008.4062,
-    86008.4062, 86013.3906, 86018.375,  86023.3438, 86018.375,  86023.3438,
-    86018.375,  86023.3438, 86023.3438, 86023.3438, 86033.3047, 86033.3047,
-    86038.2734, 86028.3281, 86033.3047, 86033.3047, 86038.2734, 86038.2734,
-    86043.2578, 86033.3047, 86043.2578, 86048.2344, 86043.2578, 86053.2188,
-    86043.2578, 86053.2188, 86048.2344, 86053.2188, 86048.2344, 86048.2344,
-    86058.1953, 86058.1953, 86058.1953, 86063.1719, 86058.1953, 86068.1562,
-    86063.1719, 86068.1562, 86073.125,  86063.1719, 86073.125,  86073.125,
-    86073.125,  86073.125,  86073.125,  86078.1094, 86078.1094, 86083.0859,
-    86088.0625, 86088.0625, 86093.0469, 86093.0469, 86093.0469, 86093.0469,
-    86093.0469, 86093.0469, 86098.0234, 86098.0234, 86098.0234, 86098.0234,
-    86103,      86103,      86103,      86107.9766, 86112.9453, 86117.9297,
-    86112.9453, 86117.9297, 86117.9297, 86117.9297, 86122.9062, 86117.9297,
-    86122.9062, 86122.9062, 86122.9062, 86132.8672, 86132.8672, 86137.8438,
-    86137.8438, 86132.8672, 86142.8203, 86132.8672, 86137.8438, 86147.8047,
-    86142.8203, 86142.8203, 86147.8047, 86147.8047, 86147.8047, 86142.8203,
-    86147.8047, 86157.75,   86157.75,   86157.75,   86162.7344, 86162.7344,
-    86157.75,   86162.7344, 86162.7344, 86162.7344, 86167.7109, 86167.7109,
-    86172.6875, 86172.6875, 86177.6719, 86177.6719, 86182.6562, 86182.6562,
-    86182.6562, 86182.6562, 86192.5938, 86182.6562, 86187.6328, 86187.6328,
-    86187.6328, 86197.5859, 86192.5938, 86192.5938, 86197.5859, 86202.5625,
-    86202.5625, 86207.5312, 86207.5312, 86212.5156, 86202.5625, 86207.5312,
-    86207.5312, 86217.4922, 86222.4766, 86212.5156, 86217.4922, 86212.5156,
-    86217.4922, 86222.4766, 86222.4766, 86222.4766, 86227.4375, 86227.4375,
-    86222.4766, 86232.4219, 86232.4219, 86237.4062, 86237.4062, 86237.4062,
-    86232.4219, 86232.4219, 86237.4062, 86242.375,  86247.3594, 86242.375,
-    86242.375,  86252.3438, 86247.3594, 86252.3438, 86252.3438, 86252.3438,
-    86257.3203, 86262.2969, 86262.2969, 86252.3438, 86262.2969, 86257.3203,
-    86272.25,   86267.2734, 86267.2734, 86272.25,   86272.25,   86272.25,
-    86272.25,   86277.2266, 86277.2266, 86272.25,   86287.1953, 86277.2266,
-    86277.2266, 86282.2031, 86282.2031, 86287.1953, 86287.1953, 86287.1953,
-    86287.1953, 86292.1641, 86292.1641, 86297.1406, 86297.1406, 86292.1641,
-    86302.125,  86297.1406, 86297.1406, 86302.125,  86302.125,  86307.1016,
-    86307.1016, 86317.0469, 86307.1016, 86312.0781, 86317.0469, 86317.0469,
-    86317.0469, 86322.0312, 86322.0312, 86327.0078, 86322.0312, 86331.9844,
-    86327.0078, 86331.9844, 86331.9844, 86331.9844, 86336.9688, 86327.0078,
-    86341.9531, 86341.9531, 86346.9141, 86341.9531, 86346.9141, 86346.9141,
-    86351.8984, 86346.9141, 86346.9141, 86351.8984, 86356.8828, 86351.8984,
-    86361.8516, 86361.8516, 86361.8516, 86356.8828, 86366.8359, 86366.8359,
-    86371.8125, 86361.8516, 86371.8125, 86371.8125, 86371.8125, 86371.8125,
-    86376.7891, 86381.7734, 86381.7734, 86386.7422, 86386.7422, 86386.7422,
-    86386.7422, 86391.7266, 86391.7266, 86396.7031, 86396.7031, 86396.7031,
-    86401.6797, 86401.6797, 86406.6641, 86401.6797, 86406.6641, 86406.6641,
-    86411.6406, 86406.6641, 86411.6406, 86416.625,  86411.6406, 86416.625,
-    86416.625,  86416.625,  86416.625,  86421.5938, 86426.5703, 86421.5938,
-    86421.5938, 86426.5703, 86431.5469, 86436.5234, 86441.5,    86431.5469,
-    86431.5469, 86436.5234, 86441.5,    86446.4844, 86441.5,    86441.5,
-    86446.4844, 86441.5,    86446.4844, 86446.4844, 86456.4453, 86461.4141,
-    86461.4141, 86461.4141, 86461.4141, 86466.3906, 86466.3906, 86466.3906,
-    86466.3906, 86466.3906, 86461.4141, 86471.375,  86461.4141, 86471.375,
-    86476.3516, 86476.3516, 86481.3281, 86486.3125, 86486.3125, 86481.3281,
-    86486.3125, 86486.3125, 86491.2891, 86491.2891, 86491.2891, 86491.2891,
-    86496.2656, 86496.2656, 86506.2188, 86501.2422, 86511.2031, 86501.2422,
-    86506.2188, 86511.2031, 86511.2031, 86511.2031, 86516.1719, 86516.1719,
-    86511.2031, 86511.2031, 86516.1719, 86526.1328, 86526.1328, 86526.1328,
-    86526.1328, 86526.1328, 86531.1016, 86536.0938, 86541.0625, 86541.0625,
-    86541.0625, 86541.0625, 86541.0625, 86541.0625, 86541.0625, 86546.0391,
-    86546.0391, 86551.0156, 86551.0156, 86541.0625, 86556,      86560.9844,
-    86560.9844, 86560.9844, 86556,      86565.9531, 86565.9531, 86575.9219,
-    86565.9531, 86560.9844, 86570.9375, 86570.9375, 86570.9375, 86570.9375,
-    86585.8672, 86580.8906, 86580.8906, 86585.8672, 86585.8672, 86580.8906,
-    86590.8516, 86590.8516, 86590.8516, 86585.8672, 86585.8672, 86600.8047,
-    86595.8281, 86600.8047, 86595.8281, 86600.8047, 86605.7812, 86605.7812,
-    86605.7812, 86610.7656, 86610.7656, 86610.7656, 86615.7422, 86605.7812,
-    86615.7422, 86615.7422, 86615.7422, 86615.7422, 86620.7109, 86620.7109,
-    86625.6953, 86625.6953, 86630.6719, 86625.6953, 86625.6953, 86640.625,
-    86630.6719, 86630.6719, 86635.6406, 86635.6406, 86645.6094, 86640.625,
-    86640.625,  86645.6094, 86645.6094, 86645.6094, 86655.5625, 86655.5625,
-    86655.5625, 86655.5625, 86660.5391, 86660.5391, 86655.5625, 86660.5391,
-    86660.5391, 86665.5234, 86670.4922, 86670.4922, 86670.4922, 86675.4688,
-    86675.4688, 86670.4922, 86680.4609, 86675.4688, 86680.4609, 86680.4609,
-    86680.4609, 86685.4297, 86680.4609, 86680.4609, 86685.4297, 86695.3828,
-    86690.4141, 86695.3828, 86700.3594, 86695.3828, 86695.3828, 86695.3828,
-    86705.3438, 86705.3438, 86705.3438, 86700.3594, 86705.3438, 86710.3203,
-    86715.3047, 86715.3047, 86720.2812, 86720.2812, 86720.2812, 86720.2812,
-    86720.2812, 86725.2578, 86725.2578, 86730.2344, 86725.2578, 86730.2344,
-    86720.2812, 86730.2344, 86730.2344, 86735.2031, 86735.2031, 86740.1797,
-    86740.1797, 86740.1797, 86740.1797, 86740.1797, 86740.1797, 86740.1797,
-    86750.1484, 86750.1484, 86755.125,  86750.1484, 86750.1484, 86755.125,
-    86765.0781, 86760.1016, 86755.125,  86765.0781, 86770.0625, 86765.0781,
-    86765.0781, 86775.0312, 86780.0078, 86770.0625, 86775.0312, 86780.0078,
-    86770.0625, 86775.0312, 86770.0625, 86784.9922, 86789.9688, 86789.9688,
-    86784.9922, 86794.9531, 86794.9531, 86794.9531, 86794.9531, 86794.9531,
-    86794.9531, 86789.9688, 86794.9531, 86799.9297, 86804.9062, 86804.9062,
-    86809.8906, 86804.9062, 86809.8906, 86809.8906, 86814.8594, 86824.8203,
-    86809.8906, 86814.8594, 86814.8594, 86824.8203, 86829.7969, 86824.8203,
-    86824.8203, 86824.8203, 86834.7734, 86834.7734, 86829.7969, 86834.7734,
-    86834.7734, 86839.75,   86829.7969, 86834.7734, 86844.7266, 86844.7266,
-    86849.7109, 86844.7266, 86844.7266, 86849.7109, 86854.6719, 86854.6719,
-    86859.6641, 86849.7109, 86859.6641, 86859.6641, 86864.6406, 86864.6406,
-    86859.6641, 86869.6172, 86864.6406, 86869.6172, 86859.6641, 86874.5938,
-    86874.5938, 86869.6172, 86874.5938, 86879.5781, 86884.5625, 86879.5781,
-    86884.5625, 86889.5312, 86889.5312, 86889.5312, 86889.5312, 86889.5312,
-    86894.5078, 86894.5078, 86894.5078, 86889.5312, 86899.4922, 86899.4922,
-    86909.4375, 86904.4609, 86899.4922, 86904.4609, 86909.4375, 86909.4375,
-    86909.4375, 86914.4297, 86914.4297, 86914.4297, 86919.4062, 86919.4062,
-    86919.4062, 86929.3594, 86929.3594, 86929.3594, 86929.3594, 86929.3594,
-    86934.3359, 86929.3594, 86934.3359, 86939.3047, 86934.3359, 86934.3359,
-    86934.3359, 86939.3047, 86949.2656, 86944.2812, 86944.2812, 86954.25,
-    86954.25,   86954.25,   86959.2188, 86954.25,   86959.2188, 86959.2188,
-    86949.2656, 86964.2031, 86954.25,   86964.2031, 86969.1797, 86964.2031,
-    86969.1797, 86964.2031, 86974.1484, 86974.1484, 86979.1328, 86974.1484,
-    86984.1172, 86979.1328, 86979.1328, 86974.1484, 86984.1172, 86989.0938,
-    86984.1172, 86984.1172, 86989.0938, 86989.0938, 86994.0703, 86994.0703,
-    86999.0469, 86994.0703, 86999.0469, 86994.0703, 86999.0469, 86999.0469,
-    86999.0469, 87009,      87004.0391, 87009,      87013.9766, 87018.9609,
-    87018.9609, 87018.9609, 87018.9609, 87023.9375, 87023.9375, 87023.9375,
-    87023.9375, 87028.9219, 87028.9219, 87023.9375, 87028.9219, 87028.9219,
-    87038.8828, 87038.8828, 87028.9219, 87033.8984, 87033.8984, 87043.8516,
-    87038.8828, 87038.8828, 87043.8516, 87043.8516, 87038.8828, 87048.8203,
-    87038.8828, 87048.8203, 87048.8203, 87053.8047, 87048.8203, 87058.7812,
-    87053.8047, 87053.8047, 87063.7578, 87058.7812, 87058.7812, 87058.7812,
-    87063.7578, 87063.7578, 87063.7578, 87058.7812, 87058.7812, 87063.7578,
-    87063.7578, 87078.6953, 87073.7266, 87078.6953, 87073.7266, 87078.6953,
-    87073.7266, 87073.7266, 87078.6953, 87078.6953, 87078.6953, 87078.6953,
-    87073.7266, 87073.7266, 87083.6797, 87078.6953, 87088.6484, 87083.6797,
-    87088.6484, 87088.6484, 87088.6484, 87088.6484, 87088.6484, 87083.6797,
-    87093.6328, 87088.6484, 87093.6328, 87093.6328, 87093.6328, 87098.6094,
-    87103.5859, 87098.6094, 87108.5625, 87103.5859, 87118.5312, 87108.5625,
-    87103.5859, 87113.5469, 87113.5469, 87113.5469, 87118.5312, 87108.5625,
-    87113.5469, 87113.5469, 87123.5078, 87128.4766, 87128.4766, 87123.5078,
-    87128.4766, 87123.5078, 87143.4062, 87138.4375, 87133.4609, 87138.4375,
-    87143.4062, 87143.4062, 87138.4375, 87143.4062, 87148.3906, 87153.3672,
-    87148.3906, 87153.3672, 87148.3906, 87153.3672, 87153.3672, 87153.3672,
-    87158.3516, 87158.3516, 87158.3516, 87158.3516, 87153.3672, 87158.3516,
-    87163.3281, 87163.3281, 87163.3281, 87163.3281, 87173.2812, 87163.3281,
-    87173.2812, 87173.2812, 87183.2344, 87178.25,   87173.2812, 87178.25,
-    87178.25,   87178.25,   87178.25,   87183.2344, 87183.2344, 87188.2188,
-    87183.2344, 87188.2188, 87188.2188, 87193.1953, 87188.2188, 87188.2188,
-    87188.2188, 87198.1719, 87198.1719, 87193.1953, 87193.1953, 87193.1953,
-    87198.1719, 87198.1719, 87203.1484, 87203.1484, 87208.125,  87198.1719,
-    87208.125,  87208.125,  87208.125,  87208.125,  87208.125,  87208.125,
-    87208.125,  87213.1016, 87208.125,  87208.125,  87213.1016, 87213.1016,
-    87223.0703, 87218.0859, 87218.0859, 87228.0391, 87223.0703, 87223.0703,
-    87228.0391, 87223.0703, 87233.0156, 87233.0156, 87228.0391, 87233.0156,
-    87233.0156, 87233.0156, 87238.0078, 87238.0078, 87238.0078, 87247.9375,
-    87242.9766, 87242.9766, 87242.9766, 87247.9375, 87238.0078, 87242.9766,
-    87247.9375, 87252.9297, 87252.9297, 87252.9297, 87257.9062, 87257.9062,
-    87257.9062, 87257.9062, 87257.9062, 87252.9297, 87252.9297, 87252.9297,
-    87262.8828, 87257.9062, 87262.8828, 87257.9062, 87267.8594, 87262.8828,
-    87267.8594, 87267.8594, 87272.8438, 87267.8594, 87272.8438, 87267.8594,
-    87277.8281, 87272.8438, 87272.8438, 87282.7891, 87267.8594, 87277.8281,
-    87272.8438, 87287.7734, 87282.7891, 87277.8281, 87277.8281, 87287.7734,
-    87282.7891, 87287.7734, 87287.7734, 87287.7734, 87292.7578, 87287.7734,
-    87292.7578, 87292.7578, 87292.7578, 87297.7266, 87302.7109, 87297.7266,
-    87302.7109, 87297.7266, 87302.7109, 87297.7266, 87297.7266, 87297.7266,
-    87302.7109, 87302.7109, 87312.6641, 87307.6953, 87302.7109, 87312.6641,
-    87312.6641, 87307.6953, 87312.6641, 87307.6953, 87317.6484, 87317.6484,
-    87322.6172, 87322.6172, 87312.6641, 87322.6172, 87322.6172, 87327.6094,
-    87322.6172, 87332.5781, 87327.6094, 87322.6172, 87332.5781, 87332.5781,
-    87332.5781, 87327.6094, 87332.5781, 87332.5781, 87337.5547, 87337.5547,
-    87342.5391, 87342.5391, 87337.5547, 87337.5547, 87342.5391, 87342.5391,
-    87352.4844, 87342.5391, 87347.5156, 87342.5391, 87352.4844, 87347.5156,
-    87347.5156, 87352.4844, 87347.5156, 87357.4688, 87352.4844, 87352.4844,
-    87362.4453, 87362.4453, 87357.4688, 87362.4453, 87362.4453, 87367.4219,
-    87367.4219, 87367.4219, 87367.4219, 87372.3984, 87367.4219, 87372.3984,
-    87372.3984, 87367.4219, 87372.3984, 87372.3984, 87372.3984, 87382.3594,
-    87372.3984, 87382.3594, 87377.3828, 87372.3984, 87377.3828, 87382.3594,
-    87377.3828, 87387.3359, 87387.3359, 87387.3359, 87382.3594, 87382.3594,
-    87397.2969, 87392.3203, 87392.3203, 87392.3203, 87402.2656, 87397.2969,
-    87402.2656, 87397.2969, 87402.2656, 87407.25,   87402.2656, 87402.2656,
-    87402.2656, 87407.25,   87407.25,   87412.2266, 87412.2266, 87412.2266,
-    87407.25,   87417.2031, 87407.25,   87422.1875, 87422.1875, 87417.2031,
-    87417.2031, 87417.2031, 87417.2031, 87422.1875, 87422.1875, 87422.1875,
-    87427.1641, 87432.1406, 87427.1641, 87432.1406, 87437.1172, 87432.1406,
-    87437.1172, 87432.1406, 87442.0938, 87442.0938, 87442.0938, 87442.0938,
-    87432.1406, 87437.1172, 87437.1172, 87447.0781, 87442.0938, 87447.0781,
-    87447.0781, 87452.0547, 87447.0781, 87447.0781, 87452.0547, 87457.0312,
-    87457.0312, 87457.0312, 87452.0547, 87452.0547, 87457.0312, 87457.0312,
-    87466.9844, 87457.0312, 87462.0078, 87466.9844, 87462.0078, 87466.9844,
-    87462.0078, 87471.9688, 87466.9844, 87471.9688, 87466.9844, 87476.9375,
-    87466.9844, 87476.9375, 87486.8984, 87481.9141, 87471.9688, 87481.9141,
-    87476.9375, 87486.8984, 87481.9141, 87486.8984, 87486.8984, 87486.8984,
-    87481.9141, 87481.9141, 87476.9375, 87486.8984, 87491.875,  87491.875,
-    87496.8594, 87496.8594, 87491.875,  87491.875,  87501.8281, 87496.8594,
-    87491.875,  87491.875,  87496.8594, 87491.875,  87496.8594, 87496.8594,
-    87491.875,  87496.8594, 87496.8594, 87501.8281, 87501.8281, 87501.8281,
-    87501.8281, 87506.8125, 87511.7969, 87511.7969, 87511.7969, 87511.7969,
-    87511.7969, 87506.8125, 87511.7969, 87521.7422, 87511.7969, 87526.7266,
-    87521.7422, 87521.7422, 87526.7266, 87526.7266, 87526.7266, 87531.7031,
-    87531.7031, 87521.7422, 87531.7031, 87526.7266, 87536.6797, 87526.7266,
-    87536.6797, 87531.7031, 87531.7031, 87536.6797, 87531.7031, 87541.6641,
-    87536.6797, 87531.7031, 87541.6641, 87541.6641, 87531.7031, 87536.6797,
-    87536.6797, 87541.6641, 87541.6641, 87551.6172, 87546.6406, 87551.6172,
-    87551.6172, 87551.6172, 87551.6172, 87546.6406, 87556.5859, 87551.6172,
-    87556.5859, 87556.5859, 87556.5859, 87561.5703, 87561.5703, 87561.5703,
-    87561.5703, 87556.5859, 87566.5469, 87566.5469, 87561.5703, 87566.5469,
-    87561.5703, 87566.5469, 87566.5469, 87566.5469, 87561.5703, 87566.5469,
-    87566.5469, 87566.5469, 87571.5156, 87576.5078, 87571.5156, 87581.4844,
-    87586.4531, 87576.5078, 87581.4844, 87576.5078, 87581.4844, 87586.4531,
-    87581.4844, 87586.4531, 87581.4844, 87591.4375, 87591.4375, 87591.4375,
-    87591.4375, 87591.4375, 87591.4375, 87591.4375, 87591.4375, 87586.4531,
-    87591.4375, 87601.3984, 87586.4531, 87596.4141, 87591.4375, 87591.4375,
-    87596.4141, 87601.3984, 87601.3984, 87601.3984, 87601.3984, 87601.3984,
-    87601.3984, 87601.3984, 87606.3672, 87611.3516, 87616.3359, 87611.3516,
-    87611.3516, 87606.3672, 87616.3359, 87611.3516, 87611.3516, 87606.3672,
-    87606.3672, 87616.3359, 87621.3047, 87621.3047, 87621.3047, 87626.2891,
-    87626.2891, 87636.2344, 87626.2891, 87626.2891, 87626.2891, 87626.2891,
-    87626.2891, 87641.2188, 87631.2734, 87636.2344, 87641.2188, 87636.2344,
-    87641.2188, 87631.2734, 87641.2188, 87641.2188, 87646.1953, 87641.2188,
-    87646.1953, 87646.1953, 87646.1953, 87656.1562, 87656.1562, 87661.1328,
-    87656.1562, 87656.1562, 87661.1328, 87651.1797, 87661.1328, 87656.1562,
-    87661.1328, 87666.1172, 87656.1562, 87661.1328, 87661.1328, 87671.0781,
-    87666.1172, 87671.0781, 87666.1172, 87661.1328, 87666.1172, 87676.0547,
-    87671.0781, 87676.0547, 87666.1172, 87671.0781, 87676.0547, 87676.0547,
-    87671.0781, 87681.0391, 87681.0391, 87681.0391, 87681.0391, 87671.0781,
-    87681.0391, 87686.0234, 87686.0234, 87686.0234, 87686.0234, 87686.0234,
-    87695.9766, 87681.0391, 87686.0234, 87686.0234, 87691,      87686.0234,
-    87691,      87695.9766, 87686.0234, 87691,      87691,      87695.9766,
-    87686.0234, 87691,      87700.9609, 87691,      87695.9766, 87695.9766,
-    87695.9766, 87695.9766, 87695.9766, 87705.9375, 87705.9375, 87695.9766,
-    87705.9375, 87710.9062, 87705.9375, 87705.9375, 87710.9062, 87710.9062,
-    87705.9375, 87705.9375, 87710.9062, 87705.9375, 87715.8828, 87720.8672,
-    87720.8672, 87715.8828, 87720.8672, 87715.8828, 87725.8438, 87720.8672,
-    87725.8438, 87720.8672, 87730.8281, 87725.8438, 87725.8438, 87735.8047,
-    87730.8281, 87730.8281, 87730.8281, 87735.8047, 87735.8047, 87735.8047,
-    87745.7656, 87745.7656, 87740.7812, 87740.7812, 87735.8047, 87745.7656,
-    87740.7812, 87745.7656, 87750.7344, 87750.7344, 87750.7344, 87750.7344,
-    87760.6953, 87755.7109, 87755.7109, 87755.7109, 87760.6953, 87760.6953,
-    87755.7109, 87760.6953, 87760.6953, 87760.6953, 87760.6953, 87770.6484,
-    87770.6484, 87775.625,  87770.6484, 87770.6484, 87775.625,  87770.6484,
-    87780.6016, 87775.625,  87780.6016, 87785.5859, 87770.6484, 87780.6016,
-    87770.6484, 87780.6016, 87785.5859, 87775.625,  87790.5547, 87785.5859,
-    87775.625,  87805.4922, 87790.5547, 87795.5391, 87785.5859, 87785.5859,
-    87775.625,  87780.6016, 87775.625,  87785.5859, 87780.6016, 87780.6016,
-    87775.625,  87785.5859, 87780.6016, 87790.5547, 87775.625,  87780.6016,
-    87785.5859, 87785.5859, 87785.5859, 87785.5859, 87780.6016, 87780.6016,
-    87780.6016, 87785.5859, 87790.5547, 87785.5859, 87780.6016, 87780.6016,
-    87790.5547, 87790.5547, 87785.5859, 87780.6016, 87785.5859, 87785.5859,
-    87785.5859, 87780.6016, 87785.5859, 87790.5547, 87790.5547, 87785.5859,
-    87780.6016, 87785.5859, 87780.6016, 87795.5391, 87785.5859, 87785.5859,
-    87785.5859, 87795.5391, 87785.5859, 87785.5859, 87785.5859, 87780.6016,
-    87780.6016, 87790.5547, 87785.5859, 87785.5859, 87785.5859, 87785.5859,
-    87785.5859, 87785.5859, 87780.6016, 87785.5859, 87785.5859, 87785.5859,
-    87780.6016, 87780.6016, 87785.5859, 87785.5859, 87785.5859, 87785.5859,
-    87780.6016, 87785.5859, 87780.6016, 87785.5859, 87785.5859, 87785.5859,
-    87785.5859, 87780.6016, 87780.6016, 87780.6016, 87785.5859, 87780.6016,
-    87780.6016, 87785.5859, 87785.5859, 87775.625,  87780.6016, 87785.5859,
-    87785.5859, 87780.6016, 87780.6016, 87780.6016, 87780.6016, 87780.6016,
-    87785.5859, 87785.5859, 87780.6016, 87775.625,  87780.6016, 87785.5859,
-    87780.6016, 87785.5859, 87780.6016, 87785.5859, 87785.5859, 87785.5859,
-    87780.6016, 87780.6016, 87780.6016, 87780.6016, 87785.5859, 87785.5859,
-    87780.6016, 87785.5859, 87780.6016, 87775.625,  87785.5859, 87780.6016,
-    87775.625,  87780.6016, 87785.5859, 87775.625,  87780.6016, 87780.6016,
-    87780.6016, 87780.6016, 87780.6016, 87780.6016, 87785.5859, 87785.5859,
-    87780.6016, 87785.5859, 87785.5859, 87785.5859, 87785.5859, 87790.5547,
-    87775.625,  87780.6016, 87775.625,  87785.5859, 87785.5859, 87780.6016,
-    87780.6016, 87780.6016, 87780.6016, 87780.6016, 87785.5859, 87780.6016,
-    87790.5547, 87780.6016, 87780.6016, 87775.625,  87780.6016, 87780.6016,
-    87785.5859, 87780.6016, 87785.5859, 87785.5859, 87780.6016, 87780.6016,
-    87775.625,  87780.6016, 87780.6016, 87780.6016, 87780.6016, 87780.6016,
-    87780.6016, 87780.6016, 87780.6016, 87780.6016, 87780.6016, 87785.5859,
-    87780.6016, 87780.6016, 87780.6016, 87780.6016, 87785.5859, 87780.6016,
-    87785.5859, 87785.5859, 87780.6016, 87775.625,  87780.6016, 87775.625,
-    87785.5859, 87780.6016, 87780.6016, 87785.5859, 87780.6016, 87780.6016,
-    87780.6016, 87775.625,  87780.6016, 87780.6016, 87780.6016, 87770.6484,
-    87775.625,  87775.625,  87775.625,  87780.6016, 87775.625,  87780.6016,
-    87780.6016, 87780.6016, 87785.5859, 87780.6016, 87785.5859, 87785.5859,
-    87780.6016, 87775.625,  87775.625,  87780.6016, 87780.6016, 87780.6016,
-    87780.6016, 87780.6016, 87780.6016, 87780.6016, 87775.625,  87780.6016,
-    87780.6016, 87780.6016, 87780.6016, 87780.6016, 87780.6016, 87780.6016,
-    87775.625,  87780.6016, 87775.625,  87780.6016, 87780.6016, 87785.5859,
-    87775.625,  87775.625,  87785.5859, 87780.6016, 87780.6016, 87780.6016,
-    87775.625,  87775.625,  87770.6484, 87780.6016, 87780.6016, 87775.625,
-    87780.6016, 87780.6016, 87775.625,  87780.6016, 87780.6016, 87780.6016,
-    87780.6016, 87775.625,  87770.6484, 87780.6016, 87775.625,  87780.6016,
-    87780.6016, 87775.625,  87775.625,  87775.625,  87775.625,  87785.5859,
-    87785.5859, 87775.625,  87780.6016, 87770.6484, 87785.5859, 87775.625,
-    87775.625,  87775.625,  87780.6016, 87775.625,  87780.6016, 87780.6016,
-    87785.5859, 87775.625,  87785.5859, 87780.6016, 87780.6016, 87775.625,
-    87775.625,  87780.6016, 87770.6484, 87775.625,  87775.625,  87780.6016,
-    87775.625,  87780.6016, 87775.625,  87775.625,  87770.6484, 87775.625,
-    87775.625,  87780.6016, 87780.6016, 87775.625,  87780.6016, 87775.625,
-    87770.6484, 87775.625,  87775.625,  87780.6016, 87780.6016, 87780.6016,
-    87780.6016, 87780.6016, 87775.625,  87775.625,  87780.6016, 87780.6016,
-    87780.6016, 87780.6016, 87775.625,  87775.625,  87780.6016, 87780.6016,
-    87775.625,  87780.6016, 87780.6016, 87780.6016, 87780.6016, 87780.6016,
-    87775.625,  87775.625,  87780.6016, 87780.6016, 87775.625,  87775.625,
-    87780.6016, 87775.625,  87780.6016, 87780.6016, 87780.6016, 87780.6016,
-    87775.625,  87775.625,  87770.6484, 87780.6016, 87780.6016, 87780.6016,
-    87780.6016, 87775.625,  87775.625,  87780.6016, 87775.625,  87775.625,
-    87775.625,  87780.6016, 87780.6016, 87780.6016, 87780.6016, 87775.625,
-    87780.6016, 87780.6016, 87775.625,  87775.625,  87780.6016, 87780.6016,
-    87775.625,  87775.625,  87780.6016, 87780.6016, 87780.6016, 87780.6016,
-    87775.625,  87780.6016, 87780.6016, 87775.625,  87785.5859, 87780.6016,
-    87770.6484, 87775.625,  87785.5859, 87780.6016, 87780.6016, 87780.6016,
-    87780.6016, 87780.6016, 87780.6016, 87775.625,  87780.6016, 87775.625,
-    87780.6016, 87780.6016, 87775.625,  87780.6016, 87780.6016, 87775.625,
-    87780.6016, 87775.625,  87780.6016, 87780.6016, 87780.6016, 87770.6484,
-    87780.6016, 87780.6016, 87780.6016, 87780.6016, 87775.625,  87775.625,
-    87775.625,  87780.6016, 87775.625,  87775.625,  87785.5859, 87775.625,
-    87780.6016, 87780.6016, 87780.6016, 87775.625,  87780.6016, 87780.6016,
-    87780.6016, 87775.625,  87775.625,  87770.6484, 87775.625,  87775.625,
-    87780.6016, 87780.6016, 87770.6484, 87780.6016, 87780.6016, 87780.6016,
-    87780.6016, 87780.6016, 87785.5859, 87780.6016, 87775.625,  87780.6016,
-    87780.6016, 87785.5859, 87775.625,  87780.6016, 87775.625,  87780.6016,
-    87785.5859, 87775.625,  87780.6016, 87775.625,  87780.6016, 87775.625,
-    87780.6016, 87780.6016, 87775.625,  87775.625,  87780.6016, 87780.6016,
-    87785.5859, 87780.6016, 87780.6016, 87780.6016, 87775.625,  87780.6016,
-    87775.625,  87785.5859, 87775.625,  87770.6484, 87770.6484, 87780.6016,
-    87775.625,  87780.6016, 87785.5859, 87770.6484, 87780.6016, 87775.625,
-    87775.625,  87780.6016, 87775.625,  87780.6016, 87780.6016, 87775.625,
-    87780.6016, 87780.6016, 87780.6016, 87780.6016, 87775.625,  87775.625,
-    87775.625,  87770.6484, 87780.6016, 87780.6016, 87785.5859, 87780.6016,
-    87780.6016, 87785.5859, 87780.6016, 87780.6016, 87780.6016, 87785.5859,
-    87775.625,  87780.6016, 87780.6016, 87785.5859, 87780.6016, 87780.6016,
-    87780.6016, 87775.625,  87780.6016, 87780.6016, 87775.625,  87780.6016,
-    87775.625,  87785.5859, 87780.6016, 87775.625,  87780.6016, 87780.6016,
-    87775.625,  87775.625,  87775.625,  87780.6016, 87780.6016, 87780.6016,
-    87785.5859, 87775.625,  87775.625,  87775.625,  87780.6016, 87785.5859,
-    87780.6016, 87780.6016, 87785.5859, 87780.6016, 87775.625,  87775.625,
-    87785.5859, 87775.625,  87780.6016, 87775.625,  87785.5859, 87780.6016,
-    87775.625,  87775.625,  87780.6016, 87780.6016, 87770.6484, 87780.6016,
-    87775.625,  87780.6016, 87780.6016, 87780.6016, 87775.625,  87780.6016,
-    87780.6016, 87775.625,  87780.6016, 87775.625,  87780.6016, 87785.5859,
-    87775.625,  87770.6484, 87785.5859, 87780.6016, 87780.6016, 87775.625,
-    87780.6016, 87785.5859, 87770.6484, 87775.625,  87770.6484, 87785.5859,
-    87780.6016, 87780.6016, 87785.5859, 87775.625,  87775.625,  87780.6016,
-    87780.6016, 87780.6016, 87780.6016, 87785.5859, 87775.625,  87780.6016,
-    87775.625,  87775.625,  87785.5859, 87780.6016, 87780.6016, 87780.6016,
-    87780.6016, 87785.5859, 87780.6016, 87775.625,  87775.625,  87780.6016,
-    87780.6016, 87775.625,  87780.6016, 87780.6016, 87770.6484, 87775.625,
-    87775.625,  87780.6016, 87785.5859, 87775.625,  87775.625,  87785.5859,
-    87780.6016, 87780.6016, 87775.625,  87780.6016, 87775.625,  87780.6016,
-    87770.6484, 87770.6484, 87780.6016, 87775.625,  87785.5859, 87780.6016,
-    87780.6016, 87775.625,  87780.6016, 87780.6016, 87780.6016, 87780.6016,
-    87780.6016, 87775.625,  87775.625,  87765.6719, 87775.625,  87775.625,
-    87775.625,  87785.5859, 87775.625,  87780.6016, 87775.625,  87785.5859,
-    87780.6016, 87780.6016, 87780.6016, 87780.6016, 87775.625,  87775.625,
-    87780.6016, 87770.6484, 87775.625,  87770.6484, 87785.5859, 87780.6016,
-    87775.625,  87775.625,  87775.625,  87780.6016, 87780.6016, 87775.625,
-    87770.6484, 87780.6016, 87780.6016, 87780.6016, 87780.6016, 87780.6016,
-    87780.6016, 87780.6016, 87780.6016, 87785.5859, 87775.625,  87775.625,
-    87775.625,  87780.6016, 87775.625,  87770.6484, 87775.625,  87780.6016,
-    87780.6016, 87775.625,  87775.625,  87775.625,  87780.6016, 87780.6016,
-    87775.625,  87780.6016, 87780.6016, 87780.6016, 87780.6016, 87780.6016,
-    87770.6484, 87780.6016, 87780.6016, 87785.5859, 87770.6484, 87780.6016,
-    87770.6484, 87780.6016, 87780.6016, 87780.6016, 87785.5859, 87780.6016,
-    87775.625,  87775.625,  87765.6719, 87780.6016, 87780.6016, 87775.625,
-    87785.5859, 87770.6484, 87780.6016, 87780.6016, 87785.5859, 87785.5859,
-    87775.625,  87775.625,  87775.625,  87775.625,  87775.625,  87775.625,
-    87770.6484, 87780.6016, 87775.625,  87780.6016, 87770.6484, 87780.6016,
-    87780.6016, 87780.6016, 87770.6484, 87780.6016, 87780.6016, 87775.625,
-    87785.5859, 87775.625,  87775.625,  87770.6484, 87780.6016, 87775.625,
-    87780.6016, 87780.6016, 87780.6016, 87775.625,  87775.625,  87780.6016,
-    87780.6016, 87775.625,  87780.6016, 87780.6016, 87780.6016, 87770.6484,
-    87780.6016, 87780.6016, 87775.625,  87775.625,  87775.625,  87775.625,
-    87775.625,  87780.6016, 87780.6016, 87770.6484, 87780.6016, 87765.6719,
-    87780.6016, 87770.6484, 87775.625,  87770.6484, 87775.625,  87775.625,
-    87775.625,  87780.6016, 87780.6016, 87770.6484, 87780.6016, 87770.6484,
-    87775.625,  87775.625,  87775.625,  87785.5859, 87775.625,  87775.625,
-    87775.625,  87780.6016, 87770.6484, 87785.5859, 87785.5859, 87775.625,
-    87775.625,  87775.625,  87780.6016, 87775.625,  87780.6016, 87775.625,
-    87770.6484, 87775.625,  87780.6016, 87785.5859, 87775.625,  87770.6484,
-    87775.625,  87765.6719, 87780.6016, 87775.625,  87785.5859, 87770.6484,
-    87770.6484, 87780.6016, 87780.6016, 87770.6484, 87780.6016, 87775.625,
-    87775.625,  87775.625,  87775.625,  87780.6016, 87775.625,  87780.6016,
-    87770.6484, 87775.625,  87775.625,  87780.6016, 87775.625,  87770.6484,
-    87770.6484, 87775.625,  87775.625,  87775.625,  87770.6484, 87775.625,
-    87775.625,  87770.6484, 87775.625,  87770.6484, 87775.625,  87770.6484,
-    87775.625,  87775.625,  87770.6484, 87765.6719, 87775.625,  87770.6484,
-    87775.625,  87775.625,  87775.625,  87770.6484, 87775.625,  87770.6484,
-    87770.6484, 87770.6484, 87775.625,  87765.6719, 87770.6484, 87775.625,
-    87775.625,  87770.6484, 87770.6484, 87770.6484, 87775.625,  87770.6484,
-    87775.625,  87770.6484, 87775.625,  87775.625,  87770.6484, 87770.6484,
-    87765.6719, 87770.6484, 87770.6484, 87770.6484, 87775.625,  87775.625,
-    87770.6484, 87770.6484, 87775.625,  87770.6484, 87775.625,  87775.625,
-    87775.625,  87775.625,  87770.6484, 87775.625,  87765.6719, 87770.6484,
-    87765.6719, 87770.6484, 87765.6719, 87765.6719, 87765.6719, 87775.625,
-    87775.625,  87765.6719, 87770.6484, 87765.6719, 87770.6484, 87765.6719,
-    87765.6719, 87765.6719, 87770.6484, 87765.6719, 87775.625,  87775.625,
-    87770.6484, 87770.6484, 87770.6484, 87770.6484, 87765.6719, 87775.625,
-    87770.6484, 87770.6484, 87770.6484, 87765.6719, 87765.6719, 87775.625,
-    87770.6484, 87775.625,  87780.6016, 87770.6484, 87770.6484, 87765.6719,
-    87770.6484, 87770.6484, 87770.6484, 87765.6719, 87765.6719, 87765.6719,
-    87765.6719, 87765.6719, 87775.625,  87775.625,  87765.6719, 87760.6953,
-    87765.6719, 87765.6719, 87770.6484, 87770.6484, 87765.6719, 87770.6484,
-    87765.6719, 87770.6484, 87765.6719, 87770.6484, 87765.6719, 87760.6953,
-    87765.6719, 87770.6484, 87760.6953, 87775.625,  87765.6719, 87765.6719,
-    87770.6484, 87765.6719, 87770.6484, 87765.6719, 87765.6719, 87770.6484,
-    87765.6719, 87765.6719, 87775.625,  87765.6719, 87770.6484, 87765.6719,
-    87770.6484, 87770.6484, 87765.6719, 87765.6719, 87770.6484, 87760.6953,
-    87760.6953, 87760.6953, 87765.6719, 87765.6719, 87765.6719, 87770.6484,
-    87765.6719, 87770.6484, 87770.6484, 87770.6484, 87765.6719, 87765.6719,
-    87765.6719, 87770.6484, 87770.6484, 87765.6719, 87760.6953, 87770.6484,
-    87760.6953, 87770.6484, 87770.6484, 87775.625,  87775.625,  87770.6484,
-    87765.6719, 87770.6484, 87760.6953, 87765.6719, 87770.6484, 87775.625,
-    87760.6953, 87770.6484, 87770.6484, 87765.6719, 87770.6484, 87770.6484,
-    87765.6719, 87770.6484, 87765.6719, 87760.6953, 87765.6719, 87765.6719,
-    87770.6484, 87760.6953, 87765.6719, 87765.6719, 87765.6719, 87765.6719,
-    87765.6719, 87765.6719, 87765.6719, 87775.625,  87770.6484, 87770.6484,
-    87760.6953, 87770.6484, 87775.625,  87765.6719, 87755.7109, 87760.6953,
-    87760.6953, 87765.6719,
-};
\ No newline at end of file
diff --git a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_pressure_static_data.h b/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_pressure_static_data.h
deleted file mode 100644
index f28074904..000000000
--- a/src/boards/Parafoil/mocksensors/lynx_flight_data/lynx_pressure_static_data.h
+++ /dev/null
@@ -1,30 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Authors: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-/**
- * sTATIC pressure data from Lynx flight test in Roccaraso.
- * Sampled at 42 Hz (24 ms period).
- */
-static constexpr unsigned PRESSURE_STATIC_DATA_SIZE = 5384;
-extern const float PRESSURE_STATIC_DATA[PRESSURE_STATIC_DATA_SIZE];
\ No newline at end of file
diff --git a/src/boards/Parafoil/mocksensors/mock_data/test-mock-data.cpp b/src/boards/Parafoil/mocksensors/mock_data/test-mock-data.cpp
deleted file mode 100644
index 0c7d0f7fd..000000000
--- a/src/boards/Parafoil/mocksensors/mock_data/test-mock-data.cpp
+++ /dev/null
@@ -1,14664 +0,0 @@
-/* Copyright (c) 2019 Skyward Experimental Rocketry
- * Author: Luca Mozzarelli
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-#include "test-mock-data.h"
-
-const float SIMULATED_PRESSURE[PRESSURE_DATA_SIZE] = {
-    101158.8, 100978.8, 101196,   101187.6, 101259.6, 101278.8, 101410.8,
-    101190,   101308.8, 101184,   101368.8, 101226,   101270.4, 101332.8,
-    101074.8, 101311.2, 101244,   101118,   101239.2, 101320.8, 101437.2,
-    101168.4, 101379.6, 101335.2, 101284.8, 101161.2, 101217.6, 101184,
-    101240.4, 101100,   101496,   101292,   101430,   101240.4, 101164.8,
-    101160,   101188.8, 101266.8, 101103.6, 101215.2, 101298,   101134.8,
-    101234.4, 101269.2, 101118,   101089.2, 101187.6, 101270.4, 101224.8,
-    101120.4, 101208,   101166,   101133.6, 101103.6, 100971.6, 101043.6,
-    101130,   101052,   101128.8, 101072.4, 101142,   101108.4, 101206.8,
-    101082,   100965.6, 100947.6, 101005.2, 101016,   101218.8, 101043.6,
-    101006.4, 101107.2, 101036.4, 101037.6, 101138.4, 101100,   101007.6,
-    100960.8, 101024.4, 100856.4, 101028,   100891.2, 100898.4, 100896,
-    100935.6, 101067.6, 100872,   101091.6, 101032.8, 101025.6, 100806,
-    100920,   101070,   100870.8, 100953.6, 100938,   100918.8, 100812,
-    100808.4, 100948.8, 100670.4, 100800,   100737.6, 100819.2, 100813.2,
-    100795.2, 100722,   100680,   100638,   100646.4, 100654.8, 100784.4,
-    100639.2, 100567.2, 100647.6, 100641.6, 100695.6, 100501.2, 100531.2,
-    100416,   100681.2, 100518,   100485.6, 100521.6, 100320,   100417.2,
-    100542,   100718.4, 100425.6, 100240.8, 100357.2, 100299.6, 100356,
-    100302,   100356,   100334.4, 100273.2, 100389.6, 100345.2, 100228.8,
-    100340.4, 100300.8, 100302,   100177.2, 100122,   100126.8, 100070.4,
-    100144.8, 100143.6, 100162.8, 100190.4, 100058.4, 100245.6, 99991.2,
-    100029.6, 99950.4,  100034.4, 100164,   99891.6,  100011.6, 99954,
-    99751.2,  99742.8,  99972,    99973.2,  100005.6, 99957.6,  99794.4,
-    99883.2,  99900,    99868.8,  99601.2,  99734.4,  99626.4,  99463.2,
-    99621.6,  99766.8,  99610.8,  99584.4,  99516,    99852,    99553.2,
-    99634.8,  99444,    99460.8,  99362.4,  99416.4,  99553.2,  99406.8,
-    99357.6,  99172.8,  99350.4,  99264,    99370.8,  99346.8,  99195.6,
-    99136.8,  99068.4,  99160.8,  99285.6,  99258,    99238.8,  99135.6,
-    99087.6,  98980.8,  99030,    99008.4,  98827.2,  99152.4,  98905.2,
-    98864.4,  98886,    98862,    98944.8,  98878.8,  98728.8,  98781.6,
-    98881.2,  98820,    98584.8,  98696.4,  98640,    98684.4,  98701.2,
-    98646,    98463.6,  98611.2,  98522.4,  98571.6,  98396.4,  98484,
-    98529.6,  98280,    98431.2,  98576.4,  98430,    98300.4,  98344.8,
-    98089.2,  98234.4,  98204.4,  98170.8,  98137.2,  98163.6,  98426.4,
-    98166,    98001.6,  98002.8,  98018.4,  97959.6,  97941.6,  98044.8,
-    97903.2,  98001.6,  97825.2,  97765.2,  97704,    97942.8,  97768.8,
-    97868.4,  97839.6,  97524,    97736.4,  97744.8,  97558.8,  97543.2,
-    97584,    97468.8,  97696.8,  97477.2,  97467.6,  97444.8,  97450.8,
-    97336.8,  97222.8,  97311.6,  97261.2,  97311.6,  97322.4,  97209.6,
-    96990,    96921.6,  97089.6,  97126.8,  96904.8,  97246.8,  96854.4,
-    96962.4,  96975.6,  96841.2,  96883.2,  96992.4,  96818.4,  96850.8,
-    96716.4,  96720,    96536.4,  96669.6,  96627.6,  96594,    96616.8,
-    96649.2,  96679.2,  96250.8,  96608.4,  96550.8,  96444,    96391.2,
-    96243.6,  96484.8,  96272.4,  96134.4,  96302.4,  96351.6,  96150,
-    95992.8,  95953.2,  96084,    95959.2,  95928,    95853.6,  96062.4,
-    95856,    95732.4,  95818.8,  95552.4,  95788.8,  95682,    95857.2,
-    95695.2,  95877.6,  95874,    95703.6,  95401.2,  95408.4,  95317.2,
-    95440.8,  95526,    95394,    95337.6,  95377.2,  95296.8,  95116.8,
-    95212.8,  95193.6,  95072.4,  95325.6,  95186.4,  95103.6,  95152.8,
-    94970.4,  94978.8,  95018.4,  94867.2,  95008.8,  94782,    94588.8,
-    94724.4,  94802.4,  94836,    94778.4,  94693.2,  94819.2,  94399.2,
-    94507.2,  94581.6,  94399.2,  94286.4,  94284,    94263.6,  94287.6,
-    94470,    94189.2,  94225.2,  94077.6,  93970.8,  94102.8,  94173.6,
-    94020,    94044,    94075.2,  94016.4,  93832.8,  93958.8,  93870,
-    93718.8,  93607.2,  93849.6,  93698.4,  93459.6,  93648,    93782.4,
-    93702,    93584.4,  93592.8,  93487.2,  93403.2,  93388.8,  93422.4,
-    93453.6,  93423.6,  93349.2,  93588,    93259.2,  93172.8,  93105.6,
-    93265.2,  93229.2,  93211.2,  93043.2,  93192,    93019.2,  93096,
-    92859.6,  92995.2,  92919.6,  92800.8,  92846.4,  92710.8,  92834.4,
-    92778,    92624.4,  92517.6,  92474.4,  92660.4,  92692.8,  92526,
-    92426.4,  92493.6,  92310,    92371.2,  92377.2,  92310,    92226,
-    92505.6,  92484,    92271.6,  92259.6,  92108.4,  92084.4,  92068.8,
-    92042.4,  92175.6,  91982.4,  91990.8,  92082,    91821.6,  91922.4,
-    91867.2,  91879.2,  92061.6,  91701.6,  91623.6,  91791.6,  91750.8,
-    91747.2,  91723.2,  91620,    91633.2,  91692,    91576.8,  91429.2,
-    91479.6,  91398,    91353.6,  91237.2,  91382.4,  91046.4,  91285.2,
-    91117.2,  91224,    91206,    91333.2,  91119.6,  90898.8,  91126.8,
-    90934.8,  90939.6,  90958.8,  90841.2,  90865.2,  90832.8,  90708,
-    90910.8,  90794.4,  90675.6,  90715.2,  90808.8,  90870,    90576,
-    90463.2,  90620.4,  90583.2,  90645.6,  90518.4,  90447.6,  90466.8,
-    90517.2,  90344.4,  90320.4,  90429.6,  90330,    90188.4,  90339.6,
-    90213.6,  90195.6,  90234,    90236.4,  90099.6,  90082.8,  90025.2,
-    89965.2,  90201.6,  90210,    89840.4,  89968.8,  89850,    90031.2,
-    89650.8,  89713.2,  89872.8,  89775.6,  89732.4,  89826,    89662.8,
-    89712,    89490,    89534.4,  89570.4,  89502,    89392.8,  89643.6,
-    89310,    89446.8,  89317.2,  89466,    89222.4,  89372.4,  89260.8,
-    89356.8,  89193.6,  89211.6,  89274,    89140.8,  89103.6,  88778.4,
-    88971.6,  88947.6,  89008.8,  88809.6,  88717.2,  88886.4,  89052,
-    88734,    88762.8,  88780.8,  88588.8,  88574.4,  88945.2,  88728,
-    88722,    88628.4,  88440,    88557.6,  88527.6,  88563.6,  88222.8,
-    88446,    88627.2,  88358.4,  88374,    88381.2,  88231.2,  88154.4,
-    88250.4,  88263.6,  88245.6,  88296,    88183.2,  88246.8,  88155.6,
-    88136.4,  88075.2,  87933.6,  88063.2,  88101.6,  88249.2,  87756,
-    87927.6,  88063.2,  87986.4,  87895.2,  87898.8,  87626.4,  87888,
-    87520.8,  87901.2,  87666,    87642,    87726,    87430.8,  87616.8,
-    87639.6,  87618,    87374.4,  87595.2,  87572.4,  87264,    87655.2,
-    87199.2,  87409.2,  87432,    87156,    87302.4,  87121.2,  87034.8,
-    87172.8,  87260.4,  87241.2,  87096,    87306,    87097.2,  86790,
-    87037.2,  87040.8,  86763.6,  87139.2,  86818.8,  86697.6,  87030,
-    86868,    87025.2,  86898,    86938.8,  86798.4,  86632.8,  86766,
-    86606.4,  86774.4,  86683.2,  86539.2,  86671.2,  86515.2,  86467.2,
-    86571.6,  86526,    86554.8,  86607.6,  86518.8,  86335.2,  86245.2,
-    86316,    86293.2,  86302.8,  86346,    86196,    86212.8,  86276.4,
-    86148,    86050.8,  86090.4,  86214,    86187.6,  86179.2,  85905.6,
-    86024.4,  86140.8,  85767.6,  85840.8,  85954.8,  85971.6,  85980,
-    85816.8,  86030.4,  85624.8,  85702.8,  85764,    85600.8,  85666.8,
-    85789.2,  85629.6,  85510.8,  85730.4,  85670.4,  85411.2,  85686,
-    85322.4,  85594.8,  85412.4,  85744.8,  85513.2,  85416,    85663.2,
-    85446,    85580.4,  85195.2,  85312.8,  85431.6,  85240.8,  85222.8,
-    85114.8,  85198.8,  85038,    85045.2,  85028.4,  85046.4,  85033.2,
-    84813.6,  85240.8,  85040.4,  84973.2,  85040.4,  84806.4,  84775.2,
-    84886.8,  84878.4,  84790.8,  84850.8,  84730.8,  84590.4,  84710.4,
-    84572.4,  84696,    84588,    84477.6,  84464.4,  84534,    84573.6,
-    84472.8,  84522,    84442.8,  84444,    84362.4,  84438,    84512.4,
-    84242.4,  84384,    84339.6,  84211.2,  84264,    84284.4,  84181.2,
-    84264,    84363.6,  84082.8,  84248.4,  84076.8,  84234,    83976,
-    84027.6,  83986.8,  84102,    83919.6,  83894.4,  84144,    84040.8,
-    83984.4,  83971.2,  83929.2,  83800.8,  83689.2,  83890.8,  83751.6,
-    83707.2,  83887.2,  83798.4,  83805.6,  83634,    83810.4,  83658,
-    83679.6,  83523.6,  83431.2,  83516.4,  83500.8,  83413.2,  83562,
-    83496,    83505.6,  83430,    83302.8,  83367.6,  83274,    83415.6,
-    83434.8,  83174.4,  83398.8,  83198.4,  83199.6,  83293.2,  83068.8,
-    83139.6,  83198.4,  82993.2,  83100,    82940.4,  82970.4,  83060.4,
-    83047.2,  82975.2,  82814.4,  82994.4,  82794,    82960.8,  82904.4,
-    82791.6,  82600.8,  82681.2,  82794,    82641.6,  82599.6,  82844.4,
-    82632,    82663.2,  82693.2,  82602,    82544.4,  82584,    82495.2,
-    82587.6,  82488,    82614,    82472.4,  82560,    82340.4,  82474.8,
-    82594.8,  82546.8,  82310.4,  82479.6,  82270.8,  82341.6,  82280.4,
-    82023.6,  82101.6,  82297.2,  82098,    82176,    82096.8,  82303.2,
-    82156.8,  82065.6,  82016.4,  81987.6,  82083.6,  82088.4,  81974.4,
-    82016.4,  81861.6,  81790.8,  81796.8,  81943.2,  82110,    81745.2,
-    81962.4,  81794.4,  81811.2,  81694.8,  81732,    81775.2,  81537.6,
-    81721.2,  81708,    81778.8,  81715.2,  81532.8,  81650.4,  81597.6,
-    81632.4,  81508.8,  81470.4,  81642,    81496.8,  81483.6,  81392.4,
-    81398.4,  81469.2,  81344.4,  81277.2,  81424.8,  81399.6,  81249.6,
-    81250.8,  81108,    81386.4,  81213.6,  81124.8,  81304.8,  81217.2,
-    81084,    81212.4,  81091.2,  80942.4,  80892,    80910,    81033.6,
-    80937.6,  80995.2,  81018,    80878.8,  80955.6,  80941.2,  80928,
-    80943.6,  80901.6,  80672.4,  80860.8,  80918.4,  80820,    80713.2,
-    80829.6,  80786.4,  80608.8,  80734.8,  80613.6,  80782.8,  80545.2,
-    80678.4,  80538,    80636.4,  80775.6,  80508,    80472,    80343.6,
-    80589.6,  80275.2,  80458.8,  80281.2,  80396.4,  80308.8,  80355.6,
-    80222.4,  80212.8,  80242.8,  80274,    80216.4,  80172,    80180.4,
-    80149.2,  80167.2,  80209.2,  80115.6,  80238,    80283.6,  80179.2,
-    80102.4,  79945.2,  79957.2,  80089.2,  79744.8,  80019.6,  79926,
-    79893.6,  79874.4,  79935.6,  79996.8,  79906.8,  79923.6,  79989.6,
-    79910.4,  80073.6,  79788,    79912.8,  79843.2,  79675.2,  79681.2,
-    79742.4,  79790.4,  79561.2,  79548,    79657.2,  79580.4,  79516.8,
-    79754.4,  79537.2,  79581.6,  79465.2,  79422,    79510.8,  79459.2,
-    79376.4,  79461.6,  79478.4,  79347.6,  79476,    79152,    79342.8,
-    79328.4,  79561.2,  79347.6,  79282.8,  79257.6,  79257.6,  79262.4,
-    79347.6,  79060.8,  79216.8,  79158,    78950.4,  79168.8,  79092,
-    79203.6,  79111.2,  78902.4,  79052.4,  78988.8,  78914.4,  79068,
-    78879.6,  78921.6,  79006.8,  78831.6,  78838.8,  78948,    79035.6,
-    78770.4,  78730.8,  78860.4,  78627.6,  78753.6,  78698.4,  78848.4,
-    78874.8,  78696,    78751.2,  78918,    78682.8,  78508.8,  78634.8,
-    78524.4,  78523.2,  78524.4,  78596.4,  78336,    78583.2,  78312,
-    78452.4,  78471.6,  78549.6,  78408,    78304.8,  78294,    78345.6,
-    78368.4,  78378,    78343.2,  78218.4,  78438,    78300,    78429.6,
-    78056.4,  78267.6,  78343.2,  78297.6,  78337.2,  78020.4,  78115.2,
-    78093.6,  77992.8,  78222,    78157.2,  78028.8,  78010.8,  77858.4,
-    78069.6,  77886,    78063.6,  77995.2,  78040.8,  78099.6,  78218.4,
-    77818.8,  77847.6,  77935.2,  77850,    77810.4,  77796,    77870.4,
-    77676,    77782.8,  77764.8,  77632.8,  77680.8,  77773.2,  77926.8,
-    77877.6,  77730,    77632.8,  77691.6,  77661.6,  77676,    77568,
-    77416.8,  77517.6,  77428.8,  77426.4,  77508,    77500.8,  77640,
-    77430,    77692.8,  77416.8,  77353.2,  77469.6,  77246.4,  77222.4,
-    77348.4,  77356.8,  77216.4,  77288.4,  77384.4,  77332.8,  77550,
-    77118,    77322,    77157.6,  77353.2,  77134.8,  77128.8,  77337.6,
-    77091.6,  77013.6,  77042.4,  77144.4,  77121.6,  77094,    77020.8,
-    77110.8,  76970.4,  76994.4,  76977.6,  76785.6,  77098.8,  76939.2,
-    76882.8,  76879.2,  77030.4,  76959.6,  76986,    76870.8,  76828.8,
-    76759.2,  76825.2,  76776,    76795.2,  76730.4,  76849.2,  76804.8,
-    76620,    76798.8,  76662,    76702.8,  76545.6,  76610.4,  76790.4,
-    76645.2,  76860,    76657.2,  76530,    76711.2,  76561.2,  76416,
-    76532.4,  76624.8,  76456.8,  76524,    76550.4,  76327.2,  76521.6,
-    76406.4,  76200,    76515.6,  76282.8,  76197.6,  76390.8,  76414.8,
-    76290,    76347.6,  76269.6,  76347.6,  76202.4,  76374,    76239.6,
-    76269.6,  76113.6,  76162.8,  76178.4,  76206,    76135.2,  76257.6,
-    76180.8,  76120.8,  76238.4,  76143.6,  76077.6,  76215.6,  76054.8,
-    76077.6,  75993.6,  75924,    75913.2,  75934.8,  76047.6,  75978,
-    76021.2,  75979.2,  75703.2,  75987.6,  75993.6,  76036.8,  75661.2,
-    75792,    75910.8,  75846,    75817.2,  75860.4,  75934.8,  75903.6,
-    75675.6,  75846,    75607.2,  75742.8,  75597.6,  75699.6,  75565.2,
-    75564,    75376.8,  75524.4,  75384,    75675.6,  75615.6,  75626.4,
-    75589.2,  75408,    75541.2,  75572.4,  75607.2,  75177.6,  75328.8,
-    75724.8,  75612,    75291.6,  75316.8,  75530.4,  75220.8,  75206.4,
-    75260.4,  75133.2,  75244.8,  75453.6,  75259.2,  75211.2,  75321.6,
-    75206.4,  75255.6,  75132,    75325.2,  75194.4,  75111.6,  75061.2,
-    75039.6,  75309.6,  75031.2,  75019.2,  75039.6,  75297.6,  74966.4,
-    74919.6,  74932.8,  75222,    75009.6,  74965.2,  75031.2,  75181.2,
-    74934,    74979.6,  74814,    74910,    74858.4,  74799.6,  74799.6,
-    75000,    74772,    74922,    74995.2,  74756.4,  74830.8,  74772,
-    74834.4,  74874,    74844,    74691.6,  74911.2,  74757.6,  74652,
-    74686.8,  74643.6,  74540.4,  74542.8,  74559.6,  74895.6,  74570.4,
-    74557.2,  74829.6,  74583.6,  74677.2,  74612.4,  74517.6,  74508,
-    74574,    74649.6,  74472,    74494.8,  74473.2,  74490,    74475.6,
-    74380.8,  74527.2,  74526,    74582.4,  74248.8,  74208,    74437.2,
-    74263.2,  74088,    74469.6,  74451.6,  74347.2,  74380.8,  74348.4,
-    74326.8,  74263.2,  74361.6,  74205.6,  74238,    74170.8,  74314.8,
-    74209.2,  74192.4,  74146.8,  74152.8,  74002.8,  74059.2,  74102.4,
-    74172,    74197.2,  74132.4,  74210.4,  74042.4,  74037.6,  73977.6,
-    74013.6,  73983.6,  74019.6,  73915.2,  73845.6,  74086.8,  73926,
-    73850.4,  74018.4,  73824,    74176.8,  73867.2,  73878,    73904.4,
-    73708.8,  73832.4,  73717.2,  73959.6,  74008.8,  73807.2,  73780.8,
-    73708.8,  73724.4,  73593.6,  73866,    73773.6,  73894.8,  73744.8,
-    73620,    73927.2,  73706.4,  73706.4,  73639.2,  73720.8,  73705.2,
-    73551.6,  73737.6,  73621.2,  73482,    73537.2,  73500,    73543.2,
-    73518,    73503.6,  73371.6,  73492.8,  73459.2,  73370.4,  73398,
-    73519.2,  73586.4,  73306.8,  73460.4,  73357.2,  73407.6,  73450.8,
-    73407.6,  73334.4,  73243.2,  73279.2,  73314,    73362,    73317.6,
-    73558.8,  73144.8,  73371.6,  73330.8,  73273.2,  73294.8,  73098,
-    73226.4,  73234.8,  73104,    73197.6,  73100.4,  73272,    73143.6,
-    73068,    73106.4,  73138.8,  73132.8,  72980.4,  73056,    72980.4,
-    73064.4,  72979.2,  73093.2,  73047.6,  73044,    72957.6,  73304.4,
-    72904.8,  72927.6,  72919.2,  72835.2,  73062,    73132.8,  72877.2,
-    72835.2,  72886.8,  72910.8,  72902.4,  72859.2,  73132.8,  72894,
-    72684,    73059.6,  72979.2,  72846,    72804,    72734.4,  72906,
-    72690,    72684,    72814.8,  72763.2,  72746.4,  72586.8,  72698.4,
-    72627.6,  72675.6,  72705.6,  72625.2,  72712.8,  72675.6,  72523.2,
-    72624,    72686.4,  72565.2,  72627.6,  72468,    72672,    72480,
-    72636,    72686.4,  72453.6,  72578.4,  72405.6,  72453.6,  72483.6,
-    72541.2,  72312,    72300,    72548.4,  72288,    72555.6,  72427.2,
-    72411.6,  72450,    72375.6,  72398.4,  72334.8,  72542.4,  72358.8,
-    72393.6,  72368.4,  72242.4,  72374.4,  72348,    72381.6,  72216,
-    72246,    72372,    72319.2,  72127.2,  72187.2,  72174,    72163.2,
-    72124.8,  72325.2,  72220.8,  72016.8,  72300,    72103.2,  72212.4,
-    72332.4,  72086.4,  72100.8,  72289.2,  72056.4,  71959.2,  72069.6,
-    72133.2,  72010.8,  71964,    71967.6,  72076.8,  72145.2,  72277.2,
-    72090,    71924.4,  71852.4,  71755.2,  72148.8,  71959.2,  71924.4,
-    71858.4,  71866.8,  72091.2,  71860.8,  71794.8,  71758.8,  71913.6,
-    71827.2,  71809.2,  71925.6,  71811.6,  71761.2,  72064.8,  71770.8,
-    71784,    71877.6,  71786.4,  71706,    71743.2,  71688,    71752.8,
-    71835.6,  71792.4,  71599.2,  71672.4,  71661.6,  71581.2,  71728.8,
-    71600.4,  71631.6,  71584.8,  71510.4,  71809.2,  71772,    71592,
-    71529.6,  71517.6,  71808,    71815.2,  71614.8,  71461.2,  71552.4,
-    71599.2,  71490,    71492.4,  71569.2,  71562,    71392.8,  71408.4,
-    71360.4,  71517.6,  71326.8,  71469.6,  71366.4,  71485.2,  71168.4,
-    71485.2,  71308.8,  71317.2,  71660.4,  71396.4,  71176.8,  71304,
-    71253.6,  71522.4,  71272.8,  71359.2,  71276.4,  71407.2,  71328,
-    71233.2,  71089.2,  71330.4,  71443.2,  71346,    71275.2,  71176.8,
-    71198.4,  71228.4,  71211.6,  71293.2,  71323.2,  71305.2,  71209.2,
-    71188.8,  71265.6,  71119.2,  71115.6,  71300.4,  71109.6,  71060.4,
-    71064,    71252.4,  71158.8,  71149.2,  70826.4,  71046,    71032.8,
-    71095.2,  71168.4,  71055.6,  71030.4,  71096.4,  70928.4,  71043.6,
-    70998,    70856.4,  70980,    71005.2,  71040,    70972.8,  71056.8,
-    71024.4,  70952.4,  70893.6,  70831.2,  70994.4,  70776,    70789.2,
-    70932,    70965.6,  70808.4,  70776,    70707.6,  70897.2,  70965.6,
-    70737.6,  70677.6,  70768.8,  70785.6,  70833.6,  70898.4,  70569.6,
-    70900.8,  70708.8,  70862.4,  70816.8,  70755.6,  70755.6,  70875.6,
-    70771.2,  70744.8,  70639.2,  70677.6,  70646.4,  70732.8,  70623.6,
-    70663.2,  70584,    70686,    70538.4,  70592.4,  70495.2,  70659.6,
-    70603.2,  70456.8,  70633.2,  70485.6,  70634.4,  70498.8,  70456.8,
-    70362,    70617.6,  70596,    70508.4,  70543.2,  70639.2,  70345.2,
-    70602,    70536,    70537.2,  70508.4,  70440,    70335.6,  70428,
-    70218,    70342.8,  70465.2,  70418.4,  70521.6,  70497.6,  70178.4,
-    70491.6,  70395.6,  70221.6,  70416,    70336.8,  70122,    70275.6,
-    70342.8,  70072.8,  70095.6,  70401.6,  70321.2,  70286.4,  70267.2,
-    70263.6,  70194,    70282.8,  70341.6,  70185.6,  70194,    70116,
-    70153.2,  70108.8,  70364.4,  70251.6,  70142.4,  70092,    70053.6,
-    70117.2,  70201.2,  70350,    70305.6,  70197.6,  70096.8,  70033.2,
-    70207.2,  70065.6,  69981.6,  70219.2,  70083.6,  69919.2,  70023.6,
-    70162.8,  70090.8,  69842.4,  69978,    70080,    69850.8,  70026,
-    70146,    70009.2,  70084.8,  69993.6,  70018.8,  69774,    70086,
-    69873.6,  69898.8,  70056,    70052.4,  69969.6,  69916.8,  70080,
-    69985.2,  69960,    70092,    69817.2,  69966,    69748.8,  69810,
-    69961.2,  69832.8,  69699.6,  69765.6,  69856.8,  69616.8,  69856.8,
-    69777.6,  69820.8,  69937.2,  69847.2,  69789.6,  69889.2,  69751.2,
-    69870,    69727.2,  69756,    69919.2,  69855.6,  69657.6,  69745.2,
-    69726,    69805.2,  69752.4,  69628.8,  69573.6,  69834,    69711.6,
-    69676.8,  69625.2,  69810,    69637.2,  69673.2,  69702,    69567.6,
-    69530.4,  69651.6,  69770.4,  69516,    69616.8,  69612,    69644.4,
-    69469.2,  69594,    69644.4,  69324,    69476.4,  69430.8,  69541.2,
-    69614.4,  69609.6,  69660,    69624,    69573.6,  69546,    69531.6,
-    69453.6,  69392.4,  69445.2,  69444,    69225.6,  69391.2,  69436.8,
-    69444,    69340.8,  69321.6,  69442.8,  69349.2,  69416.4,  69486,
-    69466.8,  69280.8,  69478.8,  69460.8,  69154.8,  69417.6,  69368.4,
-    69262.8,  69343.2,  69379.2,  69246,    69397.2,  69120,    69296.4,
-    69229.2,  69339.6,  69386.4,  69361.2,  69099.6,  69472.8,  69246,
-    69213.6,  69279.6,  69410.4,  69324,    69402,    69187.2,  69307.2,
-    69398.4,  69374.4,  69034.8,  69284.4,  69130.8,  68974.8,  69253.2,
-    69178.8,  69190.8,  69256.8,  69280.8,  69446.4,  69091.2,  69084,
-    69111.6,  68940,    68953.2,  69123.6,  69060,    69206.4,  69172.8,
-    68905.2,  68914.8,  69154.8,  69092.4,  69174,    69086.4,  68926.8,
-    69160.8,  68935.2,  68922,    69122.4,  68961.6,  69046.8,  69030,
-    68932.8,  68947.2,  69126,    68960.4,  69031.2,  69084,    69012,
-    68794.8,  68934,    68966.4,  68895.6,  68853.6,  68888.4,  68845.2,
-    69009.6,  69097.2,  68908.8,  69030,    68950.8,  68827.2,  69008.4,
-    68833.2,  68985.6,  68907.6,  68607.6,  68919.6,  69024,    69044.4,
-    68956.8,  69046.8,  68949.6,  68896.8,  68847.6,  68836.8,  68643.6,
-    68676,    68925.6,  68863.2,  68719.2,  68798.4,  68630.4,  68592,
-    68635.2,  68820,    68851.2,  68730,    68880,    68840.4,  68658,
-    68882.4,  68853.6,  68788.8,  68749.2,  68815.2,  68677.2,  68685.6,
-    68744.4,  68769.6,  68798.4,  68658,    68686.8,  68858.4,  68533.2,
-    68668.8,  68712,    68733.6,  68618.4,  68556,    68626.8,  68622,
-    68652,    68911.2,  68696.4,  68430,    68673.6,  68734.8,  68370,
-    68424,    68692.8,  68511.6,  68550,    68608.8,  68502,    68650.8,
-    68607.6,  68636.4,  68424,    68716.8,  68539.2,  68439.6,  68559.6,
-    68566.8,  68485.2,  68336.4,  68601.6,  68396.4,  68404.8,  68491.2,
-    68416.8,  68584.8,  68547.6,  68716.8,  68328,    68521.2,  68565.6,
-    68546.4,  68679.6,  68505.6,  68475.6,  68581.2,  68568,    68090.4,
-    68469.6,  68673.6,  68626.8,  68539.2,  68343.6,  68655.6,  68307.6,
-    68288.4,  68449.2,  68472,    68296.8,  68576.4,  68384.4,  68332.8,
-    68503.2,  68505.6,  68484,    68413.2,  68254.8,  68329.2,  68625.6,
-    68186.4,  68403.6,  68487.6,  68284.8,  68251.2,  68222.4,  68349.6,
-    68414.4,  68492.4,  68214,    68251.2,  68265.6,  68550,    68164.8,
-    68462.4,  68335.2,  68155.2,  68436,    68388,    68377.2,  68097.6,
-    68308.8,  68271.6,  68338.8,  68145.6,  68325.6,  68215.2,  68313.6,
-    68253.6,  68154,    68372.4,  68275.2,  68254.8,  68562,    68392.8,
-    68133.6,  68245.2,  68131.2,  68209.2,  68256,    68224.8,  68152.8,
-    67959.6,  68251.2,  68154,    68056.8,  68281.2,  68210.4,  68275.2,
-    68344.8,  68041.2,  68200.8,  67970.4,  68181.6,  68064,    68137.2,
-    68269.2,  68269.2,  67960.8,  68380.8,  68203.2,  68126.4,  68162.4,
-    67940.4,  68198.4,  68233.2,  68059.2,  68280,    68322,    68023.2,
-    67990.8,  68020.8,  68113.2,  68110.8,  68085.6,  67956,    68068.8,
-    68191.2,  68005.2,  67921.2,  67987.2,  68139.6,  68028,    68137.2,
-    68083.2,  68077.2,  68026.8,  68066.4,  67993.2,  67957.2,  67975.2,
-    68144.4,  68030.4,  67908,    68115.6,  68024.4,  68030.4,  68136,
-    68026.8,  68008.8,  68036.4,  68060.4,  67896,    68126.4,  68090.4,
-    67944,    67806,    68047.2,  67910.4,  67791.6,  67866,    67850.4,
-    67974,    67814.4,  68154,    68044.8,  67867.2,  68072.4,  67936.8,
-    67958.4,  68013.6,  67844.4,  67900.8,  67887.6,  67770,    67964.4,
-    67935.6,  67830,    67861.2,  67978.8,  67689.6,  68109.6,  67874.4,
-    67905.6,  67852.8,  67707.6,  67974,    67645.2,  67988.4,  67851.6,
-    68056.8,  67915.2,  67986,    67876.8,  67812,    67741.2,  67920,
-    67884,    67819.2,  67903.2,  67737.6,  67803.6,  67788,    67860,
-    67812,    67716,    67975.2,  67929.6,  67864.8,  67786.8,  67876.8,
-    67868.4,  67706.4,  67944,    67850.4,  67696.8,  67779.6,  67783.2,
-    67850.4,  67682.4,  67714.8,  67808.4,  67786.8,  67927.2,  67790.4,
-    67946.4,  67687.2,  67790.4,  67720.8,  67622.4,  67597.2,  67701.6,
-    67731.6,  67725.6,  67798.8,  67826.4,  67932,    67638,    67668,
-    67628.4,  67668,    67704,    67857.6,  67658.4,  67623.6,  67771.2,
-    67672.8,  67842,    67764,    67676.4,  67602,    67780.8,  67611.6,
-    67788,    67716,    67688.4,  67660.8,  67836,    67804.8,  67855.2,
-    67912.8,  67545.6,  67722,    67572,    67542,    67701.6,  67578,
-    67658.4,  67802.4,  67663.2,  67580.4,  67556.4,  67768.8,  67617.6,
-    67693.2,  67455.6,  67747.2,  67602,    67681.2,  67682.4,  67658.4,
-    67602,    67545.6,  67570.8,  67594.8,  67506,    67606.8,  67482,
-    67596,    67569.6,  67622.4,  67572,    67629.6,  67567.2,  67608,
-    67580.4,  67494,    67622.4,  67582.8,  67671.6,  67563.6,  67646.4,
-    67754.4,  67574.4,  67538.4,  67527.6,  67596,    67412.4,  67558.8,
-    67660.8,  67580.4,  67510.8,  67530,    67712.4,  67520.4,  67633.2,
-    67584,    67611.6,  67635.6,  67536,    67550.4,  67537.2,  67455.6,
-    67414.8,  67550.4,  67656,    67668,    67564.8,  67538.4,  67557.6,
-    67404,    67474.8,  67639.2,  67538.4,  67791.6,  67834.8,  67508.4,
-    67586.4,  67468.8,  67466.4,  67460.4,  67648.8,  67527.6,  67423.2,
-    67689.6,  67642.8,  67504.8,  67486.8,  67502.4,  67413.6,  67558.8,
-    67546.8,  67492.8,  67365.6,  67489.2,  67531.2,  67417.2,  67467.6,
-    67440,    67496.4,  67527.6,  67600.8,  67327.2,  67387.2,  67513.2,
-    67532.4,  67634.4,  67462.8,  67399.2,  67513.2,  67402.8,  67341.6,
-    67586.4,  67621.2,  67496.4,  67371.6,  67460.4,  67460.4,  67288.8,
-    67405.2,  67467.6,  67506,    67599.6,  67549.2,  67450.8,  67490.4,
-    67540.8,  67428,    67471.2,  67542,    67453.2,  67495.2,  67438.8,
-    67437.6,  67422,    67369.2,  67405.2,  67572,    67449.6,  67338,
-    67407.6,  67402.8,  67302,    67479.6,  67603.2,  67482,    67438.8,
-    67479.6,  67322.4,  67356,    67429.2,  67578,    67422,    67412.4,
-    67506,    67376.4,  67332,    67372.8,  67377.6,  67629.6,  67444.8,
-    67492.8,  67500,    67437.6,  67411.2,  67423.2,  67324.8,  67387.2,
-    67317.6,  67440,    67554,    67455.6,  67382.4,  67522.8,  67357.2,
-    67394.4,  67248,    67395.6,  67670.4,  67350,    67250.4,  67240.8,
-    67399.2,  67376.4,  67574.4,  67342.8,  67323.6,  67401.6,  67239.6,
-    67344,    67510.8,  67209.6,  67242,    67436.4,  67285.2,  67261.2,
-    67470,    67272,    67251.6,  67412.4,  67216.8,  67425.6,  67273.2,
-    67314,    67432.8,  67219.2,  67414.8,  67483.2,  67294.8,  67357.2,
-    67245.6,  67420.8,  67436.4,  67459.2,  67399.2,  67233.6,  67377.6,
-    67328.4,  67341.6,  67413.6,  67420.8,  67356,    67293.6,  67363.2,
-    67370.4,  67311.6,  67424.4,  67308,    67198.8,  67324.8,  67327.2,
-    67401.6,  67257.6,  67407.6,  67242,    67490.4,  67338,    67388.4,
-    67305.6,  67384.8,  67245.6,  67514.4,  67510.8,  67249.2,  67222.8,
-    67332,    67561.2,  67215.6,  67506,    67311.6,  67296,    67360.8,
-    67438.8,  67284,    67323.6,  67312.8,  67425.6,  67350,    67178.4,
-    67346.4,  67215.6,  67263.6,  67234.8,  67322.4,  67179.6,  67399.2,
-    67284,    67378.8,  67454.4,  67178.4,  67300.8,  67413.6,  67329.6,
-    67138.8,  67184.4,  67458,    67467.6,  67285.2,  67364.4,  67189.2,
-    67380,    67452,    67279.2,  67480.8,  67423.2,  67392,    67257.6,
-    67210.8,  67479.6,  67340.4,  67370.4,  67338,    67369.2,  67315.2,
-    67380};
-
-const float SIMULATED_LAT[GPS_DATA_SIZE] = {
-    3.76934E-07,  2.12122E-07,  -1.71812E-07, 1.8447E-07,   2.22564E-07,
-    1.61956E-07,  -3.27081E-08, -3.67698E-07, -8.8245E-08,  2.36561E-07,
-    1.66147E-07,  6.51119E-10,  5.97583E-08,  2.08472E-07,  1.10656E-07,
-    -2.03282E-07, -5.01795E-08, -2.49524E-08, -1.34027E-07, -6.24701E-08,
-    -1.11716E-07, -3.42272E-07, -5.52034E-08, 2.54705E-07,  1.73384E-07,
-    -2.34695E-07, 1.68062E-07,  6.71245E-08,  -1.12273E-07, 8.19417E-08,
-    5.39269E-08,  -2.01298E-07, -1.3188E-07,  -7.59062E-08, 2.87466E-07,
-    -4.21843E-08, 4.84208E-07,  2.28063E-07,  -1.08865E-08, -6.15637E-08,
-    1.01032E-07,  -2.74606E-07, -5.82089E-08, -1.38132E-07, 4.65425E-09,
-    -1.52543E-07, -1.35982E-07, 1.58534E-07,  -2.27316E-07, -1.63257E-08,
-    -6.15608E-08, -2.1505E-07,  1.38163E-07,  -6.1444E-08,  -3.51964E-07,
-    2.18889E-07,  -2.27062E-07, 1.42957E-08,  3.7949E-07,   1.315E-07,
-    4.11432E-08,  4.38274E-08,  5.32794E-09,  2.80431E-07,  -1.14516E-07,
-    9.52305E-08,  8.11298E-08,  -2.89916E-08, 2.95824E-07,  3.01238E-07,
-    2.97799E-08,  -2.01909E-07, -5.44123E-08, 3.23747E-07,  1.93315E-07,
-    3.62168E-08,  -6.77334E-08, 1.24657E-07,  1.65701E-07,  5.39991E-08,
-    -1.63911E-07, -2.0362E-08,  1.97007E-07,  -2.58482E-07, -4.10798E-07,
-    3.45168E-07,  4.01655E-07,  -3.64355E-07, -2.83517E-07, -5.81187E-08,
-    2.98609E-08,  -1.22408E-07, -4.65224E-07, -5.09004E-08, -2.19067E-07,
-    9.80145E-09,  -8.92895E-09, -2.75929E-07, -1.27299E-07, -4.71347E-07,
-    -1.04301E-07, 2.57856E-07,  -9.40528E-08, 7.85311E-08,  1.11771E-07,
-    -2.63113E-07, -2.14946E-07, 2.11097E-08,  -3.24808E-08, -2.23056E-07,
-    -4.70109E-07, 4.26524E-08,  4.61181E-08,  -2.86103E-07, -1.93316E-07,
-    1.94906E-07,  1.43105E-07,  1.5916E-07,   -1.11042E-08, -1.16749E-07,
-    -1.72716E-07, -2.49052E-08, 9.74565E-08,  1.35746E-07,  1.66931E-07,
-    1.29304E-07,  7.76291E-08,  -1.54247E-07, -6.56644E-08, -2.93574E-07,
-    -7.41989E-08, 6.58051E-08,  2.28718E-07,  -8.82466E-08, -7.59378E-08,
-    -2.17243E-09, -6.30933E-08, 4.87519E-08,  3.87932E-07,  -3.08058E-07,
-    -3.7991E-07,  6.09921E-09,  -7.63216E-07, 4.1687E-07,   2.1309E-07,
-    6.84652E-09,  -1.05982E-07, 8.98257E-08,  2.48217E-07,  -1.35843E-07,
-    2.18528E-07,  1.04768E-07,  6.395E-08,    8.59627E-08,  -1.37216E-07,
-    -2.71795E-07, -3.46347E-07, -1.79066E-07, -1.59695E-07, -1.91646E-07,
-    2.67202E-07,  1.29719E-07,  -2.33781E-08, -2.08154E-07, -1.02285E-07,
-    -8.53781E-08, 7.95985E-08,  -2.01229E-07, -6.30371E-08, -1.98727E-07,
-    2.43502E-08,  -3.17344E-07, 1.53155E-07,  4.89643E-07,  -1.96821E-07,
-    1.08141E-07,  1.30763E-07,  1.74285E-07,  1.59301E-07,  -8.38133E-08,
-    -3.76713E-08, 3.7599E-07,   3.54125E-07,  2.25801E-07,  3.51639E-07,
-    8.97044E-09,  -1.19867E-08, -3.04683E-07, 3.10394E-07,  -1.62884E-07,
-    -5.85739E-08, -1.41581E-07, 2.39545E-07,  -1.97129E-08, -2.81045E-07,
-    5.18673E-08,  -4.36651E-07, 1.43414E-07,  3.50339E-07,  1.79237E-07,
-    8.86588E-08,  2.03958E-07,  4.77796E-07,  -8.48529E-08, -3.82859E-08,
-    -1.05497E-07, 9.38306E-08,  2.75094E-07,  2.05437E-07,  1.08035E-07,
-    2.70916E-07,  -1.51795E-07, -2.65978E-08, 3.65574E-08,  -2.22295E-07,
-    3.26666E-07,  -4.78899E-08, 3.60915E-07,  -3.88395E-07, 2.09375E-07,
-    -2.29577E-07, 5.5004E-08,   3.31515E-07,  2.81451E-08,  -2.44606E-07,
-    2.42212E-07,  -7.16788E-08, -3.87553E-08, 2.335E-08,    -1.40683E-07,
-    2.58588E-08,  -2.01772E-08, 3.76379E-07,  -1.15572E-07, -2.42319E-07,
-    3.74149E-08,  2.43294E-08,  1.10673E-07,  8.72279E-08,  1.27571E-07,
-    -2.25981E-07, 1.27195E-07,  2.23826E-08,  -3.20174E-07, 3.21856E-08,
-    -2.68136E-07, -3.71116E-07, -7.344E-08,   -1.07119E-07, 5.31866E-08,
-    9.04118E-08,  2.48115E-07,  -2.42338E-08, -1.73219E-07, -2.47003E-08,
-    1.85956E-07,  -2.24154E-07, -1.70864E-07, 1.67873E-07,  3.75802E-08,
-    7.54004E-08,  5.66849E-09,  -9.58147E-08, -3.9131E-07,  -2.4055E-07,
-    2.64792E-07,  9.05351E-08,  3.08814E-07,  9.02224E-08,  -2.3836E-07,
-    -4.01966E-08, -4.91776E-07, -3.09592E-09, 4.34199E-07,  4.56393E-07,
-    -2.85331E-07, -4.28243E-08, -9.0535E-08,  -1.66351E-07, -9.6062E-08,
-    2.36603E-07,  -8.17096E-09, 1.52501E-07,  2.6562E-07,   3.18883E-08,
-    3.85047E-08,  -9.9221E-08,  3.40032E-08,  -1.78432E-08, -1.45885E-07,
-    1.13226E-07,  1.83697E-07,  4.30458E-07,  2.4484E-08,   -1.78475E-08,
-    -1.54759E-07, 3.05778E-07,  -2.05695E-07, 6.39378E-08,  -1.21166E-07,
-    1.17516E-07,  4.93873E-08,  -2.72045E-08, 1.75233E-08,  3.24445E-07,
-    5.29042E-08,  1.01796E-07,  1.12074E-07,  7.02373E-08,  -2.47207E-07,
-    7.92019E-07,  2.83616E-07,  5.91542E-08,  2.64248E-07,  1.742E-07,
-    -1.64314E-07, 5.17861E-09,  -2.23724E-07, -3.18962E-07, 1.67487E-07,
-    8.90668E-08,  -2.84997E-07, -4.77309E-07, -3.96104E-08, -1.20889E-07,
-    4.05684E-08,  1.56952E-07,  5.28963E-07,  1.54991E-08,  1.0416E-07,
-    -6.41972E-08, 1.48924E-08,  2.89395E-07,  1.00629E-07,  -2.1309E-07,
-    6.71141E-07,  2.88868E-07,  1.63219E-07,  1.15999E-07,  9.5636E-08,
-    -1.23719E-07, 1.49386E-07,  -2.93838E-07, 4.28709E-07,  -1.85328E-07,
-    1.28787E-07,  1.11139E-07,  -1.1925E-07,  -7.4553E-08,  -2.69638E-08,
-    1.26527E-07,  6.57827E-07,  -1.74398E-07, 3.40294E-07,  8.47443E-09,
-    9.78399E-08,  -8.1528E-08,  3.04273E-07,  -4.15214E-08, 5.86915E-08,
-    5.68868E-07,  -1.62137E-07, -1.71217E-08, 5.6724E-08,   -1.06476E-07,
-    1.85715E-07,  -3.8599E-09,  -6.64407E-09, 1.17404E-07,  -2.56204E-07,
-    -1.75241E-07, 1.71596E-07,  -1.4762E-07,  4.16646E-07,  9.69343E-08,
-    1.82059E-07,  -8.3673E-08,  1.26423E-07,  -1.02764E-07, 1.39617E-08,
-    2.47254E-07,  6.72091E-08,  -4.55932E-08, 4.89326E-08,  5.28676E-07,
-    -1.34328E-07, 2.51601E-07,  4.22153E-07,  -2.38294E-07, -3.2331E-08,
-    -9.2493E-08,  -1.73735E-07, 4.90407E-08,  6.12707E-08,  3.47552E-07,
-    -6.39062E-08, 1.61706E-07,  1.88663E-07,  1.26598E-07,  -1.23814E-07,
-    1.90992E-07,  8.8243E-09,   1.14491E-07,  2.70083E-07,  3.94591E-07,
-    1.82845E-07,  4.07766E-07,  3.16535E-07,  -1.90365E-07, -3.51666E-08,
-    1.05588E-07,  3.92326E-07,  1.00873E-07,  1.79402E-07,  1.33758E-07,
-    -4.23842E-08, -2.49972E-07, 1.81966E-07,  5.06369E-07,  8.14509E-09,
-    1.55945E-07,  -3.22357E-07, 5.0511E-07,   1.89089E-07,  5.0358E-07,
-    -5.85379E-08, 3.76608E-07,  1.32459E-07,  3.97731E-07,  1.26059E-07,
-    1.2545E-07,   -4.79149E-08, -1.88091E-07, -1.0095E-07,  -2.09027E-07,
-    4.55574E-07,  2.3318E-07,   -2.25007E-07, 1.41289E-07,  3.60225E-07,
-    -3.51109E-08, 2.77369E-08,  3.12882E-07,  1.37439E-07,  -3.22587E-08,
-    5.02227E-07,  2.0798E-08,   2.27387E-08,  -5.25458E-09, 1.92431E-07,
-    1.16708E-07,  -3.64609E-07, 2.50435E-07,  2.03234E-07,  -5.69815E-08,
-    1.35059E-07,  -3.19073E-08, 4.79436E-08,  9.50161E-08,  4.37039E-07,
-    2.90042E-08,  3.94144E-07,  7.00003E-07,  -6.74312E-08, 4.29219E-07,
-    7.49522E-08,  1.56493E-07,  3.45089E-07,  -2.51653E-09, 3.71912E-08,
-    -4.75243E-07, 3.67593E-07,  2.60062E-07,  3.04229E-07,  -5.58112E-08,
-    2.33565E-07,  -1.0599E-07,  1.09906E-07,  3.57026E-07,  -3.251E-07,
-    -1.4299E-07,  1.77976E-07,  5.80065E-07,  6.21202E-09,  -2.11489E-07,
-    3.26742E-07,  2.96697E-07,  3.01139E-07,  -3.84749E-08, 1.55941E-07,
-    5.27668E-08,  2.19175E-08,  2.47696E-07,  3.44804E-07,  2.2413E-07,
-    4.32379E-07,  8.00394E-08,  6.79679E-08,  1.04711E-07,  -2.93326E-07,
-    5.15893E-07,  6.86966E-08,  1.41436E-07,  -5.1175E-09,  2.79959E-08,
-    4.25647E-07,  1.02152E-07,  6.18334E-07,  2.48212E-07,  4.08957E-07,
-    4.22657E-07,  9.87536E-08,  -6.15099E-08, -1.71758E-08, 4.5777E-08,
-    1.13523E-07,  5.09769E-07,  3.22232E-07,  8.0301E-08,   3.28425E-07,
-    1.829E-07,    3.79398E-07,  1.24663E-07,  9.5638E-08,   3.42618E-07,
-    5.51992E-08,  1.139E-07,    -8.79583E-08, 2.34549E-07,  3.2584E-07,
-    1.32815E-07,  2.23702E-07,  6.4596E-07,   2.01261E-07,  1.69186E-07,
-    1.10583E-07,  8.54538E-08,  4.05363E-09,  2.30544E-07,  -2.81641E-07,
-    4.32508E-07,  3.03467E-08,  3.39017E-07,  1.43908E-07,  2.9265E-07,
-    3.8134E-07,   -1.24763E-07, -3.5858E-07,  1.6614E-08,   2.07675E-07,
-    4.10685E-08,  1.56855E-07,  3.14779E-07,  5.14184E-07,  2.25746E-07,
-    2.98339E-07,  -2.96785E-08, 6.90695E-09,  -1.83533E-07, 7.82588E-08,
-    3.1694E-07,   4.22748E-08,  1.69505E-07,  3.46751E-07,  5.22543E-08,
-    2.44437E-07,  -2.14923E-07, 4.15526E-07,  2.76735E-08,  2.65348E-07,
-    1.31599E-07,  1.14923E-07,  1.84765E-07,  2.10938E-07,  4.99983E-07,
-    1.66245E-07,  1.61719E-07,  4.50525E-08,  1.5116E-07,   1.70525E-07,
-    5.15745E-07,  6.75539E-07,  6.04561E-07,  1.28565E-07,  -1.68076E-07,
-    3.1469E-07,   1.67784E-07,  2.53309E-07,  6.15648E-07,  -1.37485E-07,
-    4.02993E-07,  5.81048E-07,  1.07197E-07,  -3.84591E-08, -4.70557E-08,
-    4.03077E-07,  2.97067E-07,  3.93186E-07,  2.74167E-07,  -3.14718E-07,
-    -3.31321E-07, 4.21682E-07,  3.98249E-07,  3.63485E-07,  4.21728E-07,
-    -1.62575E-08, 5.41185E-07,  4.03863E-07,  7.39092E-07,  2.59721E-07,
-    7.31732E-07,  1.80858E-07,  3.47947E-07,  1.86029E-07,  3.27507E-07,
-    1.73963E-07,  4.24296E-07,  2.94336E-08,  7.87342E-08,  9.61727E-08,
-    1.37111E-07,  -1.07064E-07, -4.31554E-08, -1.63853E-07, 2.13895E-07,
-    4.26615E-07,  6.7162E-07,   6.50324E-07,  5.14163E-07,  2.69901E-08,
-    7.34751E-07,  2.19974E-07,  3.92115E-07,  3.21091E-07,  3.27927E-07,
-    -1.15923E-07, 5.67661E-07,  3.36355E-07,  -2.68389E-08, 8.38852E-08,
-    2.7667E-07,   6.22976E-08,  1.50801E-07,  5.19361E-07,  3.25352E-07,
-    7.36864E-08,  4.48116E-07,  3.69353E-07,  1.39618E-07,  3.25917E-07,
-    3.23688E-07,  2.51912E-07,  6.97721E-07,  4.91709E-07,  7.25924E-08,
-    -4.96837E-08, 3.58817E-07,  4.28857E-07,  3.78063E-07,  1.53949E-07,
-    -3.39137E-08, 4.37494E-07,  2.75632E-07,  1.25201E-07,  2.88497E-07,
-    1.48405E-07,  7.43164E-08,  2.72429E-07,  4.46933E-09,  2.48668E-07,
-    1.36716E-07,  3.15534E-07,  1.46811E-09,  -7.62545E-08, 1.97662E-07,
-    4.0739E-07,   3.30811E-07,  2.00283E-07,  1.93852E-08,  9.80604E-08,
-    -1.27911E-07, 3.32752E-07,  2.59761E-07,  1.83099E-07,  3.75473E-07,
-    5.43587E-07,  -4.41739E-08, -3.44284E-07, 6.02875E-07,  2.28467E-07,
-    2.82846E-07,  6.78824E-07,  -8.58618E-08, 2.32597E-07,  8.44949E-08,
-    2.84292E-07,  3.47198E-07,  4.78178E-07,  6.61631E-07,  2.59669E-07,
-    3.13543E-08,  2.66253E-07,  -1.91963E-08, 3.30198E-07,  -1.74934E-09,
-    2.43273E-07,  -1.55982E-07, 4.5496E-07,   2.18412E-07,  4.03623E-07,
-    4.22904E-07,  3.86318E-07,  3.45661E-07,  2.19722E-07,  2.95303E-07,
-    2.53137E-07,  2.31238E-07,  2.27292E-07,  3.54686E-07,  3.41388E-07,
-    -3.10595E-09, 3.99313E-07,  -1.80688E-07, -2.38015E-08, 8.96541E-09,
-    -2.62316E-09, 6.90012E-07,  1.2403E-07,   1.67086E-07,  4.67675E-07,
-    1.62634E-07,  3.22439E-07,  2.35106E-07,  2.98439E-07,  7.56885E-08,
-    3.1733E-07,   1.66434E-07,  2.6317E-07,   5.18119E-07,  3.52609E-07,
-    -2.92566E-07, 1.03912E-07,  2.74456E-07,  5.24184E-08,  8.78391E-08,
-    4.40749E-07,  2.30784E-07,  7.33978E-07,  5.70596E-07,  4.92872E-07,
-    1.87486E-07,  2.60052E-07,  6.08186E-07,  5.05143E-07,  -1.45117E-07,
-    6.15534E-08,  3.90429E-07,  1.88996E-07,  4.62594E-07,  4.60953E-07,
-    2.17185E-07,  4.36624E-07,  3.3126E-07,   2.53269E-08,  4.33314E-07,
-    3.03545E-07,  1.58187E-07,  -1.06813E-07, 3.13589E-07,  1.54831E-07,
-    1.56194E-08,  4.79352E-07,  2.81844E-07,  3.43639E-07,  3.5813E-07,
-    2.42665E-07,  5.763E-07,    2.71523E-07,  -1.62852E-07, 4.66001E-07,
-    1.36111E-07,  3.12783E-07,  1.21314E-07,  1.9202E-07,   1.30285E-07,
-    1.85722E-08,  4.56776E-07,  2.54433E-07,  2.16893E-07,  6.25719E-07,
-    2.67656E-07,  3.37036E-07,  2.93638E-07,  1.28865E-07,  1.73601E-07,
-    4.58188E-07,  4.18983E-07,  4.62456E-07,  1.1491E-07,   -1.68978E-09,
-    2.96414E-07,  2.59159E-07,  3.91169E-07,  1.13165E-07,  -5.60955E-08,
-    4.62481E-07,  5.26984E-07,  3.47018E-07,  2.55614E-07,  4.56998E-07,
-    2.88484E-07,  4.24019E-07,  3.18946E-07,  5.8359E-08,   -1.89786E-08,
-    5.80776E-07,  4.60101E-07,  6.96266E-07,  4.81719E-07,  3.30842E-07,
-    3.25864E-07,  3.26425E-07,  1.69471E-07,  6.58624E-07,  2.26247E-07,
-    2.38573E-07,  1.19507E-07,  5.13737E-07,  1.76005E-07,  6.98724E-07,
-    3.41996E-07,  3.57223E-07,  2.39603E-07,  4.14681E-07,  4.76989E-07,
-    2.76831E-07,  4.44548E-07,  4.83482E-08,  8.111E-07,    4.05891E-07,
-    5.03339E-07,  -1.37595E-07, 6.70822E-07,  1.09145E-07,  8.35362E-08,
-    1.15073E-08,  1.24085E-07,  9.25172E-08,  6.84858E-07,  4.99671E-07,
-    2.77959E-07,  1.83701E-07,  1.87268E-07,  3.42776E-07,  3.53348E-07,
-    5.33311E-08,  1.63708E-07,  1.93731E-07,  3.35638E-07,  6.58741E-07,
-    5.25028E-07,  3.15438E-08,  2.81862E-07,  5.14124E-07,  -2.96436E-08,
-    3.62692E-07,  3.11441E-07,  7.99812E-07,  2.94803E-07,  5.42033E-07,
-    4.43783E-07,  4.72707E-07,  8.85159E-07,  4.56953E-07,  3.53887E-07,
-    3.82514E-07,  8.87906E-07,  2.68582E-07,  3.84237E-07,  3.92789E-07,
-    8.1394E-07,   5.26365E-07,  2.34925E-07,  3.69081E-07,  3.04649E-07,
-    5.68641E-07,  3.13766E-07,  8.44336E-07,  2.48769E-07,  4.24854E-07,
-    6.01978E-07,  7.14109E-07,  2.36984E-07,  1.26208E-07,  6.26918E-07,
-    -3.67796E-08, 3.15344E-07,  3.10279E-07,  4.40788E-07,  5.91082E-07,
-    5.40173E-07,  2.92114E-07,  1.02907E-07,  4.19004E-07,  6.22223E-08,
-    7.77029E-07,  5.35426E-07,  5.80406E-07,  1.43836E-07,  5.5226E-07,
-    3.75246E-07,  6.40993E-07,  5.0517E-07,   2.83657E-07,  2.13748E-07,
-    2.8984E-07,   6.87168E-07,  3.27529E-07,  3.41771E-07,  6.37378E-07,
-    6.90703E-07,  6.90406E-07,  4.86049E-07,  3.20396E-08,  3.39522E-07,
-    3.50431E-07,  2.16964E-07,  4.01237E-07,  4.49876E-07,  6.85882E-07,
-    8.67061E-07,  2.89037E-07,  6.38809E-07,  1.39138E-07,  5.52058E-07,
-    6.69598E-07,  6.38367E-08,  4.91919E-07,  4.8665E-07,   4.67906E-07,
-    3.15027E-07,  6.38065E-08,  2.39189E-07,  4.65544E-07,  5.70284E-07,
-    7.27188E-07,  2.95759E-07,  2.42866E-07,  4.50052E-07,  1.15958E-07,
-    6.02928E-07,  3.46188E-07,  4.40401E-07,  1.16984E-07,  -1.07559E-07,
-    7.31657E-07,  4.89459E-07,  1.09201E-07,  4.125E-07,    5.76982E-07,
-    4.61014E-07,  3.75026E-07,  6.3537E-07,   2.49458E-07,  2.66286E-07,
-    1.72686E-07,  4.11271E-07,  4.61492E-07,  6.37899E-07,  3.36987E-07,
-    7.74077E-07,  6.60381E-07,  2.24091E-07,  -7.53405E-08, 3.37517E-07,
-    4.4892E-07,   1.13367E-07,  9.43538E-07,  1.99671E-07,  2.88424E-07,
-    7.11627E-07,  6.99267E-07,  3.6811E-07,   5.46671E-07,  1.98761E-07,
-    6.6924E-07,   4.54519E-07,  2.89802E-07,  4.22434E-07,  4.50725E-07,
-    3.3101E-07,   3.30194E-07,  4.74076E-07,  3.9691E-07,   4.36405E-07,
-    1.84678E-07,  4.02748E-07,  4.62169E-07,  7.38964E-07,  6.30887E-07,
-    2.75148E-07,  6.9305E-07,   1.65885E-07,  4.01321E-07,  5.43484E-07,
-    4.37937E-08,  3.28615E-07,  5.90611E-07,  4.39795E-07,  4.36635E-07,
-    5.1449E-07,   3.73898E-07,  4.82856E-08,  5.28446E-07,  7.10669E-07,
-    4.61377E-07,  5.46876E-07,  5.03047E-07,  7.13356E-07,  2.58069E-07,
-    -9.62128E-08, 4.71884E-07,  2.51452E-07,  3.40176E-07,  3.95032E-07,
-    2.68876E-07,  3.75268E-07,  -2.51222E-08, 6.16164E-07,  1.07169E-07,
-    3.82748E-07,  1.26826E-07,  3.71241E-07,  4.69658E-07,  1.76793E-07,
-    7.59831E-07,  2.11284E-07,  2.81563E-07,  4.37143E-07,  5.03805E-07,
-    8.31503E-07,  3.32433E-07,  6.68708E-07,  8.99892E-07,  6.10378E-07,
-    5.16117E-07,  5.93846E-07,  4.92307E-07,  -6.11545E-08, 5.20679E-07,
-    3.49166E-07,  2.04111E-07,  4.55106E-07,  5.65561E-07,  3.24893E-07,
-    3.96027E-07,  5.37924E-07,  4.13636E-07,  4.47237E-07,  3.07009E-07,
-    5.972E-07,    5.88401E-07,  1.69286E-07,  4.16011E-07,  1.29484E-07,
-    1.33329E-07,  5.14593E-07,  4.59271E-07,  1.35368E-08,  4.85127E-07,
-    6.7831E-07,   1.41112E-07,  3.18904E-07,  4.65298E-07,  3.12985E-07,
-    5.43456E-07,  7.55217E-07,  1.67973E-07,  3.16582E-07,  3.38444E-07,
-    3.77391E-07,  6.75231E-07,  3.10216E-07,  6.42141E-07,  5.05824E-07,
-    6.06116E-07,  5.67224E-07,  3.95601E-07,  5.90806E-07,  6.10517E-07,
-    7.76635E-08,  5.85962E-07,  3.75336E-07,  7.43052E-07,  4.81385E-07,
-    8.58713E-08,  6.75051E-07,  3.33767E-07,  5.06048E-07,  2.28521E-07,
-    1.68417E-07,  5.22104E-07,  7.48642E-07,  -4.91246E-08, 5.02858E-07,
-    1.90265E-07,  3.28226E-07,  3.32533E-07,  2.63497E-07,  4.66771E-07,
-    2.10939E-07,  3.63075E-07,  5.31147E-07,  6.1292E-07,   5.18619E-07,
-    3.602E-07,    5.1435E-07,   4.71911E-07,  5.85486E-07,  3.55702E-07,
-    6.94706E-07,  1.95845E-07,  2.52414E-07,  6.84836E-07,  3.9232E-07,
-    6.08009E-07,  5.63924E-07,  8.17148E-07,  4.67387E-07,  4.52419E-07,
-    5.63551E-07,  5.20357E-07,  -4.43501E-09, 3.56878E-07,  4.98768E-07,
-    3.99647E-07,  5.04262E-07,  4.87356E-07,  3.60702E-07,  5.08408E-07,
-    2.66501E-07,  1.63755E-07,  5.83924E-07,  6.97951E-07,  7.24249E-07,
-    1.78187E-07,  4.26173E-07,  5.47619E-07,  7.12395E-07,  6.59994E-07,
-    6.95583E-07,  4.98723E-07,  2.05388E-07,  5.71976E-07,  4.98643E-08,
-    3.63037E-07,  2.05371E-07,  7.01863E-08,  1.33856E-07,  9.0386E-07,
-    5.78131E-07,  6.25304E-07,  3.251E-07,    2.5932E-07,   4.42904E-07,
-    5.00095E-07,  1.29878E-07,  3.17349E-08,  4.97886E-07,  2.87772E-07,
-    2.1782E-07,   4.36432E-07,  1.55109E-07,  4.34165E-07,  7.53837E-07,
-    4.30119E-07,  2.97717E-07,  4.3584E-07,   -1.31868E-07, 3.13235E-07,
-    8.45309E-07,  3.0712E-07,   5.20997E-07,  9.88335E-07,  5.85708E-07,
-    6.14821E-07,  8.09163E-07,  3.1095E-07,   3.78177E-07,  1.09151E-06,
-    5.34319E-07,  9.1483E-07,   9.06959E-07,  1.84598E-07,  6.26935E-07,
-    6.56133E-08,  1.37399E-07,  8.85784E-07,  4.08103E-07,  3.01895E-07,
-    5.07298E-07,  1.9605E-07,   3.89331E-07,  2.76314E-07,  7.51574E-07,
-    4.31574E-07,  7.22702E-07,  7.02651E-07,  1.57576E-07,  2.41137E-07,
-    8.03308E-07,  4.36404E-07,  6.83234E-07,  3.85247E-07,  2.06997E-07,
-    7.36806E-07,  7.96621E-07,  7.15796E-07,  9.31265E-07,  3.31266E-08,
-    4.71284E-07,  4.25304E-07,  4.2604E-07,   1.51657E-07,  7.76277E-07,
-    5.66973E-07,  6.91298E-07,  4.02118E-07,  6.53179E-07,  5.38639E-07,
-    4.68801E-07,  6.49496E-07,  2.38776E-07,  4.65935E-07,  5.03468E-07,
-    6.84853E-07,  7.64307E-07,  1.06877E-07,  5.93099E-07,  2.7211E-07,
-    2.24536E-07,  3.18711E-07,  4.54799E-07,  2.05728E-07,  5.45438E-07,
-    3.77433E-07,  3.36027E-07,  4.37484E-07,  5.7132E-07,   6.57772E-07,
-    3.35435E-07,  2.31045E-07,  6.9187E-07,   4.7727E-07,   5.7104E-07,
-    5.09243E-07,  3.81214E-07,  6.22616E-07,  7.94663E-07,  3.12949E-07,
-    2.71216E-07,  6.87413E-07,  -1.4409E-07,  3.70349E-07,  6.53573E-07,
-    5.12776E-07,  2.22411E-07,  5.92519E-07,  7.13681E-07,  3.68427E-07,
-    5.25275E-07,  6.98196E-07,  6.83187E-07,  3.57218E-07,  2.30839E-07,
-    6.43597E-07,  8.20524E-07,  -1.62657E-08, 8.59613E-07,  5.81985E-07,
-    4.52627E-07,  4.52554E-07,  7.61057E-07,  8.07896E-07,  7.03395E-07,
-    5.82255E-07,  6.81718E-07,  7.28229E-07,  4.717E-07,    3.71095E-07,
-    5.80015E-08,  7.12153E-07,  4.79455E-07,  6.36934E-07,  6.26606E-07,
-    5.09777E-07,  3.92585E-07,  3.6786E-07,   1.26685E-07,  8.83978E-07,
-    1.73773E-07,  7.57403E-07,  7.22322E-07,  4.01634E-07,  7.74588E-07,
-    8.19117E-07,  2.84339E-07,  4.24787E-07,  7.22572E-07,  6.04852E-07,
-    1.01788E-07,  6.53814E-07,  -3.2755E-08,  6.87165E-07,  6.03928E-07,
-    2.63609E-07,  3.48812E-07,  4.68404E-07,  5.09688E-07,  5.71163E-07,
-    7.63253E-07,  5.50409E-07,  5.15328E-07,  6.67003E-07,  5.16048E-07,
-    2.10456E-07,  4.32267E-07,  6.61492E-07,  3.61794E-07,  2.66644E-07,
-    3.82955E-07,  3.55708E-07,  9.87041E-07,  5.78699E-07,  9.01598E-07,
-    3.95467E-07,  7.06755E-07,  3.3168E-07,   6.74315E-07,  8.35158E-07,
-    8.33303E-07,  3.27687E-07,  7.22572E-07,  5.0582E-07,   4.84095E-07,
-    2.96555E-07,  2.76895E-07,  4.76635E-07,  6.7625E-07,   6.57486E-07,
-    8.60145E-07,  5.61585E-07,  1.6521E-07,   5.71664E-07,  7.14619E-07,
-    5.12783E-07,  6.66017E-08,  3.8933E-07,   5.33127E-07,  6.83998E-07,
-    6.08649E-07,  4.8867E-07,   1.06914E-06,  4.41095E-07,  3.12009E-07,
-    9.09385E-07,  1.50159E-07,  5.87673E-07,  6.06796E-07,  5.59761E-07,
-    2.97967E-07,  3.62042E-07,  4.79037E-07,  3.58792E-07,  1.81651E-07,
-    4.37691E-07,  3.98959E-07,  1.01068E-06,  7.33268E-07,  9.71471E-07,
-    7.56725E-07,  1.05442E-06,  2.96232E-07,  3.20394E-07,  2.75402E-07,
-    5.98413E-07,  9.47218E-07,  3.15337E-07,  8.47428E-07,  3.44367E-07,
-    6.84433E-07,  6.05551E-07,  7.03481E-07,  3.08964E-07,  4.7095E-07,
-    5.1271E-07,   5.50433E-07,  4.78849E-07,  6.83504E-07,  8.00266E-07,
-    6.17849E-07,  6.80301E-07,  3.1633E-07,   8.41341E-07,  5.20786E-07,
-    2.27087E-07,  3.21207E-07,  3.06591E-07,  6.94168E-07,  5.08057E-07,
-    2.96556E-07,  -6.73466E-08, 3.57986E-07,  8.54299E-07,  6.76559E-07,
-    4.98335E-07,  6.31299E-07,  6.65502E-07,  5.01349E-07,  9.39548E-07,
-    3.53597E-07,  2.06021E-07,  3.96238E-07,  4.13217E-07,  8.16658E-07,
-    4.61265E-07,  5.29631E-07,  5.1819E-07,   7.07341E-07,  9.00059E-07,
-    6.80614E-07,  9.81769E-07,  6.42255E-07,  4.79011E-07,  7.64033E-07,
-    3.83575E-07,  5.14271E-07,  5.8324E-07,   7.51059E-07,  7.01172E-07,
-    1.94809E-07,  6.03129E-07,  4.9366E-07,   7.63842E-07,  4.57237E-07,
-    8.59058E-07,  5.87943E-07,  7.9433E-07,   2.56729E-07,  5.98815E-07,
-    1.07798E-06,  8.2063E-07,   5.69521E-07,  5.60207E-07,  5.83383E-07,
-    4.39279E-07,  2.55421E-07,  6.33668E-07,  1.22436E-07,  4.00587E-07,
-    9.08059E-07,  4.76726E-07,  7.06674E-07,  5.34291E-07,  2.1121E-07,
-    4.20983E-07,  5.37036E-07,  4.65662E-07,  1.37602E-07,  3.19143E-07,
-    6.33814E-07,  5.80594E-07,  5.57141E-07,  7.00927E-07,  5.25485E-07,
-    5.54261E-07,  2.65493E-07,  6.59737E-07,  3.51037E-07,  5.35126E-07,
-    7.61726E-07,  7.26301E-07,  5.22346E-07,  8.72359E-07,  9.69091E-07,
-    2.98928E-07,  1.10481E-06,  6.12839E-07,  5.44351E-07,  3.37904E-07,
-    8.68476E-07,  1.00438E-06,  8.5139E-07,   8.45094E-07,  8.2242E-07,
-    9.81487E-07,  4.68897E-07,  7.45395E-07,  5.75876E-07,  4.41358E-07,
-    6.28174E-07,  8.87356E-07,  3.59556E-07,  7.36999E-07,  9.82377E-08,
-    3.82654E-07,  4.79728E-07,  1.47964E-07,  4.85844E-07,  6.22145E-07,
-    5.82505E-07,  4.66394E-07,  4.2551E-07,   6.28908E-07,  6.35802E-07,
-    4.946E-07,    6.89955E-07,  5.86421E-07,  6.07741E-07,  3.15998E-07,
-    3.52035E-07,  3.64328E-07,  5.12186E-07,  8.35698E-07,  4.15805E-07,
-    5.63711E-07,  7.28527E-07,  6.7841E-07,   7.80969E-07,  6.63385E-07,
-    2.28157E-07,  8.77636E-07,  1.05348E-06,  6.80084E-07,  1.98753E-07,
-    7.97042E-07,  4.84903E-07,  8.55167E-07,  5.57934E-07,  6.97996E-07,
-    3.52109E-07,  6.26773E-07,  5.3312E-07,   7.4876E-07,   8.00969E-07,
-    8.82651E-07,  7.85148E-07,  1.17512E-06,  3.6744E-07,   8.55814E-07,
-    4.99202E-07,  1.01832E-06,  5.022E-07,    8.21731E-07,  1.04283E-06,
-    1.59986E-07,  5.69402E-07,  7.98816E-07,  8.98257E-07,  8.22677E-07,
-    1.1691E-06,   6.54726E-07,  6.55E-07,     5.94028E-07,  6.89328E-07,
-    8.55687E-07,  2.63729E-07,  6.74874E-07,  4.99291E-07,  4.99376E-07,
-    5.47195E-07,  7.08862E-07,  4.98164E-07,  7.34018E-07,  5.55972E-07,
-    6.36141E-07,  6.74781E-07,  6.93496E-07,  5.28119E-07,  5.89503E-07,
-    8.12319E-07,  3.48921E-07,  7.35968E-07,  7.6714E-07,   9.76346E-07,
-    5.94384E-07,  4.55885E-07,  3.03447E-07,  3.12256E-07,  9.07714E-07,
-    7.85438E-07,  4.83577E-07,  5.58356E-07,  1.0008E-06,   5.1497E-07,
-    6.85606E-07,  6.27599E-07,  6.50068E-07,  6.35332E-07,  1.14241E-06,
-    3.45645E-07,  9.65422E-07,  4.19979E-07,  5.73274E-07,  5.8287E-07,
-    4.036E-07,    7.81148E-07,  6.12824E-07,  1.26142E-06,  3.13189E-07,
-    8.64758E-07,  7.11363E-07,  7.13097E-07,  7.82466E-07,  5.18369E-07,
-    5.50909E-07,  6.29709E-07,  6.99076E-07,  4.10409E-07,  8.34343E-07,
-    4.24549E-07,  1.04369E-06,  9.28835E-07,  5.38838E-07,  9.29732E-07,
-    7.20093E-07,  5.58478E-07,  6.56105E-07,  8.47952E-07,  2.87647E-07,
-    5.06522E-07,  5.41565E-07,  6.89327E-07,  8.61232E-07,  5.07766E-07,
-    6.19447E-07,  7.11609E-07,  5.87218E-07,  4.1928E-07,   5.03905E-07,
-    6.1528E-07,   1.01844E-06,  5.2767E-07,   8.17664E-07,  9.38428E-07,
-    7.79238E-07,  8.02621E-07,  5.10544E-07,  4.11051E-07,  4.25927E-07,
-    7.21417E-07,  4.47019E-07,  4.7425E-07,   7.83066E-07,  6.71848E-07,
-    7.09852E-07,  5.6588E-07,   2.08407E-07,  5.14476E-07,  5.88994E-07,
-    8.00861E-07,  5.34024E-07,  7.02772E-07,  7.52933E-07,  2.9196E-07,
-    9.33582E-07,  6.53747E-07,  7.07025E-07,  7.40819E-07,  8.82499E-07,
-    8.99769E-07,  4.75446E-07,  6.56858E-07,  6.65791E-07,  5.0845E-07,
-    8.68989E-07,  6.92259E-07,  5.13645E-08,  5.07448E-07,  4.77084E-07,
-    6.35104E-07,  5.36342E-07,  5.14937E-07,  9.39478E-07,  6.9814E-07,
-    4.66611E-07,  4.46305E-07,  9.73917E-07,  4.43573E-07,  5.86071E-07,
-    4.25134E-07,  5.40401E-07,  2.79352E-07,  2.45074E-07,  8.10726E-07,
-    5.71619E-07,  6.8158E-07,   3.70016E-07,  6.48764E-07,  7.73522E-07,
-    6.21811E-07,  5.79637E-07,  5.6783E-07,   3.58305E-07,  5.05352E-07,
-    2.98723E-07,  5.88613E-07,  8.72919E-07,  5.3377E-07,   5.12491E-07,
-    6.03532E-07,  9.41264E-07,  5.33109E-07,  3.73368E-07,  9.78579E-07,
-    9.33609E-07,  4.85875E-07,  7.28735E-07,  9.79759E-07,  1.09736E-06,
-    6.24609E-07,  7.8959E-07,   1.38738E-07,  4.11922E-07,  5.34056E-07,
-    7.96481E-07,  5.33397E-07,  7.02661E-07,  5.54345E-07,  3.07605E-07,
-    9.27642E-07,  4.02612E-07,  4.4826E-07,   8.77177E-07,  5.46556E-07,
-    7.56858E-07,  8.12908E-07,  1.12244E-06,  6.81324E-07,  4.46519E-07,
-    9.89779E-07,  7.84284E-07,  6.91761E-07,  2.5327E-07,   5.00255E-07,
-    1.24998E-06,  4.20599E-07,  7.35953E-07,  9.88749E-07,  5.94785E-07,
-    7.35253E-07,  9.03222E-07,  8.81024E-07,  1.03997E-06,  6.68177E-07,
-    6.11756E-07,  8.20331E-07,  5.43699E-07,  6.48492E-07,  4.58018E-07,
-    5.76385E-07,  6.15443E-07,  8.17724E-07,  1.30614E-06,  4.94546E-07,
-    2.73049E-07,  1.9201E-07,   6.72776E-07,  4.91968E-07,  1.00504E-07,
-    3.50675E-07,  7.5466E-07,   8.31081E-07,  6.20516E-07,  8.61186E-07,
-    7.47773E-07,  7.30435E-07,  6.39607E-07,  6.5334E-07,   7.7868E-07,
-    7.37545E-07,  9.48707E-07,  5.98457E-07,  3.87945E-07,  9.48542E-07,
-    8.54379E-07,  6.16224E-07,  9.40769E-07,  9.24717E-07,  8.40893E-07,
-    7.20019E-07,  9.45572E-07,  5.6666E-07,   9.13419E-07,  4.20845E-07,
-    4.75831E-07,  6.07023E-07,  4.44465E-07,  8.4033E-07,   5.90143E-07,
-    9.53968E-07,  6.04483E-07,  8.59412E-07,  6.69747E-07,  4.79243E-07,
-    1.03603E-06,  7.96978E-07,  6.9984E-07,   4.33286E-07,  9.44909E-07,
-    9.14619E-07,  4.5106E-07,   6.38047E-07,  9.40743E-07,  5.63481E-07,
-    4.37821E-07,  6.40688E-07,  6.21255E-07,  7.85131E-07,  8.24598E-07,
-    5.92203E-07,  7.57019E-07,  6.70287E-07,  8.66138E-07,  6.0037E-07,
-    4.61995E-07,  7.49631E-07,  8.29553E-07,  4.13557E-07,  8.01052E-07,
-    5.59415E-07,  5.29615E-07,  9.32314E-07,  7.32218E-07,  1.15559E-06,
-    6.91908E-07,  8.51348E-07,  4.86207E-07,  4.44089E-07,  8.38212E-07,
-    7.5097E-07,   1.08536E-06,  5.70427E-07,  6.22885E-07,  4.58644E-07,
-    5.88858E-07,  7.71919E-07,  9.09943E-07,  3.34829E-07,  5.17068E-07,
-    6.38138E-07,  9.79417E-07,  6.37088E-07,  1.15143E-06,  4.41621E-07,
-    7.89098E-07,  7.49192E-07,  4.17254E-07,  6.14801E-07,  7.23981E-07,
-    6.26778E-07,  7.52833E-07,  8.98562E-07,  8.63662E-07,  6.28047E-07,
-    5.82346E-07,  5.39143E-07,  1.03085E-06,  9.58594E-07,  6.27659E-07,
-    8.02338E-07,  4.67431E-07,  4.33071E-07,  6.48388E-07,  7.44739E-07,
-    5.8263E-07,   8.05556E-07,  7.8856E-07,   8.58293E-07,  5.10707E-07,
-    5.92764E-07,  8.54274E-07,  7.14182E-07,  1.00597E-06,  8.22293E-07,
-    6.6971E-07,   6.22159E-07,  7.57922E-07,  9.92379E-07,  8.51902E-07,
-    1.18208E-06,  1.03043E-06,  9.98909E-07,  6.10743E-07,  4.3555E-07,
-    9.19269E-07,  6.85437E-07,  3.40787E-07,  9.08677E-07,  7.11441E-07,
-    6.59073E-07,  3.96671E-07,  6.26773E-07,  6.07048E-07,  5.90329E-07,
-    7.57068E-07,  1.042E-06,    3.04829E-07,  6.3825E-07,   1.47423E-07,
-    2.70017E-07,  1.33766E-06,  5.69429E-07,  3.40015E-07,  5.53223E-07,
-    1.07237E-06,  9.5196E-07,   4.96368E-07,  8.31239E-07,  9.5463E-08,
-    1.16382E-07,  9.3383E-07,   6.28538E-07,  7.54373E-07,  7.6029E-07,
-    4.51705E-07,  7.57947E-07,  6.76715E-07,  7.38647E-07,  1.27647E-06,
-    3.26588E-07,  9.01306E-07,  4.00086E-07,  7.82981E-07,  4.35197E-07,
-    6.34925E-07,  8.70151E-07,  4.47978E-07,  4.96528E-07,  8.75344E-07,
-    5.89439E-07,  5.09808E-07,  6.4829E-07,   6.79625E-07,  6.87151E-07,
-    1.00326E-06,  7.06529E-07,  5.83762E-07,  9.30897E-07,  7.37148E-07,
-    5.76077E-07,  3.46547E-07,  4.74715E-07,  7.22023E-07,  8.99295E-08,
-    4.74161E-07,  5.36119E-07,  4.34514E-07,  8.6132E-07,   8.82588E-07,
-    7.08668E-07,  4.5464E-07,   4.79263E-07,  8.80604E-07,  8.49341E-07,
-    5.2641E-07,   1.01802E-06,  7.11718E-07,  5.3727E-07,   8.69342E-07,
-    8.1106E-07,   8.61435E-07,  8.23442E-07,  7.99519E-07,  4.00435E-07,
-    7.63173E-07,  1.36186E-06,  8.72092E-07,  5.65605E-07,  5.16438E-07,
-    5.23424E-07,  6.35271E-07,  5.1946E-07,   3.58714E-07,  7.15944E-07,
-    1.19467E-06,  7.57973E-07,  1.17217E-06,  7.86832E-07,  8.22139E-07,
-    9.93314E-07,  6.90562E-07,  1.04823E-06,  6.93166E-07,  5.88137E-07,
-    6.9595E-07,   9.23774E-07,  7.79845E-07,  1.29296E-06,  6.93531E-07,
-    7.71556E-07,  5.01213E-07,  8.29332E-07,  7.84292E-07,  7.23142E-07,
-    6.09091E-07,  6.50793E-07,  7.1758E-07,   8.63491E-07,  7.37199E-07,
-    -7.4089E-08,  8.35999E-07,  7.12919E-07,  7.28359E-07,  6.51327E-07,
-    5.94988E-07,  7.89168E-07,  8.05735E-07,  1.00568E-06,  6.05964E-07,
-    7.05999E-07,  3.28728E-07,  6.90501E-07,  2.57336E-07,  6.88954E-07,
-    7.39458E-07,  6.48236E-07,  6.58993E-07,  5.08107E-07,  9.7468E-07,
-    6.21876E-07,  7.21331E-07,  8.35957E-07,  8.72166E-07,  8.0847E-07,
-    5.29404E-07,  1.09702E-06,  7.79662E-07,  1.02473E-06,  8.00136E-07,
-    4.81251E-07,  1.01676E-06,  8.98495E-07,  7.17994E-07,  8.16323E-07,
-    3.31749E-07,  5.96504E-07,  6.4248E-07,   6.97075E-07,  7.83474E-07,
-    7.96138E-07,  1.03076E-06,  9.36527E-07,  4.04232E-07,  8.34154E-07,
-    7.54609E-07,  7.08022E-07,  9.90108E-07,  9.05433E-07,  1.0775E-06,
-    5.55569E-07,  8.79434E-07,  6.35791E-07,  1.17494E-06,  9.24654E-07,
-    6.31248E-07,  7.36805E-07,  9.7465E-07,   6.37868E-07,  1.36838E-06,
-    6.24483E-07,  6.71469E-07,  7.95298E-07,  1.01337E-06,  3.32969E-07,
-    6.4223E-07,   6.76885E-07,  8.48766E-07,  7.71914E-07,  7.88367E-07,
-    7.66755E-07,  8.859E-07,    6.41637E-07,  6.5983E-07,   8.49487E-07,
-    7.83005E-07,  1.18978E-06,  6.48237E-07,  7.33127E-07,  7.52263E-07,
-    3.65409E-07,  1.07283E-06,  6.17127E-07,  6.44099E-07,  1.09572E-06,
-    7.05965E-07,  5.53396E-07,  9.20541E-07,  9.2099E-07,   6.66099E-07,
-    6.96492E-07,  5.09556E-07,  7.80707E-07,  9.01011E-07,  9.83518E-07,
-    5.30961E-07,  6.45435E-07,  1.18203E-06,  9.92244E-07,  3.46591E-07,
-    7.00707E-07,  7.3569E-07,   5.98252E-07,  9.49421E-07,  9.39943E-07,
-    1.19374E-06,  7.64183E-07,  1.13768E-06,  1.03588E-06,  3.39583E-07,
-    7.40852E-07,  5.91631E-07,  7.90072E-07,  1.0413E-06,   8.69654E-07,
-    5.7419E-07,   9.97073E-07,  8.40171E-07,  7.86044E-07,  9.80443E-07,
-    7.81505E-07,  9.80078E-07,  8.12703E-07,  6.15003E-07,  4.40749E-07,
-    7.18715E-07,  1.11068E-06,  6.64199E-07,  9.92143E-07,  4.55201E-07,
-    8.96104E-07,  8.33538E-07,  9.21129E-07,  7.94242E-07,  2.67711E-07,
-    9.56535E-07,  9.5759E-07,   3.12927E-07,  1.0718E-06,   6.57949E-07,
-    1.03175E-06,  2.65932E-07,  8.61841E-07,  5.81272E-07,  7.92501E-07,
-    8.5889E-07,   6.00189E-07,  7.66688E-07,  6.95267E-07,  1.04901E-06,
-    3.83731E-07,  1.02278E-06,  4.50037E-07,  3.54633E-07,  7.80923E-07,
-    1.14843E-06,  5.97326E-07,  5.17678E-07,  8.25672E-07,  8.89943E-07,
-    1.34484E-06,  7.31577E-07,  7.96753E-07,  6.90724E-07,  7.99833E-07,
-    6.13949E-07,  8.61232E-07,  8.04032E-07,  6.21858E-07,  1.13479E-06,
-    7.33542E-07,  6.93347E-07,  7.4396E-07,   7.10217E-07,  5.4328E-07,
-    1.04889E-06,  7.39458E-07,  7.16415E-07,  1.05761E-06,  6.23901E-07,
-    6.95321E-07,  9.37053E-07,  4.96784E-07,  8.33675E-07,  8.71297E-07,
-    7.50956E-07,  9.76181E-07,  9.12762E-07,  6.74734E-07,  5.87794E-07,
-    9.34256E-07,  7.49617E-07,  6.91564E-07,  1.15599E-06,  9.27458E-07,
-    8.64946E-07,  6.34393E-07,  1.163E-06,    1.2083E-06,   6.71584E-07,
-    7.467E-07,    4.67167E-07,  8.6799E-07,   8.26236E-07,  6.49105E-07,
-    1.0288E-06,   5.66028E-07,  1.16242E-06,  7.43714E-07,  8.04109E-07,
-    8.77172E-07,  8.45287E-07,  1.08061E-06,  8.73257E-07,  8.47922E-07,
-    1.14064E-06,  9.66321E-07,  1.19805E-06,  9.52882E-07,  8.76441E-07,
-    8.62864E-07,  8.6858E-07,   7.10705E-07,  6.89993E-07,  8.01967E-07,
-    9.8396E-07,   9.39822E-07,  6.5701E-07,   6.55685E-07,  8.16724E-07,
-    6.98231E-07,  1.17226E-06,  1.11701E-06,  6.85002E-07,  6.3326E-07,
-    7.50889E-07,  6.32072E-07,  8.64675E-07,  4.77722E-07,  7.86743E-07,
-    8.9173E-07,   8.66493E-07,  8.04294E-07,  1.24342E-06,  1.09745E-06,
-    5.67288E-07,  1.13759E-06,  8.25677E-07,  1.00339E-06,  1.14477E-06,
-    8.73911E-07,  1.0357E-06,   7.7091E-07,   9.66002E-07,  7.34938E-07,
-    7.99203E-07,  7.81485E-07,  1.07401E-06,  8.30632E-07,  9.87711E-07,
-    1.16139E-06,  4.99503E-07,  7.02415E-07,  8.73305E-07,  7.63255E-07,
-    8.64658E-07,  9.11422E-07,  9.45615E-07,  1.43242E-06,  1.25111E-06,
-    7.67838E-07,  1.19231E-06,  6.47251E-07,  4.74402E-07,  8.84412E-07,
-    1.0143E-06,   7.21798E-07,  9.24691E-07,  5.86634E-07,  9.31902E-07,
-    1.58816E-06,  7.52255E-07,  5.33458E-07,  1.30467E-06,  7.73324E-07,
-    9.40731E-07,  7.49181E-07,  5.95982E-07,  6.21722E-07,  9.59335E-07,
-    6.67062E-07,  6.82339E-07,  6.64114E-07,  7.28678E-07,  5.85814E-07,
-    7.72103E-07,  6.1889E-07,   6.93982E-07,  1.03393E-06,  9.68661E-07,
-    9.60956E-07,  7.34083E-07,  4.17893E-07,  8.15143E-07,  8.06252E-07,
-    5.4366E-07,   8.84008E-07,  9.6047E-07,   1.07322E-06,  7.64625E-07,
-    7.75806E-07,  9.98409E-07,  7.6006E-07,   1.04122E-06,  7.72776E-07,
-    1.06111E-06,  7.26022E-07,  9.28308E-07,  4.00797E-07,  8.3272E-07,
-    6.90645E-07,  1.16462E-06,  8.95027E-07,  9.37293E-07,  5.18907E-07,
-    7.84881E-07,  6.93101E-07,  6.94006E-07,  9.24326E-07,  8.82409E-07,
-    1.07037E-06,  9.72377E-07,  7.02753E-07,  2.44265E-07,  4.3405E-07,
-    6.89691E-07,  1.11954E-06,  1.05286E-06,  1.07122E-06,  6.6617E-07,
-    8.53269E-07,  9.21634E-07,  1.01228E-06,  9.29855E-07,  9.5902E-07,
-    1.05409E-06,  6.97731E-07,  9.7755E-07,   1.17406E-06,  6.69577E-07,
-    8.42354E-07,  9.8906E-07,   1.10245E-06,  8.72108E-07,  5.01064E-07,
-    8.82596E-07,  6.92193E-07,  5.6957E-07,   6.37495E-07,  6.34359E-07,
-    1.19115E-06,  9.54097E-07,  6.88443E-07,  6.99306E-07,  7.07803E-07,
-    1.10638E-06,  1.36627E-06,  7.52874E-07,  1.03324E-06,  8.94366E-07,
-    7.61462E-07,  1.17439E-06,  8.66062E-07,  5.62692E-07,  6.92464E-07,
-    8.99409E-07,  6.22799E-07,  7.37371E-07,  8.60126E-07,  8.44594E-07,
-    9.99771E-07,  9.74801E-07,  7.56842E-07,  5.3138E-07,   8.38478E-07,
-    1.09159E-06,  7.72521E-07,  1.99399E-07,  5.03006E-07,  9.67002E-07,
-    8.48901E-07,  9.89654E-07,  1.22541E-06,  8.38004E-07,  8.44552E-07,
-    4.56493E-07,  6.85664E-07,  7.44531E-07,  1.06591E-06,  7.49924E-07,
-    1.09124E-06,  1.18163E-06,  1.20446E-06,  4.76519E-07,  8.94345E-07,
-    3.14884E-07,  1.11941E-06,  1.0202E-06,   1.36631E-06,  7.56107E-07,
-    8.67986E-07,  7.06493E-07,  6.09909E-07,  7.77416E-07,  1.2596E-06,
-    8.47531E-07,  1.05479E-06,  8.76432E-07,  9.786E-07,    1.1614E-06,
-    1.11506E-06,  7.43139E-07,  6.56986E-07,  1.1081E-06,   1.14742E-06,
-    6.2705E-07,   8.48619E-07,  1.24041E-06,  1.0665E-06,   1.14463E-06,
-    6.66733E-07,  6.7127E-07,   6.36273E-07,  7.7304E-07,   9.8662E-07,
-    8.03777E-07,  8.20806E-07,  9.16395E-07,  1.06008E-06,  9.78505E-07,
-    3.52237E-07,  1.04273E-06,  6.67692E-07,  9.15508E-07,  7.92001E-07,
-    6.41589E-07,  8.59196E-07,  1.25006E-06,  1.11173E-06,  9.19134E-07,
-    8.973E-07,    1.20206E-06,  1.32887E-06,  5.40778E-07,  1.1285E-06,
-    7.57389E-07,  1.09803E-06,  8.02909E-07,  7.09518E-07,  1.04255E-06,
-    9.8428E-07,   9.58411E-07,  9.93108E-07,  7.19764E-07,  5.31746E-07,
-    8.58355E-07,  8.34268E-07,  7.4916E-07,   1.21932E-06,  1.00119E-06,
-    7.658E-07,    1.30277E-06,  8.82274E-07,  1.07979E-06,  2.39519E-07,
-    6.67309E-07,  1.23185E-06,  6.14517E-07,  8.85193E-07,  9.6302E-07,
-    7.79428E-07,  9.42905E-07,  8.39067E-07,  8.437E-07,    7.28212E-07,
-    6.73206E-07,  1.04563E-06,  1.00965E-06,  1.15922E-06,  8.95904E-07,
-    7.71634E-07,  1.31439E-06,  1.15785E-06,  9.30824E-07,  1.1291E-06,
-    9.40332E-07,  9.58844E-07,  1.21479E-06,  9.83935E-07,  1.14012E-06,
-    1.05523E-06,  8.65039E-07,  9.7072E-07,   9.53568E-07,  1.17753E-06,
-    1.08051E-06,  3.88371E-07,  1.22734E-06,  7.92292E-07,  1.15768E-06,
-    1.03087E-06,  1.20672E-06,  8.2451E-07,   6.88979E-07,  1.18245E-06,
-    4.78418E-07,  9.02653E-07,  1.03626E-06,  9.68673E-07,  1.10886E-06,
-    1.25685E-06,  1.0482E-06,   9.69588E-07,  1.0638E-06,   1.95597E-07,
-    1.05237E-06,  6.5608E-07,   9.70894E-07,  7.71207E-07,  7.54129E-07,
-    1.32389E-06,  7.53319E-07,  8.64409E-07,  1.18315E-06,  1.19807E-06,
-    8.81027E-07,  1.01591E-06,  9.45173E-07,  7.17715E-07,  9.39903E-07,
-    9.53732E-07,  1.13461E-06,  8.63744E-07,  1.06467E-06,  7.68493E-07,
-    1.32415E-06,  1.11344E-06,  8.6706E-07,   1.00143E-06,  1.26624E-06,
-    9.36024E-07,  1.12295E-06,  6.42617E-07,  9.78988E-07,  1.10093E-06,
-    8.53099E-07,  6.57678E-07,  8.94819E-07,  6.08003E-07,  8.92252E-07};
-
-const float SIMULATED_LON[GPS_DATA_SIZE] = {
-    -1.74842E-07, -1.43698E-09, -5.54666E-07, -4.02391E-07, -2.23117E-07,
-    1.88671E-07,  -3.5403E-08,  -1.23698E-07, 2.33816E-07,  -5.19344E-09,
-    2.14989E-08,  3.13253E-08,  -2.13007E-07, -2.74618E-07, -4.58129E-07,
-    -1.61634E-07, -3.10375E-08, 5.97976E-09,  1.56018E-07,  2.19836E-08,
-    -1.92872E-07, 1.46669E-08,  -8.02885E-08, 2.40283E-07,  -1.97468E-07,
-    -2.68672E-08, 2.47379E-08,  1.85072E-08,  5.08885E-08,  2.07897E-08,
-    7.31081E-08,  -8.44016E-08, 2.01954E-07,  -2.39677E-07, 3.69962E-07,
-    1.87407E-09,  3.13371E-07,  -1.88277E-08, 1.87107E-07,  -5.41445E-08,
-    6.0013E-07,   -5.26029E-08, 2.13072E-07,  1.01267E-07,  -9.02709E-08,
-    -6.70766E-08, 4.90507E-07,  5.97063E-07,  2.50172E-07,  4.12252E-07,
-    3.72828E-07,  -7.99828E-08, 1.17874E-07,  -2.82005E-07, -1.14941E-07,
-    2.92413E-07,  2.57534E-07,  2.33206E-07,  5.2684E-08,   8.1069E-08,
-    3.28281E-07,  6.21948E-08,  3.3226E-07,   4.5595E-07,   4.14124E-08,
-    8.70226E-08,  2.86791E-07,  3.99446E-07,  1.59651E-07,  1.47298E-07,
-    3.34205E-07,  3.30733E-07,  6.29568E-07,  3.09161E-07,  4.44505E-07,
-    3.7364E-08,   3.08953E-07,  7.83087E-07,  3.31264E-07,  4.13066E-07,
-    3.7659E-07,   5.83559E-07,  8.84798E-07,  6.47322E-07,  2.77282E-07,
-    5.46164E-07,  6.27263E-07,  7.88335E-07,  4.78571E-07,  5.64501E-07,
-    8.07642E-07,  1.08091E-06,  5.57284E-07,  7.53156E-07,  6.9771E-07,
-    1.19875E-06,  3.90133E-07,  7.25626E-07,  8.89069E-07,  8.15802E-07,
-    5.37213E-07,  1.14432E-06,  9.36041E-07,  8.81542E-07,  9.5323E-07,
-    8.30789E-07,  9.85588E-07,  9.94458E-07,  1.1319E-06,   1.02166E-06,
-    1.212E-06,    1.15386E-06,  1.46501E-06,  1.34377E-06,  1.47415E-06,
-    1.43883E-06,  1.27025E-06,  1.37272E-06,  1.27638E-06,  1.51444E-06,
-    1.23756E-06,  1.11896E-06,  1.31868E-06,  1.14909E-06,  1.72765E-06,
-    1.06403E-06,  1.72671E-06,  1.58306E-06,  1.98953E-06,  1.51145E-06,
-    1.62799E-06,  1.85744E-06,  1.71914E-06,  2.01847E-06,  1.55683E-06,
-    2.13283E-06,  1.78452E-06,  1.81388E-06,  2.01537E-06,  2.77443E-06,
-    2.69883E-06,  2.35388E-06,  2.37209E-06,  2.38904E-06,  2.57429E-06,
-    2.11987E-06,  2.39973E-06,  2.79557E-06,  2.97796E-06,  2.82446E-06,
-    2.67604E-06,  2.73506E-06,  2.6423E-06,   2.79535E-06,  2.671E-06,
-    2.72992E-06,  2.68549E-06,  3.04277E-06,  2.84237E-06,  3.21573E-06,
-    3.52807E-06,  3.52327E-06,  3.21216E-06,  3.48578E-06,  3.38792E-06,
-    3.03178E-06,  3.34051E-06,  3.3565E-06,   3.22759E-06,  3.63669E-06,
-    3.83651E-06,  3.50946E-06,  3.50718E-06,  3.76854E-06,  3.95235E-06,
-    3.80879E-06,  4.18231E-06,  3.76084E-06,  3.97083E-06,  4.24936E-06,
-    4.50894E-06,  4.5313E-06,   4.22036E-06,  4.38518E-06,  4.73348E-06,
-    4.58713E-06,  4.76896E-06,  4.85375E-06,  4.50045E-06,  4.93459E-06,
-    4.60257E-06,  4.48873E-06,  5.06708E-06,  5.14712E-06,  4.96803E-06,
-    5.17089E-06,  5.13006E-06,  5.19507E-06,  5.31662E-06,  5.10885E-06,
-    5.32887E-06,  5.64757E-06,  5.85663E-06,  5.19602E-06,  5.70449E-06,
-    5.89747E-06,  5.9334E-06,   6.22835E-06,  5.759E-06,    6.08503E-06,
-    6.41906E-06,  6.58022E-06,  6.49082E-06,  6.04903E-06,  6.79989E-06,
-    6.72814E-06,  6.56948E-06,  6.37929E-06,  6.0753E-06,   7.05238E-06,
-    6.74556E-06,  7.11518E-06,  6.74694E-06,  7.17498E-06,  7.00337E-06,
-    7.4202E-06,   7.22857E-06,  7.17565E-06,  7.87569E-06,  7.31919E-06,
-    7.83351E-06,  7.67951E-06,  7.76318E-06,  7.77836E-06,  8.42574E-06,
-    7.79381E-06,  8.03714E-06,  8.27594E-06,  7.9897E-06,   8.53773E-06,
-    8.31707E-06,  8.55452E-06,  8.89383E-06,  8.7788E-06,   8.75077E-06,
-    8.65245E-06,  9.15622E-06,  9.59952E-06,  9.20581E-06,  9.28821E-06,
-    8.67433E-06,  9.77508E-06,  9.81606E-06,  9.71414E-06,  9.89993E-06,
-    1.00336E-05,  9.92448E-06,  9.93046E-06,  1.01085E-05,  9.94495E-06,
-    9.81141E-06,  1.02572E-05,  1.03388E-05,  1.04371E-05,  1.06578E-05,
-    1.07632E-05,  1.0801E-05,   1.08781E-05,  1.06862E-05,  1.08676E-05,
-    1.12333E-05,  1.09313E-05,  1.14511E-05,  1.16046E-05,  1.10289E-05,
-    1.11995E-05,  1.20586E-05,  1.17584E-05,  1.18106E-05,  1.20865E-05,
-    1.19624E-05,  1.25514E-05,  1.26332E-05,  1.23805E-05,  1.27278E-05,
-    1.29555E-05,  1.30787E-05,  1.27129E-05,  1.30108E-05,  1.27719E-05,
-    1.29303E-05,  1.31739E-05,  1.36754E-05,  1.35607E-05,  1.35108E-05,
-    1.37622E-05,  1.3541E-05,   1.40747E-05,  1.37348E-05,  1.39242E-05,
-    1.40053E-05,  1.40008E-05,  1.43779E-05,  1.45548E-05,  1.47008E-05,
-    1.48928E-05,  1.51637E-05,  1.47202E-05,  1.4892E-05,   1.51119E-05,
-    1.5356E-05,   1.52083E-05,  1.55988E-05,  1.58973E-05,  1.58581E-05,
-    1.54842E-05,  1.56569E-05,  1.63407E-05,  1.61269E-05,  1.6541E-05,
-    1.64121E-05,  1.62688E-05,  1.65154E-05,  1.66618E-05,  1.6762E-05,
-    1.77232E-05,  1.74112E-05,  1.74674E-05,  1.76711E-05,  1.697E-05,
-    1.76833E-05,  1.78388E-05,  1.788E-05,    1.78846E-05,  1.82848E-05,
-    1.82281E-05,  1.86676E-05,  1.78981E-05,  1.86583E-05,  1.84184E-05,
-    1.85799E-05,  1.88185E-05,  1.88588E-05,  1.90517E-05,  1.88702E-05,
-    1.95612E-05,  1.95541E-05,  1.96544E-05,  1.99635E-05,  1.98705E-05,
-    1.98518E-05,  1.9822E-05,   1.99906E-05,  2.05492E-05,  2.04496E-05,
-    2.04899E-05,  2.04777E-05,  2.05575E-05,  2.07719E-05,  2.09589E-05,
-    2.14999E-05,  2.0848E-05,   2.11653E-05,  2.16718E-05,  2.15925E-05,
-    2.18043E-05,  2.18126E-05,  2.17071E-05,  2.21502E-05,  2.2353E-05,
-    2.1964E-05,   2.24749E-05,  2.24457E-05,  2.24815E-05,  2.26374E-05,
-    2.27907E-05,  2.31454E-05,  2.29867E-05,  2.32327E-05,  2.37127E-05,
-    2.34223E-05,  2.35978E-05,  2.38124E-05,  2.34624E-05,  2.35823E-05,
-    2.40711E-05,  2.41665E-05,  2.42042E-05,  2.43833E-05,  2.46394E-05,
-    2.46247E-05,  2.50904E-05,  2.49873E-05,  2.47532E-05,  2.54394E-05,
-    2.49237E-05,  2.56787E-05,  2.57265E-05,  2.56735E-05,  2.55599E-05,
-    2.60245E-05,  2.59436E-05,  2.61673E-05,  2.63082E-05,  2.62199E-05,
-    2.66409E-05,  2.65758E-05,  2.66739E-05,  2.69805E-05,  2.64178E-05,
-    2.72706E-05,  2.70751E-05,  2.75905E-05,  2.71027E-05,  2.78494E-05,
-    2.78847E-05,  2.7709E-05,   2.8331E-05,   2.76243E-05,  2.83226E-05,
-    2.81676E-05,  2.82096E-05,  2.79862E-05,  2.84133E-05,  2.86782E-05,
-    2.93485E-05,  2.93124E-05,  2.93678E-05,  2.92139E-05,  2.97182E-05,
-    2.96879E-05,  2.96585E-05,  2.95046E-05,  2.98102E-05,  3.01522E-05,
-    3.05819E-05,  3.06885E-05,  3.07289E-05,  3.05099E-05,  3.02663E-05,
-    3.08782E-05,  3.07609E-05,  3.07522E-05,  3.09181E-05,  3.14313E-05,
-    3.1436E-05,   3.1234E-05,   3.17747E-05,  3.18473E-05,  3.16627E-05,
-    3.17932E-05,  3.22052E-05,  3.23369E-05,  3.23138E-05,  3.23427E-05,
-    3.24528E-05,  3.3053E-05,   3.27163E-05,  3.27328E-05,  3.29383E-05,
-    3.31338E-05,  3.29583E-05,  3.33267E-05,  3.29829E-05,  3.37763E-05,
-    3.34858E-05,  3.36354E-05,  3.42679E-05,  3.39776E-05,  3.41204E-05,
-    3.48733E-05,  3.40027E-05,  3.45474E-05,  3.45785E-05,  3.50267E-05,
-    3.47721E-05,  3.52764E-05,  3.51182E-05,  3.50768E-05,  3.53526E-05,
-    3.53002E-05,  3.5907E-05,   3.57188E-05,  3.57604E-05,  3.58546E-05,
-    3.58492E-05,  3.62641E-05,  3.59599E-05,  3.64845E-05,  3.65055E-05,
-    3.65364E-05,  3.64551E-05,  3.72926E-05,  3.69839E-05,  3.72464E-05,
-    3.71167E-05,  3.78754E-05,  3.69113E-05,  3.77719E-05,  3.72778E-05,
-    3.77936E-05,  3.81969E-05,  3.76221E-05,  3.8367E-05,   3.8226E-05,
-    3.88528E-05,  3.78126E-05,  3.85755E-05,  3.87919E-05,  3.87765E-05,
-    3.92154E-05,  3.88931E-05,  3.95637E-05,  3.9513E-05,   3.91258E-05,
-    3.95504E-05,  3.96765E-05,  3.93899E-05,  3.98829E-05,  3.9923E-05,
-    3.99587E-05,  4.05694E-05,  4.02209E-05,  4.02156E-05,  4.03727E-05,
-    4.0604E-05,   4.07866E-05,  4.0823E-05,   4.13979E-05,  4.11889E-05,
-    4.13418E-05,  4.10883E-05,  4.14174E-05,  4.16921E-05,  4.17177E-05,
-    4.19397E-05,  4.14112E-05,  4.19968E-05,  4.23231E-05,  4.16951E-05,
-    4.28704E-05,  4.24014E-05,  4.23066E-05,  4.3051E-05,   4.26863E-05,
-    4.31986E-05,  4.2999E-05,   4.34881E-05,  4.33575E-05,  4.30503E-05,
-    4.35587E-05,  4.30826E-05,  4.34715E-05,  4.37939E-05,  4.43174E-05,
-    4.39998E-05,  4.45862E-05,  4.431E-05,    4.44014E-05,  4.44652E-05,
-    4.46025E-05,  4.46263E-05,  4.46279E-05,  4.49759E-05,  4.47751E-05,
-    4.53018E-05,  4.51535E-05,  4.54441E-05,  4.57844E-05,  4.58643E-05,
-    4.57071E-05,  4.57996E-05,  4.59663E-05,  4.64306E-05,  4.63392E-05,
-    4.60829E-05,  4.64844E-05,  4.67352E-05,  4.66102E-05,  4.6818E-05,
-    4.69511E-05,  4.66908E-05,  4.71509E-05,  4.72848E-05,  4.75273E-05,
-    4.72681E-05,  4.74569E-05,  4.75588E-05,  4.75426E-05,  4.80719E-05,
-    4.79121E-05,  4.82426E-05,  4.85834E-05,  4.85861E-05,  4.85626E-05,
-    4.83646E-05,  4.90569E-05,  4.89256E-05,  4.88528E-05,  4.87774E-05,
-    4.87468E-05,  4.93922E-05,  4.92511E-05,  4.96346E-05,  4.97331E-05,
-    4.96802E-05,  5.02926E-05,  4.99139E-05,  4.99846E-05,  5.01785E-05,
-    5.03402E-05,  5.00806E-05,  5.02935E-05,  5.03918E-05,  5.09243E-05,
-    5.08605E-05,  5.10304E-05,  5.07244E-05,  5.15329E-05,  5.15249E-05,
-    5.14659E-05,  5.13756E-05,  5.13327E-05,  5.13873E-05,  5.19527E-05,
-    5.16721E-05,  5.20402E-05,  5.21446E-05,  5.22459E-05,  5.26861E-05,
-    5.24207E-05,  5.26073E-05,  5.22335E-05,  5.28373E-05,  5.30041E-05,
-    5.30021E-05,  5.2717E-05,   5.32482E-05,  5.30845E-05,  5.31812E-05,
-    5.37672E-05,  5.35874E-05,  5.35896E-05,  5.39094E-05,  5.36587E-05,
-    5.38527E-05,  5.44327E-05,  5.45892E-05,  5.41071E-05,  5.43866E-05,
-    5.49208E-05,  5.48037E-05,  5.49447E-05,  5.53776E-05,  5.52516E-05,
-    5.49569E-05,  5.53238E-05,  5.55869E-05,  5.53022E-05,  5.55632E-05,
-    5.53718E-05,  5.60733E-05,  5.56712E-05,  5.60158E-05,  5.6214E-05,
-    5.58406E-05,  5.6417E-05,   5.67829E-05,  5.70215E-05,  5.66799E-05,
-    5.66628E-05,  5.70953E-05,  5.67459E-05,  5.75115E-05,  5.70824E-05,
-    5.70472E-05,  5.71147E-05,  5.76551E-05,  5.77437E-05,  5.80687E-05,
-    5.76778E-05,  5.79731E-05,  5.7565E-05,   5.80392E-05,  5.8317E-05,
-    5.84187E-05,  5.87538E-05,  5.88184E-05,  5.90267E-05,  5.91042E-05,
-    5.88851E-05,  5.9574E-05,   5.91351E-05,  5.93028E-05,  5.92032E-05,
-    5.90531E-05,  5.96031E-05,  5.96927E-05,  5.99122E-05,  6.01678E-05,
-    6.05515E-05,  6.01938E-05,  6.02091E-05,  6.02936E-05,  6.03631E-05,
-    6.05829E-05,  6.06069E-05,  6.04865E-05,  6.12117E-05,  6.12292E-05,
-    6.05379E-05,  6.10265E-05,  6.18976E-05,  6.18814E-05,  6.19784E-05,
-    6.17416E-05,  6.14828E-05,  6.18693E-05,  6.22055E-05,  6.22036E-05,
-    6.19394E-05,  6.22341E-05,  6.23318E-05,  6.26086E-05,  6.25904E-05,
-    6.23753E-05,  6.28976E-05,  6.32297E-05,  6.28663E-05,  6.33194E-05,
-    6.30031E-05,  6.34179E-05,  6.35567E-05,  6.38062E-05,  6.39398E-05,
-    6.35886E-05,  6.3862E-05,   6.37822E-05,  6.41548E-05,  6.40523E-05,
-    6.43069E-05,  6.41644E-05,  6.44279E-05,  6.46926E-05,  6.45171E-05,
-    6.44539E-05,  6.49285E-05,  6.48881E-05,  6.52714E-05,  6.49178E-05,
-    6.54191E-05,  6.56162E-05,  6.56923E-05,  6.55846E-05,  6.60856E-05,
-    6.60651E-05,  6.57057E-05,  6.60446E-05,  6.61061E-05,  6.62905E-05,
-    6.63266E-05,  6.65456E-05,  6.6485E-05,   6.67239E-05,  6.65219E-05,
-    6.69511E-05,  6.67189E-05,  6.6919E-05,   6.69672E-05,  6.71336E-05,
-    6.7401E-05,   6.74825E-05,  6.745E-05,    6.76238E-05,  6.79005E-05,
-    6.77092E-05,  6.78976E-05,  6.82092E-05,  6.86002E-05,  6.81367E-05,
-    6.88185E-05,  6.86054E-05,  6.87078E-05,  6.91751E-05,  6.88129E-05,
-    6.88867E-05,  6.935E-05,    6.91528E-05,  6.94951E-05,  6.93939E-05,
-    6.90065E-05,  6.94156E-05,  6.96123E-05,  6.95861E-05,  6.9767E-05,
-    7.00486E-05,  7.01037E-05,  7.01033E-05,  7.04899E-05,  7.01639E-05,
-    7.04945E-05,  7.01751E-05,  7.04892E-05,  7.10621E-05,  7.10951E-05,
-    7.10594E-05,  7.08086E-05,  7.08717E-05,  7.14405E-05,  7.1252E-05,
-    7.14563E-05,  7.19803E-05,  7.19249E-05,  7.15269E-05,  7.19118E-05,
-    7.23974E-05,  7.19321E-05,  7.19468E-05,  7.21616E-05,  7.23578E-05,
-    7.25625E-05,  7.21701E-05,  7.26515E-05,  7.29559E-05,  7.27545E-05,
-    7.27504E-05,  7.31683E-05,  7.32067E-05,  7.35382E-05,  7.34771E-05,
-    7.36716E-05,  7.38431E-05,  7.34911E-05,  7.36841E-05,  7.39104E-05,
-    7.43433E-05,  7.40525E-05,  7.40761E-05,  7.4413E-05,   7.41736E-05,
-    7.52072E-05,  7.45261E-05,  7.47582E-05,  7.49798E-05,  7.45996E-05,
-    7.48501E-05,  7.50166E-05,  7.48161E-05,  7.52879E-05,  7.51987E-05,
-    7.53722E-05,  7.58225E-05,  7.57622E-05,  7.58545E-05,  7.61049E-05,
-    7.59664E-05,  7.63501E-05,  7.60327E-05,  7.601E-05,    7.63797E-05,
-    7.67704E-05,  7.676E-05,    7.68394E-05,  7.6889E-05,   7.73226E-05,
-    7.69956E-05,  7.69341E-05,  7.67913E-05,  7.73366E-05,  7.73796E-05,
-    7.70388E-05,  7.77687E-05,  7.75884E-05,  7.72375E-05,  7.7562E-05,
-    7.82232E-05,  7.80391E-05,  7.82003E-05,  7.85904E-05,  7.84134E-05,
-    7.84694E-05,  7.85027E-05,  7.8855E-05,   7.89383E-05,  7.89223E-05,
-    7.90722E-05,  7.91763E-05,  7.91493E-05,  7.93268E-05,  7.9599E-05,
-    7.93344E-05,  7.95676E-05,  7.96048E-05,  7.98594E-05,  7.98712E-05,
-    8.01175E-05,  8.01325E-05,  7.97035E-05,  8.02953E-05,  8.0169E-05,
-    8.06882E-05,  8.09835E-05,  8.08845E-05,  8.09728E-05,  8.05278E-05,
-    8.0959E-05,   8.09602E-05,  8.16246E-05,  8.10656E-05,  8.15875E-05,
-    8.13485E-05,  8.12411E-05,  8.17574E-05,  8.14807E-05,  8.17573E-05,
-    8.20176E-05,  8.17697E-05,  8.25216E-05,  8.23022E-05,  8.24016E-05,
-    8.23206E-05,  8.2494E-05,   8.27879E-05,  8.28925E-05,  8.26265E-05,
-    8.3487E-05,   8.33099E-05,  8.32545E-05,  8.31823E-05,  8.33141E-05,
-    8.34378E-05,  8.32539E-05,  8.43139E-05,  8.35052E-05,  8.37188E-05,
-    8.44156E-05,  8.40837E-05,  8.44789E-05,  8.44372E-05,  8.40002E-05,
-    8.41137E-05,  8.46393E-05,  8.48501E-05,  8.47134E-05,  8.4936E-05,
-    8.44708E-05,  8.48256E-05,  8.53661E-05,  8.48658E-05,  8.4871E-05,
-    8.53654E-05,  8.57668E-05,  8.5634E-05,   8.55549E-05,  8.58815E-05,
-    8.56756E-05,  8.61648E-05,  8.61027E-05,  8.63716E-05,  8.59768E-05,
-    8.64122E-05,  8.67038E-05,  8.69841E-05,  8.6372E-05,   8.65631E-05,
-    8.69486E-05,  8.66044E-05,  8.68605E-05,  8.7265E-05,   8.77564E-05,
-    8.74281E-05,  8.71789E-05,  8.7587E-05,   8.77832E-05,  8.75239E-05,
-    8.7508E-05,   8.79789E-05,  8.78462E-05,  8.81884E-05,  8.82138E-05,
-    8.8648E-05,   8.89153E-05,  8.88117E-05,  8.86022E-05,  8.89003E-05,
-    8.88431E-05,  8.87245E-05,  8.88994E-05,  8.92278E-05,  8.87199E-05,
-    8.92607E-05,  8.95076E-05,  8.93227E-05,  8.98147E-05,  8.97439E-05,
-    8.97411E-05,  8.98322E-05,  8.9803E-05,   9.01968E-05,  9.02114E-05,
-    9.03658E-05,  9.02286E-05,  9.01706E-05,  8.9996E-05,   9.11892E-05,
-    9.04786E-05,  9.06867E-05,  9.06153E-05,  9.06483E-05,  9.1574E-05,
-    9.09279E-05,  9.12144E-05,  9.14887E-05,  9.18096E-05,  9.17803E-05,
-    9.13073E-05,  9.13352E-05,  9.1845E-05,   9.1538E-05,   9.19866E-05,
-    9.23044E-05,  9.20543E-05,  9.26326E-05,  9.23586E-05,  9.25261E-05,
-    9.28034E-05,  9.24722E-05,  9.24912E-05,  9.32681E-05,  9.32993E-05,
-    9.31663E-05,  9.32453E-05,  9.30912E-05,  9.31702E-05,  9.33058E-05,
-    9.31825E-05,  9.36462E-05,  9.32959E-05,  9.36245E-05,  9.38519E-05,
-    9.42948E-05,  9.37456E-05,  9.40234E-05,  9.44975E-05,  9.399E-05,
-    9.4332E-05,   9.46454E-05,  9.43883E-05,  9.51645E-05,  9.48064E-05,
-    9.51989E-05,  9.50716E-05,  9.50848E-05,  9.50654E-05,  9.53231E-05,
-    9.52265E-05,  9.53674E-05,  9.56336E-05,  9.57968E-05,  9.57107E-05,
-    9.59629E-05,  9.58575E-05,  9.61211E-05,  9.61882E-05,  9.632E-05,
-    9.66913E-05,  9.65983E-05,  9.6861E-05,   9.64922E-05,  9.69722E-05,
-    9.69253E-05,  9.70342E-05,  9.71645E-05,  9.71095E-05,  9.76141E-05,
-    9.74688E-05,  9.72902E-05,  9.7741E-05,   9.7345E-05,   9.78263E-05,
-    9.76857E-05,  9.83573E-05,  9.79769E-05,  9.83281E-05,  9.83002E-05,
-    9.83298E-05,  9.83446E-05,  9.81482E-05,  9.83431E-05,  9.8386E-05,
-    9.85918E-05,  9.88738E-05,  9.89461E-05,  9.90952E-05,  9.93306E-05,
-    9.87831E-05,  9.93083E-05,  9.94452E-05,  9.97238E-05,  9.95871E-05,
-    9.96113E-05,  9.95488E-05,  9.96361E-05,  9.99507E-05,  0.000100022,
-    0.000100194,  0.000100093,  0.000100038,  0.000100003,  0.000100228,
-    0.000100546,  0.000100711,  0.000100595,  0.000100599,  0.000101023,
-    0.000101112,  0.00010087,   0.000101348,  0.000101303,  0.00010146,
-    0.000101277,  0.000101524,  0.000101624,  0.0001015,    0.000101798,
-    0.00010181,   0.000101459,  0.000102195,  0.000101981,  0.000102125,
-    0.000102283,  0.000102971,  0.000102912,  0.000102856,  0.000103006,
-    0.000103206,  0.000102899,  0.000103265,  0.000103335,  0.000103445,
-    0.000103402,  0.000103433,  0.000103356,  0.000103936,  0.00010363,
-    0.000103861,  0.000104033,  0.000104142,  0.00010406,   0.00010416,
-    0.000104405,  0.000104151,  0.000104628,  0.000104381,  0.000104339,
-    0.000104705,  0.000104713,  0.00010495,   0.000104998,  0.000105018,
-    0.000104898,  0.00010533,   0.000105172,  0.00010487,   0.000106115,
-    0.000105545,  0.000105385,  0.000105428,  0.000105651,  0.000105919,
-    0.000106017,  0.000105788,  0.000105947,  0.000106304,  0.000105985,
-    0.000106554,  0.000106425,  0.000106391,  0.000106852,  0.000107028,
-    0.000106971,  0.000107038,  0.000107096,  0.000107439,  0.000107319,
-    0.00010713,   0.00010758,   0.00010708,   0.00010774,   0.000107722,
-    0.000107631,  0.00010869,   0.000108556,  0.000108403,  0.00010814,
-    0.000108115,  0.000108398,  0.00010858,   0.000108666,  0.000108905,
-    0.000108795,  0.000108697,  0.000109171,  0.000108974,  0.000109598,
-    0.000109409,  0.000109221,  0.000109532,  0.000109295,  0.000109853,
-    0.000109545,  0.000109443,  0.0001095,    0.000109935,  0.000110097,
-    0.000110062,  0.000110695,  0.000110453,  0.00011057,   0.000110599,
-    0.000110525,  0.000110656,  0.000110575,  0.000111184,  0.000111084,
-    0.000111058,  0.000111337,  0.000111014,  0.000110935,  0.00011099,
-    0.000111254,  0.000111314,  0.000111701,  0.000111588,  0.000111582,
-    0.000111932,  0.00011204,   0.000112176,  0.000112038,  0.000112545,
-    0.000112739,  0.000112618,  0.000112344,  0.000112534,  0.000112507,
-    0.000113126,  0.000112899,  0.000112967,  0.00011305,   0.00011304,
-    0.00011317,   0.000113575,  0.000113358,  0.000113559,  0.000113588,
-    0.000112968,  0.000113938,  0.000113831,  0.00011397,   0.000114312,
-    0.00011443,   0.000113934,  0.000114458,  0.00011458,   0.000114507,
-    0.000114828,  0.000115114,  0.000114414,  0.000114997,  0.000115027,
-    0.000114647,  0.000114904,  0.000115538,  0.000115286,  0.000115445,
-    0.000115798,  0.000115585,  0.000115629,  0.000115609,  0.000116293,
-    0.000115968,  0.000116284,  0.000116329,  0.000116094,  0.000116492,
-    0.000116616,  0.000116204,  0.000116148,  0.000116572,  0.000116475,
-    0.000116943,  0.000117096,  0.00011719,   0.000116634,  0.00011663,
-    0.000117188,  0.000117805,  0.000117579,  0.000117608,  0.000117931,
-    0.000117772,  0.00011774,   0.00011802,   0.000117677,  0.000118072,
-    0.000118137,  0.000118114,  0.000118212,  0.000118027,  0.000118538,
-    0.000118514,  0.000118507,  0.000118909,  0.000118884,  0.000118631,
-    0.000119074,  0.000119104,  0.000118684,  0.000119409,  0.000119479,
-    0.000119595,  0.000119509,  0.000119972,  0.000119884,  0.000119581,
-    0.000120132,  0.000120012,  0.000119884,  0.000120071,  0.000120379,
-    0.000120155,  0.000120317,  0.000120468,  0.000120444,  0.000120522,
-    0.000120824,  0.000120813,  0.000121154,  0.000121278,  0.000120965,
-    0.000120866,  0.000121549,  0.000121148,  0.000121877,  0.000121519,
-    0.000121789,  0.000121721,  0.000121526,  0.000121893,  0.00012175,
-    0.000122,     0.000122392,  0.00012228,   0.000122241,  0.000122478,
-    0.000122712,  0.000122576,  0.000122991,  0.000122786,  0.000122641,
-    0.000122834,  0.000123295,  0.000123204,  0.00012337,   0.000123323,
-    0.000123537,  0.000123584,  0.000123164,  0.000123075,  0.00012356,
-    0.00012377,   0.000124265,  0.000123988,  0.000124141,  0.000124005,
-    0.000124407,  0.0001245,    0.000124616,  0.000124172,  0.000124677,
-    0.000124833,  0.000124812,  0.000124727,  0.000125278,  0.000125017,
-    0.000124718,  0.000125466,  0.000125341,  0.000125097,  0.00012497,
-    0.000125439,  0.000125901,  0.000125333,  0.000126408,  0.000125859,
-    0.000126248,  0.000126085,  0.000126706,  0.000126271,  0.000126237,
-    0.000126502,  0.000126643,  0.000126313,  0.00012642,   0.000126825,
-    0.000126739,  0.00012678,   0.000127098,  0.000127298,  0.000126856,
-    0.000126995,  0.000127149,  0.000127357,  0.000127536,  0.000127291,
-    0.000127489,  0.000127719,  0.000127739,  0.000128051,  0.000127628,
-    0.000128167,  0.000128089,  0.000128337,  0.000128418,  0.000128217,
-    0.000128272,  0.000128745,  0.000128905,  0.000128552,  0.000128961,
-    0.000128948,  0.000129073,  0.000129106,  0.000129348,  0.000129462,
-    0.000129213,  0.000129236,  0.000129422,  0.00012961,   0.000130121,
-    0.000129987,  0.000129766,  0.000129878,  0.00012999,   0.00013024,
-    0.000130123,  0.000130552,  0.000130641,  0.000130298,  0.000130286,
-    0.000130607,  0.000130831,  0.000130878,  0.000130921,  0.000131,
-    0.000130846,  0.000131325,  0.000131028,  0.000131736,  0.000131321,
-    0.000131755,  0.000131268,  0.000131499,  0.000131905,  0.00013166,
-    0.000131896,  0.000131997,  0.000132215,  0.000132316,  0.00013252,
-    0.000132033,  0.000132533,  0.000132248,  0.000132045,  0.000132512,
-    0.000132365,  0.000132827,  0.000132756,  0.00013279,   0.000132882,
-    0.000132962,  0.000132965,  0.000133239,  0.000133244,  0.000133672,
-    0.000133556,  0.000133836,  0.000133873,  0.000134165,  0.000134059,
-    0.000134178,  0.000133812,  0.000134159,  0.000134283,  0.000134128,
-    0.000134329,  0.000134073,  0.000134498,  0.000134933,  0.000134524,
-    0.000134895,  0.000134483,  0.000134842,  0.000134903,  0.000135252,
-    0.000135527,  0.000135959,  0.00013519,   0.000135505,  0.00013577,
-    0.000135754,  0.000135502,  0.000135688,  0.000135993,  0.000136136,
-    0.000136015,  0.000136229,  0.000136391,  0.000135676,  0.000136093,
-    0.000136664,  0.000136609,  0.000136842,  0.000136516,  0.000137013,
-    0.000136956,  0.000136965,  0.000137115,  0.000137056,  0.000137018,
-    0.000137432,  0.000137575,  0.000137492,  0.000137283,  0.000137783,
-    0.000137622,  0.00013762,   0.000138033,  0.000138115,  0.000138255,
-    0.000137852,  0.000138161,  0.000138247,  0.000138253,  0.000138476,
-    0.000138301,  0.000138975,  0.00013836,   0.000138931,  0.000138961,
-    0.000139191,  0.000139015,  0.000139095,  0.000139423,  0.00013974,
-    0.000139344,  0.000139523,  0.000139857,  0.000139685,  0.000139842,
-    0.000140308,  0.000140064,  0.000139726,  0.000139535,  0.000140272,
-    0.000140261,  0.00014011,   0.000140163,  0.000140704,  0.000140547,
-    0.000140476,  0.000140919,  0.00014079,   0.000141151,  0.000140724,
-    0.000140939,  0.00014113,   0.000141357,  0.00014123,   0.000141538,
-    0.000141348,  0.000141681,  0.000141821,  0.000141798,  0.000141393,
-    0.000141982,  0.000141734,  0.000142244,  0.000142145,  0.000141963,
-    0.000142055,  0.000142265,  0.000142665,  0.000142358,  0.000142457,
-    0.000143157,  0.000142869,  0.000142852,  0.00014288,   0.00014252,
-    0.000143593,  0.000143024,  0.000143169,  0.000143196,  0.000143483,
-    0.000143676,  0.000143821,  0.000143635,  0.000143701,  0.000143907,
-    0.000143921,  0.00014374,   0.00014384,   0.000143807,  0.000144342,
-    0.000144662,  0.000144433,  0.000144409,  0.000144448,  0.000144449,
-    0.000145057,  0.000145062,  0.000144861,  0.000144992,  0.000145052,
-    0.000145429,  0.000145682,  0.000145439,  0.000145181,  0.000145522,
-    0.000145698,  0.000145873,  0.000146043,  0.000145463,  0.000145871,
-    0.000146068,  0.000146021,  0.000145992,  0.000146015,  0.000146621,
-    0.000146446,  0.000145913,  0.000146311,  0.000146757,  0.000146243,
-    0.000146863,  0.000146668,  0.000146902,  0.000147098,  0.000146945,
-    0.000146883,  0.000146972,  0.000147571,  0.000147082,  0.000147331,
-    0.00014755,   0.000147756,  0.000147786,  0.000147581,  0.000147609,
-    0.000148169,  0.000147862,  0.000148157,  0.000148403,  0.000148398,
-    0.000148,     0.000148353,  0.000148456,  0.000148236,  0.00014831,
-    0.000148512,  0.000148794,  0.000149022,  0.000148536,  0.00014911,
-    0.000148912,  0.00014903,   0.00014934,   0.000149462,  0.000149687,
-    0.000149808,  0.000149688,  0.000149877,  0.000149908,  0.000149737,
-    0.000149928,  0.000150196,  0.000150071,  0.000150585,  0.000149831,
-    0.000150162,  0.000150416,  0.000150173,  0.000150383,  0.000150603,
-    0.000150631,  0.000150803,  0.000150994,  0.000151079,  0.000151063,
-    0.00015098,   0.000150814,  0.000151323,  0.000151362,  0.000151131,
-    0.00015143,   0.000151759,  0.000151697,  0.000151539,  0.000151977,
-    0.000152119,  0.000151495,  0.000151962,  0.000152396,  0.000152118,
-    0.000152324,  0.000152484,  0.000152583,  0.000152979,  0.000152257,
-    0.000153027,  0.000152961,  0.00015291,   0.000153141,  0.000152745,
-    0.000153268,  0.000152807,  0.000152981,  0.000153498,  0.000153227,
-    0.000153815,  0.000153605,  0.000153557,  0.000154066,  0.000153627,
-    0.00015419,   0.000154136,  0.000153978,  0.000154182,  0.000154179,
-    0.000154456,  0.000154726,  0.000154643,  0.000154265,  0.00015434,
-    0.000154854,  0.000154887,  0.000155159,  0.000155056,  0.000155339,
-    0.000155051,  0.000155363,  0.000155108,  0.000155529,  0.000155551,
-    0.00015595,   0.000155978,  0.000155941,  0.000155444,  0.000155924,
-    0.000156187,  0.000155939,  0.00015596,   0.000156,     0.000156138,
-    0.000156006,  0.000156434,  0.000156697,  0.000156307,  0.000156541,
-    0.00015686,   0.000156416,  0.000156659,  0.000156885,  0.000156774,
-    0.000157484,  0.000157672,  0.000157453,  0.000157114,  0.000157972,
-    0.000157926,  0.000157596,  0.000157968,  0.000157611,  0.000158167,
-    0.000157726,  0.000158002,  0.000157799,  0.000158158,  0.000158364,
-    0.000158451,  0.0001588,    0.000158662,  0.00015878,   0.000158389,
-    0.0001589,    0.000158791,  0.000158754,  0.000158862,  0.000158933,
-    0.000159243,  0.000158947,  0.000159354,  0.000159058,  0.000159479,
-    0.000159579,  0.000159315,  0.000159632,  0.000159793,  0.00015993,
-    0.000159841,  0.000159952,  0.000159932,  0.000160374,  0.000160116,
-    0.000160206,  0.00016041,   0.000160679,  0.000160619,  0.000161142,
-    0.000160815,  0.000160637,  0.00016067,   0.000160974,  0.000160934,
-    0.000161029,  0.000161064,  0.000161164,  0.000161267,  0.000161623,
-    0.000161913,  0.000161642,  0.00016132,   0.000161615,  0.000161738,
-    0.000162161,  0.000161832,  0.000161986,  0.000162591,  0.000162346,
-    0.000161885,  0.00016238,   0.000162804,  0.000162372,  0.00016286,
-    0.000162647,  0.000162593,  0.000162541,  0.000162885,  0.000163218,
-    0.000162897,  0.000163034,  0.000162948,  0.000163072,  0.000163473,
-    0.000163075,  0.000163558,  0.000163628,  0.000163971,  0.000164212,
-    0.000163799,  0.000164451,  0.000164174,  0.000163639,  0.000164236,
-    0.00016443,   0.000164077,  0.000164015,  0.000164706,  0.0001646,
-    0.00016474,   0.00016472,   0.000164892,  0.000165054,  0.000164851,
-    0.000165147,  0.000164847,  0.000165194,  0.000165218,  0.000165441,
-    0.000165325,  0.000165637,  0.000165234,  0.000165974,  0.000165942,
-    0.000165754,  0.00016602,   0.000166046,  0.000166184,  0.00016601,
-    0.000165709,  0.000165915,  0.000166902,  0.000166605,  0.000166699,
-    0.000166456,  0.000166855,  0.000166708,  0.000167269,  0.000166718,
-    0.000166921,  0.000167105,  0.000167041,  0.000167387,  0.000166787,
-    0.000167431,  0.000167399,  0.000167603,  0.000167186,  0.000167693,
-    0.000167762,  0.000167578,  0.000168108,  0.000168488,  0.000168389,
-    0.000167947,  0.000167938,  0.000168185,  0.0001687,    0.000168383,
-    0.0001685,    0.000168796,  0.000168593,  0.000168702,  0.000168999,
-    0.000169293,  0.000169044,  0.000169258,  0.000169173,  0.000169179,
-    0.000169627,  0.000169403,  0.000169712,  0.000169569,  0.000169812,
-    0.000169644,  0.000169971,  0.000170127,  0.000169731,  0.000169787,
-    0.000170014,  0.000170098,  0.000170174,  0.000170448,  0.000169889,
-    0.000170341,  0.000170332,  0.000170479,  0.000170425,  0.000170757,
-    0.000170575,  0.000170601,  0.000171096,  0.000170868,  0.000171132,
-    0.000171386,  0.000171474,  0.00017131,   0.000171733,  0.000171245,
-    0.000171505,  0.000171742,  0.000172022,  0.000171943,  0.000171938,
-    0.000171855,  0.000172392,  0.000172107,  0.000172342,  0.000172446,
-    0.000172261,  0.000172862,  0.000172636,  0.000172525,  0.000172761,
-    0.00017302,   0.000172968,  0.000173233,  0.000172913,  0.000173483,
-    0.000173138,  0.000173146,  0.000173014,  0.000173317,  0.000173665,
-    0.000173944,  0.000173608,  0.000173821,  0.000173792,  0.000173866,
-    0.000173939,  0.00017411,   0.000174248,  0.000174148,  0.000174268,
-    0.000174209,  0.000174301,  0.000174369,  0.000174613,  0.000174378,
-    0.000174902,  0.000175014,  0.000174751,  0.000174988,  0.000175154,
-    0.000175053,  0.000174936,  0.000175556,  0.000175381,  0.000175287,
-    0.00017574,   0.000175935,  0.000175691,  0.000175845,  0.000175484,
-    0.000175617,  0.000176023,  0.000176472,  0.000175989,  0.000175929,
-    0.000176325,  0.000176537,  0.000176449,  0.000176273,  0.000176943,
-    0.000176882,  0.000176396,  0.000176695,  0.0001768,    0.000176889,
-    0.000176849,  0.000177473,  0.000177218,  0.000177556,  0.000177391,
-    0.000177764,  0.000177393,  0.000177536,  0.000177696,  0.000177552,
-    0.000177727,  0.000178209,  0.000177863,  0.000177814,  0.000178154,
-    0.000178288,  0.00017793,   0.000178132,  0.000178495,  0.000178506,
-    0.000178632,  0.000178705,  0.000178973,  0.000178832,  0.000178805,
-    0.000178985,  0.000178903,  0.00017906,   0.000178938,  0.000178755,
-    0.000179452,  0.000179253,  0.000179406,  0.000179514,  0.000179495,
-    0.000180054,  0.000179965,  0.000179524,  0.000179695,  0.000180206,
-    0.000179653,  0.000180092,  0.000180881,  0.00018016,   0.000180215,
-    0.000180288,  0.000180583,  0.000180502,  0.000180632,  0.000180586,
-    0.00018067,   0.0001807,    0.000180775,  0.000180895,  0.000181111,
-    0.000180869,  0.000181282,  0.000181078,  0.000181677,  0.000181526,
-    0.000181468,  0.000181577,  0.00018155,   0.000181635,  0.000182169,
-    0.000181897,  0.000181933,  0.000181674,  0.000182407,  0.000182123,
-    0.000182468,  0.000182169,  0.000182317,  0.000182826,  0.000182515,
-    0.000182752,  0.000182759,  0.000182677,  0.000183296,  0.000183161,
-    0.000183269,  0.000183473,  0.000182815,  0.000183368,  0.000183369,
-    0.000183484,  0.000183276,  0.000183754,  0.000183544,  0.000183935,
-    0.000183457,  0.000184221,  0.000184415,  0.000183981,  0.000184269,
-    0.000184202,  0.000184358,  0.000184337,  0.000183918,  0.000184149,
-    0.000184864,  0.00018474,   0.000184832,  0.000184895,  0.000184443,
-    0.000184828,  0.000185533,  0.000185135,  0.000184673,  0.000185565,
-    0.000185127,  0.000185527,  0.000185342,  0.000185668,  0.000185662,
-    0.000185519,  0.000185784,  0.000186153,  0.000186136,  0.000186158,
-    0.00018615,   0.000185922,  0.000186678,  0.000186487,  0.000186309,
-    0.000186221,  0.000186836,  0.000186536,  0.000186309,  0.00018697,
-    0.000186936,  0.000186518,  0.000186816,  0.000186831,  0.000186751,
-    0.000187421,  0.00018746,   0.000187352,  0.000187204,  0.000187538,
-    0.000187621,  0.000187546,  0.000187597,  0.000187921,  0.000187665,
-    0.000187594,  0.000187755,  0.000188155,  0.00018809,   0.000188551,
-    0.000188565,  0.000188298,  0.000188406,  0.000188524,  0.000188482,
-    0.00018883,   0.00018909,   0.000189373,  0.000188547,  0.000188915,
-    0.000188648,  0.000189166,  0.000189068,  0.000189557,  0.000189299,
-    0.000189577,  0.00018948,   0.000189226,  0.000189471,  0.000189795,
-    0.00018972,   0.000190287,  0.000190055,  0.000190061,  0.000190428,
-    0.000190065,  0.000190402,  0.000190256,  0.000190006,  0.000190657,
-    0.00019025,   0.000190721,  0.000190551,  0.000190987,  0.000190311,
-    0.000191317,  0.000191238,  0.00019125,   0.00019124,   0.000191004,
-    0.000191556,  0.000191574,  0.000191771,  0.000190945,  0.000191786,
-    0.000191338,  0.000191684,  0.000191968,  0.000192126,  0.000192154,
-    0.000191919,  0.000191732,  0.000192018,  0.000192226,  0.000192127,
-    0.000192054,  0.000192944,  0.00019261,   0.000192514,  0.000192806,
-    0.000192377,  0.000192899,  0.000192826,  0.000193226,  0.000193154,
-    0.0001932,    0.000193128,  0.000193061,  0.000193325,  0.000193724,
-    0.000193282,  0.000193756,  0.000194111,  0.000193947,  0.00019365,
-    0.000194337,  0.000194056,  0.000193778,  0.000194125,  0.000194214,
-    0.000194474,  0.000194523,  0.000194703,  0.000194452,  0.000194598,
-    0.000194413,  0.000194865,  0.000194887,  0.000194951,  0.000195033,
-    0.000195074,  0.000195288,  0.000195096,  0.00019539,   0.000195038,
-    0.000195259,  0.000195512,  0.000195596,  0.000195821,  0.000195093,
-    0.000195309,  0.000196041,  0.000195918,  0.000195944,  0.000196524,
-    0.000196333,  0.000195685,  0.000196103,  0.000196779,  0.00019648,
-    0.000196249,  0.000196316,  0.000196935,  0.000196353,  0.000196703,
-    0.000196724,  0.000196934,  0.000197085,  0.000197261,  0.000197354,
-    0.000197351,  0.000197331,  0.000197116,  0.000197693,  0.000197573,
-    0.0001974,    0.000197961,  0.000197901,  0.000197998,  0.000197982,
-    0.000198268,  0.000198383,  0.000198324,  0.000198112,  0.000198286,
-    0.000198422,  0.000198098,  0.000198313,  0.000198275,  0.000198938,
-    0.000198979,  0.0001993,    0.000198666,  0.000198844,  0.000199255,
-    0.000199148,  0.000199398,  0.000198945,  0.00019903,   0.000199264,
-    0.000199493,  0.000199295,  0.000199444,  0.000199977,  0.000199567,
-    0.000199458,  0.000200074,  0.000200012,  0.000200007,  0.00019972,
-    0.000200342,  0.000200295,  0.000200192,  0.000200241,  0.000200405,
-    0.000200319,  0.000200646,  0.000201118,  0.000200526,  0.000200638,
-    0.000200805,  0.000201327,  0.000201288,  0.000200846,  0.000201322,
-    0.000201575,  0.000201533,  0.000201377,  0.00020153,   0.000201628,
-    0.000201931,  0.000201811,  0.000201777,  0.000201923,  0.000201624,
-    0.000202196,  0.000202466,  0.000201979,  0.000202177,  0.000202013,
-    0.000202486,  0.00020305,   0.000202604,  0.000202438,  0.000202754,
-    0.000202833,  0.00020302,   0.00020246,   0.000202853,  0.000203155,
-    0.000203379,  0.000202699,  0.000203371,  0.000203288,  0.000203628,
-    0.000203132,  0.000203507,  0.000203286,  0.000204256,  0.000203808,
-    0.000203819,  0.000204131,  0.000204011,  0.00020374,   0.000204365,
-    0.000204161,  0.00020424,   0.000204149,  0.000204552,  0.000204438,
-    0.000203991,  0.000204584,  0.000204351,  0.000205068,  0.00020508,
-    0.000204759,  0.000204981,  0.000205225,  0.000205203,  0.000205406,
-    0.000205405,  0.000204973,  0.000205566,  0.000205209,  0.00020557,
-    0.00020577,   0.000205441,  0.000206037,  0.000205844,  0.000205684,
-    0.000206081,  0.000205828,  0.000206342,  0.000206331,  0.000206208,
-    0.000206651,  0.000206378,  0.000206545,  0.000206793,  0.000206251,
-    0.000206543,  0.000206414,  0.000206666,  0.000207184,  0.000207137,
-    0.000207241,  0.000206859,  0.000207272,  0.00020718,   0.000207415,
-    0.000206881,  0.000207671,  0.000207321,  0.000207528,  0.00020762,
-    0.000207919,  0.000208007,  0.000208086,  0.000207944,  0.000208318,
-    0.000207979,  0.000207908,  0.000208329,  0.000208802,  0.000208524,
-    0.000208583,  0.000208374,  0.000208448,  0.000208445,  0.000209072,
-    0.000209027,  0.000208642,  0.00020831,   0.000208948,  0.000209155,
-    0.000209056,  0.000209099,  0.00020919,   0.000209363,  0.000209793,
-    0.000209266,  0.000209357,  0.000209243,  0.000209401,  0.000209981,
-    0.000210148,  0.000209922,  0.000209919,  0.000210436,  0.000210418,
-    0.000210133,  0.000210512,  0.000210331,  0.000210774,  0.000210842,
-    0.000210616,  0.000210566,  0.000211083,  0.00021111,   0.000210927,
-    0.000211038,  0.000210986,  0.000211097,  0.000211374,  0.000211366,
-    0.000211093,  0.00021141,   0.00021145,   0.000211462,  0.000211652,
-    0.000211708,  0.000212047,  0.000211726,  0.000211804,  0.000212197,
-    0.000212103,  0.000212139,  0.000212591,  0.000212525,  0.000212171,
-    0.000212575,  0.000212867,  0.000213036,  0.000213095,  0.000213141,
-    0.000212999,  0.000213001,  0.000212899,  0.000213322,  0.000212964,
-    0.000213118,  0.000213111,  0.000213218,  0.000213268,  0.000213382,
-    0.000213554,  0.000213368,  0.000213681,  0.000213389,  0.000213582,
-    0.000213766,  0.00021404,   0.000213829,  0.000214348,  0.000214414,
-    0.000214275,  0.000214353,  0.000214506,  0.000214483,  0.000214227,
-    0.000214599,  0.000215184,  0.00021464,   0.000215007,  0.000214721,
-    0.000214652,  0.000215345,  0.0002149,    0.000215168,  0.000215604,
-    0.00021572,   0.000214934,  0.000215976,  0.00021586,   0.000215687,
-    0.000216085,  0.000215481,  0.000215592,  0.000216069,  0.000216216,
-    0.000216199,  0.000216717,  0.000216684,  0.000216517,  0.000216377,
-    0.000216373,  0.000216484,  0.00021633,   0.000216643,  0.000216514};
-
-const float SIMULATED_VNORD[GPS_DATA_SIZE] = {
-    1.15585745,  2.647533222, 1.633673835, 2.440768363,  -0.224579152,
-    0.555666515, 0.305991203, 1.609186897, -0.988004271, 2.173881475,
-    1.027173233, 2.038831934, 0.157196085, 1.491739423,  2.626959942,
-    0.707236476, 0.165023409, 2.012414442, -0.268334118, -0.290011332,
-    2.259172135, 1.618978071, 2.005067687, 2.334486131,  2.988992842,
-    3.113279939, 3.672095799, 2.108945202, 4.283241154,  1.300542348,
-    4.720951071, 2.081800207, 2.877127389, 6.674254624,  1.492449822,
-    2.430972769, 1.761014537, 3.470831897, 4.763776693,  3.33372637,
-    2.470452213, 1.928342135, 3.091402897, 4.007698156,  4.395192915,
-    2.933121526, 2.070452492, 4.875346461, 1.611071282,  3.382661195,
-    3.988769454, 2.117752108, 4.978095616, 5.178880433,  7.121581955,
-    6.32689645,  4.261496552, 6.191930351, 3.542679238,  7.692246641,
-    7.1409436,   7.038212109, 4.93506517,  8.554804769,  7.557956548,
-    7.277787649, 6.819191612, 5.589444209, 4.214224696,  7.608443299,
-    7.641846605, 7.875224607, 8.433248252, 7.04182257,   6.154524485,
-    11.95796085, 10.14533385, 8.026891459, 10.26669566,  8.858089595,
-    8.983353872, 10.89104647, 8.35536853,  8.38241596,   9.371915541,
-    10.43285196, 11.60773717, 10.71407429, 12.63654397,  11.08923186,
-    11.50781576, 12.47098857, 12.93866449, 11.80151878,  15.5563638,
-    12.65029149, 14.44810845, 11.6510697,  14.461477,    15.76450435,
-    14.19918536, 16.04263321, 16.47534173, 15.26166015,  17.49047395,
-    14.15033867, 16.56990801, 16.3792729,  16.97776586,  16.9990111,
-    19.58805361, 20.9056177,  18.3877234,  18.54591925,  20.29777508,
-    23.76524555, 23.61457645, 21.17792138, 22.67055555,  20.74194287,
-    23.11367136, 21.3255154,  20.10205358, 21.8817294,   22.70360344,
-    23.45641554, 26.04735146, 21.99535836, 24.61412757,  22.73566029,
-    24.93503656, 23.1813962,  24.28223407, 24.8466966,   26.6511174,
-    26.59720529, 26.40348136, 27.15562764, 27.26100736,  26.59110911,
-    27.30542375, 24.41607209, 28.60368352, 27.22431562,  28.02744339,
-    29.42342397, 26.25759766, 28.17442339, 27.81422419,  29.63388113,
-    29.69386067, 29.67150489, 30.02256501, 29.63519141,  30.24012858,
-    34.27908155, 29.91127814, 34.20447844, 30.90724067,  30.12376771,
-    32.20333768, 31.13130708, 33.97611373, 32.5779354,   36.52409547,
-    35.02567693, 33.43619495, 34.81006352, 34.11995299,  35.78626168,
-    32.28249578, 35.69005902, 33.5581562,  34.98717251,  34.58819228,
-    34.4349169,  39.28707226, 38.03271686, 35.1414805,   36.39625394,
-    35.70833086, 37.44807624, 37.03748635, 37.15166738,  35.83117728,
-    40.04227332, 38.94890846, 39.60926355, 37.73149902,  39.47911602,
-    36.4460395,  42.60299859, 40.39884414, 38.11947945,  40.53529207,
-    38.93676839, 42.29785284, 42.96324452, 41.10141164,  45.63066766,
-    43.21353524, 44.32496471, 43.7405277,  43.00101222,  45.07336498,
-    43.90530672, 43.53767108, 44.76185389, 43.19098,     45.67561082,
-    45.89343077, 45.87835599, 47.85125661, 47.42620914,  44.15008873,
-    45.92901614, 46.01439111, 50.06218182, 48.70180614,  47.64184366,
-    46.98759299, 48.95881914, 47.70906795, 47.977445,    49.41934701,
-    49.63940159, 51.54129376, 51.76250824, 50.52679439,  49.90780586,
-    52.77287047, 45.71987946, 50.35323213, 51.13573022,  52.85336431,
-    50.62144186, 51.10940628, 53.30882757, 54.59536793,  55.48964014,
-    52.97319184, 51.62643297, 52.68690051, 54.26775617,  53.20877221,
-    53.95906549, 55.34828392, 56.76341234, 54.69423734,  56.48401697,
-    57.29801772, 53.46352735, 56.5422492,  58.20345059,  57.12004164,
-    59.30098567, 58.44107525, 56.25200596, 59.00594408,  59.50046022,
-    57.29462657, 58.3524092,  58.52901546, 59.12330128,  57.68166733,
-    61.6427304,  61.16233907, 61.53802678, 59.22141548,  60.16682856,
-    62.53572909, 59.89328596, 61.34305639, 62.16506401,  63.42104904,
-    61.94392353, 62.27035396, 63.34709837, 63.7702423,   63.13497201,
-    63.23393317, 63.94294497, 63.96725013, 66.55061823,  66.61920594,
-    66.83930943, 65.76591082, 65.42274617, 65.36775457,  64.80686847,
-    66.63117461, 65.33436192, 64.42102413, 65.88624711,  66.43458292,
-    66.30085275, 67.53340601, 66.80546729, 69.71956784,  68.16892852,
-    67.99334308, 70.2310648,  67.01034184, 68.82338857,  69.99487743,
-    69.86740044, 70.89019929, 71.5994174,  71.31321112,  67.69659066,
-    70.18275553, 68.52444675, 69.83903237, 72.38846082,  73.01392244,
-    72.44185492, 68.34762835, 71.40449505, 72.65702559,  72.35964244,
-    71.83605999, 71.08736201, 73.21579639, 73.99435291,  72.36428626,
-    75.64255727, 73.11395841, 74.59722057, 73.2591383,   74.36179845,
-    73.54987464, 74.82481476, 73.62638979, 74.43589685,  75.29467993,
-    73.82601023, 76.36820795, 74.03369948, 73.32047987,  74.39709283,
-    74.50402097, 75.39340526, 73.54127518, 77.59747255,  74.38301479,
-    76.13683827, 75.44100843, 74.98024237, 75.0735294,   77.94859909,
-    73.19195139, 75.3954696,  74.97800095, 75.83556289,  76.05372928,
-    73.08056813, 75.53638265, 74.15750034, 73.26781844,  75.74929151,
-    74.76864666, 76.02782123, 76.18566877, 76.50625818,  74.75802764,
-    77.13307356, 77.71482307, 75.73933853, 75.95401388,  75.24060415,
-    75.81747124, 77.18974985, 76.70753047, 76.02080601,  77.42603557,
-    76.13531751, 76.83810738, 73.9633067,  76.99510161,  77.29847935,
-    77.78203857, 79.04655076, 77.56202805, 78.7377561,   77.35072352,
-    76.5717882,  76.15741685, 77.55836151, 77.3516651,   76.26932943,
-    77.43257092, 74.73226488, 77.24084866, 75.37298761,  79.75721558,
-    77.54871751, 79.12615084, 78.29046938, 78.49329988,  78.25273212,
-    76.65027842, 74.76613811, 77.07232587, 78.05849965,  80.12515372,
-    75.93682613, 74.74828104, 75.67215363, 76.7351655,   78.39950277,
-    78.34962537, 76.13441469, 77.28327022, 76.55483696,  75.38986469,
-    77.78060645, 78.07637543, 75.94155638, 76.74610275,  75.4909619,
-    77.32160076, 77.37450362, 77.25553425, 77.16446042,  77.60310542,
-    76.68814451, 76.77786689, 74.77562702, 75.78699034,  75.34429875,
-    76.8683999,  79.549265,   78.54301552, 79.38982041,  74.78362825,
-    75.0779789,  75.82356974, 75.02429286, 78.49091782,  76.4932699,
-    76.41659587, 73.83152331, 77.73677494, 75.56910047,  73.8839607,
-    73.96573537, 74.69086915, 78.0137119,  75.28458625,  75.55138471,
-    75.38130719, 75.22102212, 76.80128636, 76.83220998,  75.93115587,
-    75.05687109, 74.95654951, 79.03163996, 75.89676925,  74.5272369,
-    74.97973482, 73.64555241, 75.98528321, 75.18110421,  74.81253983,
-    74.47907039, 75.51657341, 76.45153187, 75.82539348,  73.55867513,
-    73.46464288, 76.44096717, 75.10450099, 72.95222878,  75.17468584,
-    75.1068783,  74.95677152, 75.10449727, 75.70520186,  74.2803231,
-    74.2443118,  73.68395474, 75.24109405, 74.2571342,   74.88153597,
-    75.17068346, 75.79864853, 76.14970876, 74.90805888,  76.35649063,
-    72.96335162, 74.80592276, 76.19134328, 72.90512979,  72.13825143,
-    76.6120901,  73.61039096, 75.53510584, 73.15969612,  73.37091497,
-    75.7222139,  76.17043437, 74.1615178,  76.57041232,  74.05204865,
-    74.28777403, 73.33920095, 73.32087641, 74.80418857,  72.91587925,
-    75.88530626, 71.92349202, 73.06891304, 73.59358493,  75.01424631,
-    73.79324418, 73.90504796, 74.23715714, 72.76547829,  74.92804893,
-    71.61463472, 74.59838429, 71.99078556, 72.03242216,  72.33034792,
-    71.69663043, 73.99669254, 75.3526135,  71.72645885,  76.23799148,
-    73.63978428, 73.2878603,  73.72544464, 73.61002546,  74.2741748,
-    71.36826774, 72.49439287, 73.1690653,  72.70995669,  73.57717672,
-    74.6790249,  72.79072302, 73.54586682, 71.13449559,  73.63791211,
-    73.08465566, 70.8469633,  72.08980727, 73.69844312,  71.1524809,
-    71.3383815,  74.57769191, 71.2581346,  71.87553852,  71.15980274,
-    70.6091649,  71.55671494, 72.52578437, 69.86983284,  70.23822074,
-    71.03121715, 71.43148232, 71.94143532, 69.6998805,   70.44945668,
-    71.92178271, 71.36934355, 71.14850777, 72.14536498,  70.10278797,
-    72.68736479, 70.44474159, 72.25641771, 72.48415874,  71.99337322,
-    71.47806659, 73.80552756, 69.94625879, 69.85928401,  70.13856729,
-    71.61738468, 69.32056042, 71.46582481, 70.45302537,  73.39158875,
-    71.96381822, 69.58974158, 71.94068167, 67.52300928,  68.85319126,
-    71.06770095, 69.70757978, 71.52010128, 71.77937028,  69.83472779,
-    69.79899317, 70.23177589, 69.61458741, 71.18053482,  70.29947675,
-    70.21690922, 71.12242153, 70.57951463, 71.35529828,  70.22823771,
-    70.21971418, 70.47337087, 69.73845951, 70.71907322,  69.91173287,
-    69.68827517, 69.91716806, 69.34883153, 74.1904669,   68.70172436,
-    70.70605023, 71.49519684, 69.90130057, 71.91092983,  69.8793647,
-    71.00553175, 71.38746345, 70.31246361, 69.58918228,  71.71143929,
-    72.0009619,  67.96677776, 67.67593883, 70.64376999,  69.06632908,
-    71.35338002, 69.20444953, 68.47196482, 68.34393504,  66.6882325,
-    68.48333252, 68.75238101, 70.49675295, 71.30019954,  71.66991249,
-    70.43493326, 70.40101285, 68.77405068, 69.30526061,  69.0513704,
-    67.76555772, 70.71581855, 69.81049261, 67.80866213,  71.30545498,
-    67.1656762,  69.98907962, 70.39518186, 68.74593009,  68.61020089,
-    71.03167902, 68.29810648, 69.72544358, 70.48229533,  70.50340765,
-    66.89961777, 71.91552777, 68.74188531, 67.65350683,  68.74043104,
-    69.48534305, 67.79288437, 68.27904704, 71.48170455,  69.39566133,
-    67.24983107, 70.955554,   68.98462001, 70.43415005,  70.78106405,
-    65.67736491, 68.26464645, 68.39726166, 67.87329749,  67.60126761,
-    68.35444885, 68.27567876, 68.40880048, 66.73935043,  66.4997693,
-    67.80348808, 70.2578506,  67.80705791, 66.89611794,  67.58021201,
-    68.69587304, 69.64697624, 68.42934325, 67.90204001,  69.41140094,
-    69.0409256,  68.28583182, 66.78909138, 68.53360522,  67.87303666,
-    68.48964377, 69.36127295, 70.69842318, 67.64891864,  64.86510759,
-    68.15832758, 63.93142639, 68.46825255, 67.69202514,  64.03453377,
-    68.26491449, 66.49058202, 63.93651866, 67.74016404,  66.65459079,
-    66.82566665, 66.83837435, 68.03435903, 69.21212657,  67.0096958,
-    68.51664412, 68.42363656, 67.61130003, 68.57499402,  69.2705466,
-    68.97381037, 66.388133,   67.30990653, 66.43902007,  66.70160026,
-    66.6584105,  68.36695994, 66.81643564, 66.00805942,  69.03420169,
-    67.61190815, 66.13504711, 65.59244565, 66.32730322,  67.02387866,
-    68.05816053, 66.04719432, 70.70224595, 66.55623571,  64.49063272,
-    65.51351211, 66.9698342,  65.30847356, 66.02919264,  65.53104404,
-    67.29083353, 65.26513791, 69.13561518, 65.27148741,  66.72396203,
-    67.91487347, 65.04060386, 66.30319173, 65.29757218,  65.66148828,
-    66.86795257, 64.71526606, 67.68715978, 68.06554605,  65.62695667,
-    68.08595355, 67.95374093, 66.22642701, 62.85735427,  66.63094358,
-    67.90641896, 67.2683348,  65.35766248, 64.51605953,  67.49407092,
-    65.54383737, 66.53007655, 65.59524148, 64.63515241,  64.4544024,
-    67.59166192, 63.68823632, 62.7394781,  68.5115317,   67.3426382,
-    64.6512592,  67.67670823, 66.41807768, 65.54423298,  64.82603184,
-    65.95292973, 65.82737648, 65.74635622, 64.82393295,  64.91427946,
-    65.27702955, 64.33362896, 64.61094286, 63.83004288,  64.25235067,
-    64.09787119, 65.36913656, 65.95287661, 65.90461838,  63.18024737,
-    64.29430188, 65.89729286, 65.13439702, 66.75227486,  63.93682337,
-    65.10021209, 66.72139419, 65.7911315,  65.67928855,  65.4620239,
-    62.4203603,  65.11585701, 65.98333437, 64.7610827,   63.97985941,
-    65.16900877, 66.63215907, 66.25084848, 65.93801275,  64.01565354,
-    65.27610374, 63.04634605, 63.57519467, 65.98679996,  65.34232711,
-    64.06975385, 63.91963796, 63.48190118, 64.68797288,  66.07107703,
-    64.1556208,  62.31266691, 63.45781723, 64.16002317,  62.76733885,
-    62.20682292, 64.82997138, 64.79508798, 61.08693693,  63.94586797,
-    62.59127303, 62.02119275, 64.7105879,  61.83776901,  62.81968213,
-    61.95383325, 62.86339116, 64.63454762, 64.91542686,  63.15528884,
-    64.67456734, 64.75712045, 65.17399974, 65.07708752,  63.79215694,
-    63.88159111, 64.32922595, 62.42247112, 62.58907834,  62.12561669,
-    63.47771625, 64.01002369, 64.59800032, 65.61309425,  63.91514067,
-    62.35287707, 63.27415876, 64.3260363,  64.83443866,  65.61973504,
-    62.87014986, 61.47404704, 62.67269238, 64.52928061,  63.85010161,
-    62.06893351, 62.43313519, 60.62381769, 60.42649972,  64.72509125,
-    63.1748496,  63.94057892, 60.99701945, 63.57616695,  62.91335257,
-    62.71965775, 61.72759875, 64.44319618, 65.17783264,  65.31842783,
-    60.97953355, 62.35646669, 63.29296135, 63.61372004,  59.4992666,
-    59.60062782, 63.67118577, 62.982435,   65.66206276,  61.66981619,
-    62.2959332,  64.73975497, 61.34257779, 62.34753218,  63.31225531,
-    63.6468068,  62.23660119, 62.29632785, 63.49894026,  62.2499156,
-    61.41528544, 64.09107752, 59.62302367, 63.40271774,  61.93124684,
-    61.96989167, 61.07952588, 59.46912436, 59.3287135,   62.58440822,
-    63.14269719, 62.70728198, 61.81239616, 60.83673511,  64.79089048,
-    62.60743261, 63.28169151, 60.2249967,  62.7995922,   63.52389421,
-    63.68725819, 62.709139,   61.03840652, 62.90977741,  63.46411083,
-    63.67368164, 63.38042352, 59.91435247, 64.98330217,  61.64182526,
-    63.73147585, 62.24602574, 58.87122196, 60.85683956,  60.95715128,
-    60.70062944, 63.96648758, 61.81679795, 61.89719074,  61.5008703,
-    61.8969134,  61.08673538, 58.89519933, 62.02894101,  58.06230773,
-    59.07723551, 62.32949987, 60.6895586,  63.67079867,  60.93568117,
-    60.78516237, 62.06076399, 63.01556564, 60.0589714,   63.66114314,
-    63.40526453, 64.5747104,  61.09988043, 62.35403704,  61.50936419,
-    61.77290478, 63.08813599, 61.77644321, 62.11665883,  62.38608126,
-    61.28488651, 58.58354395, 61.31326009, 63.20482456,  62.90451935,
-    59.03300234, 60.24419107, 63.38769542, 60.56071143,  60.482896,
-    61.02168856, 60.79869185, 65.30070646, 62.1810499,   60.82203362,
-    60.96354579, 63.04537257, 60.13716998, 62.8293777,   62.32895002,
-    62.98387389, 59.21121109, 59.35789336, 61.7064356,   59.03217666,
-    62.08611069, 61.83041469, 61.1673883,  57.6514031,   61.66755141,
-    57.79531899, 58.76236536, 61.1522658,  59.25180219,  60.04890468,
-    59.0333338,  59.41941367, 60.91328133, 61.99773912,  59.59568798,
-    59.45919094, 62.1051842,  57.89554123, 59.50358342,  60.09099722,
-    60.92624691, 61.28761015, 60.76332899, 60.14557689,  58.51122248,
-    60.44057738, 59.96549824, 59.87087273, 59.95132298,  59.48202396,
-    61.33779783, 59.4914262,  59.50082544, 61.59434729,  61.64020497,
-    59.85694188, 58.47766643, 58.33846183, 60.25473251,  62.55780949,
-    62.57786434, 59.75254602, 61.35586922, 61.26170262,  58.05106014,
-    61.13476804, 62.03419092, 60.30971491, 60.4204663,   58.47577204,
-    58.39362031, 57.28299175, 62.13974138, 59.94935751,  60.08819871,
-    57.93823578, 62.46128683, 61.94650719, 60.91270909,  58.69018622,
-    58.60882423, 58.55903531, 58.58742118, 61.24094777,  59.5836443,
-    59.80424023, 60.09597848, 59.1053668,  58.29026371,  59.53621322,
-    58.38574331, 60.44497481, 59.30404694, 58.78324325,  59.51588447,
-    60.16787498, 58.46656642, 59.07306472, 59.7195711,   58.8684741,
-    58.24056049, 59.77918712, 59.48428973, 58.74112168,  57.71659181,
-    56.45603349, 59.78996392, 57.84377943, 56.61567467,  57.48708959,
-    58.42415221, 57.5204844,  61.93724399, 58.45617318,  59.94161156,
-    62.05144769, 58.90958278, 60.24435515, 58.57918735,  59.77878279,
-    57.4231158,  59.6407741,  58.80253621, 57.1883754,   60.35764808,
-    58.77259766, 58.22478141, 58.99650737, 59.23191176,  61.13187064,
-    58.68731995, 59.86685634, 58.44432886, 58.7628867,   60.4235064,
-    57.40457042, 59.69968269, 57.01097459, 61.34352356,  59.16534188,
-    58.3987454,  59.48910233, 57.81774599, 60.74114549,  57.42743864,
-    57.87355333, 58.0695507,  58.71418979, 61.79645823,  59.69941574,
-    57.82909004, 58.22340449, 59.81088908, 58.84501368,  58.62162432,
-    59.74913176, 57.61771918, 59.3938011,  56.01509094,  57.98268279,
-    59.14032382, 55.09875178, 58.18297823, 58.00268799,  57.30593085,
-    57.56637532, 58.18386979, 56.18731239, 58.44955987,  60.68241139,
-    56.91405476, 57.77932588, 59.68421971, 57.61160106,  61.11772639,
-    59.91941609, 58.51719764, 55.49456926, 57.55388183,  58.75304689,
-    56.07785778, 58.80628624, 57.52154544, 58.16462518,  55.73670039,
-    59.65960473, 56.11444842, 58.51882447, 57.17127062,  59.45437159,
-    60.7460867,  56.27048472, 56.06136871, 54.80469729,  57.04541557,
-    57.29206032, 57.45584207, 55.667039,   56.24477948,  60.33494805,
-    56.38989933, 57.17901563, 60.16774967, 56.59829213,  56.79840756,
-    57.0273846,  57.00635182, 58.26153077, 59.02864088,  56.46336681,
-    54.9311482,  54.44794028, 57.90735397, 59.06245751,  59.19846477,
-    57.2586643,  56.82002103, 58.2498309,  60.25501626,  58.28337268,
-    57.64086719, 58.30701542, 58.76272363, 57.58948387,  57.26245249,
-    59.36561616, 56.65068795, 56.91977516, 58.12364737,  56.97463795,
-    56.67248744, 57.88741241, 55.89422588, 58.29877005,  57.84199065,
-    57.25926989, 57.03856426, 55.75822268, 56.83751614,  57.72205937,
-    56.60577173, 54.2667815,  58.45274184, 57.97238117,  57.22844942,
-    55.70059902, 53.52317101, 55.98202935, 55.32021937,  55.80706187,
-    56.1481161,  57.30662913, 56.46884104, 56.63907212,  58.13362101,
-    59.35158807, 56.08406545, 57.3063078,  57.6850355,   58.91762634,
-    58.59708079, 56.54617969, 56.50973046, 56.44629826,  57.28071141,
-    58.4167253,  55.5730407,  56.8496542,  57.14179833,  57.82461961,
-    56.08745484, 57.97729638, 56.73080157, 55.59096547,  57.0605365,
-    56.31713068, 56.23460339, 56.35656199, 56.31618108,  56.95960519,
-    56.50709068, 56.33236645, 58.90554512, 56.55464285,  56.15753068,
-    56.46102099, 56.89366726, 58.03248964, 54.84068847,  57.90492131,
-    57.77709421, 53.37849399, 55.79066439, 54.7424831,   54.40327502,
-    56.36917496, 55.7205906,  54.62733587, 55.27242724,  58.71689563,
-    55.86027486, 57.12328952, 55.33737619, 54.25028262,  54.87313106,
-    56.33447006, 56.94631128, 56.25214146, 55.39485128,  59.09698617,
-    57.09947836, 56.41116974, 54.98497441, 56.78872075,  56.23337276,
-    55.91383606, 55.17225838, 54.26693468, 57.70876036,  56.9804999,
-    56.85652361, 57.03000629, 54.48491965, 54.83239185,  54.80594262,
-    54.8219576,  57.55448093, 57.12988134, 59.10643787,  54.60246794,
-    56.59846501, 57.79339191, 54.17306282, 56.29451228,  54.30043212,
-    56.53920835, 54.72616204, 53.78750718, 54.94973804,  53.42229919,
-    59.83067904, 54.31326276, 56.81144128, 56.68352834,  56.0481564,
-    56.12240655, 55.07084268, 56.7094825,  54.56983612,  53.2788382,
-    56.49558653, 55.03339006, 56.22968168, 55.15403225,  53.92132064,
-    59.54531865, 52.98410921, 54.65958655, 56.62100495,  55.49697307,
-    55.17151051, 53.77031307, 55.57765936, 53.63198003,  56.64795999,
-    56.55572681, 56.0318899,  55.15342028, 57.58697409,  55.39896643,
-    52.08235869, 52.43976384, 56.36572197, 55.20849221,  58.19254473,
-    56.24224272, 55.27196942, 54.20645382, 54.96004685,  56.67502483,
-    54.11653066, 54.10435174, 53.64389486, 56.46750262,  57.28397422,
-    55.76208362, 54.29448003, 58.18078563, 55.40233682,  56.04404664,
-    54.51877343, 54.44971519, 55.76001543, 53.5203576,   52.50958367,
-    53.72655175, 53.94545728, 53.83211407, 52.44991489,  54.84983439,
-    51.715566,   54.73290331, 54.25627596, 52.49409128,  54.2549528,
-    52.1335208,  54.09211293, 55.9047755,  55.14037929,  53.20878345,
-    56.15451316, 52.36379065, 51.68534819, 55.58212564,  55.2009634,
-    55.95434575, 52.90978974, 54.08831841, 55.39296363,  53.45200507,
-    56.50372549, 53.61458295, 54.78993596, 51.15624165,  53.74322805,
-    55.48157757, 52.75259888, 54.54829714, 53.68102696,  53.9721637,
-    56.85290296, 56.86143177, 54.10633483, 53.91030057,  53.83360755,
-    54.26472009, 54.14483056, 56.54109897, 56.63492476,  54.24670983,
-    55.01395861, 53.17388112, 56.64999286, 54.32878376,  53.3195045,
-    51.01621461, 53.65254661, 52.97634043, 54.9678073,   53.04647754,
-    53.86518485, 53.68890308, 52.97314776, 52.79469532,  54.99354852,
-    55.73969594, 53.04711831, 52.97414634, 55.92721334,  55.56239478,
-    56.37749467, 53.18475169, 52.81640664, 54.5887424,   55.29834146,
-    51.55884652, 53.73215075, 52.43731494, 54.98259042,  55.94830859,
-    52.95825746, 54.96438871, 54.98361916, 54.33590534,  53.17406902,
-    52.82454506, 53.32913079, 52.0721292,  53.55374383,  54.71234203,
-    52.61150156, 51.2211317,  53.62862954, 54.04352851,  52.01405375,
-    56.39384616, 53.99892033, 53.27917992, 51.68955393,  53.81234085,
-    53.41769273, 52.15436137, 52.58078658, 54.81327587,  51.9964659,
-    56.8495859,  53.32568754, 51.27590625, 53.85325772,  51.05514768,
-    54.09410325, 55.42830296, 52.25303911, 53.78944969,  52.93632671,
-    50.46318079, 54.28256863, 54.9485591,  53.06498828,  51.33894239,
-    52.97897802, 53.78248498, 53.85118601, 51.96829007,  52.79086763,
-    54.56060686, 52.76721477, 51.91524224, 51.70803706,  52.43610776,
-    54.05864338, 52.38570473, 53.1737549,  51.8004268,   53.44671068,
-    50.6512485,  54.707901,   52.19234327, 53.09783876,  52.08664216,
-    52.32017058, 52.13439656, 51.27736353, 55.28786727,  55.04092739,
-    53.71142704, 53.52460067, 53.21010271, 53.12573388,  54.10377155,
-    52.742695,   53.83846541, 52.68094029, 55.41788717,  52.08147991,
-    52.49086918, 51.68232635, 51.68631683, 54.60943078,  53.14884065,
-    51.53552774, 51.2201983,  53.75991158, 53.31126171,  52.12161275,
-    52.118373,   50.5248803,  53.36849479, 54.65199275,  55.94962329,
-    51.3790091,  52.16131094, 53.46365641, 54.36719747,  52.25449808,
-    51.74828839, 54.55281623, 52.49680517, 53.3923283,   53.20552285,
-    52.39606461, 53.81090869, 51.55467408, 54.36373577,  52.17164144,
-    50.88749862, 49.87696111, 52.74010884, 49.84002041,  53.81016372,
-    52.6133462,  50.24595676, 52.61735983, 56.03569255,  53.51176325,
-    53.47080511, 52.61486606, 50.91610583, 53.3226644,   53.84154322,
-    51.9499374,  53.39505441, 51.89959411, 53.27207463,  54.54451445,
-    53.94357493, 52.48389145, 50.26436601, 51.58469616,  48.82941081,
-    53.76515582, 54.11781397, 52.50936341, 53.7739929,   51.57633909,
-    50.99952638, 51.9994075,  50.20495699, 49.88221686,  54.20791048,
-    51.49757579, 53.24720179, 52.07932089, 51.70594323,  54.1870675,
-    51.84684323, 51.76592761, 50.79137341, 52.31874039,  51.37465597,
-    53.13589934, 53.07627339, 51.61524068, 54.31626504,  50.81287623,
-    49.85730172, 53.1188765,  51.61211612, 52.61567511,  53.30671276,
-    54.17355055, 52.82065509, 48.62882659, 47.94054626,  51.61919912,
-    52.47067301, 50.18779171, 53.74378538, 51.08338206,  53.14909379,
-    51.99321355, 51.04377831, 52.91436114, 53.7299382,   51.40650444,
-    51.50432216, 48.43579872, 52.30460796, 53.27384103,  51.51955488,
-    51.90471506, 51.61378538, 52.37333133, 55.20421989,  52.9777495,
-    51.32038827, 52.80569656, 52.81560693, 50.66306396,  51.5472497,
-    52.17055438, 53.40500556, 51.55221648, 54.35235976,  51.09918939,
-    50.38828725, 49.43592493, 52.531144,   51.62608759,  52.45509605,
-    53.76742791, 53.29656597, 49.78618613, 48.5203366,   52.2320687,
-    51.2116226,  51.49246997, 51.52322008, 51.95067116,  49.50593681,
-    52.68428264, 55.06196312, 49.69274319, 51.62852891,  51.76717319,
-    51.04044188, 52.9822104,  54.88981451, 54.03821528,  49.61753843,
-    52.59098926, 51.52476496, 53.4769185,  50.70400791,  51.5253717,
-    52.06864626, 52.77743442, 51.19594424, 51.78063071,  50.48099678,
-    53.44800893, 52.44462669, 48.12924828, 50.11543355,  51.98261463,
-    51.09810543, 51.22573629, 51.00936891, 51.54463949,  52.60399837,
-    50.99208685, 52.32099316, 51.33484121, 48.10862658,  52.19775507,
-    50.62364952, 51.54374032, 50.93894146, 51.78941585,  50.3905159,
-    50.73465709, 51.49848361, 51.1102004,  49.76645796,  50.19167866,
-    51.69532709, 53.74283388, 50.8340685,  54.39165847,  53.27737095,
-    49.15476391, 50.63974814, 50.48326611, 51.86201905,  50.13838621,
-    50.92011548, 51.99634612, 50.31179079, 50.83592951,  55.12162165,
-    51.74258393, 49.35575372, 52.19022018, 51.08720749,  52.0497061,
-    50.12058384, 50.57826049, 50.30676951, 52.59815279,  49.40645192,
-    50.51729151, 48.63107329, 52.68146863, 51.24905604,  51.60112559,
-    51.60339927, 50.17375717, 51.78863909, 48.52189595,  50.29803665,
-    51.52626243, 51.42677271, 51.31467334, 47.65225953,  50.78319287,
-    48.87138898, 50.3981076,  49.2058683,  48.75368675,  51.86095856,
-    48.61022329, 50.43953799, 48.45471394, 50.58783663,  53.38659709,
-    49.36189437, 49.90967798, 51.20352523, 48.59521782,  49.82485719,
-    50.89236537, 51.68528463, 50.81372603, 52.28870477,  49.52788925,
-    49.77119353, 50.3376299,  50.76491807, 48.2970292,   50.99671595,
-    51.55936764, 50.05950116, 48.85852124, 51.85266022,  51.5006031,
-    49.76111716, 49.02337872, 50.25658777, 48.94450109,  51.22074824,
-    49.41852146, 51.37234509, 52.74129401, 51.32241672,  50.30951169,
-    52.3506678,  50.00237641, 50.46956439, 49.49679562,  52.02368409,
-    52.00840758, 48.11574761, 51.56974458, 52.29982224,  49.64640702,
-    51.75805136, 49.54765166, 49.96695634, 51.00619781,  47.9263993,
-    48.59324828, 54.02031396, 51.85537934, 50.64181188,  52.38032751,
-    49.07337457, 52.76331737, 50.78364762, 51.51359204,  48.29851345,
-    50.45156191, 48.60250589, 47.49652071, 51.08858749,  50.37017836,
-    48.96585564, 51.66668931, 50.43403636, 49.55074966,  51.17528373,
-    48.646493,   50.29508404, 49.80925205, 49.68035976,  49.91670365,
-    47.21912107, 50.93150271, 49.8462539,  51.47358518,  50.04053062,
-    50.66848798, 50.96512812, 47.83424212, 51.074619,    50.9205553,
-    48.68129483, 51.35786843, 48.32656463, 51.91123497,  49.5911589,
-    49.71312591, 52.23435798, 49.54435529, 50.01496335,  49.95629841,
-    49.90336451, 49.37411987, 51.67442667, 50.32949952,  50.48855263,
-    49.68242482, 53.07603501, 45.99775939, 50.17714143,  50.78352834,
-    48.36739597, 51.66583425, 47.56810045, 50.12963237,  47.70099105,
-    51.32590012, 51.15861172, 51.70600683, 47.52344302,  48.96908595,
-    49.8872012,  51.62510173, 48.61126644, 51.08746905,  51.65434643,
-    49.75058731, 46.02035273, 47.47760714, 49.45573221,  49.84249778,
-    49.14341689, 50.49799886, 48.31027414, 47.82737113,  51.23326584,
-    49.05937476, 47.37579607, 48.28400861, 49.70046761,  51.13190256,
-    49.35211177, 49.25452665, 48.22757306, 49.84350917,  48.37902535,
-    50.25993233, 46.84149693, 48.52661618, 48.91242715,  50.6058431,
-    48.02183812, 49.20977133, 50.12674573, 48.88122243,  49.30254354,
-    50.24175522, 48.13594325, 49.89704255, 49.13698254,  46.14847664,
-    50.9974204,  48.14950444, 47.73756921, 47.14284531,  49.66814215,
-    48.63324316, 50.18253066, 48.82232156, 48.9528056,   51.12258884,
-    46.97937413, 48.90859586, 48.078761,   50.87910313,  50.51298837,
-    48.94736348, 50.46056681, 47.03734932, 49.88878016,  49.18173496,
-    48.371876,   49.8570422,  50.3486331,  48.33283184,  50.89855763,
-    48.43359649, 49.06556292, 47.82607215, 48.13477573,  47.26081906,
-    48.79693584, 51.43157184, 49.38134665, 49.02504851,  51.47554705,
-    48.94351266, 50.24940035, 47.21996907, 50.62074302,  48.71038689,
-    49.61172928, 49.51119665, 46.86533315, 52.17898536,  46.41470216,
-    48.83824506, 51.10080536, 47.68610786, 48.19002165,  53.25329176,
-    47.15899348, 50.10955576, 50.85246046, 50.35858658,  47.53958299,
-    50.00220699, 49.58345517, 49.38131622, 49.9552403,   51.67244513,
-    49.39609772, 47.33083548, 49.60214437, 49.32387365,  49.33544588,
-    47.96521476, 48.46712509, 49.29610904, 48.81633282,  50.29713922,
-    50.05502429, 47.58283358, 47.87064155, 49.96921084,  47.84859141,
-    46.92878661, 47.67439745, 49.27681919, 49.07294303,  48.22898062,
-    50.61733466, 47.7189316,  48.19067194, 48.23381424,  48.38284268,
-    48.5775388,  48.81268961, 50.26814271, 47.08296601,  50.48029145,
-    47.4851254,  45.87236041, 48.02295976, 50.07151452,  48.46464226,
-    50.36367153, 47.83584821, 49.10618446, 49.10265469,  50.4185086,
-    47.15192772, 48.13237111, 48.33532715, 45.3153211,   49.23831397,
-    49.31790475, 46.6383609,  48.76938039, 48.98999085,  48.93124383,
-    48.90273597, 48.55262327, 48.31076794, 46.6916889,   51.59277358,
-    47.8268692,  49.19577973, 48.26682164, 49.19152878,  47.44213378,
-    48.47805185, 48.27639326, 48.9644763,  47.47787724,  50.29954586,
-    48.26765234, 50.52738604, 51.1991314,  48.25261691,  47.60141451,
-    48.54978419, 48.14680822, 50.89965802, 49.93528839,  46.2656863,
-    50.68578916, 50.64060155, 49.1055874,  47.95383243,  51.49176531,
-    47.02288199, 48.63848468, 49.80215084, 48.9937351,   46.49714686,
-    48.21454999, 49.42652264, 46.97805169, 50.0695457,   52.37071327,
-    46.44549979, 49.94083781, 49.92589961, 49.11896283,  49.19726675,
-    48.8373052,  46.27375372, 50.07735452, 49.01043956,  48.831747,
-    48.62724768, 48.88724168, 43.71057128, 47.52080541,  48.87730742,
-    46.66953825, 48.03489947, 47.93013278, 46.93473556,  46.5612022,
-    49.24567942, 48.11307283, 47.46535558, 49.69062771,  48.38576285,
-    49.12204295, 45.22570023, 47.69942089, 47.90933048,  47.59743617,
-    50.19240482, 48.47704663, 49.1101135,  49.64638339,  47.92403591,
-    47.41180546, 50.52338424, 48.16587322, 46.67461557,  49.16335222,
-    47.84441689, 49.03083145, 48.27285676, 46.24336362,  48.25389299,
-    51.31752149, 46.74862513, 51.1693147,  47.8978836,   47.90709376,
-    46.29908022, 46.17721173, 47.4089717,  48.31397761,  49.68277875,
-    51.99437075, 47.24360887, 45.45215971, 46.2817328,   47.32813918,
-    48.9271041,  48.42709031, 48.01701981, 48.84388508,  46.88849086,
-    49.35684472, 46.182204,   46.6525444,  47.30963056,  48.20125466,
-    48.73841812, 50.02372819, 45.85635522, 49.14544406,  49.90740559,
-    46.08463023, 47.78581441, 46.54522004, 47.53810545,  50.17820039,
-    47.71822933, 49.02277849, 46.30133758, 48.86444256,  46.00802067,
-    45.83803388, 45.31529088, 46.22807795, 48.29491889,  47.40502217,
-    47.02931806, 49.37463735, 46.29302506, 48.83639382,  47.04947176,
-    48.89951064, 48.41738934, 46.05331967, 47.33507465,  48.96855365,
-    48.78303395, 47.60737065, 46.90315461, 46.16867964,  47.99242064,
-    49.6301018,  48.37438503, 46.81777148, 47.47262078,  47.69148055,
-    45.02854792, 46.32347018, 46.85386698, 46.70799955,  46.51895617,
-    47.44014772, 45.65866433, 50.17560801, 48.23812406,  46.38860977,
-    47.50990316, 45.22491595, 46.78734552, 46.07455513,  47.32627594,
-    46.52049433, 48.91388822, 49.37134994, 46.93988398,  48.08381196,
-    46.99298396, 44.59855881, 47.31529203, 46.85967395,  48.88782424,
-    45.55644483, 46.43875015, 45.06783561, 47.13336619,  47.39166498,
-    48.95850534, 45.82770661, 47.78814395, 45.87340733,  47.79042687,
-    47.20417906, 47.52862623, 46.87895752, 47.95924382,  45.62654178,
-    45.84824009, 47.3693143,  48.29626289, 47.82453188,  46.22738151,
-    45.75582566, 46.68768967, 46.52388609, 49.04599276,  49.3420453,
-    49.62374966, 46.7286964,  45.82540313, 47.60506104,  47.35536499,
-    47.1698668,  49.86558537, 44.15559291, 47.80788356,  49.13069025,
-    47.39066889, 47.32058291, 49.38370913, 47.78814581,  47.72790779,
-    47.37484336, 48.53174889, 46.89314994, 47.32849846,  48.18963226,
-    49.34947666, 46.6823194,  44.55350791, 48.25812406,  47.75037012,
-    45.9056424,  46.37197348, 47.32019127, 48.52970085,  48.84019016,
-    47.42864679, 48.60401525, 48.4959618,  42.71099033,  47.99749963,
-    47.11429438, 47.45238084, 46.68243998, 47.02397774,  46.73904732,
-    46.28407128, 42.87367229, 47.2777852,  47.97150217,  47.47546872,
-    47.82988241, 44.02934717, 46.00774567, 44.73794902,  47.42263441,
-    46.89568035, 47.73856744, 46.69788575, 47.31625979,  47.36135648,
-    45.42372243, 46.37245991, 47.36334758, 48.84048578,  45.55464241,
-    46.10593582, 48.46040977, 46.57893333, 48.24397811,  46.26489521,
-    47.44188555, 47.83101916, 48.15602988, 47.47870314,  47.69725973,
-    46.03012023, 47.45267199, 45.84809532, 46.77537042,  47.81241082,
-    46.5114458,  48.36007307, 46.65994596, 46.38590272,  49.53688092,
-    46.08943171, 47.11794954, 47.62007326, 46.77363833,  46.46017129,
-    47.78244837, 48.05027318, 47.12172928, 49.10122618,  44.74898731,
-    44.13461826, 45.86859372, 47.02350571, 47.66420687,  46.23365158,
-    48.97025813, 46.94072569, 48.78699892, 45.88260644,  45.17578008,
-    48.32027428, 46.65464326, 45.42423998, 45.68884457,  45.11416846,
-    50.64665161, 46.73820616, 44.60276907, 46.64439725,  47.19955709,
-    46.36609819, 47.0413817,  45.12295717, 44.80186107,  49.00193353,
-    47.976253,   46.14217462, 45.24139658, 46.96814406,  46.48947903,
-    45.45483444, 47.37707199, 48.79510407, 44.74752298,  44.57291786,
-    45.74759363, 45.94866229, 44.64113453, 45.43445381,  48.11458179,
-    47.42690058, 46.9029463,  45.65942858, 46.85245684,  48.95101273,
-    46.58683243, 45.84088048, 47.7773991,  46.39678091,  47.56579937,
-    46.63719269, 51.15467375, 44.88160144, 49.2025143,   50.66840359,
-    45.61101668, 47.66557041, 44.62406741, 47.26377156,  45.38735222,
-    46.14266112, 47.64243355, 47.33878635, 46.74841959,  46.47681254,
-    47.09399527, 46.68782735, 48.62113214, 46.48788694,  45.42268181,
-    47.16763203, 44.70327301, 46.82300862, 47.13952842,  43.66012491,
-    43.93676197, 47.40317503, 46.32725053, 46.49187467,  47.23056011,
-    46.7613803,  49.95869996, 47.59461686, 49.63824186,  46.50441385,
-    47.18015836, 44.3099505,  49.23870527, 44.58418426,  46.09863721,
-    44.64833153, 46.74440667, 48.3018921,  46.80030809,  44.98428767,
-    42.93431268, 47.82593913, 46.26167919, 48.0902586,   46.12866623,
-    43.48032186, 47.33538622, 45.76988797, 46.29879358,  49.79043602,
-    42.62085603, 45.71594682, 46.52186009, 47.13697014,  48.50388741,
-    43.22042805, 44.93871623, 47.55933907, 47.78019495,  45.04956556,
-    46.45838194, 48.29944958, 44.88860625, 46.54581886,  45.71152084,
-    45.72296563, 46.49448033, 45.55039039, 46.22045458,  47.42782414,
-    44.07255108, 48.26874715, 47.5204795,  47.1337446,   47.84326159,
-    46.63224302, 46.61549044, 43.55608883, 45.84882753,  47.30500215,
-    47.47601836, 45.20485351, 48.2945965,  46.80742963,  47.18170177,
-    45.14698067, 44.95741067, 48.08841285, 45.60241605,  48.08675353,
-    47.10104534, 46.27042907, 44.76196322, 44.85858866,  47.4266035,
-    46.48647077, 46.7627719,  48.41688797, 47.01995636,  45.72807726,
-    45.91887011, 48.45922398, 43.2301402,  47.05882433,  44.56947932,
-    45.54738502, 46.0571001,  44.60466781, 49.27456269,  46.59190667,
-    45.50003112, 44.504287,   42.57398237, 47.065903,    47.19546833,
-    45.42504976, 47.87709923, 45.85797557, 47.2203195,   44.62287244,
-    45.17060364, 44.9063807,  44.19356869, 47.52569177,  45.75253315,
-    46.82864278, 44.91954823, 44.43950133, 46.66823264,  47.64431357,
-    46.57875476, 46.47256268, 43.30172834, 45.09087795,  48.32023412,
-    45.23973431, 47.09003625, 45.6177087,  48.20682562,  46.73706528,
-    43.60833919, 47.07241511, 46.6706366,  46.03267592,  45.93587553,
-    46.70148978, 49.20116114, 45.23934094, 46.75309841,  44.85915855,
-    48.88880298, 44.9614572,  43.3868302,  45.40129593,  46.43889776,
-    45.88336428, 45.1059271,  45.20395543, 44.82545692,  45.20751869,
-    46.89540149, 42.94405937, 46.19252319, 46.53868137,  46.60512431,
-    44.91742447, 46.9548162,  46.5482309,  45.40563964,  44.17918456,
-    45.83888446, 47.29804539, 48.71969097, 43.83807917,  45.68657121,
-    44.50284763, 45.13621865, 47.29664164, 43.58496476,  49.38687518,
-    44.34423725, 46.59713179, 46.39881514, 46.89151227,  47.10282176,
-    44.87918024, 43.04891339, 46.04773455, 45.49310318,  47.58866801,
-    45.75686759, 47.89649419, 43.97431989, 46.94638184,  46.16877428,
-    47.64785301, 45.89139306, 45.5507501,  45.48660009,  47.28411938,
-    46.20095812, 45.93171489, 45.61300329, 43.95132512,  46.4593379};
-
-const float SIMULATED_VEAST[GPS_DATA_SIZE] = {
-    1.123925133,  -1.120688682, 3.077857733,  -1.97573061,  -1.624232809,
-    -0.243835631, 0.604868232,  -0.995493815, 0.74131936,   -1.201807635,
-    -1.080352028, -0.848625068, -1.464741105, -0.803565782, -0.568754275,
-    0.491804544,  2.147147298,  -0.351163696, -0.222060087, 0.803585041,
-    0.762989586,  2.330660768,  1.451482974,  -0.240341058, -1.030122575,
-    1.479906643,  -2.308339787, 0.540638945,  -1.259205664, -0.40142712,
-    2.109759595,  -0.341807264, -1.340056391, -0.762490265, -0.08466474,
-    0.31631243,   -1.249806725, 2.592886512,  0.593182867,  0.006891127,
-    0.231485122,  -2.530822571, -0.764450711, -2.35766534,  -1.682172022,
-    0.524918741,  -0.871117864, 1.150666821,  -1.983310449, -0.102733929,
-    -1.611250414, 1.11003025,   1.133274016,  0.192212178,  -0.02447497,
-    1.302048961,  1.760127826,  2.219839547,  1.146604176,  1.817096788,
-    0.907950593,  -1.699113212, 0.826883139,  -0.430019737, 0.93261029,
-    0.636172031,  0.204243267,  1.117425706,  0.731854873,  2.653820492,
-    -3.004174156, -0.084773495, 1.539299233,  -0.739260309, -0.239592605,
-    0.811554368,  -1.675241808, 3.682571182,  -1.090180536, 2.538447461,
-    0.891217563,  -0.720548638, -1.647123637, -1.418638042, 0.192431562,
-    5.008987073,  -0.483707112, -2.166579384, 2.339332231,  0.731724891,
-    -2.038842428, -0.560808188, -1.395576267, -0.672463363, -0.360154814,
-    -0.376780703, -0.824452193, 0.612824495,  -2.13915436,  0.495738433,
-    2.757305122,  -0.963169877, 0.665738743,  -2.241899989, -1.66327343,
-    -0.850889616, -0.246099374, 3.374650946,  -1.284991136, -0.852165657,
-    2.682144448,  -0.735207943, -1.560123549, -1.11010547,  0.471665185,
-    -3.907441645, -0.992524383, 0.208134188,  1.248364079,  0.68021698,
-    -0.23844202,  0.498925016,  -1.765530472, 0.797281356,  -2.986063021,
-    0.379582615,  0.132366784,  -1.676147953, 1.599897131,  1.677280155,
-    -1.353206824, 3.892698525,  -0.592720481, 1.619602166,  -0.23232626,
-    0.981976372,  0.331297644,  1.345503544,  -0.700362291, -0.91253154,
-    -1.802800875, 0.323661298,  0.38721404,   -0.32296837,  1.319951062,
-    -0.223409915, 1.114525166,  -1.959925981, -0.133233418, 3.774554686,
-    2.483916399,  -0.159555899, -1.307826225, 1.268905046,  -1.033859725,
-    -0.478664019, -1.44305206,  -0.421515496, 0.284244701,  -0.399355006,
-    -3.066429233, 0.062996776,  0.218999928,  1.959552241,  -0.541084666,
-    -0.099679173, 0.628680116,  -0.479385665, -1.354715944, -0.146433004,
-    0.093946168,  -0.06390901,  1.052413396,  1.968298014,  1.696012951,
-    -0.006671612, -1.841288495, -0.114286564, 0.575346371,  -3.018347271,
-    1.726893298,  -1.608543002, 0.651820675,  -0.599311177, -1.263546871,
-    -1.623935643, 1.413595168,  2.267897719,  -1.112612345, -1.233317848,
-    -0.341568786, 1.336030287,  -0.610093603, 1.62426153,   -1.337912214,
-    -0.805964196, -0.953813731, 0.628590165,  -1.206835177, -3.176868665,
-    -0.132373141, -0.004579647, 1.056617665,  -1.561324964, 3.010497929,
-    -0.788169761, -0.042703416, 1.247037718,  -0.978336561, -0.870887148,
-    0.761751466,  -2.029527982, 0.688403906,  1.606771084,  -2.184468964,
-    -2.70154824,  2.150222559,  -1.168684544, -0.870580755, -0.622226201,
-    -0.005271962, -1.305787183, -1.290702848, 0.965814133,  0.590940206,
-    -1.432834854, 1.971998036,  -2.439830054, 1.428304645,  2.536641416,
-    -2.014655671, 0.40976155,   0.555717656,  0.399549594,  1.218619603,
-    -0.968256401, 2.076868069,  -1.605360952, 0.294550963,  -0.912458987,
-    0.850484311,  2.01175084,   1.68982154,   -0.096569938, -0.794252364,
-    -0.353232642, -0.757313016, -0.25156108,  2.654295711,  1.070192085,
-    0.533094383,  1.432531405,  -0.263281474, 0.570449426,  -1.353791496,
-    2.267686646,  0.257606369,  -1.502040189, 0.369209174,  -0.58327102,
-    -1.398750876, 0.17589707,   2.439454934,  2.33398271,   -0.609801433,
-    0.924947067,  -1.327405469, 0.390345077,  -2.233184938, -1.349370953,
-    -1.606178427, 0.566866939,  0.074954436,  -1.671411752, 1.38804014,
-    -1.558586871, -0.852136058, 1.612909797,  1.640117049,  2.400075718,
-    1.73825388,   -2.293397308, -0.326435361, -1.807105589, 2.145946642,
-    0.476526935,  0.423026367,  -1.63883838,  0.005559238,  -0.981641993,
-    -0.510066687, -0.629871704, 0.827877292,  0.995809113,  -0.835897131,
-    0.979927278,  0.5539637,    -0.114651219, 1.769314461,  0.654822784,
-    2.119309335,  -0.483245068, 0.677621228,  0.762871088,  0.315761873,
-    1.686426781,  1.681554196,  3.745268612,  -0.042513933, -0.487579968,
-    0.007881613,  -2.351066252, 1.040764849,  1.354153666,  -1.679230478,
-    1.288142608,  3.304530587,  0.537471923,  0.878843113,  0.74047792,
-    0.020563602,  -2.48086971,  -2.156691874, 1.654531667,  -1.381700886,
-    -0.901112757, 0.821407141,  -0.40894876,  0.156449172,  0.976583332,
-    1.565190657,  0.041146375,  -1.194159773, -0.636890941, -0.050882094,
-    -0.823680134, 2.583985676,  -1.475096267, -0.497742483, -1.259989923,
-    -0.700364224, 0.909897812,  -0.256345556, 1.881076329,  0.198843014,
-    -2.543632117, 0.282603017,  -1.565964235, 0.540242433,  -2.442810642,
-    1.052655976,  0.855796713,  -1.304813968, 2.049441175,  -0.901334,
-    0.650926792,  3.052402291,  -0.134595519, 4.557092439,  0.340044355,
-    0.504148406,  0.316137682,  2.471981227,  -0.946784691, 1.134727822,
-    -1.052199523, -0.228289752, 2.720241779,  -1.09233825,  -0.147703414,
-    0.607710877,  2.375894043,  2.792997879,  -0.373082809, 2.692619087,
-    -1.248370123, 1.881366445,  -0.698171853, 0.887125038,  -0.998181409,
-    0.879736718,  0.952582334,  0.838039217,  -1.532832218, 1.293076076,
-    0.216213255,  0.630645429,  0.964351044,  0.486550464,  -0.40893838,
-    0.704058796,  2.308576595,  1.745364273,  0.070156118,  1.376212892,
-    1.403580591,  0.872611335,  2.475850228,  -0.285277155, -3.375203644,
-    -0.439010814, 0.319099226,  -0.605889823, 2.826890484,  -0.498192648,
-    -0.11427501,  -1.567864684, 2.599468457,  -2.736439498, -0.455349938,
-    1.136158044,  1.015355345,  -0.1819495,   -1.213311236, 0.906482084,
-    -0.631334048, 2.378749526,  -1.547674301, 0.952674508,  1.752111562,
-    -0.305313789, -1.048184266, -1.394074807, 0.284413671,  1.599912886,
-    1.623117751,  -0.981474759, -0.550672409, -0.156453035, 0.682704427,
-    0.067744249,  -0.227488633, 1.459592959,  0.718391938,  -3.520697093,
-    1.026509808,  1.739419119,  0.466924469,  -0.246135774, -0.26558037,
-    0.504289225,  -2.080141715, -0.382144179, 0.416433547,  -1.19991614,
-    -1.058501986, 0.599342234,  -0.742280703, 0.766842956,  1.868462358,
-    1.06826954,   0.683594578,  1.539396212,  1.587681648,  -0.457063646,
-    -0.499406581, 0.250472159,  2.633666891,  2.615310062,  0.924595709,
-    -1.40942825,  -0.408417489, 2.225439799,  -0.169201296, 2.054434775,
-    1.994175433,  1.204409709,  -2.160656836, 1.610625041,  -0.545706574,
-    -0.496914054, -0.532906892, 2.32461998,   -1.396479844, -1.433428652,
-    2.067777341,  -1.342353359, 2.541774562,  -2.970596773, -2.354801324,
-    1.359863621,  -1.374497956, 1.62466443,   2.337483761,  0.359624203,
-    -1.057649003, 0.629078617,  0.306746741,  2.838632928,  1.848397869,
-    0.385918115,  0.947797779,  -0.852781344, -0.413483403, 4.209579997,
-    2.124880184,  -0.904679867, 0.195842495,  1.955357387,  1.448190984,
-    1.580536482,  1.995192661,  1.623291868,  -0.250025441, 0.882953557,
-    -1.04008737,  -1.113430696, 2.012385177,  1.9848939,    0.720330636,
-    -0.073291214, 0.448748383,  1.287883174,  -1.55272048,  1.683770932,
-    2.476280878,  1.721055774,  -1.500597776, 1.045158004,  0.205754678,
-    2.021914418,  -0.883572193, 1.201005953,  0.464065552,  -0.879416867,
-    0.459448793,  1.092206906,  0.62904761,   0.521218696,  1.619633249,
-    1.266784107,  -1.091717293, 0.197572129,  -0.858095807, 1.821776965,
-    0.327084324,  0.671747251,  1.354418259,  0.868807593,  3.757970303,
-    0.382603982,  2.7155264,    1.244113893,  1.731844067,  -0.804743109,
-    -1.089831474, 2.881109171,  -0.233551021, 0.818685088,  -2.357738669,
-    2.89332174,   1.329017641,  -2.183810283, 2.276912557,  0.897442733,
-    -0.491074652, 0.281183208,  0.458582956,  1.275034519,  0.345538206,
-    -0.114530969, 0.234870863,  0.673117863,  -0.569001119, -0.027185051,
-    1.444451293,  -0.19551902,  1.485542978,  0.758941513,  2.211265275,
-    0.519051529,  -0.380528768, 2.384178234,  -0.483936615, 2.232825747,
-    -0.453465462, -0.143803383, 2.002509985,  0.743340208,  0.117873524,
-    -0.742907139, 2.022066643,  -1.004969366, 0.401323547,  -2.653339188,
-    0.017433264,  -1.628695227, 1.540684438,  -2.372450545, 0.349724954,
-    -3.801739542, 3.041271259,  -0.819242516, 2.341596249,  0.449962259,
-    -2.156353165, -1.128436067, -0.305567237, 1.905003952,  -0.223023949,
-    -0.973945462, 1.533210364,  0.046960593,  -1.221497708, 0.786342537,
-    -0.450454991, -1.101489542, -1.700083038, -0.571914127, -0.592839139,
-    -0.959302184, 2.404372576,  1.152413825,  0.716993885,  -1.73530736,
-    -1.366667038, 2.183531638,  0.111029784,  1.947492032,  1.591037477,
-    -2.08320759,  2.510154952,  -1.865252263, 1.640625887,  0.778523879,
-    1.596747249,  4.265666753,  -0.773933648, -0.196789287, 1.098085217,
-    0.903211325,  1.671128346,  1.557957056,  0.461027441,  -0.495051796,
-    0.390893179,  2.330250332,  0.171553868,  -0.552222918, 1.607373581,
-    1.641373528,  -1.801295102, -1.238171385, 0.259752783,  1.738185943,
-    0.927323989,  1.620667568,  -1.733463344, -0.692715102, 1.175136392,
-    0.200680761,  2.092231661,  -1.814482877, 0.089461285,  -1.182209334,
-    -0.027942983, -2.180687816, 0.779451197,  0.971713489,  -3.236397044,
-    0.580053004,  1.199200878,  2.01752181,   1.26400507,   2.713307027,
-    1.540537168,  -0.395101153, 0.763755701,  0.536524385,  1.048600249,
-    0.162457145,  -0.446961206, -0.010525594, -0.425524141, 2.832545509,
-    -1.169735189, -2.388113562, 0.91313736,   0.85833751,   0.444488164,
-    2.590301262,  0.7528403,    0.40821949,   0.439925469,  -1.313989786,
-    0.656691861,  -0.721659261, -1.711662432, -1.910479466, 0.628776373,
-    -0.649671431, 1.648903551,  2.04072536,   0.028256172,  -1.728670379,
-    -1.006113804, 1.481389194,  1.798996369,  -0.971189088, -2.02110358,
-    -0.742560866, -2.325365663, -0.569135145, -3.289952428, -0.89752459,
-    2.243975879,  -1.476407217, -1.140467288, -0.13433331,  -0.577226016,
-    -0.866547422, -0.017672184, -1.017380726, 1.233805889,  1.307184003,
-    -1.310334455, -1.399679351, -1.144709677, -0.741616817, -0.620473253,
-    0.446913226,  -0.833832927, 1.909169248,  0.610277425,  -1.495965604,
-    2.253938895,  0.576886633,  3.432813653,  2.36483092,   1.853728966,
-    0.854378135,  0.362114513,  -1.435697164, -1.634454426, 1.008386064,
-    0.799481574,  -1.387059458, -0.692021241, 0.037467906,  -0.709340056,
-    -0.280135259, -0.155187467, 0.249371939,  2.199769277,  1.691902384,
-    -0.416058505, 0.61560844,   -1.436410387, 2.008539584,  2.544143055,
-    0.529851323,  -1.140906923, -0.591209136, 1.602469752,  2.771587908,
-    -0.756172103, 1.9658752,    1.386825924,  -0.188944239, 1.84084632,
-    -1.149047963, -1.509359377, 2.715633108,  0.581051563,  0.707574237,
-    -2.006536861, 1.444919697,  -3.19159248,  -0.210402774, -0.865312849,
-    0.839369875,  -0.277539324, -1.577831793, -1.450301029, 0.51102979,
-    3.039499234,  2.421107411,  1.05272487,   1.985062744,  0.416701688,
-    -2.138626124, -0.352304611, 0.77008402,   0.861958888,  1.812387162,
-    2.012945327,  0.076608593,  -0.286771798, -1.194613812, -0.952123561,
-    0.222167598,  0.36407537,   0.669997978,  -0.542146281, -0.326285013,
-    0.842116284,  -0.40789859,  0.501487819,  2.292870081,  -1.595471139,
-    -1.434530815, 0.66235057,   -0.497548247, -1.053051478, 1.001684093,
-    3.116399367,  1.321067799,  1.588253458,  1.063354772,  1.830607934,
-    -1.31646588,  0.996233317,  -0.13431018,  1.437859769,  -2.744320043,
-    3.02996071,   1.019639855,  -0.859034916, 1.607730702,  0.199327806,
-    -0.593733131, -0.21645903,  1.575883713,  0.834035354,  2.272736206,
-    0.643517562,  0.4333004,    -0.41693513,  0.458183563,  1.003343549,
-    -0.90321986,  2.174933786,  0.839597802,  -0.011354717, -1.557211144,
-    0.18764625,   0.592608531,  -0.955295621, 2.563267179,  -2.688766231,
-    -0.338835259, -2.660866038, 2.138126698,  2.447938622,  1.853718315,
-    1.44769605,   2.350090845,  2.122995314,  -2.005671167, 0.173223808,
-    0.022702781,  0.686049156,  -1.413335359, 0.853796145,  0.413264431,
-    -0.682475257, -2.977961154, 3.307122428,  -0.845409855, 1.069756317,
-    -1.51608332,  -0.310163079, 0.602863063,  2.11540277,   1.900302931,
-    -0.330256401, -1.110319336, 0.269261347,  -0.920847666, 2.414482244,
-    4.805376066,  -0.577482039, -0.056947263, -2.001917795, 0.119155967,
-    -0.47205224,  0.686414046,  1.872225186,  0.033384606,  -1.806912943,
-    -0.007079513, 0.986837583,  0.509731588,  -1.244768939, -0.214564888,
-    3.367507072,  0.523367563,  2.006322392,  0.102059933,  1.278686201,
-    0.098948297,  0.76056752,   -1.109462893, -0.148037024, 1.002912808,
-    -1.824792222, 0.267142516,  3.113228914,  1.222834011,  0.175437375,
-    -1.854974019, 1.584990392,  1.14686631,   0.067193995,  -0.019331696,
-    -0.18427938,  0.480956163,  -0.315803402, 1.430525363,  -0.594858497,
-    1.412615444,  -0.142429552, -1.550019885, 2.281793398,  2.383484067,
-    -1.229100874, -0.32105663,  2.84419721,   0.250579068,  -1.177915978,
-    0.200490245,  0.965732241,  -0.541500851, 1.364462372,  -0.645717628,
-    0.678133902,  -0.038582607, -1.216405105, 0.089920323,  -0.238515973,
-    -0.789376995, -0.485312778, -1.377026505, -1.547735536, 0.073371865,
-    0.008839298,  -1.380370117, 1.252079681,  0.44539402,   -1.564501365,
-    -0.012388971, 0.634724257,  1.022824146,  -1.201086522, 0.533389699,
-    -0.769439627, 0.009543408,  3.109627473,  0.305617611,  -1.055539048,
-    1.925563005,  0.945593931,  0.911584031,  3.518608724,  -0.678243209,
-    0.637437813,  -0.020296169, -2.405518172, 0.221560642,  -2.060290873,
-    2.844785617,  2.628139897,  0.846686057,  -2.359092365, 0.199282562,
-    -0.38079297,  1.544117693,  -0.023783432, 1.115552944,  0.678235144,
-    0.731063323,  0.169845881,  -0.34181282,  -0.049160643, 0.469873703,
-    1.336290888,  0.700942253,  -2.44047181,  3.923963673,  1.171027921,
-    -2.103954526, 0.188902889,  1.483428355,  -0.569223819, 0.680726555,
-    1.503527713,  -0.034392208, -0.195604247, -0.121002662, -1.909986842,
-    0.180793046,  0.611906548,  2.477381784,  0.093561094,  -2.162704367,
-    0.679999017,  0.257088527,  -2.029297735, 1.119056451,  0.083477466,
-    3.363407883,  1.045975166,  1.491553909,  1.602136748,  -0.094216367,
-    -1.556712777, -1.885536786, -2.759298981, 0.834808364,  1.871076003,
-    2.808409381,  -0.162975151, 1.615174642,  0.921825968,  2.888364098,
-    0.235961318,  -1.628865798, 1.545587101,  0.226612449,  1.270137874,
-    -1.569925137, -0.653925764, -1.774682385, 2.179149063,  -0.983529965,
-    -0.029301711, 2.144270447,  1.566702312,  -1.010491887, -0.851219571,
-    0.849135255,  0.140053276,  -0.003884728, 1.097611674,  0.869278922,
-    2.238837305,  0.24465101,   -0.20992344,  -2.087410446, 0.266885181,
-    0.915464279,  0.554165413,  1.62228536,   1.356218018,  -1.668175494,
-    2.305518793,  2.023943548,  1.009899154,  0.082677887,  1.29767767,
-    0.61944694,   0.596659127,  0.237806751,  -2.012317211, -1.618816039,
-    1.801597027,  0.016660046,  -0.583427335, -2.114943517, -1.347881675,
-    -2.885994509, -0.007004256, 1.623807924,  2.820585623,  1.35748284,
-    -2.624543765, 1.686777825,  0.708083581,  -0.925952805, 1.850902442,
-    -0.614967883, -0.999406023, 0.533296873,  -1.265418534, 1.009122853,
-    0.683204851,  2.089819051,  0.724259613,  -0.18594275,  -0.613325895,
-    -3.45870145,  0.966181088,  1.717194883,  0.729864815,  3.008499754,
-    1.228194282,  2.359845892,  0.940212028,  -0.229548107, 1.632402175,
-    2.209887243,  1.724582635,  0.769277426,  -1.824048782, 0.007320447,
-    -0.582533919, -1.431635112, 1.235107671,  -0.340820518, 1.265695392,
-    1.986816896,  0.293241224,  1.236962056,  1.504130654,  2.388258902,
-    0.564790498,  -1.587556429, 2.783216032,  0.194935145,  0.424470985,
-    -0.54553692,  1.903584021,  2.32391633,   -4.101877874, -1.21373924,
-    0.063899649,  -1.291012889, 2.524620851,  -0.302191945, 2.481970074,
-    1.144044823,  1.39193599,   2.112708426,  0.670169598,  -0.765938533,
-    -0.791517007, -0.985290144, 3.820075311,  -0.285770708, -1.51582182,
-    -0.998915403, 3.112780087,  1.842923285,  0.281852928,  1.274490217,
-    0.053920865,  -1.741479531, 1.286564254,  1.467623325,  0.527254309,
-    2.314605709,  0.774966554,  0.875432356,  -0.584788876, -0.095782347,
-    1.548032481,  0.118550432,  1.331027452,  1.434627917,  2.63091738,
-    0.526503647,  1.696594491,  1.207324686,  2.735659097,  0.885743563,
-    -1.327846221, 0.907681352,  2.182323763,  0.310932898,  0.648917955,
-    -1.322601889, 0.312228454,  1.103933545,  -1.522846932, -0.616690377,
-    0.627756229,  0.711281358,  0.700413742,  1.571916396,  1.229500822,
-    -1.857422729, -1.024613104, 0.428021907,  1.346762301,  0.793324472,
-    -0.414231445, 3.52352521,   0.717467573,  1.596509668,  0.595389715,
-    1.195126441,  1.488087964,  -0.759961733, 2.736437773,  -0.052256774,
-    -0.30831256,  -1.761745429, 0.775729409,  0.567398268,  0.868491332,
-    -0.320460361, -0.276052319, 0.802882844,  -3.335469263, -2.366748986,
-    -1.050264965, -1.142877823, 2.333557578,  -0.575255017, -1.776918191,
-    -0.249401631, 0.368228382,  -0.646397252, 3.402838087,  0.800323383,
-    -0.447051815, 1.299119769,  0.197676406,  -0.185570598, 0.165483161,
-    1.134848285,  2.927159774,  1.153010932,  -0.565297978, 1.920985442,
-    3.145492917,  1.23640579,   1.955446758,  -3.657266703, 1.935070276,
-    1.092096281,  1.058721972,  -0.029358872, 0.099383062,  -0.835941561,
-    2.593672885,  2.399392751,  -0.449927151, 0.005546844,  0.198201187,
-    1.172232453,  1.38797488,   0.661482384,  -1.340632124, 0.480567569,
-    1.790477977,  1.389858065,  -1.673960997, 1.546369724,  0.152188723,
-    -1.097126477, 0.503022858,  -0.448114363, -1.805615132, 0.060180725,
-    0.800643307,  1.595802291,  -0.75660658,  0.729096119,  1.301565667,
-    1.062077279,  -0.758823825, -0.135388761, -0.593216108, 0.428574209,
-    0.066833057,  -1.449294843, 0.628135845,  -0.159418031, -0.55000601,
-    -0.285601006, 1.293826392,  -2.114371094, 1.780373342,  -1.631371817,
-    -2.703350057, -0.413514467, 0.189690975,  -0.213151495, 1.656325236,
-    -0.05360659,  0.29300288,   2.172158185,  1.190813112,  -0.652027261,
-    -2.40332705,  0.056930197,  -1.836982512, -0.983402586, -0.761513057,
-    -0.358907652, -1.514462073, -0.347427505, 1.582562802,  3.452454681,
-    2.456137107,  1.290356648,  0.123268415,  1.463220202,  -0.17497932,
-    0.232963373,  0.338533459,  0.669513935,  0.566869227,  0.827777935,
-    2.214083556,  1.075964218,  -0.359119787, -0.36353274,  -1.02061679,
-    1.292514497,  1.325485942,  0.193749925,  1.287520944,  -1.147978707,
-    -0.245547886, 0.976648973,  -0.461379498, -0.197190217, 1.132271083,
-    0.080652484,  -0.547565877, -1.499904668, 0.326322692,  -0.72791293,
-    -0.816125452, 2.562778287,  -0.388261746, -3.034550974, -1.884864923,
-    0.566230288,  0.286592052,  -1.985685193, 1.858981685,  -0.030772587,
-    1.980432396,  -0.251097443, -0.059747521, 0.763078314,  0.0755844,
-    0.791849005,  2.510046149,  0.517859899,  -0.059894442, 0.808724046,
-    -1.099168396, 2.199436528,  -0.604409791, 1.210341835,  1.058134083,
-    1.088447822,  0.914621791,  2.317251582,  -2.0824251,   -1.613300533,
-    0.722042585,  -1.152425875, -0.036792785, -0.283623294, 0.36507122,
-    1.966509829,  -0.743496402, -1.070938003, -0.011383237, -0.597942061,
-    0.938354114,  1.779062866,  -1.432832288, -1.869878411, 0.240525811,
-    -0.99129146,  3.072613118,  1.300675083,  1.125817174,  1.011275482,
-    0.886601371,  -0.516365725, 1.550037203,  2.116749051,  0.23292923,
-    0.155581406,  1.12702405,   0.231372271,  -2.712564001, 0.368089782,
-    -0.662278638, -0.305311658, -0.204281991, -0.260957222, 0.630725683,
-    -0.060135938, -0.495011161, -1.42217047,  -0.457938779, 3.127249921,
-    0.964094177,  -0.317302827, -2.205146865, -0.917860139, -1.543324573,
-    -0.020722091, 0.009926673,  -0.163746266, 0.922349701,  -1.251024404,
-    1.42511299,   1.396743423,  1.400223278,  -0.494173719, 0.158901096,
-    1.25924283,   0.589486012,  -1.537176094, -0.520506819, 1.194485066,
-    0.372706525,  -1.581999101, 2.46838069,   0.489175552,  -1.186059859,
-    1.488111776,  3.76339336,   -0.445596702, -0.655262797, 1.31334385,
-    0.87751287,   -1.362033008, 2.485032141,  -0.559170821, 0.046956705,
-    0.131427651,  -1.542227192, 0.353027499,  2.268824741,  2.316870461,
-    0.088155684,  -1.443347715, -1.021856763, 1.488715885,  -0.441663799,
-    -0.954756371, 0.793711033,  -0.03696681,  1.440621863,  0.304196746,
-    -1.76452531,  2.015333733,  -2.139067939, -0.857557924, 0.406930951,
-    2.400895278,  0.452117178,  0.121162137,  2.610249121,  0.300008888,
-    -0.604066235, -1.350652178, -1.687136006, -0.490258913, 1.458027209,
-    5.289107198,  -1.466948299, 0.412679753,  1.366175908,  2.172152359,
-    -0.538083145, 1.499054293,  -1.451139797, 1.088292188,  -0.093435674,
-    0.759701754,  1.265919892,  1.663072618,  0.369630909,  -1.002785698,
-    -1.350731781, -0.623074078, -0.493552034, 0.896680234,  -2.147363324,
-    -0.49282741,  0.878126982,  -1.382176753, 2.245369757,  -0.725861534,
-    1.70136147,   1.853109759,  -1.279124706, -2.371670711, -0.578016305,
-    2.392039938,  0.005963482,  1.409651627,  1.396533131,  -1.808486231,
-    0.766287797,  1.788877445,  1.445236548,  -2.31146934,  -3.316750241,
-    0.167144782,  1.911461741,  0.341867179,  -0.692709115, 0.469708286,
-    -0.328149129, 2.675635074,  -2.448583386, -0.942981478, 0.420531871,
-    0.0472463,    2.907244524,  -0.582013031, -1.064828526, -0.84774717,
-    1.979902183,  0.334935492,  1.257289405,  -0.0905649,   -0.76330356,
-    -0.826062174, -1.755858204, -1.061159054, -0.065143801, 0.401009003,
-    3.503555358,  0.71511531,   1.825573341,  -0.498099769, 0.754146445,
-    0.905587029,  2.040290295,  -1.981109477, 0.166393107,  -1.789263813,
-    -0.884534464, 0.871336884,  1.860719385,  0.84082732,   1.866276818,
-    0.407819081,  0.797413425,  0.969168063,  1.660251486,  -0.610636177,
-    -1.47224957,  1.880596608,  -1.546600473, 0.367880654,  0.219952818,
-    2.503304998,  -0.033202459, -0.322816661, -0.521791642, -2.725154094,
-    -0.245783324, 2.075939597,  -0.576293831, 0.754107847,  -0.747277442,
-    1.577479468,  -2.686322933, 1.949315905,  -2.487528423, -0.697518804,
-    -0.972004924, 1.233150558,  0.76701988,   -0.891585286, -1.546511986,
-    -0.003607555, -0.582195818, -1.322817853, 2.397346969,  0.270528217,
-    0.523634785,  2.209909651,  1.537891044,  0.244241427,  -0.907216415,
-    -0.095672762, -0.634258841, 1.057223397,  0.8953283,    2.279877487,
-    -1.494937042, -1.947909399, -0.447272675, 1.968050323,  -1.166421019,
-    1.724625941,  0.813347047,  -2.750457696, 2.415328374,  -1.279157099,
-    -1.575171978, 0.459912017,  1.045666027,  1.580295193,  -0.514686288,
-    -0.744782283, 0.524319964,  -0.213417921, -1.668887657, -3.947388306,
-    -0.194083981, 0.683288342,  -1.831793001, 0.907471475,  0.483257502,
-    0.95692032,   -0.041081761, -0.630854,    -1.074810279, -0.019258458,
-    1.416719095,  3.417939932,  -2.062220318, 0.430456877,  1.21766735,
-    -0.141318281, 0.505580878,  4.420514215,  1.024463712,  0.267547162,
-    -1.227936992, -0.991670056, -0.8936344,   -0.091065641, 1.591750208,
-    2.122530825,  0.666258014,  -1.092880227, -0.204897047, 0.361693101,
-    0.224188538,  0.57881251,   0.824471842,  -0.312963607, 3.567410305,
-    -0.300219044, 2.099013534,  3.776727201,  0.973724414,  -0.821893668,
-    1.397723503,  -2.165222485, 0.145957056,  1.561644871,  0.588455323,
-    0.992526961,  0.018700155,  -2.305011471, 1.188925805,  1.683880796,
-    0.373947268,  -0.120034566, -3.06551328,  -0.826704597, 0.457881145,
-    1.437263621,  2.484647434,  -0.571774554, 1.843247667,  0.164353463,
-    0.958227674,  -0.156224487, 1.817900234,  -0.002264615, -3.035174629,
-    -1.211970069, -0.520819679, 2.132070239,  0.923590125,  0.188409444,
-    -2.159797496, 1.216359868,  0.452391806,  3.243891632,  -1.99609264,
-    3.092169237,  1.139399734,  2.206082834,  -0.132530667, 0.492112095,
-    -0.176906446, 1.978241958,  0.823919121,  2.729490431,  0.373026315,
-    -0.056335652, -1.468616493, 1.008203532,  -0.293358319, 0.167804427,
-    2.373939117,  -1.450959143, 0.201844139,  0.84046227,   0.593609211,
-    1.265362011,  -0.385409769, 0.266458448,  -0.515161552, -1.880138238,
-    -2.024077849, -1.299513099, 2.402613685,  2.222157657,  -0.251500404,
-    -0.630069623, -0.628891903, -0.709660234, 0.851838803,  -0.698597626,
-    3.049287355,  -1.6149106,   -1.927081707, 1.918138555,  -1.269452134,
-    -1.80420512,  1.141090727,  0.670000249,  -1.91741656,  0.083464807,
-    -1.775744538, -0.297945026, 3.694692688,  2.084143517,  1.737330869,
-    0.487444855,  -0.60996227,  1.184610997,  -2.14943899,  -0.903895022,
-    2.021254708,  -0.059073692, -1.018550037, -1.557652553, 0.090863145,
-    0.256465285,  0.727052019,  -1.812877674, 0.969863002,  -1.897692813,
-    -0.375852285, 0.22712039,   -2.796802924, -0.821638024, -1.597260846,
-    2.197220202,  -0.159525394, 0.51668669,   0.147147491,  -0.843365315,
-    -0.053503757, 1.363101478,  1.753133159,  1.754455246,  -1.127151655,
-    0.606370201,  1.082566604,  0.012637048,  0.211280462,  -1.23692247,
-    0.558462559,  0.070828279,  0.044307747,  -0.259496689, -0.804888795,
-    0.793374797,  -2.419361894, 2.397771459,  0.813688551,  0.709392118,
-    1.585978154,  -0.714452416, 2.995573439,  -0.648880185, 1.77432724,
-    1.797405896,  -1.812307803, -0.121980407, 1.070824747,  0.274422153,
-    1.285574685,  -0.219218111, 1.735338579,  -0.226355349, -2.833132972,
-    1.623264216,  -0.429309569, -0.527687632, 2.04389432,   -1.212411816,
-    -0.003291687, -1.475884332, -1.13999695,  2.607874853,  1.804612142,
-    1.124069672,  1.927328928,  2.389264933,  1.362671732,  -1.609573236,
-    -0.133528443, -0.138384005, 0.672561359,  1.312195519,  -3.675499919,
-    -0.00216216,  -1.183359036, -0.464207104, 0.691192147,  1.80666532,
-    0.714666717,  0.405350211,  -1.7621341,   -0.846460527, 0.43822416,
-    0.296008479,  -2.215874128, -0.278254515, 1.218972292,  1.670299342,
-    -0.408137004, -0.285827372, -1.155245049, -0.955690706, 1.058421041,
-    1.111706542,  -1.701430466, 1.026677608,  -0.175678155, -0.07494604,
-    -0.915953289, 0.63251776,   -1.474537275, 2.853330932,  0.310785621,
-    0.364663639,  0.848361991,  -0.127431792, 0.416892679,  -0.215719819,
-    1.997654186,  1.35031807,   -0.063042535, 0.727870745,  -3.376893375,
-    1.206018577,  0.515723828,  -0.400636896, 1.453179958,  0.274872362,
-    0.774340884,  1.648432495,  0.361709017,  -0.609525767, 1.815449062,
-    1.497443169,  1.230256027,  1.166972024,  -0.14990035,  -0.040401336,
-    -0.710003731, -1.416526773, -0.955993605, 1.65073934,   0.201491364,
-    -0.350695537, 2.615230539,  -1.551784506, 0.375667912,  2.645946656,
-    0.682155697,  -2.894325873, -3.982720111, -0.419990401, 2.310531766,
-    -1.908981383, -2.09390227,  -0.046004026, 0.868955889,  0.247102064,
-    -1.101351396, 1.225216123,  0.237778089,  -1.402513632, 1.628312945,
-    1.363855853,  1.317260285,  2.010694666,  -0.42430637,  0.981780268,
-    0.148340135,  0.289268163,  1.603728907,  0.345215102,  0.196336158,
-    1.32727439,   1.265454825,  -2.001170731, 0.399447087,  -1.403738697,
-    -0.441049265, 0.747101963,  2.609234798,  2.508843239,  0.677854717,
-    1.343707019,  0.062563543,  -0.237599485, 3.364924592,  -0.404672551,
-    0.724344413,  0.715514569,  0.599782389,  0.010745858,  1.225901619,
-    0.896168029,  -0.409035438, 0.317583234,  0.226837627,  0.070142538,
-    0.164437968,  -1.110793885, 1.653966112,  -1.379667164, -0.777256325,
-    -1.179518868, 1.39781246,   0.23600978,   -1.048941178, 0.342508936,
-    -1.229353632, 0.549509167,  -0.876597994, -1.266782932, 0.87277752,
-    1.031138514,  1.54155358,   1.001400503,  0.283936255,  -1.86546816,
-    -0.61605017,  0.481075388,  -1.660543988, 1.751534339,  0.540899856,
-    0.509294149,  1.78644306,   -0.058001203, 0.245602149,  0.807037513,
-    0.528749274,  -0.587547022, 1.716926718,  2.301480201,  3.440973437,
-    -0.020516581, 0.928470415,  -2.445302882, 1.717475321,  1.092803308,
-    1.869049938,  3.014946231,  -0.794056944, 2.01736103,   0.597613201,
-    1.635747497,  -0.225541041, -0.97828082,  0.742982621,  2.0546451,
-    0.573111754,  2.169703639,  -0.791468085, -0.306110546, -1.789587304,
-    2.067655611,  1.504923309,  -1.52286389,  1.695755641,  -0.164157461,
-    -0.901043643, 0.264403752,  -0.212823824, 1.539979262,  0.712952658,
-    0.393523622,  1.136906817,  1.227850403,  0.103172014,  -1.346179328,
-    0.183656357,  0.437088043,  0.108778004,  -0.481362792, 1.672347787,
-    1.567111756,  -0.620631196, 0.149633963,  -2.06877202,  2.624683522,
-    -0.59513515,  -3.495076176, -0.780071653, -0.10202848,  1.822852664,
-    -1.494294913, -0.405669511, -1.630174247, 0.057850587,  1.377075114,
-    0.118763601,  1.115238847,  -1.154151313, -2.151221389, -1.604743989,
-    0.122237589,  1.700550553,  0.216717329,  0.367590526,  1.047867853,
-    -1.13339013,  -0.030181953, -1.72867427,  -0.611826217, -1.913771395,
-    -1.763564218, -0.161666547, -0.334339126, -0.763200547, 1.030559995,
-    0.58798261,   1.093305059,  -0.931104677, 0.907465064,  0.302792188,
-    -1.104880389, 2.671022486,  -1.093517097, 2.147944675,  2.828718984,
-    -0.913522148, 3.432869063,  0.560067983,  -1.401103015, 0.095025613,
-    0.301602919,  2.092174969,  0.048264734,  -1.079992248, -0.103264757,
-    4.113418085,  1.146893845,  -1.422481544, 0.93009919,   -1.279897774,
-    2.123972491,  0.563584813,  0.214626163,  -1.273609865, -1.763108521,
-    -2.107955653, -1.415487513, 1.562198165,  -1.113590919, -1.204285669,
-    2.253840458,  -0.008218922, -1.55096459,  -0.422119434, 1.414220622,
-    -0.382153337, 2.787651495,  0.73184156,   0.245980326,  0.343996678,
-    -0.161954919, -1.221516539, 0.891469383,  0.452937192,  -1.225358249,
-    1.235552398,  0.446619284,  1.665574603,  -0.893170049, 1.337596711,
-    0.183757152,  -0.61887269,  0.065192563,  -2.123984533, -1.227810734,
-    0.025162375,  -0.651007732, 0.290569809,  0.854172515,  -1.190188261,
-    0.796943802,  0.792435549,  -0.422167028, 0.024266268,  0.234692408,
-    0.703284537,  -0.214504255, -1.367520329, -1.612400537, -0.271011952,
-    1.268275976,  -1.176272185, 2.850113121,  4.009423465,  1.050897074,
-    0.455787147,  1.186778102,  0.184213001,  -0.000879537, -1.34014317,
-    2.408974589,  0.269199612,  -2.649608335, -2.516299847, -1.535931386,
-    0.299984919,  -2.264319552, 0.700768983,  0.556737982,  0.40325214,
-    -0.987952904, 0.996469322,  0.056938113,  -1.48477869,  0.665648282,
-    0.500494562,  0.71715095,   -0.993503203, -1.279376596, -1.117481329,
-    -1.011410036, 0.474176803,  0.845707778,  1.001441284,  0.397955452,
-    -0.699286715, -1.687685557, -1.386879571, 2.27558231,   0.029092693,
-    -0.973558664, 0.91718233,   0.700856832,  2.550515426,  -0.464792942,
-    -2.276326557, 2.201909379,  -2.172840696, -1.219186837, 2.126802148,
-    0.920387928,  1.474365161,  -1.337279324, 0.522324677,  -0.6292902,
-    0.310686451,  -1.262586009, 0.053683935,  -1.775108966, 0.13443679,
-    1.640400524,  0.752863736,  0.805356949,  0.453956969,  2.955811787,
-    0.939734014,  -0.898693403, -0.682942853, 0.522115493,  0.290743643,
-    -2.744873176, -0.650948914, -0.825822157, 0.036289286,  2.35851884,
-    -2.066822543, 1.706630528,  2.397176118,  -1.830931368, -1.26049062,
-    0.563661143,  -1.206870531, 1.998078103,  -0.511818947, -2.707018818,
-    -1.163787354, 0.483297455,  0.425049209,  -0.835398937, -0.358465006,
-    1.169932505,  -2.894782496, 1.659873843,  1.588417846,  0.583777019,
-    1.915019154,  2.343132919,  1.96863736,   0.745661389,  1.406556589,
-    -1.508826165, -1.142917171, 1.762597046,  0.56987792,   1.375523874,
-    -1.938998091, 0.40693206,   0.238203489,  0.976584803,  2.627005767,
-    -0.709392163, 1.123145034,  1.028645838,  -0.001941209, -0.622606759,
-    0.484872501,  0.774228962,  -2.34688901,  0.999128756,  0.46127639,
-    -0.415641465, -0.805967562, 4.03481652,   -1.919844046, -0.116683876,
-    -0.175496456, -1.019130486, -0.990293967, 2.146444112,  -1.292401591,
-    -0.840575448, 2.060081962,  -1.788947083, 2.530081414,  3.230873458,
-    0.160244772,  -0.530951483, 0.72794049,   -2.260466314, 0.652572945,
-    0.318972501,  1.291042044,  -0.07155115,  -2.798517996, 4.095462522,
-    1.619520692,  -0.417640937, 0.008003157,  1.726111894,  -0.816381331,
-    -0.104527854, -1.074706544, -1.124537415, -0.186036562, 0.473611018,
-    -4.162339414, -3.035651066, 1.422241431,  1.084445861,  0.364127369,
-    -3.160183506, 0.59928583,   -2.441105329, 1.173114846,  2.333246387,
-    -0.387920297, -2.223338459, 1.619011811,  0.401000065,  -0.381396115,
-    -2.280394319, -1.354751273, -0.48520788,  1.309242675,  0.7322256,
-    0.142046401,  2.255346027,  -3.184031724, -1.116550968, -1.310222827,
-    0.704560642,  -0.673482634, -0.092914183, -0.112176567, 1.049523962,
-    0.584804148,  -1.440454665, -0.164614946, -0.086822089, 0.336898011,
-    -0.077126214, -1.245431979, 2.401252597,  0.177680644,  0.437918889,
-    1.902307217,  1.988220333,  -1.362948647, -0.200077393, 3.590309097,
-    0.858918798,  -0.019623438, 0.498353046,  -2.103343871, -0.000154881,
-    1.557796982,  -0.43546615,  2.1832457,    0.152692029,  0.595102768,
-    1.79166552,   1.454043,     -0.185638046, 0.589250605,  -0.272087614,
-    1.884411299,  0.012884378,  0.710016883,  2.485399061,  -1.308911069,
-    0.104209337,  0.033886585,  0.78454266,   2.369837945,  -0.960717052,
-    0.371822457,  2.248967927,  0.55992114,   2.237446929,  -0.824086218,
-    2.246105985,  3.17607526,   1.2454744,    0.283162021,  -1.369623558,
-    0.702482598,  -0.937351797, 1.299665639,  -0.640907521, -0.620065725,
-    0.945243243,  -1.037456257, -0.698398585, 0.078864991,  2.988747365,
-    -0.308089093, 1.017701787,  -1.425564592, -0.23549295,  -0.645751715,
-    -1.433667028, -1.072376149, 2.121220993,  -0.579776331, -1.643443172,
-    2.085982482,  -1.923063201, -0.321205048, 0.507524295,  -2.712482382,
-    -3.064074894, 0.339948091,  -0.962430717, 0.507077451,  1.699442501,
-    1.449384543,  0.725804724,  0.602611108,  0.469401636,  0.529803224,
-    0.262635649,  -3.610754294, 0.323158222,  0.029692017,  -1.178334135,
-    -0.270242172, 0.898974098,  -0.134509516, -2.357446925, 0.856909527,
-    1.364070448,  0.558424506,  -0.356538345, -0.753820362, -0.379182667,
-    -1.740609329, -0.058055642, 1.554925386,  1.418515953,  1.287007965,
-    0.448858743,  -1.687837774, 1.050009195,  0.522292321,  3.025384263,
-    -0.280388008, -0.79212641,  2.458800809,  1.313987701,  0.703108899,
-    -1.397646223, -1.582677315, 1.312790017,  -1.486910204, 0.633946741,
-    -0.256881439, 2.067897303,  2.481722326,  -0.84814557,  0.28732032,
-    -0.284214887, -0.041828072, -1.161012902, -1.70169471,  -0.074733256,
-    0.125735971,  1.739011015,  -1.255194305, -1.058735728, -0.973651084,
-    0.488282848,  0.934815237,  0.486467365,  -1.565648596, 3.441606598,
-    0.211683453,  -2.283196984, 0.184270804,  0.417195623,  -1.405034279,
-    -0.076054368, 1.584783224,  -0.003135455, 1.409339729,  -0.715932146,
-    -2.640649556, 1.525658051,  3.042343981,  -1.373483909, 1.572633691,
-    1.018089415,  3.971245117,  0.441086315,  -0.062926057, 2.286728394,
-    0.570473322,  -0.681163756, 0.650330916,  0.922985516,  -0.630953637,
-    -2.533212851, 2.592750505,  -0.045107404, -1.392494488, -2.797720532,
-    1.020783918,  1.671664788,  -0.235019709, 0.744736002,  -1.517601615,
-    2.256849153,  2.090523962,  2.60398147,   0.378676667,  -1.449549584,
-    1.092139771,  2.899815325,  -1.832637271, -2.776032219, 1.03135609,
-    -0.372958538, -1.090211998, 1.248494658,  0.58448001,   0.688642347,
-    -0.754263922, -2.885575712, 0.919086543,  -3.841311531, -1.75178116,
-    3.045766472,  2.589631709,  3.121029595,  2.073435349,  0.620360664,
-    -0.541385749, -0.042689635, -2.379938645, -0.057167837, -3.246115673,
-    0.820910153,  -0.384768879, 0.020306601,  1.186834386,  0.210583953,
-    0.869384476,  -0.768637368, 0.009513777,  -0.891858299, 1.607001697,
-    0.286264357,  0.132137018,  -2.674998467, 0.257006206,  0.677868603,
-    2.601310752,  -0.144490105, 0.664659897,  -2.085568319, 2.28760246,
-    3.344528752,  1.729666589,  1.717457486,  -0.125653334, 4.467710331,
-    2.087064038,  0.367153221,  -1.061759864, 0.390129963,  1.469903071,
-    2.394681952,  -1.149315042, 2.266347626,  1.030153451,  -0.087997232,
-    -1.660320676, 0.202804671,  2.816287157,  3.632231121,  2.64266144,
-    1.068537672,  -0.168980476, 2.147994656,  0.34399136,   1.780024187,
-    1.593336942,  2.155929444,  1.579955892,  -1.241889337, 0.077217715,
-    0.648339359,  -1.057207702, 0.654047371,  -1.405485163, 0.451083249,
-    2.922196733,  -1.161332255, 0.634733978,  -0.052460799, 1.014153865,
-    1.824880453,  -0.049095127, -1.766937441, 0.9970873,    -0.553968497,
-    0.507521904,  -0.976342078, 1.022960964,  -1.879712418, 0.612033994,
-    -1.601029481, 3.605605168,  1.085561287,  1.791048571,  2.919575227,
-    -2.783826825, 0.746994973,  1.612013384,  -2.114449766, 1.521916866};
-
-const float ACCELEROMETER_DATA[MOTION_SENSOR_AXIS_NUM][IMU_DATA_SIZE] = {
-    {-9.7563F,     29.18325888,  68.1828354,   66.58149024,  69.71237136,
-     75.1483278,   80.00262972,  84.37581,     88.12425024,  89.56043424,
-     89.56043424,  90.93198996,  92.32508844,  93.72536784,  93.91925268,
-     93.77563428,  93.61765404,  93.44531196,  93.39504552,  93.35914092,
-     93.33759816,  93.30169356,  93.25142712,  93.19397976,  93.15807516,
-     93.10780872,  93.15807516,  93.20116068,  93.30169356,  93.38068368,
-     93.40222644,  93.48839748,  93.56020668,  93.6751014,   93.711006,
-     93.81153888,  93.86180532,  93.9623382,   93.9982428,   94.070052,
-     94.06287108,  94.1418612,   94.20648948,  94.24239408,  94.2854796,
-     94.3931934,   94.37883156,  94.49372628,  94.50808812,  94.58707824,
-     94.55117364,  94.59425916,  94.65170652,  94.68761112,  94.68761112,
-     94.7163348,   94.73787756,  94.72351572,  94.63016376,  94.62298284,
-     94.58707824,  94.58707824,  94.5009072,   94.42191708,  94.36446972,
-     94.33574604,  94.20648948,  94.1059566,   94.04850924,  93.9264336,
-     93.91925268,  93.87616716,  93.73972968,  93.64637772,  93.55302576,
-     93.48839748,  93.35914092,  93.2442462,   93.16525608,  93.05036136,
-     93.0647232,   92.9570094,   92.8852002,   92.84211468,  92.7774864,
-     92.72003904,  92.67695352,  92.61950616,  92.61232524,  92.61950616,
-     92.64822984,  92.64822984,  92.64104892,  92.69131536,  92.82057192,
-     92.86365744,  92.91392388,  93.04318044,  93.10780872,  93.21552252,
-     93.22988436,  93.41658828,  93.6032922,   93.7469106,   93.98388096,
-     94.20648948,  94.45782168,  94.73069664,  94.94612424,  95.26208472,
-     95.26208472,  95.5421406,   95.84373924,  96.17406156,  96.41103192,
-     96.7269924,   96.97114368,  97.2655614,   97.53843636,  97.74668304,
-     97.73950212,  97.93338696,  98.14881456,  98.31397572,  98.38578492,
-     98.47195596,  98.53658424,  98.53658424,  98.53658424,  98.44323228,
-     98.42168952,  98.36424216,  98.22780468,  98.0554626,   97.96211064,
-     97.76104488,  97.60306464,  97.45944624,  97.301466,    97.09321932,
-     97.10040024,  96.85624896,  96.71263056,  96.50438388,  96.37512732,
-     96.16688064,  96.05916684,  95.9011866,   95.80065372,  95.6498544,
-     95.66421624,  95.49187416,  95.36979852,  95.2908084,   95.21181828,
-     95.1112854,   94.967667,    94.80250584,  94.67324928,  94.5368118,
-     94.55117364,  94.35010788,  94.17058488,  94.0341474,   93.8187198,
-     93.63201588,  93.3878646,   93.1365324,   92.98573308,  92.813391,
-     92.7774864,   92.65541076,  92.60514432,  92.47588776,  92.43280224,
-     92.36817396,  92.36099304,  92.37535488,  92.41125948,  92.454345,
-     92.48306868,  92.53333512,  92.633868,    92.71285812,  92.813391,
-     92.92828572,  93.05036136,  93.07908504,  93.12935148,  93.21552252,
-     93.2442462,   93.22270344,  93.21552252,  93.12217056,  93.08626596,
-     92.9570094,   92.79902916,  92.66259168,  92.48306868,  92.3107266,
-     92.29636476,  92.15274636,  91.90141416,  91.67880564,  91.46337804,
-     91.26231228,  91.01098008,  90.80991432,  90.66629592,  90.43650648,
-     90.45804924,  90.19953612,  89.99847036,  89.81894736,  89.581977,
-     89.33782572,  89.21575008,  88.99314156,  88.76335212,  88.54792452,
-     88.59101004,  88.31813508,  88.09552656,  87.8585562,   87.607224,
-     87.4636056,   87.26972076,  87.18354972,  87.02556948,  86.9250366,
-     86.93939844,  86.86040832,  86.75269452,  86.69524716,  86.58753336,
-     86.50854324,  86.40801036,  86.3146584,   86.25003012,  86.0633262,
-     86.09204988,  85.96997424,  85.79763216,  85.65401376,  85.44576708,
-     85.23033948,  85.10826384,  84.84975072,  84.6630468,   84.42607644,
-     84.41889552,  84.15320148,  83.93059296,  83.65053708,  83.4063858,
-     83.17659636,  82.87499772,  82.67393196,  82.40823792,  82.16408664,
-     82.19281032,  81.91275444,  81.682965,    81.4316328,   81.26647164,
-     81.0366822,   80.92178748,  80.72790264,  80.56274148,  80.41912308,
-     80.38321848,  80.25396192,  80.14624812,  79.98826788,  79.80156396,
-     79.67948832,  79.57895544,  79.40661336,  79.26299496,  79.14091932,
-     79.11219564,  78.92549172,  78.73160688,  78.5592648,   78.1284096,
-     77.733459,    77.36723208,  77.00818608,  76.56296904,  76.14647568,
-     76.13211384,  75.74434416,  75.27040344,  74.88981468,  74.32970292,
-     73.79113392,  73.23820308,  72.66372948,  72.11079864,  71.60813424,
-     71.60813424,  71.091108,    70.552539,    70.07859828,  68.95119384,
-     67.65144732,  66.3157962,   64.987326,    63.68757948,  62.3662902,
-     62.39501388,  60.75776412,  59.19232356,  57.57661656,  55.9752714,
-     54.3236598,   52.73667648,  51.22868328,  50.18744988,  49.17494016,
-     49.17494016,  48.112164,    47.09965428,  46.02251628,  44.98128288,
-     43.89696396,  42.87727332,  41.81449716,  40.75890192,  39.72484944,
-     39.75357312,  38.58308316,  37.4125932,   36.263646,    35.10751788,
-     33.90112332,  32.72345244,  31.53141972,  30.40401528,  29.24788716,
-     29.23352532,  28.10612088,  26.9643546,   25.75796004,  24.57310824,
-     23.45288472,  22.28239476,  21.10472388,  19.99168128,  18.8140104,
-     18.76374396,  17.65070136,  16.48739232,  15.33844512,  14.11768872,
-     12.97592244,  11.84133708,  10.6636662,   8.62428492,   8.03544948,
-     8.0426304,    7.5040614,    7.01575884,   6.52745628,   6.03915372,
-     5.48622288,   4.96919664,   4.49525592,   3.9854106,    3.41811792,
-     3.47556528,   2.81492064,   2.18299968,   1.59416424,   0.95506236,
-     0.33032232,   -0.31596048,  -0.88325316,  -1.53671688,  -2.154276,
-     -2.16145692,  -2.78619696,  -3.21705216,  -3.50428896,  -3.8417922,
-     -4.22238096,  -4.55270328,  -4.94047296,  -5.27079528,  -5.565213,
-     -5.59393668,  -5.93862084,  -6.29766684,  -6.63517008,  -6.95113056,
-     -7.30299564,  -7.60459428,  -7.96364028,  -8.26523892,  -8.66737044,
-     -8.71763688,  -9.2633868,   -8.95460724,  -9.5506236,   -10.09637352,
-     -10.67084712, -11.24532072, -11.848518,   -12.4229916,  -13.0692744,
-     -13.06209348, -13.63656708, -14.30439264, -14.98658004, -15.67594836,
-     -16.31505024, -17.01159948, -17.72251056, -18.36161244, -19.0653426,
-     -19.03661892, -19.51774056, -19.9629576,  -20.38663188, -20.80312524,
-     -21.26988504, -21.67201656, -22.11005268, -22.55526972, -23.02202952,
-     -23.0148486,  -23.0148486,  -22.95022032, -22.93585848, -22.95740124,
-     -22.88559204, -22.87841112, -22.84250652, -22.799421,   -22.77787824,
-     -22.799421,   -22.73479272, -22.75633548, -22.74197364, -22.69888812,
-     -22.6917072,  -22.63425984, -22.59835524, -22.59835524, -22.52654604,
-     -22.5480888,  -22.5121842,  -22.49064144, -22.45473684, -22.44755592,
-     -22.39728948, -22.37574672, -22.34702304, -22.31829936, -22.26803292,
-     -22.2967566,  -22.260852,   -22.28239476, -22.27521384, -22.21058556,
-     -22.1531382,  -22.13159544, -22.12441452, -22.10287176, -22.1172336,
-     -22.11005268, -22.06696716, -21.99515796, -22.02388164, -21.96643428,
-     -21.94489152, -21.94489152, -21.88744416, -21.90898692, -21.85872048,
-     -21.85153956, -21.81563496, -21.78691128, -21.7581876,  -21.75100668,
-     -21.70792116, -21.67201656, -21.66483564, -21.62893104, -21.38477976,
-     -21.3991416,  -21.34887516, -21.3273324,  -21.33451332, -21.26988504,
-     -21.26270412, -21.24116136, -21.19807584, -21.24116136, -21.16217124,
-     -21.19807584, -21.16217124, -21.09754296, -21.08318112, -21.08318112,
-     -21.04727652, -21.0400956,  -21.01855284, -20.97546732, -20.9682864,
-     -20.98264824, -20.98982916, -20.93956272, -20.91083904, -20.88929628,
-     -20.8605726,  -20.83902984, -20.83902984, -20.7887634,  -20.77440156,
-     -20.77440156, -20.72413512, -20.7169542,  -20.68823052, -20.6810496,
-     -20.65950684, -20.5733358,  -20.58769764, -20.5733358,  -20.53025028,
-     -20.58051672, -20.55179304, -20.50870752, -20.465622,   -20.50870752,
-     -20.43689832, -20.4297174,  -20.3938128,  -20.3938128,  -20.34354636,
-     -20.37227004, -20.32918452, -20.3220036,  -20.29327992, -20.27173716,
-     -20.24301348, -20.26455624, -20.19274704, -20.17120428, -20.13529968,
-     -20.14966152, -20.1424806,  -20.11375692, -20.07785232, -20.05630956,
-     -20.0706714,  -19.98450036, -20.02040496, -19.9629576,  -19.98450036,
-     -19.98450036, -19.9988622,  -19.95577668, -19.91987208, -19.90551024,
-     -19.89832932, -19.86242472, -19.83370104, -19.84806288, -19.84088196,
-     -19.76907276, -19.79061552, -19.76189184, -19.74753,    -19.73316816,
-     -19.75471092, -19.74753,    -19.76189184, -19.69008264, -19.69008264,
-     -19.70444448, -19.66135896, -19.66853988, -19.61827344, -19.6039116,
-     -19.57518792, -19.58954976, -19.53928332, -19.55364516, -19.51055964,
-     -19.52492148, -19.4602932,  -19.45311228, -19.45311228, -19.43875044,
-     -19.43875044, -19.40284584, -19.33103664, -19.3166748,  -19.3166748,
-     -19.30949388, -19.32385572, -19.30231296, -19.26640836, -19.26640836,
-     -19.23050376, -19.19459916, -19.19459916, -19.16587548, -19.1730564,
-     -19.1730564,  -19.14433272, -19.1371518,  -19.08688536, -19.05816168,
-     -19.05098076, -19.05098076, -19.029438,   -19.029438,   -18.98635248,
-     -18.97917156, -19.01507616, -18.93608604, -18.93608604, -18.93608604,
-     -18.849915,   -18.86427684, -18.83555316, -18.86427684, -18.80682948,
-     -18.85709592, -18.7781058,  -18.79964856, -18.8140104,  -18.78528672,
-     -18.76374396, -18.71347752, -18.69911568, -18.69193476, -18.64166832,
-     -18.64166832, -18.670392,   -18.64884924, -18.61294464, -18.64166832,
-     -18.56985912, -18.51959268, -18.5267736,  -18.50523084, -18.49804992,
-     -18.51241176, -18.48368808, -18.44778348, -18.490869,   -18.4549644,
-     -18.40469796, -18.40469796, -18.40469796, -18.39751704, -18.36161244,
-     -18.34006968, -18.28262232, -18.31852692, -18.28262232, -18.2754414,
-     -18.28262232, -18.2754414,  -18.29698416, -18.30416508, -18.25389864,
-     -18.26107956, -18.2395368,  -18.26107956, -18.21799404, -18.23235588,
-     -18.2036322,  -18.16054668, -18.14618484, -18.10309932, -18.12464208,
-     -18.11746116, -18.10309932, -18.08873748, -18.07437564, -18.03129012,
-     -18.03129012, -18.03847104, -18.00974736, -17.99538552, -17.95948092,
-     -17.97384276, -17.9523,     -17.96666184, -17.93075724, -17.90921448,
-     -17.89485264, -17.90203356, -17.83740528, -17.8445862,  -17.8086816,
-     -17.83740528, -17.83740528, -17.8086816,  -17.772777,   -17.75841516,
-     -17.70814872, -17.7009678,  -17.68660596, -17.71532964, -17.65788228,
-     -17.69378688, -17.65788228, -17.62197768, -17.65070136, -17.60043492,
-     -17.61479676, -17.5573494,  -17.58607308, -17.57889216, -17.51426388,
-     -17.52862572, -17.50708296, -17.52862572, -17.49272112, -17.50708296,
-     -17.47117836, -17.4496356,  -17.44245468, -17.413731,   -17.39218824,
-     -17.40655008, -17.39218824, -17.34910272, -17.35628364, -17.33474088,
-     -17.34910272, -17.34910272, -17.29883628, -17.3060172,  -17.2701126,
-     -17.29883628, -17.25575076, -17.25575076, -17.234208,   -17.234208,
-     -17.17676064, -17.19112248, -17.14085604, -17.1623988,  -17.14803696,
-     -17.14803696, -17.11213236, -17.14085604, -17.07622776, -17.09777052,
-     -17.04750408, -17.01159948, -17.01159948, -16.99005672, -16.99005672,
-     -16.99723764, -16.97569488, -16.96851396, -16.99005672, -16.9110666,
-     -17.01159948, -17.00441856, -16.96851396, -16.9469712,  -16.93260936,
-     -16.92542844, -16.89670476, -16.88952384, -16.88234292, -16.9110666,
-     -16.82489556, -16.86798108, -16.8392574,  -16.81771464, -16.81771464,
-     -16.82489556, -16.78181004, -16.77462912, -16.73872452, -16.74590544,
-     -16.71718176, -16.68845808, -16.71718176, -16.68127716, -16.68127716,
-     -16.65255348, -16.68127716, -16.65255348, -16.61664888, -16.63101072,
-     -16.6238298,  -16.60228704, -16.59510612, -16.53047784, -16.55920152,
-     -16.5520206,  -16.50175416, -16.52329692, -16.47303048, -16.50175416,
-     -16.48739232, -16.46584956, -16.42276404, -16.42994496, -16.4443068,
-     -16.40122128, -16.39404036, -16.4084022,  -16.39404036, -16.36531668,
-     -16.35095484, -16.36531668, -16.336593,   -16.32941208, -16.28632656,
-     -16.31505024, -16.28632656, -16.23606012, -16.24324104, -16.25042196,
-     -16.2288792,  -16.20733644, -16.21451736, -16.20733644, -16.1929746,
-     -16.18579368, -16.13552724, -16.16425092, -16.14988908, -16.13552724,
-     -16.10680356, -16.10680356, -16.07807988, -16.06371804, -16.05653712,
-     -16.0493562,  -16.02063252, -16.02781344, -16.04217528, -16.00627068,
-     -15.98472792, -15.977547,   -15.95600424, -15.92728056, -15.93446148,
-     -15.9416424,  -15.97036608, -15.92009964, -15.89855688, -15.9057378,
-     -15.8698332,  -15.8339286,  -15.8339286,  -15.84829044, -15.8339286,
-     -15.8339286,  -15.85547136, -15.798024,   -15.80520492, -15.78366216,
-     -15.77648124, -15.76930032, -15.73339572, -15.74057664, -15.71903388,
-     -15.74775756, -15.70467204, -15.7621194,  -15.73339572, -15.73339572,
-     -15.73339572, -15.70467204, -15.71903388, -15.69749112, -15.63286284,
-     -15.68312928, -15.64722468, -15.66158652, -15.62568192, -15.58977732,
-     -15.62568192, -15.59695824, -15.58977732, -15.56823456, -15.63286284,
-     -15.55387272, -15.5466918,  -15.55387272, -15.53232996, -15.5107872,
-     -15.51796812, -15.52514904, -15.49642536, -15.45333984, -15.42461616,
-     -15.45333984, -15.438978,   -15.38871156, -15.39589248, -15.41743524,
-     -15.34562604, -15.37434972, -15.30972144, -15.33844512, -15.3312642,
-     -15.32408328, -15.30972144, -15.3312642,  -15.28099776, -15.2953596,
-     -15.30254052, -15.24509316, -15.23073132, -15.259455,   -15.20918856,
-     -15.23073132, -15.23073132, -15.20200764, -15.18046488, -15.20200764,
-     -15.17328396, -15.12301752, -15.1517412,  -15.18046488, -15.13019844,
-     -15.14456028, -15.13019844, -15.12301752, -15.08711292, -15.05838924,
-     -15.05120832, -15.07275108, -15.05838924, -15.079932,   -15.01530372,
-     -15.00094188, -15.01530372, -15.02966556, -14.98658004, -15.01530372,
-     -14.9722182,  -14.99376096, -14.94349452, -14.96503728, -14.94349452,
-     -14.98658004, -14.91477084, -14.92195176, -14.87168532, -14.8645044,
-     -14.85732348, -14.85732348, -14.81423796, -14.84296164, -14.82141888,
-     -14.8285998,  -14.80705704, -14.7926952,  -14.76397152, -14.72806692,
-     -14.77833336, -14.7567906,  -14.71370508, -14.72806692, -14.720886,
-     -14.69216232, -14.70652416, -14.67780048, -14.6849814,  -14.67780048,
-     -14.66343864, -14.67780048, -14.65625772, -14.63471496, -14.59881036,
-     -14.62753404, -14.62035312, -14.62753404, -14.6131722,  -14.55572484,
-     -14.59881036, -14.65625772, -14.6131722,  -14.62035312, -14.59881036,
-     -14.57008668, -14.62035312, -14.56290576, -14.53418208, -14.54854392,
-     -14.55572484, -14.541363,   -14.5054584,  -14.51982024, -14.5054584,
-     -14.51263932, -14.49827748, -14.47673472, -14.49109656, -14.46237288,
-     -14.46237288, -14.44083012, -14.42646828, -14.41210644, -14.41210644,
-     -14.41210644, -14.4336492,  -14.3977446,  -14.3977446,  -14.34747816,
-     -14.34747816, -14.36184,    -14.31875448, -14.33311632, -14.31875448,
-     -14.31875448, -14.29721172, -14.31875448, -14.2541262,  -14.2900308,
-     -14.2541262,  -14.28284988, -14.2900308,  -14.20385976, -14.2182216,
-     -14.23258344, -14.23976436, -14.24694528, -14.23976436, -14.182317,
-     -14.18949792, -14.1464124,  -14.13923148, -14.16795516, -14.15359332,
-     -14.13923148, -14.13923148, -14.08896504, -14.09614596, -14.1105078,
-     -14.11768872, -14.06742228, -14.08178412, -14.1105078,  -14.08178412,
-     -14.08896504, -14.05306044, -14.08896504, -14.08178412, -13.99561308,
-     -14.00997492, -14.01715584, -13.99561308, -13.94534664, -13.98125124,
-     -13.97407032, -14.002794,   -13.9668894,  -13.9309848,  -13.88789928,
-     -13.95252756, -13.9309848,  -13.92380388, -13.90944204, -13.8950802,
-     -13.88789928, -13.91662296, -13.85199468, -13.87353744, -13.8950802,
-     -13.81609008, -13.83763284, -13.823271,   -13.79454732, -13.81609008,
-     -13.823271,   -13.80890916, -13.80172824, -13.76582364, -13.7514618,
-     -13.80172824, -13.75864272, -13.73709996, -13.74428088, -13.7155572,
-     -13.70119536, -13.72273812, -13.6796526,  -13.70837628, -13.7155572,
-     -13.70119536, -13.69401444, -13.62938616, -13.65810984, -13.67247168,
-     -13.65092892, -13.61502432, -13.62938616, -13.62220524, -13.65092892,
-     -13.65092892, -13.61502432, -13.60066248, -13.63656708, -13.65092892,
-     -13.60066248, -13.61502432, -13.61502432, -13.62220524, -13.55757696,
-     -13.56475788, -13.55039604, -13.56475788, -13.5360342,  -13.52885328,
-     -13.54321512, -13.51449144, -13.5001296,  -13.52885328, -13.49294868,
-     -13.50731052, -13.48576776, -13.47140592, -13.44268224, -13.464225,
-     -13.44268224, -13.44268224, -13.43550132, -13.41395856, -13.44268224,
-     -13.40677764, -13.42113948, -13.36369212, -13.40677764, -13.3565112,
-     -13.34933028, -13.34214936, -13.3565112,  -13.34214936, -13.3565112,
-     -13.30624476, -13.32778752, -13.31342568, -13.27752108, -13.3206066,
-     -13.32778752, -13.30624476, -13.284702,   -13.29906384, -13.2487974,
-     -13.25597832, -13.24161648, -13.22007372, -13.2487974,  -13.24161648,
-     -13.22725464, -13.24161648, -13.19853096, -13.19135004, -13.20571188,
-     -13.23443556, -13.1769882,  -13.18416912, -13.16980728, -13.16262636,
-     -13.19135004, -13.16980728, -13.16980728, -13.16262636, -13.15544544,
-     -13.11235992, -13.09799808, -13.09081716, -13.1410836,  -13.09799808,
-     -13.09799808, -13.08363624, -13.09081716, -13.07645532, -13.05491256,
-     -13.09799808, -13.07645532, -13.05491256, -13.04055072, -12.99028428,
-     -13.04773164, -13.0333698,  -13.0333698,  -12.98310336, -13.01182704,
-     -12.9615606,  -12.9974652,  -12.96874152, -12.96874152, -12.95437968,
-     -12.94719876, -12.9615606,  -12.94719876, -12.91129416, -12.94719876,
-     -12.94001784, -12.89693232, -12.87538956, -12.8538468,  -12.87538956,
-     -12.82512312, -12.925656,   -12.87538956, -12.84666588, -12.89693232,
-     -12.8538468,  -12.83948496, -12.81076128, -12.82512312, -12.77485668,
-     -12.81076128, -12.78921852, -12.8179422,  -12.78921852, -12.73177116,
-     -12.77485668, -12.76049484, -12.73895208, -12.746133,   -12.75331392,
-     -12.746133,   -12.73895208, -12.72459024, -12.7102284,  -12.70304748,
-     -12.71740932, -12.68150472, -12.7102284,  -12.71740932, -12.75331392,
-     -12.6743238,  -12.70304748, -12.68868564, -12.65996196, -12.68868564,
-     -12.65996196, -12.68150472, -12.60969552, -12.6743238,  -12.60969552,
-     -12.68150472, -12.58097184, -12.6025146,  -12.59533368, -12.6025146,
-     -12.60969552, -12.57379092, -12.56661,    -12.59533368, -12.55942908,
-     -12.57379092, -12.53788632, -12.5307054,  -12.55224816, -12.55224816,
-     -12.4948008,  -12.54506724, -12.50916264, -12.5307054,  -12.48043896,
-     -12.4948008,  -12.46607712, -12.43735344, -12.46607712, -12.43017252,
-     -12.48761988, -12.45171528, -12.45171528, -12.43017252, -12.43735344,
-     -12.43735344, -12.43017252, -12.4229916,  -12.39426792, -12.35836332,
-     -12.40862976, -12.40144884, -12.41581068, -12.387087,   -12.40862976,
-     -12.33682056, -12.3511824,  -12.37990608, -12.35836332, -12.3511824,
-     -12.33682056, -12.34400148, -12.32963964, -12.33682056, -12.28655412,
-     -12.32245872, -12.29373504, -12.3152778,  -12.30809688, -12.26501136,
-     -12.23628768, -12.25064952, -12.22910676, -12.26501136, -12.22910676,
-     -12.20038308, -12.22910676, -12.22910676, -12.21474492, -12.207564,
-     -12.17884032, -12.17884032, -12.1716594,  -12.1716594,  -12.1716594,
-     -12.15729756, -12.15729756, -12.15011664, -12.15729756, -12.14293572,
-     -12.12857388, -12.16447848, -12.15011664, -12.08548836, -12.11421204,
-     -12.0998502,  -12.09266928, -12.0998502,  -12.10703112, -12.0998502,
-     -12.08548836, -12.07112652, -12.07112652, -12.05676468, -12.05676468,
-     -12.05676468, -12.03522192, -12.04240284, -12.04958376, -12.04958376,
-     -12.028041,   -11.99931732, -12.01367916, -11.99931732, -11.94905088,
-     -11.9562318,  -11.94186996, -11.98495548, -11.98495548, -11.9562318,
-     -11.9562318,  -11.91314628, -11.93468904, -11.93468904, -11.94186996,
-     -11.91314628, -11.91314628, -11.86287984, -11.89878444, -11.91314628,
-     -11.85569892, -11.87724168, -11.81979432, -11.82697524, -11.84133708,
-     -11.87006076, -11.87006076, -11.848518,   -11.8126134,  -11.79825156,
-     -11.8126134,  -11.82697524, -11.82697524, -11.79825156, -11.79107064,
-     -11.8126134,  -11.85569892, -11.848518,   -11.78388972, -11.7767088,
-     -11.79107064, -11.78388972, -11.78388972, -11.76952788, -11.79107064,
-     -11.76234696, -11.7767088,  -11.76234696, -11.72644236, -11.72644236,
-     -11.74798512, -11.72644236, -11.71926144, -11.7048996,  -11.71208052,
-     -11.668995,   -11.71208052, -11.71208052, -11.69771868, -11.71926144,
-     -11.67617592, -11.65463316, -11.65463316, -11.64027132, -11.64027132,
-     -11.61872856, -11.64745224, -11.65463316, -11.61154764, -11.58282396,
-     -11.5971858,  -11.61872856, -11.56846212, -11.57564304, -11.59000488,
-     -11.57564304, -11.5971858,  -11.51101476, -11.55410028, -11.54691936,
-     -11.5612812,  -11.51101476, -11.5612812,  -11.53973844, -11.5253766,
-     -11.55410028, -11.51819568, -11.53973844, -11.5253766,  -11.51819568,
-     -11.51819568, -11.47511016, -11.489472,   -11.46792924, -11.489472,
-     -11.47511016, -11.489472,   -11.49665292, -11.49665292, -11.46074832,
-     -11.4535674,  -11.46792924, -11.44638648, -11.44638648, -11.44638648,
-     -11.42484372, -11.44638648, -11.42484372, -11.4176628,  -11.38893912,
-     -11.37457728, -11.36739636, -11.40330096, -11.42484372, -11.37457728,
-     -11.38893912, -11.3817582,  -11.36739636, -11.35303452, -11.35303452,
-     -11.32431084, -11.31712992, -11.30276808, -11.30276808, -11.33149176,
-     -11.33867268, -11.29558716, -11.29558716, -11.28840624, -11.28122532,
-     -11.31712992, -11.28840624, -11.25250164, -11.24532072, -11.25968256,
-     -11.25968256, -11.24532072, -11.29558716, -11.2740444,  -11.2022352,
-     -11.2022352,  -11.22377796, -11.19505428, -11.18787336, -11.19505428,
-     -11.15914968, -11.17351152, -11.20941612, -11.17351152, -11.1663306,
-     -11.18787336, -11.18069244, -11.15196876, -11.15196876, -11.17351152,
-     -11.13760692, -11.13760692, -11.14478784, -11.130426,   -11.14478784,
-     -11.13760692, -11.12324508, -11.130426,   -11.130426,   -11.06579772,
-     -11.08734048, -11.08734048, -11.07297864, -11.03707404, -11.0586168,
-     -11.07297864, -11.05143588, -11.05143588, -11.04425496, -11.04425496,
-     -11.07297864, -11.02989312, -11.06579772, -11.0227122,  -11.0227122,
-     -11.00116944, -10.96526484, -10.99398852, -10.93654116, -10.96526484,
-     -11.00835036, -11.00835036, -10.9868076,  -11.00835036, -10.99398852,
-     -11.00116944, -10.97962668, -10.950903,   -10.92936024, -10.950903,
-     -10.9868076,  -10.9149984,  -10.96526484, -10.93654116, -10.950903,
-     -10.92217932, -10.94372208, -10.90063656, -10.8790938,  -10.95808392,
-     -10.90781748, -10.93654116, -10.88627472, -10.85755104, -10.89345564,
-     -10.85755104, -10.86473196, -10.82882736, -10.8431892,  -10.85037012,
-     -10.86473196, -10.85755104, -10.85037012, -10.82164644, -10.83600828,
-     -10.81446552, -10.75701816, -10.80010368, -10.77138,    -10.80010368,
-     -10.76419908, -10.8072846,  -10.76419908, -10.76419908, -10.78574184,
-     -10.76419908, -10.76419908, -10.75701816, -10.75701816, -10.72829448,
-     -10.72829448, -10.74265632, -10.74265632, -10.7354754,  -10.72829448,
-     -10.6636662,  -10.71393264, -10.68520896, -10.6995708,  -10.67084712,
-     -10.68520896, -10.65648528, -10.6277616,  -10.6636662,  -10.6995708,
-     -10.67802804, -10.64212344, -10.6636662,  -10.64930436, -10.64212344,
-     -10.62058068, -10.64212344, -10.57749516, -10.591857,   -10.6277616,
-     -10.61339976, -10.57749516, -10.59903792, -10.61339976, -10.62058068,
-     -10.57749516, -10.57031424, -10.60621884, -10.54877148, -10.56313332,
-     -10.54877148, -10.5559524,  -10.53440964, -10.52722872, -10.53440964,
-     -10.52722872, -10.5559524,  -10.47696228, -10.4841432,  -10.5200478,
-     -10.46260044, -10.49132412, -10.4482386,  -10.46978136, -10.47696228,
-     -10.46260044, -10.42669584, -10.44105768, -10.45541952, -10.46260044,
-     -10.412334,   -10.40515308, -10.44105768, -10.4482386,  -10.39797216,
-     -10.40515308, -10.35488664, -10.39797216, -10.35488664, -10.41951492,
-     -10.3764294,  -10.36206756, -10.34770572, -10.33334388, -10.38361032,
-     -10.3405248,  -10.36206756, -10.33334388, -10.36924848, -10.31898204,
-     -10.29025836, -10.3405248,  -10.33334388, -10.3046202,  -10.35488664,
-     -10.29743928, -10.33334388, -10.32616296, -10.32616296, -10.28307744,
-     -10.29743928, -10.27589652, -10.29743928, -10.26153468, -10.29743928,
-     -10.2687156,  -10.27589652, -10.23999192, -10.25435376, -10.1969064,
-     -10.23999192, -10.23999192, -10.21126824, -10.22563008, -10.21126824,
-     -10.23999192, -10.17536364, -10.17536364, -10.21126824, -10.18972548,
-     -10.18972548, -10.1969064,  -10.16818272, -10.15382088, -10.1610018,
-     -10.1610018,  -10.16818272, -10.1610018,  -10.16818272, -10.1610018,
-     -10.16818272, -10.1250972,  -10.11791628, -10.15382088, -10.14663996,
-     -10.10355444, -10.13945904, -10.13945904, -10.08201168, -10.14663996,
-     -10.0891926,  -10.10355444, -10.08201168, -10.06764984, -10.053288,
-     -10.04610708, -10.04610708, -10.053288,   -10.02456432, -9.9814788,
-     -10.01020248, -10.03892616, -10.0173834,  -9.98865972,  -10.0173834,
-     -9.99584064,  -10.01020248, -10.0173834,  -9.97429788,  -10.0173834,
-     -9.99584064,  -9.9814788,   -9.99584064,  -9.95275512,  -9.95993604,
-     -9.97429788,  -9.93121236,  -9.95993604,  -9.95275512,  -9.95993604,
-     -9.9455742,   -9.93121236,  -9.89530776,  -9.93839328,  -9.91685052,
-     -9.90248868,  -9.9096696,   -9.85222224,  -9.9096696,   -9.85222224,
-     -9.88812684,  -9.85940316,  -9.83067948,  -9.86658408,  -9.84504132,
-     -9.88812684,  -9.86658408,  -9.83067948,  -9.8378604,   -9.80913672,
-     -9.83067948,  -9.8378604,   -9.8378604,   -9.82349856,  -9.78759396,
-     -9.82349856,  -9.77323212,  -9.78041304,  -9.78041304,  -9.77323212,
-     -9.7660512,   -9.75168936,  -9.75168936,  -9.77323212,  -9.74450844,
-     -9.75168936,  -9.70860384,  -9.7301466,   -9.74450844,  -9.71578476,
-     -9.72296568,  -9.70142292,  -9.75887028,  -9.66551832,  -9.694242,
-     -9.70860384,  -9.68706108,  -9.66551832,  -9.70860384,  -9.67269924,
-     -9.64397556,  -9.65115648,  -9.67988016,  -9.62961372,  -9.61525188,
-     -9.60807096,  -9.60807096,  -9.6224328,   -9.63679464,  -9.60089004,
-     -9.60089004,  -9.61525188,  -9.57216636,  -9.55780452,  -9.54344268,
-     -9.56498544,  -9.54344268,  -9.53626176,  -9.57934728,  -9.52908084,
-     -9.54344268,  -9.5506236,   -9.49317624,  -9.54344268,  -9.55780452,
-     -9.52189992,  -9.53626176,  -9.50035716,  -9.47163348,  -9.46445256,
-     -9.4429098,   -9.46445256,  -9.45009072,  -9.47163348,  -9.42136704,
-     -9.45727164,  -9.43572888,  -9.4429098,   -9.4429098,   -9.4429098,
-     -9.43572888,  -9.45727164,  -9.38546244,  -9.41418612,  -9.41418612,
-     -9.39264336,  -9.39264336,  -9.39982428,  -9.37828152,  -9.3711006,
-     -9.37828152,  -9.3711006,   -9.36391968,  -9.36391968,  -9.34955784,
-     -9.34955784,  -9.34237692,  -9.34955784,  -9.29211048,  -9.32083416,
-     -9.30647232,  -9.24902496,  -9.2992914,   -9.2992914,   -9.29211048,
-     -9.27056772,  -9.27056772,  -9.24902496,  -9.24902496,  -9.24184404,
-     -9.18439668,  -9.24902496,  -9.19875852,  -9.24902496,  -9.2274822,
-     -9.2274822,   -9.23466312,  -9.1915776,   -9.19875852,  -9.17721576,
-     -9.20593944,  -9.16285392,  -9.18439668,  -9.1915776,   -9.18439668,
-     -9.17003484,  -9.16285392,  -9.14849208,  -9.155673,    -9.12694932,
-     -9.12694932,  -9.11258748,  -9.12694932,  -9.14131116,  -9.12694932,
-     -9.10540656,  -9.13413024,  -9.1197684,   -9.06232104,  -9.09104472,
-     -9.0838638,   -9.10540656,  -9.07668288,  -9.03359736,  -9.06232104,
-     -9.07668288,  -9.06950196,  -9.02641644,  -9.06232104,  -8.99769276,
-     -9.0120546,   -9.03359736,  -9.01923552,  -8.96896908,  -8.96178816,
-     -8.99051184,  -8.98333092,  -8.95460724,  -8.99051184,  -8.96178816,
-     -8.99051184,  -8.9402454,   -8.96178816,  -8.93306448,  -8.91870264,
-     -8.9402454,   -8.92588356,  -8.91152172,  -8.94742632,  -8.91870264,
-     -8.88997896,  -8.88997896,  -8.8684362,   -8.91152172,  -8.86125528,
-     -8.88997896,  -8.9043408,   -8.87561712,  -8.8325316,   -8.84689344,
-     -8.83971252,  -8.80380792,  -8.81816976,  -8.82535068,  -8.82535068,
-     -8.80380792,  -8.8325316,   -8.7607224,   -8.77508424,  -8.796627,
-     -8.76790332,  -8.77508424,  -8.73199872,  -8.73917964,  -8.7248178,
-     -8.73199872,  -8.73917964,  -8.71763688,  -8.69609412,  -8.73917964,
-     -8.68173228,  -8.70327504,  -8.63146584,  -8.69609412,  -8.6889132,
-     -8.68173228,  -8.6530086,   -8.6530086,   -8.6889132,   -8.63146584,
-     -8.63146584,  -8.617104,    -8.63146584,  -8.617104,    -8.59556124,
-     -8.5811994,   -8.5811994,   -8.59556124,  -8.56683756,  -8.55965664,
-     -8.5452948,   -8.55965664,  -8.51657112,  -8.5452948,   -8.55247572,
-     -8.53093296,  -8.5452948,   -8.50220928,  -8.48066652,  -8.44476192,
-     -8.48784744,  -8.48066652,  -8.4734856,   -8.4734856,   -8.44476192,
-     -8.43040008,  -8.48066652,  -8.45194284,  -8.45194284,  -8.41603824,
-     -8.45194284,  -8.40885732,  -8.40885732,  -8.40885732,  -8.37295272,
-     -8.34422904,  -8.38013364,  -8.38013364,  -8.30832444,  -8.33704812,
-     -8.33704812,  -8.31550536,  -8.30832444,  -8.32268628,  -8.33704812,
-     -8.31550536,  -8.30832444,  -8.30832444,  -8.258058,    -8.258058,
-     -8.30114352,  -8.23651524,  -8.24369616,  -8.23651524,  -8.25087708,
-     -8.23651524,  -8.258058,    -8.25087708,  -8.2221534,   -8.19342972,
-     -8.20061064,  -8.19342972,  -8.19342972,  -8.20061064,  -8.1503442,
-     -8.14316328,  -8.15752512,  -8.1503442,   -8.12880144,  -8.12880144,
-     -8.09289684,  -8.10007776,  -8.10725868,  -8.10007776,  -8.05699224,
-     -8.05699224,  -8.10007776,  -8.05699224,  -8.07135408,  -8.02826856,
-     -8.03544948,  -8.0426304,   -8.04981132,  -8.0067258,   -7.99236396,
-     -7.99954488,  -7.99954488,  -7.9708212,   -7.94927844,  -7.92773568,
-     -7.94927844,  -7.92773568,  -7.94209752,  -7.92773568,  -7.9349166,
-     -7.9349166,   -7.89183108,  -7.89183108,  -7.90619292,  -7.84874556,
-     -7.89183108,  -7.88465016,  -7.84156464,  -7.82002188,  -7.82002188,
-     -7.83438372,  -7.83438372,  -7.76975544,  -7.82002188,  -7.84156464,
-     -7.81284096,  -7.80566004,  -7.76975544,  -7.76257452,  -7.7553936,
-     -7.7553936,   -7.74821268,  -7.74103176,  -7.76257452,  -7.7553936,
-     -7.719489,    -7.73385084,  -7.71230808,  -7.66922256,  -7.719489,
-     -7.67640348,  -7.66922256,  -7.70512716,  -7.66204164,  -7.64049888,
-     -7.64049888,  -7.64049888,  -7.5758706,   -7.63331796,  -7.61895612,
-     -7.58305152,  -7.6117752,   -7.59023244,  -7.6117752,   -7.58305152,
-     -7.56150876,  -7.5758706,   -7.55432784,  -7.53278508,  -7.51842324,
-     -7.53278508,  -7.48251864,  -7.49688048,  -7.48251864,  -7.48969956,
-     -7.4681568,   -7.48251864,  -7.44661404,  -7.43943312,  -7.43943312,
-     -7.41070944,  -7.41789036,  -7.41789036,  -7.38916668,  -7.41070944,
-     -7.36762392,  -7.37480484,  -7.37480484,  -7.33890024,  -7.34608116,
-     -7.34608116,  -7.34608116,  -7.31735748,  -7.33171932,  -7.29581472,
-     -7.2527292,   -7.27427196,  -7.23836736,  -7.28145288,  -7.24554828,
-     -7.22400552,  -7.2527292,   -7.18810092,  -7.2527292,   -7.20246276,
-     -7.19528184,  -7.1450154,   -7.15937724,  -7.11629172,  -7.1450154,
-     -7.15219632,  -7.15219632,  -7.08038712,  -7.10192988,  -7.1091108,
-     -7.1091108,   -7.05166344,  -7.0732062,   -7.06602528,  -7.05884436,
-     -7.02293976,  -7.01575884,  -6.99421608,  -6.98703516,  -6.99421608,
-     -6.95831148,  -6.99421608,  -6.95831148,  -6.97985424,  -6.9654924,
-     -6.92240688,  -6.9295878,   -6.90086412,  -6.90086412,  -6.87214044,
-     -6.85059768,  -6.8577786,   -6.85059768,  -6.83623584,  -6.82905492,
-     -6.79315032,  -6.821874,    -6.79315032,  -6.80033124,  -6.7859694,
-     -6.75724572,  -6.74288388,  -6.73570296,  -6.7141602,   -6.7141602,
-     -6.76442664,  -6.70697928,  -6.7141602,   -6.67107468,  -6.61362732,
-     -6.66389376,  -6.64953192,  -6.62080824,  -6.62798916,  -6.61362732,
-     -6.62080824,  -6.5705418,   -6.59208456,  -6.5705418,   -6.54899904,
-     -6.57772272,  -6.4987326,   -6.51309444,  -6.51309444,  -6.47718984,
-     -6.48437076,  -6.47000892,  -6.4269234,   -6.462828,    -6.45564708,
-     -6.41256156,  -6.41974248,  -6.41256156,  -6.4269234,   -6.36229512,
-     -6.38383788,  -6.3551142,   -6.36947604,  -6.3192096,   -6.34075236,
-     -6.283305,    -6.29766684,  -6.27612408,  -6.27612408,  -6.26176224,
-     -6.24021948,  -6.23303856,  -6.23303856,  -6.18995304,  -6.16841028,
-     -6.22585764,  -6.16841028,  -6.19713396,  -6.14686752,  -6.12532476,
-     -6.15404844,  -6.103782,    -6.12532476,  -6.05351556,  -6.08942016,
-     -6.06069648,  -6.08223924,  -6.0319728,   -6.04633464,  -6.01043004,
-     -6.03915372,  -5.96734452,  -5.95298268,  -5.93862084,  -5.94580176,
-     -5.90271624,  -5.924259,    -5.8883544,   -5.87399256,  -5.86681164,
-     -5.88117348,  -5.84526888,  -5.83808796,  -5.83808796,  -5.78782152,
-     -5.79500244,  -5.7806406,   -5.75909784,  -5.73755508,  -5.73037416,
-     -5.71601232,  -5.744736,    -5.69446956,  -5.65856496,  -5.68010772,
-     -5.68010772,  -5.62984128,  -5.69446956,  -5.57957484,  -5.62266036,
-     -5.6011176,   -5.565213,    -5.6011176,   -5.55803208,  -5.55803208,
-     -5.53648932,  -5.4934038,   -5.48622288,  -5.4574992,   -5.48622288,
-     -5.44313736,  -5.46468012,  -5.40005184,  -5.4574992,   -5.4215946,
-     -5.37850908,  -5.35696632,  -5.3497854,   -5.3138808,   -5.34260448,
-     -5.30669988,  -5.28515712,  -5.29951896,  -5.26361436,  -5.22052884,
-     -5.23489068,  -5.24925252,  -5.206167,    -5.17744332,  -5.1702624,
-     -5.16308148,  -5.16308148,  -5.14871964,  -5.11999596,  -5.11999596,
-     -5.1343578,   -5.08409136,  -5.09127228,  -5.08409136,  -5.04100584,
-     -5.05536768,  -5.03382492,  -4.99792032,  -4.9907394,   -4.96919664,
-     -4.96919664,  -4.96201572,  -4.9189302,   -4.93329204,  -4.9189302,
-     -4.89738744,  -4.87584468,  -4.86148284,  -4.83275916,  -4.80403548,
-     -4.76094996,  -4.7394072,   -4.76813088,  -4.76813088,  -4.7394072,
-     -4.68914076,  -4.69632168,  -4.667598,    -4.68914076,  -4.67477892,
-     -4.64605524,  -4.64605524,  -4.58860788,  -4.61733156,  -4.5598842,
-     -4.56706512,  -4.56706512,  -4.54552236,  -4.50243684,  -4.47371316,
-     -4.49525592,  -4.4521704,   -4.43062764,  -4.4521704,   -4.42344672,
-     -4.40190396,  -4.42344672,  -4.43062764,  -4.3803612,   -4.3444566,
-     -4.35163752,  -4.32291384,  -4.2726474,   -4.27982832,  -4.2726474,
-     -4.25828556,  -4.22238096,  -4.25828556,  -4.19365728,  -4.2008382,
-     -4.14339084,  -4.1649336,   -4.129029,    -4.13620992,  -4.06440072,
-     -4.08594348,  -4.06440072,  -4.04285796,  -4.04285796,  -4.00695336,
-     -3.9854106,   -4.00695336,  -3.96386784,  -3.949506,    -3.9136014,
-     -3.94232508,  -3.90642048,  -3.89205864,  -3.87051588,  -3.8776968,
-     -3.8776968,   -3.83461128,  -3.79152576,  -3.79870668,  -3.769983,
-     -3.79152576,  -3.74125932,  -3.75562116,  -3.72689748,  -3.70535472,
-     -3.65508828,  -3.6263646,   -3.61918368,  -3.64790736,  -3.57609816,
-     -3.5545554,   -3.56173632,  -3.53301264,  -3.54737448,  -3.50428896,
-     -3.54019356,  -3.47556528,  -3.410937,    -3.43247976,  -3.41811792,
-     -3.4468416,   -3.410937,    -3.38939424,  -3.35348964,  -3.36067056,
-     -3.2673186,   -3.28168044,  -3.26013768,  -3.24577584,  -3.2673186,
-     -3.23859492,  -3.20987124,  -3.1955094,   -3.16678572,  -3.17396664,
-     -3.1237002,   -3.10215744,  -3.08061468,  -3.09497652,  -3.06625284,
-     -3.00880548,  -3.03034824,  -2.98726272,  -3.0159864,   -2.92981536,
-     -2.95135812,  -2.95135812,  -2.86518708,  -2.87954892,  -2.82928248,
-     -2.85082524,  -2.872368,    -2.79337788,  -2.80773972,  -2.7646542,
-     -2.74311144,  -2.74311144,  -2.73593052,  -2.68566408,  -2.692845,
-     -2.70002592,  -2.62821672,  -2.63539764,  -2.60667396,  -2.59949304,
-     -2.55640752,  -2.5492266,   -2.52050292,  -2.49896016,  -2.47023648,
-     -2.4774174,   -2.46305556,  -2.43433188,  -2.39842728,  -2.3697036,
-     -2.37688452,  -2.31943716,  -2.31225624,  -2.29071348,  -2.24044704,
-     -2.29071348,  -2.27635164,  -2.25480888,  -2.19736152,  -2.18299968,
-     -2.16145692,  -2.154276,    -2.12555232,  -2.12555232,  -2.08964772,
-     -2.1183714,   -2.09682864,  -2.06092404,  -2.01783852,  -1.98911484,
-     -1.96039116,  -1.974753,    -1.98193392,  -1.91012472,  -1.87422012,
-     -1.91730564,  -1.85985828,  -1.83831552,  -1.8311346,   -1.80241092,
-     -1.78086816,  -1.7234208,   -1.71623988,  -1.7593254,   -1.69469712,
-     -1.7234208,   -1.69469712,  -1.66597344,  -1.6516116,   -1.60852608,
-     -1.60852608,  -1.57262148,  -1.52235504,  -1.55107872,  -1.50081228,
-     -1.5079932,   -1.46490768,  -1.45772676,  -1.45054584,  -1.44336492,
-     -1.4002794,   -1.39309848,  -1.35719388,  -1.32128928,  -1.30692744,
-     -1.2925656,   -1.27820376,  -1.26384192,  -1.256661,    -1.20639456,
-     -1.16330904,  -1.17767088,  -1.1130426,   -1.12022352,  -1.077138,
-     -1.12022352,  -1.09149984,  -1.09868076,  -0.97660512,  -0.99814788,
-     -0.97660512,  -0.97660512,  -0.94070052,  -0.91915776,  -0.89043408,
-     -0.8617104,   -0.85452948,  -0.85452948,  -0.86889132,  -0.7899012,
-     -0.76835844,  -0.7539966,   -0.73963476,  -0.73245384,  -0.67500648,
-     -0.67500648,  -0.67500648,  -0.6103782,   -0.6103782,   -0.59601636,
-     -0.6103782,   -0.58165452,  -0.51702624,  -0.49548348,  -0.48112164,
-     -0.50984532,  -0.5026644,   -0.45957888,  -0.41649336,  -0.40213152,
-     -0.37340784,  -0.35186508,  -0.31596048,  -0.30877956,  -0.2872368},
-    {-0.01436184, 0.01436184,  -0.02872368, -0.0359046,  -0.00718092,
-     -0.00718092, 0,           0.02872368,  0.02872368,  0.02154276,
-     0.00718092,  0.02154276,  0.02154276,  0.01436184,  -0.00718092,
-     0.01436184,  -0.00718092, 0,           -0.0359046,  -0.01436184,
-     -0.01436184, 0.00718092,  0.01436184,  0.02154276,  0.02872368,
-     0.02154276,  -0.01436184, 0.01436184,  0.01436184,  0.02154276,
-     0.00718092,  -0.01436184, 0,           0.02872368,  0.0359046,
-     0.02872368,  0,           -0.00718092, 0.01436184,  -0.02154276,
-     0.00718092,  -0.00718092, -0.0359046,  0,           -0.05026644,
-     -0.05026644, -0.05026644, -0.0359046,  -0.02154276, -0.0359046,
-     -0.08617104, -0.05744736, -0.09335196, -0.08617104, -0.09335196,
-     -0.12207564, -0.15079932, -0.20106576, -0.18670392, -0.24415128,
-     -0.2513322,  -0.25851312, -0.30159864, -0.33750324, -0.359046,
-     -0.4308552,  -0.45239796, -0.50984532, -0.538569,   -0.58883544,
-     -0.61755912, -0.66064464, -0.6821874,  -0.73245384, -0.81862488,
-     -0.88325316, -0.9335196,  -0.95506236, -1.0053288,  -1.02687156,
-     -1.0412334,  -1.077138,   -1.1130426,  -1.12740444, -1.15612812,
-     -1.2207564,  -1.22793732, -1.26384192, -1.26384192, -1.3284702,
-     -1.26384192, -1.27820376, -1.31410836, -1.32128928, -1.29974652,
-     -1.2925656,  -1.27820376, -1.26384192, -1.21357548, -1.14176628,
-     -1.16330904, -1.09149984, -1.02687156, -0.99814788, -0.897615,
-     -0.87607224, -0.74681568, -0.6462828,  -0.55293084, -0.42367428,
-     -0.3949506,  -0.31596048, -0.18670392, -0.06462828, 0.08617104,
-     0.20824668,  0.33032232,  0.42367428,  0.53138808,  0.6821874,
-     0.69654924,  0.81144396,  0.94070052,  1.06995708,  1.10586168,
-     1.19203272,  1.26384192,  1.29974652,  1.34283204,  1.39309848,
-     1.37155572,  1.42182216,  1.4002794,   1.42900308,  1.436184,
-     1.4002794,   1.38591756,  1.35719388,  1.33565112,  1.28538468,
-     1.256661,    1.24229916,  1.14176628,  1.09149984,  1.0053288,
-     0.91915776,  0.83298672,  0.74681568,  0.65346372,  0.53138808,
-     0.5744736,   0.45957888,  0.33032232,  0.22978944,  0.11489472,
-     0.04308552,  -0.0718092,  -0.18670392, -0.29441772, -0.41649336,
-     -0.43803612, -0.47394072, -0.56011176, -0.69654924, -0.78272028,
-     -0.83298672, -0.84016764, -0.90479592, -0.91197684, -0.96224328,
-     -0.9694242,  -0.95506236, -0.9694242,  -0.96224328, -0.9335196,
-     -0.8617104,  -0.81862488, -0.76835844, -0.70373016, -0.63910188,
-     -0.5744736,  -0.50984532, -0.3949506,  -0.29441772, -0.22978944,
-     -0.1077138,  0.00718092,  0.13643748,  0.23697036,  0.31596048,
-     0.3231414,   0.38058876,  0.50984532,  0.58883544,  0.6821874,
-     0.74681568,  0.81144396,  0.84016764,  0.84734856,  0.88325316,
-     0.89043408,  0.84734856,  0.81862488,  0.81144396,  0.74681568,
-     0.70373016,  0.61755912,  0.54574992,  0.45957888,  0.34468416,
-     0.359046,    0.2513322,   0.15798024,  0.05026644,  -0.0359046,
-     -0.15798024, -0.20106576, -0.30877956, -0.40931244, -0.48830256,
-     -0.48830256, -0.52420716, -0.55293084, -0.60319728, -0.63192096,
-     -0.66064464, -0.6462828,  -0.58165452, -0.58165452, -0.45957888,
-     -0.4667598,  -0.38058876, -0.35186508, -0.23697036, -0.16516116,
-     -0.1077138,  -0.02154276, 0.09335196,  0.22260852,  0.25851312,
-     0.26569404,  0.33032232,  0.41649336,  0.47394072,  0.52420716,
-     0.48830256,  0.51702624,  0.52420716,  0.47394072,  0.4667598,
-     0.47394072,  0.38776968,  0.33032232,  0.33750324,  0.22260852,
-     0.12925656,  0.06462828,  -0.01436184, -0.05744736, -0.16516116,
-     -0.17234208, -0.22978944, -0.28005588, -0.31596048, -0.35186508,
-     -0.38776968, -0.36622692, -0.3231414,  -0.34468416, -0.3231414,
-     -0.33032232, -0.30159864, -0.23697036, -0.179523,   -0.09335196,
-     -0.02872368, 0,           0.08617104,  0.12207564,  0.18670392,
-     0.19388484,  0.23697036,  0.27287496,  0.29441772,  0.3231414,
-     0.27287496,  0.24415128,  0.24415128,  0.27287496,  0.15798024,
-     0.20824668,  0.16516116,  0.10053288,  0.05744736,  0.01436184,
-     -0.0359046,  -0.06462828, -0.16516116, -0.179523,   -0.18670392,
-     -0.2154276,  -0.2154276,  -0.20106576, -0.23697036, -0.2154276,
-     -0.1436184,  -0.17234208, -0.10053288, -0.02154276, -0.05026644,
-     0.02872368,  0.02154276,  0.05744736,  0.11489472,  0.12925656,
-     0.13643748,  0.15798024,  0.179523,    0.15798024,  0.16516116,
-     0.16516116,  0.13643748,  0.1436184,   0.1077138,   0.05744736,
-     0.02154276,  0.01436184,  -0.02154276, -0.00718092, -0.0718092,
-     -0.0718092,  -0.09335196, -0.09335196, -0.10053288, -0.11489472,
-     -0.0718092,  -0.08617104, -0.0718092,  -0.05744736, -0.0359046,
-     -0.02872368, -0.00718092, 0.0359046,   0.07899012,  0.10053288,
-     0.12207564,  0.10053288,  0.12207564,  0.09335196,  0.1077138,
-     0.12207564,  0.10053288,  0.08617104,  0.09335196,  0.05026644,
-     0.09335196,  0.00718092,  0,           -0.05026644, 0,
-     0.00718092,  -0.02872368, -0.04308552, -0.00718092, -0.02872368,
-     -0.05026644, -0.07899012, -0.00718092, 0.00718092,  0.04308552,
-     0.00718092,  0,           0.02872368,  0.05026644,  0.0359046,
-     0.05026644,  0.08617104,  0.06462828,  0.0718092,   0.10053288,
-     0.10053288,  0.05744736,  0.0359046,   0.05744736,  0.08617104,
-     0.05026644,  0.04308552,  0.01436184,  0.02872368,  0.02154276,
-     0.01436184,  -0.02872368, 0.00718092,  0.01436184,  0.00718092,
-     0.02154276,  -0.02872368, 0.02154276,  0.02872368,  0.04308552,
-     0.02154276,  0.04308552,  0.07899012,  0.04308552,  0.05026644,
-     0.05744736,  0.07899012,  0.02154276,  0.02872368,  0.09335196,
-     0.04308552,  0.05026644,  0.08617104,  0.05744736,  0.05744736,
-     0.0359046,   0.05026644,  0.04308552,  0.04308552,  0.02872368,
-     0.00718092,  0.05026644,  0.02872368,  0.04308552,  0.02154276,
-     0.02872368,  0.05026644,  0.05026644,  0.05026644,  0.05026644,
-     0.06462828,  0.0359046,   0.02872368,  0.02154276,  0.02154276,
-     0.05744736,  0.02872368,  0.01436184,  0.00718092,  0.00718092,
-     0.02872368,  0,           0.02872368,  0.0359046,   0.02872368,
-     0.00718092,  0.04308552,  0.01436184,  0.02154276,  0.05026644,
-     0.04308552,  0.00718092,  0.06462828,  0.02872368,  -0.01436184,
-     0.07899012,  0.02154276,  0.05744736,  0.02154276,  0.05026644,
-     0.02154276,  0.01436184,  0.05744736,  0.02154276,  0.05026644,
-     0.05026644,  0.06462828,  0.01436184,  0.05026644,  0.0359046,
-     0.05744736,  0.04308552,  0.05026644,  0.04308552,  0,
-     0.0359046,   0.05744736,  -0.01436184, 0.02872368,  0.0718092,
-     0.02154276,  0.05026644,  0.02154276,  0.06462828,  0.00718092,
-     0.06462828,  0.02154276,  0.0359046,   0.06462828,  0.07899012,
-     0.08617104,  0.02872368,  0.0718092,   0.11489472,  0.10053288,
-     0.0718092,   0.07899012,  0.06462828,  0.02154276,  0.07899012,
-     0.05744736,  0.06462828,  0.0359046,   0.01436184,  0.06462828,
-     0.0718092,   0.0359046,   0.02154276,  0.04308552,  0.01436184,
-     0.06462828,  0.0359046,   0.0718092,   0.06462828,  0.06462828,
-     0.05744736,  0.05744736,  0.05026644,  0.0718092,   0.06462828,
-     0.02872368,  0.05026644,  0.06462828,  0.08617104,  0.10053288,
-     0.02872368,  0.05026644,  0.0718092,   0.11489472,  0.07899012,
-     0.05026644,  0.06462828,  0.06462828,  0.05026644,  0.0359046,
-     0.05026644,  0.07899012,  0.0359046,   0.02872368,  0.06462828,
-     0.05026644,  0.05026644,  0.07899012,  0.05026644,  0.0359046,
-     0.01436184,  0.04308552,  0.0718092,   0.05744736,  0.09335196,
-     0.05026644,  0.09335196,  0.05744736,  0.07899012,  0.04308552,
-     0.06462828,  0.04308552,  0.05026644,  0.05026644,  0.05026644,
-     0.02872368,  0.06462828,  0.06462828,  0.02154276,  0.06462828,
-     0.07899012,  0.05744736,  0.04308552,  0.05744736,  0.05026644,
-     0.10053288,  0.04308552,  0.02872368,  0.02872368,  0.08617104,
-     0.06462828,  0.0718092,   0.05026644,  0.04308552,  0.04308552,
-     0.0718092,   0.05744736,  0.0718092,   0.09335196,  0.05026644,
-     0.02872368,  0.05026644,  0.06462828,  -0.02154276, 0.04308552,
-     0.06462828,  0.04308552,  0.0718092,   0.0359046,   0.05026644,
-     0.0359046,   0.02872368,  0.06462828,  0.02872368,  0.02872368,
-     0.04308552,  0.0359046,   0.0718092,   0.05744736,  0.0359046,
-     0.04308552,  0.05026644,  0.05744736,  0.05744736,  0.02154276,
-     0.05026644,  0.04308552,  0.04308552,  0.05026644,  0.01436184,
-     0.10053288,  0.05026644,  0.05026644,  0.05744736,  0.04308552,
-     0.08617104,  0.0359046,   0.0359046,   0.04308552,  0.0359046,
-     0.02872368,  0.01436184,  0.0359046,   0.0359046,   0.04308552,
-     0.0359046,   0.05744736,  0.04308552,  0.04308552,  0.05026644,
-     0.04308552,  0.05026644,  0.0359046,   0.02154276,  0.05026644,
-     0.05744736,  0.00718092,  0.05026644,  0.04308552,  0.06462828,
-     0.0359046,   0.02872368,  0.04308552,  0.05744736,  0.07899012,
-     -0.00718092, 0.0359046,   0.02872368,  0.01436184,  0.00718092,
-     0.02872368,  0.01436184,  0.02872368,  0.02154276,  0.02872368,
-     0.02872368,  -0.00718092, 0.00718092,  0.01436184,  0.0718092,
-     0.02154276,  -0.00718092, 0,           0.01436184,  0.05026644,
-     0.00718092,  0.0359046,   0.01436184,  0.01436184,  0.0359046,
-     0.05744736,  0.01436184,  0.04308552,  0.02872368,  0.02154276,
-     0.02872368,  0.02872368,  0.02872368,  0.05744736,  0.02154276,
-     0.01436184,  0.02872368,  0.01436184,  0.02872368,  0.02154276,
-     0.0359046,   0.04308552,  0.05026644,  0.00718092,  0.0359046,
-     0.0359046,   0.05026644,  0.01436184,  0.02872368,  -0.00718092,
-     -0.01436184, 0.02154276,  0.02154276,  0.0359046,   -0.00718092,
-     0.01436184,  0.05026644,  0.02154276,  0,           0.00718092,
-     -0.00718092, 0.04308552,  0.0359046,   0.05026644,  0.05026644,
-     0.00718092,  0.00718092,  0.02872368,  0.0359046,   0.00718092,
-     -0.01436184, 0.04308552,  -0.01436184, 0.00718092,  0.02872368,
-     0.04308552,  0.04308552,  0.0359046,   0.0359046,   0.02872368,
-     0.06462828,  0.04308552,  0.06462828,  0.0359046,   0.06462828,
-     0.04308552,  0.0359046,   0.06462828,  0.01436184,  0.02872368,
-     0.00718092,  -0.02872368, 0.05026644,  0.00718092,  0.0359046,
-     0.01436184,  0.02154276,  0,           0.02154276,  0.02872368,
-     0.07899012,  0.05744736,  0.01436184,  0.02872368,  0.05744736,
-     0.05744736,  0,           0.0718092,   0.01436184,  0.02872368,
-     0.02154276,  -0.01436184, 0,           0.00718092,  0.06462828,
-     0.01436184,  0.00718092,  0.02154276,  0.02154276,  0.02154276,
-     0.06462828,  0.01436184,  0.05744736,  0.0718092,   0.02154276,
-     0.02154276,  -0.00718092, 0.01436184,  0.02872368,  0.02872368,
-     0.04308552,  0.01436184,  0.02154276,  0.05026644,  0.05026644,
-     0.06462828,  0.02872368,  0.00718092,  0.00718092,  0.01436184,
-     0.02872368,  0.05026644,  0.05744736,  0.0359046,   0.05744736,
-     0.0359046,   0.0359046,   0.05744736,  0.02872368,  0.02154276,
-     0.06462828,  0.06462828,  0.04308552,  0.0718092,   0.06462828,
-     0.0359046,   0.02154276,  0.04308552,  0.05026644,  0.06462828,
-     0.01436184,  0.0359046,   0.0359046,   0.05744736,  0.04308552,
-     0.04308552,  0.02154276,  0.0359046,   0.02154276,  0.06462828,
-     0.04308552,  0.01436184,  0.04308552,  0.05026644,  0.04308552,
-     0.0718092,   0.02872368,  0.05026644,  0.0359046,   0.05744736,
-     0.05744736,  0.02872368,  0.05744736,  0.05744736,  0.09335196,
-     0.07899012,  0,           0.06462828,  0.02154276,  0.02154276,
-     0.09335196,  0.02154276,  0.05026644,  0.02154276,  0.06462828,
-     0.02154276,  0.00718092,  0.02872368,  0.0359046,   0.05744736,
-     0.04308552,  0.06462828,  0.05026644,  0.06462828,  0.01436184,
-     0.05744736,  0.04308552,  0.09335196,  0.04308552,  0.02872368,
-     0.02872368,  0.05744736,  0.02872368,  0.01436184,  0.02872368,
-     0.05744736,  0.02872368,  0.04308552,  0.02872368,  0.0359046,
-     0.05026644,  0.02872368,  0,           0.05744736,  0.05744736,
-     0.0359046,   0.02872368,  0.02872368,  0,           0.0718092,
-     0.07899012,  0.04308552,  0.0359046,   0.05026644,  0.02154276,
-     0.02872368,  0.05744736,  0.02872368,  -0.00718092, 0.07899012,
-     0.0359046,   0.02872368,  0.06462828,  0.02872368,  0.05026644,
-     0.02154276,  0.05744736,  0.05744736,  0.0359046,   0.05026644,
-     0,           0.04308552,  0.05026644,  0.06462828,  0.06462828,
-     0.04308552,  0.02154276,  0.00718092,  0.02872368,  0.02872368,
-     0.04308552,  0.05744736,  0.05026644,  0.01436184,  0.06462828,
-     0.05026644,  0.02872368,  0.02872368,  0.05026644,  0.02872368,
-     0.04308552,  0.07899012,  0.02872368,  0.05744736,  0.05026644,
-     0.04308552,  0.05744736,  0.05744736,  0.04308552,  0.07899012,
-     0.0359046,   0.05026644,  0.00718092,  0.06462828,  0.02154276,
-     0.04308552,  0.0718092,   0.0359046,   0.0359046,   0.04308552,
-     0.01436184,  0.05026644,  0.05026644,  0.04308552,  0.05744736,
-     0.04308552,  0.05026644,  0.0359046,   0.01436184,  0.0718092,
-     0.05744736,  0.05744736,  0.0718092,   0.1077138,   0.0718092,
-     0.0359046,   0.06462828,  0.05744736,  0.06462828,  0.06462828,
-     0.04308552,  0.02154276,  0.09335196,  0.05026644,  0.04308552,
-     0.05744736,  0.0718092,   0.04308552,  0.05026644,  0.05744736,
-     0.02872368,  0.02154276,  0.04308552,  0.00718092,  0.0359046,
-     0.05026644,  0.04308552,  0.02872368,  0.06462828,  0.09335196,
-     0.02154276,  0.00718092,  0.04308552,  0.05026644,  0.05026644,
-     0.05744736,  0.04308552,  0.00718092,  0.04308552,  0.04308552,
-     0.01436184,  0.06462828,  0.05744736,  0.04308552,  0.05026644,
-     0.0359046,   0.05744736,  0.04308552,  0.02872368,  0.05026644,
-     0.01436184,  0.00718092,  0.05026644,  0.0359046,   0.0718092,
-     0.02872368,  0.06462828,  0.06462828,  0.0718092,   0.06462828,
-     0.05744736,  0.00718092,  0.0718092,   0.04308552,  0.05026644,
-     0.01436184,  0.05026644,  0.0718092,   0.01436184,  0.04308552,
-     0.00718092,  0.08617104,  0.0718092,   0.02154276,  0.05026644,
-     0.06462828,  0.02872368,  0.0359046,   0.05026644,  0.04308552,
-     0.0718092,   0.04308552,  0.02872368,  0.05744736,  0.02154276,
-     0.04308552,  0.08617104,  0.04308552,  0.00718092,  0.04308552,
-     0.0359046,   0.0359046,   0.05026644,  0.0718092,   0.05744736,
-     0.05744736,  -0.00718092, 0.06462828,  0.06462828,  0.06462828,
-     0.0359046,   0.04308552,  0.02872368,  0.0359046,   0.0359046,
-     0.0359046,   0.05026644,  0.02872368,  0.05026644,  0.02154276,
-     0.0718092,   0.01436184,  0.05026644,  0.05744736,  0.05026644,
-     0.04308552,  0.05026644,  0.0359046,   0.06462828,  0.05744736,
-     0.05744736,  0.05026644,  0.05744736,  0.0359046,   0.05026644,
-     0.04308552,  0.02872368,  0.05026644,  0.05026644,  0.05744736,
-     0.01436184,  0.04308552,  0.05744736,  0.05744736,  0.0359046,
-     0.02154276,  0.02872368,  0.04308552,  0.05026644,  0.05744736,
-     0.05744736,  0.0359046,   0.06462828,  0.05744736,  0.0718092,
-     0.07899012,  0.04308552,  0.08617104,  0.05026644,  0.05744736,
-     0.06462828,  0.07899012,  0.06462828,  0.02872368,  0.0718092,
-     0.07899012,  0.05026644,  0.08617104,  0.01436184,  0.05026644,
-     0.09335196,  0.04308552,  0.05744736,  0.07899012,  0.09335196,
-     0.02154276,  0.05744736,  0.04308552,  0.08617104,  0.05744736,
-     0.08617104,  0.02872368,  0.0718092,   0.0359046,   0.05026644,
-     0.07899012,  0.06462828,  0.08617104,  0.05744736,  0.06462828,
-     0.06462828,  0.06462828,  0.05026644,  0.05744736,  0.01436184,
-     0.05744736,  0.08617104,  0.05026644,  0.05744736,  0.06462828,
-     0.02154276,  0.05744736,  0.05026644,  0.06462828,  0.05744736,
-     0.05026644,  0.06462828,  0.08617104,  0.04308552,  0.0718092,
-     0.05026644,  0.02154276,  0.05744736,  0.10053288,  0.08617104,
-     0.0359046,   0.04308552,  0.07899012,  0.05744736,  0.0718092,
-     0.05744736,  0.05744736,  0.04308552,  0.05744736,  0.04308552,
-     0.07899012,  0.05744736,  0.02154276,  0.06462828,  0.05744736,
-     0.0359046,   0.00718092,  0.0359046,   0.09335196,  0.0359046,
-     0.05744736,  0.07899012,  0.05026644,  0.04308552,  0.06462828,
-     0.01436184,  0.01436184,  0.0718092,   0.06462828,  0.07899012,
-     0.0359046,   0.07899012,  0.05744736,  0.02872368,  0.0718092,
-     0.05026644,  0.0359046,   0.0359046,   0.08617104,  0.07899012,
-     0.06462828,  0.04308552,  0.02154276,  0.05744736,  0.04308552,
-     0.09335196,  0.04308552,  0.09335196,  0.08617104,  0.06462828,
-     0.02154276,  0.04308552,  0.06462828,  0.07899012,  0.05026644,
-     0.08617104,  0.02872368,  0.02872368,  0.0359046,   0.02154276,
-     0.06462828,  0.07899012,  0.04308552,  0.0718092,   0.05744736,
-     0.08617104,  0.05026644,  0.0718092,   0.10053288,  0.06462828,
-     0.05744736,  0.08617104,  0.05744736,  0.0718092,   0.02872368,
-     0.07899012,  0.05744736,  0.06462828,  0.0359046,   0.05026644,
-     0.06462828,  0.07899012,  0.05026644,  0.07899012,  0.09335196,
-     0.0718092,   0.05744736,  0.08617104,  0.07899012,  0.11489472,
-     0.08617104,  0.06462828,  0.08617104,  0.09335196,  0.05026644,
-     0.09335196,  0.0359046,   0.07899012,  0.0718092,   0.07899012,
-     0.07899012,  0.05744736,  0.09335196,  0.05744736,  0.07899012,
-     0.05026644,  0.0718092,   0.09335196,  0.05026644,  0.06462828,
-     0.0718092,   0.05026644,  0.0718092,   0.0718092,   0.0359046,
-     0.06462828,  0.08617104,  0.05744736,  0.05744736,  0.07899012,
-     0.0718092,   0.05744736,  0.05744736,  0.07899012,  0.06462828,
-     0.06462828,  0.07899012,  0.08617104,  0.05026644,  0.0718092,
-     0.06462828,  0.08617104,  0.09335196,  0.0718092,   0.09335196,
-     0.07899012,  0.0718092,   0.05744736,  0.05744736,  0.08617104,
-     0.09335196,  0.05026644,  0.05744736,  0.07899012,  0.09335196,
-     0.05026644,  0.09335196,  0.07899012,  0.04308552,  0.10053288,
-     0.07899012,  0.11489472,  0.07899012,  0.07899012,  0.0718092,
-     0.07899012,  0.07899012,  0.07899012,  0.08617104,  0.09335196,
-     0.07899012,  0.06462828,  0.08617104,  0.05026644,  0.0718092,
-     0.07899012,  0.09335196,  0.09335196,  0.11489472,  0.11489472,
-     0.1077138,   0.07899012,  0.12207564,  0.0718092,   0.10053288,
-     0.07899012,  0.05744736,  0.08617104,  0.09335196,  0.13643748,
-     0.05744736,  0.10053288,  0.10053288,  0.08617104,  0.12207564,
-     0.10053288,  0.08617104,  0.10053288,  0.11489472,  0.10053288,
-     0.09335196,  0.10053288,  0.07899012,  0.08617104,  0.08617104,
-     0.12207564,  0.0718092,   0.06462828,  0.09335196,  0.10053288,
-     0.10053288,  0.05026644,  0.12207564,  0.10053288,  0.09335196,
-     0.07899012,  0.0718092,   0.10053288,  0.1436184,   0.11489472,
-     0.07899012,  0.11489472,  0.11489472,  0.10053288,  0.11489472,
-     0.07899012,  0.11489472,  0.08617104,  0.10053288,  0.12207564,
-     0.1077138,   0.08617104,  0.09335196,  0.11489472,  0.10053288,
-     0.08617104,  0.08617104,  0.08617104,  0.15079932,  0.11489472,
-     0.09335196,  0.12925656,  0.10053288,  0.08617104,  0.1077138,
-     0.07899012,  0.10053288,  0.12925656,  0.10053288,  0.1077138,
-     0.07899012,  0.08617104,  0.12207564,  0.10053288,  0.09335196,
-     0.09335196,  0.0718092,   0.11489472,  0.12207564,  0.12925656,
-     0.12925656,  0.10053288,  0.08617104,  0.12925656,  0.11489472,
-     0.13643748,  0.06462828,  0.12207564,  0.10053288,  0.12925656,
-     0.11489472,  0.12207564,  0.15079932,  0.12207564,  0.1077138,
-     0.1436184,   0.09335196,  0.12207564,  0.1077138,   0.08617104,
-     0.11489472,  0.07899012,  0.07899012,  0.08617104,  0.12207564,
-     0.10053288,  0.08617104,  0.1077138,   0.11489472,  0.1077138,
-     0.07899012,  0.12207564,  0.08617104,  0.12925656,  0.15798024,
-     0.09335196,  0.12207564,  0.0718092,   0.10053288,  0.09335196,
-     0.09335196,  0.12207564,  0.08617104,  0.0718092,   0.10053288,
-     0.09335196,  0.0718092,   0.07899012,  0.08617104,  0.09335196,
-     0.07899012,  0.07899012,  0.10053288,  0.10053288,  0.1077138,
-     0.08617104,  0.11489472,  0.07899012,  0.08617104,  0.09335196,
-     0.1077138,   0.1077138,   0.10053288,  0.10053288,  0.08617104,
-     0.0718092,   0.10053288,  0.1436184,   0.07899012,  0.10053288,
-     0.09335196,  0.1077138,   0.0718092,   0.10053288,  0.1077138,
-     0.11489472,  0.11489472,  0.12207564,  0.13643748,  0.0718092,
-     0.0718092,   0.09335196,  0.1077138,   0.12925656,  0.08617104,
-     0.09335196,  0.11489472,  0.09335196,  0.08617104,  0.08617104,
-     0.06462828,  0.10053288,  0.1077138,   0.07899012,  0.09335196,
-     0.08617104,  0.05744736,  0.11489472,  0.11489472,  0.09335196,
-     0.09335196,  0.07899012,  0.06462828,  0.07899012,  0.0718092,
-     0.0718092,   0.06462828,  0.08617104,  0.08617104,  0.06462828,
-     0.06462828,  0.05026644,  0.07899012,  0.1077138,   0.0718092,
-     0.1077138,   0.10053288,  0.06462828,  0.0718092,   0.09335196,
-     0.10053288,  0.05744736,  0.10053288,  0.05744736,  0.10053288,
-     0.08617104,  0.05744736,  0.05744736,  0.08617104,  0.06462828,
-     0.05744736,  0.0359046,   0.05744736,  0.09335196,  0.0718092,
-     0.06462828,  0.07899012,  0.09335196,  0.08617104,  0.09335196,
-     0.05744736,  0.08617104,  0.13643748,  0.0718092,   0.05026644,
-     0.06462828,  0.06462828,  0.11489472,  0.09335196,  0.0718092,
-     0.06462828,  0.0718092,   0.06462828,  0.10053288,  0.06462828,
-     0.0718092,   0.09335196,  0.12207564,  0.05026644,  0.09335196,
-     0.0718092,   0.07899012,  0.05744736,  0.07899012,  0.08617104,
-     0.0718092,   0.10053288,  0.09335196,  0.05026644,  0.0718092,
-     0.07899012,  0.10053288,  0.06462828,  0.10053288,  0.07899012,
-     0.05744736,  0.10053288,  0.05026644,  0.09335196,  0.08617104,
-     0.1077138,   0.05744736,  0.1077138,   0.05744736,  0.05744736,
-     0.0718092,   0.08617104,  0.08617104,  0.05744736,  0.08617104,
-     0.0718092,   0.1077138,   0.07899012,  0.10053288,  0.06462828,
-     0.07899012,  0.06462828,  0.06462828,  0.05744736,  0.09335196,
-     0.07899012,  0.1077138,   0.08617104,  0.07899012,  0.0718092,
-     0.11489472,  0.04308552,  0.0359046,   0.1077138,   0.06462828,
-     0.11489472,  0.07899012,  0.07899012,  0.1077138,   0.06462828,
-     0.05026644,  0.10053288,  0.08617104,  0.0718092,   0.08617104,
-     0.11489472,  0.13643748,  0.1077138,   0.11489472,  0.1077138,
-     0.10053288,  0.09335196,  0.07899012,  0.11489472,  0.10053288,
-     0.1077138,   0.11489472,  0.1077138,   0.15079932,  0.07899012,
-     0.09335196,  0.1077138,   0.08617104,  0.12207564,  0.06462828,
-     0.1077138,   0.09335196,  0.10053288,  0.05026644,  0.12925656,
-     0.10053288,  0.07899012,  0.1077138,   0.10053288,  0.06462828,
-     0.13643748,  0.05026644,  0.07899012,  0.05744736,  0.07899012,
-     0.11489472,  0.0718092,   0.09335196,  0.08617104,  0.08617104,
-     0.11489472,  0.07899012,  0.13643748,  0.11489472,  0.10053288,
-     0.10053288,  0.08617104,  0.10053288,  0.08617104,  0.08617104,
-     0.06462828,  0.12207564,  0.09335196,  0.12207564,  0.10053288,
-     0.08617104,  0.1077138,   0.11489472,  0.11489472,  0.1077138,
-     0.08617104,  0.1077138,   0.10053288,  0.08617104,  0.0718092,
-     0.12207564,  0.12207564,  0.12207564,  0.12925656,  0.08617104,
-     0.07899012,  0.10053288,  0.12207564,  0.15079932,  0.0718092,
-     0.12925656,  0.11489472,  0.10053288,  0.09335196,  0.12207564,
-     0.12207564,  0.11489472,  0.10053288,  0.08617104,  0.12925656,
-     0.11489472,  0.13643748,  0.09335196,  0.13643748,  0.13643748,
-     0.1436184,   0.1436184,   0.12207564,  0.13643748,  0.16516116,
-     0.1077138,   0.12207564,  0.15079932,  0.12207564,  0.15079932,
-     0.11489472,  0.1077138,   0.11489472,  0.12207564,  0.1077138,
-     0.1436184,   0.06462828,  0.15079932,  0.1077138,   0.10053288,
-     0.17234208,  0.1436184,   0.12207564,  0.13643748,  0.12925656,
-     0.15798024,  0.11489472,  0.11489472,  0.16516116,  0.1436184,
-     0.15079932,  0.1077138,   0.1077138,   0.12925656,  0.11489472,
-     0.11489472,  0.11489472,  0.15798024,  0.08617104,  0.13643748,
-     0.17234208,  0.13643748,  0.13643748,  0.10053288,  0.12207564,
-     0.11489472,  0.15798024,  0.15079932,  0.15079932,  0.16516116,
-     0.12925656,  0.1436184,   0.09335196,  0.08617104,  0.12207564,
-     0.1077138,   0.15798024,  0.13643748,  0.12207564,  0.13643748,
-     0.12207564,  0.09335196,  0.15798024,  0.12925656,  0.1077138,
-     0.1077138,   0.12207564,  0.13643748,  0.15079932,  0.11489472,
-     0.1436184,   0.13643748,  0.11489472,  0.13643748,  0.16516116,
-     0.13643748,  0.16516116,  0.17234208,  0.15798024,  0.1077138,
-     0.12207564,  0.13643748,  0.1436184,   0.12925656,  0.15798024,
-     0.1436184,   0.15798024,  0.13643748,  0.15798024,  0.15798024,
-     0.15079932,  0.12925656,  0.12925656,  0.12925656,  0.12207564,
-     0.13643748,  0.1436184,   0.16516116,  0.16516116,  0.15798024,
-     0.12207564,  0.16516116,  0.16516116,  0.1436184,   0.13643748,
-     0.12207564,  0.179523,    0.18670392,  0.1436184,   0.12925656,
-     0.1077138,   0.1436184,   0.1436184,   0.17234208,  0.11489472,
-     0.12925656,  0.13643748,  0.08617104,  0.16516116,  0.15079932,
-     0.13643748,  0.15798024,  0.1436184,   0.11489472,  0.16516116,
-     0.12925656,  0.13643748,  0.09335196,  0.1077138,   0.16516116,
-     0.16516116,  0.16516116,  0.15798024,  0.15079932,  0.1436184,
-     0.12925656,  0.1436184,   0.1436184,   0.12925656,  0.13643748,
-     0.1436184,   0.17234208,  0.13643748,  0.13643748,  0.13643748,
-     0.15079932,  0.16516116,  0.1436184,   0.1436184,   0.1436184,
-     0.1436184,   0.12207564,  0.15798024,  0.16516116,  0.15079932,
-     0.12925656,  0.11489472,  0.15079932,  0.16516116,  0.12207564,
-     0.13643748,  0.15798024,  0.1436184,   0.18670392,  0.12207564,
-     0.12925656,  0.15079932,  0.15798024,  0.17234208,  0.13643748,
-     0.13643748,  0.12925656,  0.179523,    0.15798024,  0.20824668,
-     0.15079932,  0.18670392,  0.07899012,  0.15798024,  0.15798024,
-     0.12925656,  0.17234208,  0.1436184,   0.179523,    0.15079932,
-     0.16516116,  0.15079932,  0.17234208,  0.18670392,  0.15798024,
-     0.17234208,  0.12207564,  0.17234208,  0.15798024,  0.15079932,
-     0.1436184,   0.15079932,  0.18670392,  0.16516116,  0.18670392,
-     0.19388484,  0.12925656,  0.1436184,   0.2154276,   0.15079932,
-     0.179523,    0.18670392,  0.179523,    0.18670392,  0.16516116,
-     0.17234208,  0.16516116,  0.12925656,  0.13643748,  0.16516116,
-     0.17234208,  0.15798024,  0.1436184,   0.15798024,  0.18670392,
-     0.20106576,  0.18670392,  0.15079932,  0.15798024,  0.15798024,
-     0.19388484,  0.17234208,  0.1436184,   0.17234208,  0.179523,
-     0.179523,    0.16516116,  0.18670392,  0.15079932,  0.1436184,
-     0.20106576,  0.19388484,  0.15079932,  0.20106576,  0.17234208,
-     0.17234208,  0.19388484,  0.18670392,  0.15798024,  0.12207564,
-     0.179523,    0.15079932,  0.179523,    0.1436184,   0.15798024,
-     0.20106576,  0.15079932,  0.17234208,  0.16516116,  0.16516116,
-     0.16516116,  0.12925656,  0.15798024,  0.17234208,  0.18670392,
-     0.19388484,  0.15079932,  0.17234208,  0.16516116,  0.179523,
-     0.19388484,  0.15798024,  0.15798024,  0.1077138,   0.15798024,
-     0.15798024,  0.179523,    0.16516116,  0.17234208,  0.1436184,
-     0.179523,    0.179523,    0.15079932,  0.1436184,   0.16516116,
-     0.15079932,  0.1436184,   0.1077138,   0.15798024,  0.17234208,
-     0.15798024,  0.17234208,  0.19388484,  0.18670392,  0.179523,
-     0.18670392,  0.179523,    0.20106576,  0.18670392,  0.20106576,
-     0.12207564,  0.20106576,  0.16516116,  0.13643748,  0.17234208,
-     0.17234208,  0.179523,    0.20106576,  0.19388484,  0.18670392,
-     0.2154276,   0.16516116,  0.16516116,  0.179523,    0.20106576,
-     0.15798024,  0.15079932,  0.19388484,  0.19388484,  0.16516116,
-     0.19388484,  0.18670392,  0.17234208,  0.15798024,  0.18670392,
-     0.20824668,  0.20106576,  0.12925656,  0.17234208,  0.17234208,
-     0.16516116,  0.179523,    0.15798024,  0.20106576,  0.18670392,
-     0.2154276,   0.13643748,  0.179523,    0.18670392,  0.17234208,
-     0.15798024,  0.17234208,  0.17234208,  0.15798024,  0.18670392,
-     0.20824668,  0.18670392,  0.179523,    0.19388484,  0.23697036,
-     0.179523,    0.18670392,  0.18670392,  0.18670392,  0.179523,
-     0.19388484,  0.22260852,  0.19388484,  0.18670392,  0.20106576,
-     0.18670392,  0.15079932,  0.19388484,  0.19388484,  0.20824668,
-     0.179523,    0.15798024,  0.19388484,  0.15798024,  0.179523,
-     0.179523,    0.18670392,  0.20824668,  0.17234208,  0.16516116,
-     0.19388484,  0.179523,    0.17234208,  0.19388484,  0.22260852,
-     0.17234208,  0.15079932,  0.20106576,  0.15079932,  0.15798024,
-     0.18670392,  0.17234208,  0.16516116,  0.15798024,  0.17234208,
-     0.20824668,  0.15079932,  0.20106576,  0.19388484,  0.17234208,
-     0.19388484,  0.16516116,  0.15798024,  0.179523,    0.17234208,
-     0.16516116,  0.16516116,  0.17234208,  0.18670392,  0.18670392,
-     0.15798024,  0.15798024,  0.20106576,  0.17234208,  0.17234208,
-     0.179523,    0.18670392,  0.15079932,  0.1436184,   0.16516116,
-     0.17234208,  0.18670392,  0.15079932,  0.15079932,  0.15798024,
-     0.15079932,  0.17234208,  0.1436184,   0.179523,    0.15798024,
-     0.12207564,  0.15079932,  0.17234208,  0.17234208,  0.15079932,
-     0.16516116,  0.179523,    0.16516116,  0.15798024,  0.2154276,
-     0.12925656,  0.15079932,  0.15798024,  0.12925656,  0.16516116,
-     0.13643748,  0.13643748,  0.16516116,  0.1436184,   0.17234208,
-     0.17234208,  0.15079932,  0.16516116,  0.12207564,  0.18670392,
-     0.17234208,  0.15079932,  0.15798024,  0.13643748,  0.16516116,
-     0.179523,    0.17234208,  0.16516116,  0.18670392,  0.179523,
-     0.13643748,  0.15079932,  0.1436184,   0.16516116,  0.1436184,
-     0.15798024,  0.1436184,   0.12925656,  0.15798024,  0.15079932,
-     0.15798024,  0.16516116,  0.1436184,   0.17234208,  0.1436184,
-     0.19388484,  0.19388484,  0.17234208,  0.17234208,  0.18670392,
-     0.13643748,  0.15798024,  0.15798024,  0.18670392,  0.20106576,
-     0.12925656,  0.15798024,  0.17234208,  0.179523,    0.16516116,
-     0.15798024,  0.18670392,  0.15798024,  0.1436184,   0.16516116,
-     0.179523,    0.15798024,  0.179523,    0.15079932,  0.20824668,
-     0.16516116,  0.15798024,  0.11489472,  0.1436184,   0.18670392,
-     0.16516116,  0.15079932,  0.13643748,  0.13643748,  0.15079932,
-     0.15079932,  0.15079932,  0.15079932,  0.1436184,   0.16516116,
-     0.16516116,  0.12925656,  0.15079932,  0.15798024,  0.17234208,
-     0.16516116,  0.1436184,   0.15079932,  0.12207564,  0.15798024,
-     0.13643748,  0.16516116,  0.22260852,  0.19388484,  0.22978944,
-     0.15079932,  0.179523,    0.15798024,  0.18670392,  0.17234208,
-     0.1436184,   0.15079932,  0.18670392,  0.1436184,   0.13643748,
-     0.179523,    0.16516116,  0.17234208,  0.15798024,  0.179523,
-     0.17234208,  0.12925656,  0.17234208,  0.18670392,  0.15079932,
-     0.18670392,  0.15798024,  0.18670392,  0.16516116,  0.17234208,
-     0.1436184,   0.1436184,   0.15798024,  0.17234208,  0.1436184,
-     0.17234208,  0.179523,    0.13643748,  0.20106576,  0.15798024,
-     0.18670392,  0.15079932,  0.15079932,  0.179523,    0.19388484,
-     0.17234208,  0.15079932,  0.20824668,  0.179523,    0.2154276,
-     0.15798024,  0.17234208,  0.15079932,  0.17234208,  0.15079932,
-     0.179523,    0.18670392,  0.18670392,  0.17234208,  0.15798024,
-     0.1436184,   0.20106576,  0.19388484,  0.17234208,  0.179523,
-     0.19388484,  0.13643748,  0.17234208,  0.1436184,   0.19388484,
-     0.19388484,  0.17234208,  0.18670392,  0.17234208,  0.179523,
-     0.1436184,   0.15079932,  0.19388484,  0.17234208,  0.179523,
-     0.22260852,  0.20106576,  0.179523,    0.16516116,  0.19388484,
-     0.18670392,  0.179523,    0.20824668,  0.18670392,  0.18670392,
-     0.16516116,  0.179523,    0.17234208,  0.20106576,  0.15079932,
-     0.19388484,  0.19388484,  0.16516116,  0.19388484,  0.19388484,
-     0.15079932,  0.15079932,  0.13643748,  0.17234208,  0.18670392,
-     0.16516116,  0.16516116,  0.15798024,  0.15079932,  0.15079932,
-     0.18670392,  0.18670392,  0.17234208,  0.17234208,  0.19388484,
-     0.179523,    0.18670392,  0.16516116,  0.179523,    0.20106576,
-     0.18670392,  0.179523,    0.19388484,  0.179523,    0.19388484,
-     0.20824668,  0.16516116,  0.19388484,  0.20106576,  0.19388484,
-     0.20824668,  0.179523,    0.179523,    0.19388484,  0.19388484,
-     0.15798024,  0.179523,    0.18670392,  0.18670392,  0.19388484,
-     0.18670392,  0.20106576,  0.20106576,  0.2154276,   0.16516116,
-     0.20824668,  0.20106576,  0.19388484,  0.15079932,  0.22260852,
-     0.18670392,  0.17234208,  0.20106576,  0.179523,    0.19388484,
-     0.19388484,  0.179523,    0.19388484,  0.20824668,  0.19388484,
-     0.16516116,  0.20824668,  0.18670392,  0.2154276,   0.19388484,
-     0.2154276,   0.19388484,  0.20106576,  0.2154276,   0.22978944,
-     0.19388484,  0.16516116,  0.20106576,  0.2154276,   0.15798024,
-     0.22260852,  0.18670392,  0.20106576,  0.19388484,  0.18670392,
-     0.19388484,  0.17234208,  0.16516116,  0.179523,    0.20106576,
-     0.22260852,  0.18670392,  0.20824668,  0.19388484,  0.20824668,
-     0.179523,    0.16516116,  0.15798024,  0.2154276,   0.15079932,
-     0.17234208,  0.179523,    0.15079932,  0.15079932,  0.15079932,
-     0.15798024,  0.16516116,  0.17234208,  0.15079932,  0.1436184,
-     0.18670392,  0.19388484,  0.16516116,  0.16516116,  0.15079932,
-     0.16516116,  0.179523,    0.18670392,  0.18670392,  0.18670392,
-     0.15798024,  0.17234208,  0.17234208,  0.16516116,  0.179523,
-     0.15798024,  0.1436184,   0.16516116,  0.16516116,  0.15798024,
-     0.1436184,   0.15079932,  0.20106576,  0.15798024,  0.17234208,
-     0.18670392,  0.17234208,  0.16516116,  0.16516116,  0.18670392,
-     0.20824668,  0.19388484,  0.18670392,  0.2154276,   0.16516116,
-     0.1436184,   0.16516116,  0.19388484,  0.20106576,  0.16516116,
-     0.179523,    0.20106576,  0.20824668,  0.16516116,  0.15798024,
-     0.20106576,  0.18670392,  0.15798024,  0.179523,    0.179523,
-     0.15079932,  0.15798024,  0.19388484,  0.20106576,  0.15798024,
-     0.18670392,  0.1436184,   0.13643748,  0.17234208,  0.16516116,
-     0.179523,    0.17234208,  0.16516116,  0.16516116,  0.18670392,
-     0.16516116,  0.15079932,  0.12925656,  0.179523,    0.15079932,
-     0.20106576,  0.20824668,  0.17234208,  0.179523,    0.19388484,
-     0.19388484,  0.19388484,  0.19388484,  0.15798024,  0.17234208,
-     0.18670392,  0.17234208,  0.15079932,  0.179523,    0.15079932,
-     0.20106576,  0.16516116,  0.18670392,  0.15079932,  0.15798024,
-     0.12925656,  0.179523,    0.15798024,  0.17234208,  0.179523,
-     0.15798024,  0.18670392,  0.17234208,  0.18670392,  0.15798024,
-     0.18670392,  0.179523,    0.15798024,  0.17234208,  0.13643748,
-     0.18670392,  0.13643748,  0.17234208,  0.1436184,   0.15079932,
-     0.12207564,  0.15798024,  0.17234208,  0.17234208,  0.16516116,
-     0.179523,    0.179523,    0.15798024,  0.15079932,  0.17234208,
-     0.12207564,  0.2154276,   0.1436184,   0.19388484,  0.13643748,
-     0.17234208,  0.17234208,  0.20106576,  0.16516116,  0.18670392},
-    {1.0254F,
-     0.00718092,
-     0.01436184,
-     0.00718092,
-     -0.01436184,
-     0.02872368,
-     -0.02154276,
-     -0.00718092,
-     0.01436184,
-     0.02872368,
-     0.02872368,
-     -0.01436184,
-     0.04308552,
-     -0.01436184,
-     0,
-     0.0359046,
-     -0.01436184,
-     -0.02872368,
-     -0.02154276,
-     -0.0359046,
-     -0.01436184,
-     0.00718092,
-     -0.01436184,
-     0.01436184,
-     -0.01436184,
-     -0.01436184,
-     0.02154276,
-     0.01436184,
-     0.01436184,
-     -0.04308552,
-     -0.02154276,
-     0.01436184,
-     0.00718092,
-     -0.00718092,
-     -0.00718092,
-     -0.84734856,
-     -1.27820376,
-     -1.76650632,
-     -2.27635164,
-     -2.8005588,
-     -2.80773972,
-     -3.32476596,
-     -3.92078232,
-     -4.58142696,
-     -5.22770976,
-     -5.87399256,
-     -6.57772272,
-     -7.30299564,
-     -8.02108764,
-     -8.77508424,
-     -8.78944608,
-     -9.5865282,
-     -10.36206756,
-     -11.12324508,
-     -11.97059364,
-     -12.79639944,
-     -13.62220524,
-     -14.46237288,
-     -15.2953596,
-     -16.13552724,
-     -16.14270816,
-     -16.97569488,
-     -17.76559608,
-     -18.59140188,
-     -19.3525794,
-     -20.12093784,
-     -20.83902984,
-     -21.62893104,
-     -22.30393752,
-     -23.00048676,
-     -22.96458216,
-     -23.58214128,
-     -24.15661488,
-     -24.68800296,
-     -25.13322,
-     -25.5999798,
-     -26.00929224,
-     -26.36833824,
-     -26.61967044,
-     -26.8566408,
-     -26.8566408,
-     -27.00744012,
-     -27.08643024,
-     -27.08643024,
-     -27.07924932,
-     -26.92845,
-     -26.69866056,
-     -26.40424284,
-     -25.98056856,
-     -25.44199956,
-     -25.46354232,
-     -24.83880228,
-     -24.07762476,
-     -23.28054264,
-     -22.31829936,
-     -21.42068436,
-     -20.56615488,
-     -19.6039116,
-     -18.56985912,
-     -17.32037904,
-     -17.36346456,
-     -16.02063252,
-     -14.6131722,
-     -13.01182704,
-     -11.31712992,
-     -9.52908084,
-     -7.61895612,
-     -5.57957484,
-     -3.51146988,
-     -1.26384192,
-     -1.27102284,
-     1.03405248,
-     3.38221332,
-     5.83090704,
-     8.32268628,
-     10.80010368,
-     13.34933028,
-     15.81956676,
-     18.3472506,
-     20.85339168,
-     20.81030616,
-     23.22309528,
-     25.60716072,
-     27.88351236,
-     30.03060744,
-     32.0269032,
-     33.85085688,
-     35.50246848,
-     36.92429064,
-     37.49158332,
-     37.50594516,
-     37.86499116,
-     38.00142864,
-     37.83626748,
-     37.4844024,
-     36.81657684,
-     35.84715264,
-     34.66230084,
-     33.11840304,
-     31.3447158,
-     31.39498224,
-     29.31251544,
-     26.9643546,
-     24.40794708,
-     21.62175012,
-     18.5985828,
-     15.46770168,
-     12.0998502,
-     8.69609412,
-     5.14871964,
-     5.15590056,
-     1.55107872,
-     -2.10400956,
-     -5.6729268,
-     -9.21312036,
-     -12.6743238,
-     -15.98472792,
-     -19.15869456,
-     -22.06696716,
-     -24.75981216,
-     -24.73108848,
-     -27.1438776,
-     -29.19762072,
-     -30.9138606,
-     -32.32850184,
-     -33.37691616,
-     -34.0375608,
-     -34.35352128,
-     -34.20272196,
-     -33.7144194,
-     -33.74314308,
-     -32.85988992,
-     -31.56732432,
-     -29.86544628,
-     -27.84042684,
-     -25.53535152,
-     -22.80660192,
-     -19.927053,
-     -16.76026728,
-     -13.38523488,
-     -13.37805396,
-     -9.81631764,
-     -6.18995304,
-     -2.44869372,
-     1.29974652,
-     4.94765388,
-     8.53811388,
-     11.9562318,
-     15.13737936,
-     18.05283288,
-     18.0241092,
-     20.66668776,
-     23.03639136,
-     24.953697,
-     26.45450928,
-     27.56037096,
-     28.19947284,
-     28.31436756,
-     27.97686432,
-     27.20850588,
-     27.1797822,
-     25.9231212,
-     24.28587144,
-     22.21058556,
-     19.69726356,
-     16.93260936,
-     13.90944204,
-     10.64212344,
-     7.19528184,
-     3.70535472,
-     3.71253564,
-     0.17234208,
-     -3.32476596,
-     -6.6782556,
-     -9.86658408,
-     -12.76767576,
-     -15.39589248,
-     -17.60043492,
-     -19.51055964,
-     -20.91801996,
-     -20.90365812,
-     -21.88744416,
-     -22.37574672,
-     -22.33984212,
-     -21.94489152,
-     -20.95392456,
-     -19.55364516,
-     -17.70814872,
-     -15.46770168,
-     -12.91847508,
-     -12.95437968,
-     -10.11791628,
-     -7.16655816,
-     -4.07876256,
-     -0.98378604,
-     2.11119048,
-     5.00510124,
-     7.76975544,
-     10.23999192,
-     12.3511824,
-     12.4229916,
-     14.17513608,
-     15.46770168,
-     16.4084022,
-     16.81771464,
-     16.78899096,
-     16.336593,
-     15.37434972,
-     13.98843216,
-     12.25783044,
-     12.2793732,
-     10.1969064,
-     7.9349166,
-     5.4215946,
-     2.89391076,
-     0.30159864,
-     -2.21172336,
-     -4.64605524,
-     -6.77878848,
-     -8.70327504,
-     -8.71045596,
-     -10.31180112,
-     -11.50383384,
-     -12.33682056,
-     -12.80358036,
-     -12.76767576,
-     -12.3152778,
-     -11.5612812,
-     -10.3764294,
-     -8.88279804,
-     -8.91152172,
-     -7.20246276,
-     -5.29951896,
-     -3.20987124,
-     -1.15612812,
-     0.84016764,
-     2.85800616,
-     4.57424604,
-     6.11814384,
-     7.40352852,
-     7.3963476,
-     8.35859088,
-     8.98333092,
-     9.17721576,
-     9.0838638,
-     8.60274216,
-     7.82002188,
-     6.7859694,
-     5.47904196,
-     4.00695336,
-     4.02849612,
-     2.41997004,
-     0.79708212,
-     -0.84734856,
-     -2.35534176,
-     -3.79152576,
-     -4.96201572,
-     -5.82372612,
-     -6.54899904,
-     -6.8936832,
-     -6.91522596,
-     -6.97267332,
-     -6.79315032,
-     -6.31202868,
-     -5.55085116,
-     -4.58860788,
-     -3.52583172,
-     -2.31225624,
-     -1.077138,
-     0.15079932,
-     0.179523,
-     1.3643748,
-     2.48459832,
-     3.31758504,
-     4.06440072,
-     4.49525592,
-     4.75376904,
-     4.7753118,
-     4.54552236,
-     4.04285796,
-     4.07158164,
-     3.42529884,
-     2.67130224,
-     1.77368724,
-     0.85452948,
-     -0.0718092,
-     -0.94070052,
-     -1.78086816,
-     -2.513322,
-     -3.09497652,
-     -3.051891,
-     -3.46120344,
-     -3.63354552,
-     -3.67663104,
-     -3.51146988,
-     -3.21705216,
-     -2.70720684,
-     -2.17581876,
-     -1.5079932,
-     -0.86889132,
-     -0.8617104,
-     -0.18670392,
-     0.50984532,
-     1.04841432,
-     1.52953596,
-     1.88858196,
-     2.13991416,
-     2.29071348,
-     2.24044704,
-     2.10400956,
-     2.1183714,
-     1.84549644,
-     1.5079932,
-     1.04841432,
-     0.6103782,
-     0.1077138,
-     -0.37340784,
-     -0.79708212,
-     -1.17767088,
-     -1.5438978,
-     -1.52953596,
-     -1.75214448,
-     -1.9029438,
-     -1.87422012,
-     -1.79523,
-     -1.66597344,
-     -1.44336492,
-     -1.17767088,
-     -0.81862488,
-     -0.49548348,
-     -0.48830256,
-     -0.15798024,
-     0.19388484,
-     0.45957888,
-     0.73963476,
-     0.91915776,
-     1.077138,
-     1.1848518,
-     1.19203272,
-     1.13458536,
-     1.1130426,
-     1.01250972,
-     0.79708212,
-     0.63910188,
-     0.40213152,
-     0.19388484,
-     -0.05026644,
-     -0.27287496,
-     -0.44521704,
-     -0.63192096,
-     -0.6103782,
-     -0.76117752,
-     -0.77553936,
-     -0.77553936,
-     -0.74681568,
-     -0.68936832,
-     -0.538569,
-     -0.45239796,
-     -0.27287496,
-     -0.07899012,
-     -0.1077138,
-     0.04308552,
-     0.2154276,
-     0.33750324,
-     0.41649336,
-     0.52420716,
-     0.59601636,
-     0.55293084,
-     0.56729268,
-     0.50984532,
-     0.49548348,
-     0.41649336,
-     0.34468416,
-     0.24415128,
-     0.15079932,
-     0.02154276,
-     -0.12207564,
-     -0.179523,
-     -0.2513322,
-     -0.30877956,
-     -0.2872368,
-     -0.30877956,
-     -0.359046,
-     -0.3231414,
-     -0.31596048,
-     -0.30877956,
-     -0.30877956,
-     -0.3231414,
-     -0.33032232,
-     -0.37340784,
-     -0.35186508,
-     -0.44521704,
-     -0.50984532,
-     -0.538569,
-     -0.58165452,
-     -0.62474004,
-     -0.72527292,
-     -0.76835844,
-     -0.7539966,
-     -0.78272028,
-     -0.81144396,
-     -0.81862488,
-     -0.78272028,
-     -0.73963476,
-     -0.718092,
-     -0.71091108,
-     -0.63910188,
-     -0.65346372,
-     -0.61755912,
-     -0.56729268,
-     -0.56729268,
-     -0.48112164,
-     -0.45239796,
-     -0.43803612,
-     -0.47394072,
-     -0.45239796,
-     -0.43803612,
-     -0.4667598,
-     -0.49548348,
-     -0.48830256,
-     -0.52420716,
-     -0.55293084,
-     -0.51702624,
-     -0.56011176,
-     -0.56729268,
-     -0.58165452,
-     -0.6103782,
-     -0.67500648,
-     -0.65346372,
-     -0.63910188,
-     -0.6462828,
-     -0.6821874,
-     -0.66064464,
-     -0.66064464,
-     -0.65346372,
-     -0.59601636,
-     -0.58883544,
-     -0.56729268,
-     -0.5744736,
-     -0.55293084,
-     -0.53138808,
-     -0.48830256,
-     -0.38058876,
-     -0.29441772,
-     -0.18670392,
-     -0.05744736,
-     0.05026644,
-     0.15798024,
-     0.25851312,
-     0.30159864,
-     0.29441772,
-     0.37340784,
-     0.41649336,
-     0.41649336,
-     0.4308552,
-     0.3949506,
-     0.37340784,
-     0.33032232,
-     0.27287496,
-     0.16516116,
-     0.20824668,
-     0.11489472,
-     0.02872368,
-     -0.07899012,
-     -0.1436184,
-     -0.15079932,
-     -0.16516116,
-     -0.22260852,
-     -0.24415128,
-     -0.28005588,
-     -0.25851312,
-     -0.25851312,
-     -0.2154276,
-     -0.13643748,
-     -0.1077138,
-     -0.10053288,
-     -0.04308552,
-     0.04308552,
-     0.0718092,
-     0.12207564,
-     0.09335196,
-     0.17234208,
-     0.20824668,
-     0.20106576,
-     0.24415128,
-     0.22978944,
-     0.22978944,
-     0.19388484,
-     0.13643748,
-     0.17234208,
-     0.17234208,
-     0.10053288,
-     0.06462828,
-     0.06462828,
-     0.02872368,
-     -0.00718092,
-     -0.0359046,
-     -0.06462828,
-     -0.06462828,
-     -0.09335196,
-     -0.0718092,
-     -0.13643748,
-     -0.12207564,
-     -0.08617104,
-     -0.0359046,
-     -0.05026644,
-     -0.0359046,
-     0,
-     -0.00718092,
-     0.05026644,
-     0.04308552,
-     0.07899012,
-     0.0718092,
-     0.0718092,
-     0.1436184,
-     0.11489472,
-     0.09335196,
-     0.1436184,
-     0.10053288,
-     0.13643748,
-     0.1077138,
-     0.06462828,
-     0.10053288,
-     0.1077138,
-     0.0718092,
-     0.09335196,
-     0.05744736,
-     0,
-     0.02154276,
-     0.00718092,
-     0.02154276,
-     -0.02154276,
-     -0.01436184,
-     -0.00718092,
-     -0.05026644,
-     0.00718092,
-     0,
-     -0.01436184,
-     -0.02154276,
-     0.02154276,
-     -0.00718092,
-     0.02872368,
-     0.0359046,
-     0.06462828,
-     0.05744736,
-     0.08617104,
-     0.05744736,
-     0.05744736,
-     0.1077138,
-     0.0718092,
-     0.1077138,
-     0.12207564,
-     0.08617104,
-     0.08617104,
-     0.09335196,
-     0.0718092,
-     0.0718092,
-     0.0718092,
-     0.05026644,
-     0.0718092,
-     0.07899012,
-     0.01436184,
-     0.02872368,
-     0.04308552,
-     0.04308552,
-     0.02154276,
-     0.01436184,
-     0.00718092,
-     0.05744736,
-     0.0359046,
-     0.00718092,
-     0.05026644,
-     0.02872368,
-     0.0359046,
-     0.04308552,
-     0.05744736,
-     0.04308552,
-     0.0359046,
-     0.0718092,
-     0.06462828,
-     0.05026644,
-     0.06462828,
-     0.05744736,
-     0.06462828,
-     0.05026644,
-     0.06462828,
-     0.0359046,
-     0.0359046,
-     0.05744736,
-     0.05026644,
-     0.05744736,
-     0.05026644,
-     0.04308552,
-     0.0718092,
-     0.04308552,
-     0.05026644,
-     0.02872368,
-     0.02154276,
-     0.04308552,
-     0.01436184,
-     0.05744736,
-     0.0359046,
-     0.04308552,
-     0.02872368,
-     0.05026644,
-     0.05744736,
-     0.0718092,
-     0.04308552,
-     0.0359046,
-     0.05026644,
-     0.05744736,
-     0.1077138,
-     0.05744736,
-     0.07899012,
-     0.0718092,
-     0.01436184,
-     0.05026644,
-     0.07899012,
-     0.08617104,
-     0.0718092,
-     0.08617104,
-     0.05744736,
-     0.06462828,
-     0.08617104,
-     0.0718092,
-     0.01436184,
-     0.0718092,
-     0.0718092,
-     0.04308552,
-     0.02154276,
-     0.06462828,
-     0.04308552,
-     0.04308552,
-     0.06462828,
-     0.05026644,
-     0.09335196,
-     0.1077138,
-     0.00718092,
-     0.02872368,
-     0.06462828,
-     0.05026644,
-     0.04308552,
-     0.04308552,
-     0.07899012,
-     0.04308552,
-     0,
-     0.06462828,
-     0.0359046,
-     0.04308552,
-     0.04308552,
-     0.06462828,
-     0.0359046,
-     0.01436184,
-     0.04308552,
-     0.02872368,
-     0.01436184,
-     0.05744736,
-     0.09335196,
-     0.06462828,
-     0.06462828,
-     0.05744736,
-     0.02154276,
-     0.0718092,
-     0.04308552,
-     0.0718092,
-     0.02872368,
-     0.05744736,
-     0.02154276,
-     0.05026644,
-     0.06462828,
-     0.06462828,
-     0.04308552,
-     0.0359046,
-     0.05026644,
-     0.06462828,
-     0.04308552,
-     0.0718092,
-     0.02154276,
-     0.05026644,
-     0.06462828,
-     0.05026644,
-     0.01436184,
-     0.02154276,
-     0.0359046,
-     0.02154276,
-     0.08617104,
-     0.05744736,
-     0.02872368,
-     0.04308552,
-     0.04308552,
-     0.00718092,
-     0.02872368,
-     0.01436184,
-     0.0359046,
-     -0.00718092,
-     0.02872368,
-     -0.02154276,
-     -0.04308552,
-     -0.00718092,
-     -0.0359046,
-     -0.02872368,
-     -0.06462828,
-     -0.04308552,
-     -0.05026644,
-     -0.01436184,
-     -0.09335196,
-     -0.05026644,
-     -0.05026644,
-     -0.02154276,
-     -0.05026644,
-     -0.05744736,
-     -0.02872368,
-     -0.05744736,
-     -0.02872368,
-     -0.02872368,
-     -0.01436184,
-     0.02872368,
-     -0.02872368,
-     0.01436184,
-     -0.00718092,
-     -0.00718092,
-     0.0359046,
-     0.02154276,
-     0,
-     0.0359046,
-     0.0359046,
-     0,
-     0.0359046,
-     0.0359046,
-     -0.00718092,
-     0,
-     0.02154276,
-     0.02872368,
-     0.01436184,
-     -0.01436184,
-     -0.00718092,
-     -0.01436184,
-     -0.00718092,
-     -0.02154276,
-     -0.02154276,
-     -0.0359046,
-     -0.02872368,
-     -0.00718092,
-     -0.01436184,
-     -0.08617104,
-     -0.01436184,
-     -0.01436184,
-     -0.02872368,
-     -0.00718092,
-     -0.05026644,
-     -0.07899012,
-     -0.0359046,
-     -0.05744736,
-     -0.01436184,
-     -0.04308552,
-     0.02154276,
-     -0.06462828,
-     -0.01436184,
-     0.02872368,
-     -0.02872368,
-     0.0359046,
-     0,
-     0,
-     0.00718092,
-     -0.01436184,
-     0.02872368,
-     -0.00718092,
-     0.01436184,
-     0.01436184,
-     0.06462828,
-     0.00718092,
-     -0.02872368,
-     0.01436184,
-     0.01436184,
-     -0.01436184,
-     -0.04308552,
-     0.00718092,
-     -0.02154276,
-     0.01436184,
-     0,
-     -0.0359046,
-     -0.02154276,
-     -0.01436184,
-     -0.02154276,
-     -0.02154276,
-     -0.04308552,
-     0,
-     -0.04308552,
-     -0.01436184,
-     0,
-     0.02872368,
-     -0.05026644,
-     0,
-     -0.01436184,
-     -0.02872368,
-     -0.01436184,
-     -0.0359046,
-     0,
-     -0.00718092,
-     -0.00718092,
-     -0.01436184,
-     0,
-     0.0359046,
-     0,
-     0.00718092,
-     -0.01436184,
-     -0.00718092,
-     0,
-     -0.02872368,
-     -0.01436184,
-     0.02154276,
-     -0.00718092,
-     0.00718092,
-     0,
-     -0.02154276,
-     0.02154276,
-     0.00718092,
-     0.00718092,
-     0.00718092,
-     0.02154276,
-     0.00718092,
-     -0.00718092,
-     -0.02872368,
-     -0.02154276,
-     -0.0359046,
-     -0.00718092,
-     -0.00718092,
-     -0.05026644,
-     -0.02872368,
-     -0.04308552,
-     -0.02872368,
-     -0.00718092,
-     -0.02872368,
-     -0.01436184,
-     -0.01436184,
-     -0.00718092,
-     0,
-     -0.02154276,
-     0,
-     -0.04308552,
-     -0.02872368,
-     -0.01436184,
-     -0.00718092,
-     -0.01436184,
-     -0.01436184,
-     0.0359046,
-     -0.04308552,
-     -0.02872368,
-     -0.01436184,
-     0.00718092,
-     -0.02154276,
-     -0.00718092,
-     -0.01436184,
-     -0.00718092,
-     -0.02154276,
-     -0.02154276,
-     0.02154276,
-     -0.00718092,
-     -0.02872368,
-     -0.0359046,
-     -0.02154276,
-     -0.02872368,
-     -0.02872368,
-     -0.02872368,
-     0.01436184,
-     -0.02154276,
-     -0.02872368,
-     -0.0359046,
-     -0.01436184,
-     0.02154276,
-     0,
-     0,
-     -0.0359046,
-     0.00718092,
-     -0.00718092,
-     -0.0359046,
-     -0.01436184,
-     0,
-     -0.01436184,
-     -0.01436184,
-     -0.04308552,
-     -0.01436184,
-     -0.05744736,
-     -0.00718092,
-     -0.00718092,
-     -0.02872368,
-     0,
-     -0.02154276,
-     -0.05026644,
-     -0.05026644,
-     -0.05026644,
-     -0.00718092,
-     -0.02872368,
-     -0.0359046,
-     -0.02154276,
-     0,
-     -0.05026644,
-     -0.04308552,
-     -0.01436184,
-     0.01436184,
-     -0.00718092,
-     0.02872368,
-     -0.05026644,
-     -0.01436184,
-     0.00718092,
-     -0.00718092,
-     -0.02872368,
-     -0.04308552,
-     -0.0359046,
-     -0.02154276,
-     -0.0359046,
-     -0.01436184,
-     -0.05026644,
-     -0.02872368,
-     -0.02872368,
-     -0.05744736,
-     -0.01436184,
-     -0.01436184,
-     0.00718092,
-     -0.02872368,
-     -0.0359046,
-     -0.01436184,
-     -0.02154276,
-     -0.00718092,
-     -0.02154276,
-     -0.0359046,
-     -0.02872368,
-     -0.01436184,
-     0,
-     -0.0359046,
-     -0.02154276,
-     -0.02872368,
-     0.02872368,
-     0,
-     -0.02872368,
-     0.00718092,
-     -0.05026644,
-     0.01436184,
-     -0.01436184,
-     -0.02872368,
-     -0.04308552,
-     0,
-     -0.00718092,
-     -0.0718092,
-     -0.0359046,
-     -0.02872368,
-     -0.05026644,
-     -0.02154276,
-     -0.04308552,
-     0.01436184,
-     -0.02154276,
-     -0.02154276,
-     -0.0359046,
-     -0.0359046,
-     -0.02154276,
-     -0.0359046,
-     -0.00718092,
-     -0.0359046,
-     -0.00718092,
-     -0.01436184,
-     -0.01436184,
-     -0.05026644,
-     -0.05744736,
-     -0.01436184,
-     -0.02154276,
-     -0.04308552,
-     -0.02154276,
-     -0.01436184,
-     -0.01436184,
-     0.00718092,
-     -0.05744736,
-     -0.04308552,
-     -0.00718092,
-     -0.08617104,
-     -0.04308552,
-     -0.0359046,
-     -0.02872368,
-     -0.04308552,
-     -0.04308552,
-     -0.01436184,
-     0,
-     -0.05026644,
-     -0.0718092,
-     -0.05026644,
-     -0.04308552,
-     -0.01436184,
-     -0.01436184,
-     -0.0359046,
-     0.00718092,
-     -0.02872368,
-     -0.05744736,
-     0,
-     -0.06462828,
-     0.01436184,
-     -0.04308552,
-     -0.04308552,
-     -0.04308552,
-     -0.04308552,
-     0.01436184,
-     -0.01436184,
-     -0.00718092,
-     -0.00718092,
-     -0.02154276,
-     -0.05744736,
-     -0.04308552,
-     -0.01436184,
-     -0.02154276,
-     -0.0359046,
-     -0.0359046,
-     -0.05744736,
-     -0.01436184,
-     -0.05744736,
-     -0.01436184,
-     -0.06462828,
-     -0.02872368,
-     -0.0359046,
-     -0.00718092,
-     -0.05744736,
-     -0.00718092,
-     -0.05744736,
-     -0.00718092,
-     -0.00718092,
-     -0.05744736,
-     -0.05744736,
-     -0.02154276,
-     -0.02154276,
-     -0.02872368,
-     -0.02154276,
-     -0.02872368,
-     -0.01436184,
-     -0.0359046,
-     -0.06462828,
-     -0.01436184,
-     -0.05744736,
-     -0.00718092,
-     -0.02872368,
-     -0.00718092,
-     -0.04308552,
-     -0.02872368,
-     -0.01436184,
-     -0.02154276,
-     -0.02154276,
-     -0.02154276,
-     -0.02872368,
-     0.01436184,
-     -0.07899012,
-     0.01436184,
-     -0.02872368,
-     0,
-     -0.00718092,
-     0,
-     0,
-     -0.00718092,
-     -0.01436184,
-     -0.02154276,
-     -0.00718092,
-     -0.01436184,
-     -0.0359046,
-     -0.02872368,
-     -0.00718092,
-     0.02154276,
-     0.00718092,
-     0,
-     0.00718092,
-     0,
-     0.0359046,
-     -0.01436184,
-     -0.0359046,
-     -0.01436184,
-     0.04308552,
-     -0.00718092,
-     0.00718092,
-     0.00718092,
-     -0.00718092,
-     0.01436184,
-     0.00718092,
-     0.00718092,
-     0.00718092,
-     -0.01436184,
-     -0.00718092,
-     -0.02154276,
-     0,
-     0.02154276,
-     0,
-     -0.00718092,
-     -0.02154276,
-     -0.02872368,
-     -0.02872368,
-     0.00718092,
-     0.02872368,
-     0,
-     -0.00718092,
-     -0.01436184,
-     0.00718092,
-     -0.02154276,
-     0.00718092,
-     -0.00718092,
-     0.01436184,
-     0,
-     0.01436184,
-     -0.01436184,
-     -0.00718092,
-     -0.02872368,
-     0.02154276,
-     -0.01436184,
-     -0.01436184,
-     -0.02154276,
-     -0.00718092,
-     -0.00718092,
-     -0.00718092,
-     0,
-     -0.02154276,
-     0.00718092,
-     0.01436184,
-     0.00718092,
-     -0.00718092,
-     -0.01436184,
-     0.00718092,
-     -0.00718092,
-     0.02154276,
-     -0.00718092,
-     -0.02872368,
-     -0.00718092,
-     -0.00718092,
-     0.01436184,
-     0.00718092,
-     0.02872368,
-     0.01436184,
-     0.02154276,
-     0.02872368,
-     -0.00718092,
-     0.02872368,
-     -0.00718092,
-     -0.00718092,
-     0.00718092,
-     0,
-     0,
-     0,
-     0,
-     0.04308552,
-     -0.00718092,
-     0.00718092,
-     -0.01436184,
-     0.01436184,
-     0.00718092,
-     0,
-     0.02872368,
-     -0.01436184,
-     -0.00718092,
-     0.01436184,
-     0,
-     0,
-     0.00718092,
-     0.00718092,
-     0.0359046,
-     0.00718092,
-     -0.0359046,
-     -0.01436184,
-     -0.01436184,
-     -0.00718092,
-     0.01436184,
-     -0.02154276,
-     -0.01436184,
-     0.00718092,
-     -0.04308552,
-     -0.01436184,
-     0,
-     0.00718092,
-     0.02154276,
-     -0.00718092,
-     0.00718092,
-     0.0359046,
-     0.00718092,
-     -0.02154276,
-     -0.00718092,
-     0.02872368,
-     0,
-     0.01436184,
-     0.01436184,
-     0.02872368,
-     -0.02154276,
-     0.02154276,
-     0.01436184,
-     -0.01436184,
-     0.00718092,
-     0.04308552,
-     0.00718092,
-     0.01436184,
-     0,
-     0,
-     -0.00718092,
-     0.04308552,
-     -0.00718092,
-     0.00718092,
-     -0.01436184,
-     0,
-     -0.00718092,
-     0.01436184,
-     0.0359046,
-     0.02872368,
-     0.01436184,
-     0.00718092,
-     0.02872368,
-     0.01436184,
-     -0.00718092,
-     0.00718092,
-     0.04308552,
-     0.0359046,
-     0.0359046,
-     -0.01436184,
-     -0.00718092,
-     -0.00718092,
-     0.01436184,
-     0.00718092,
-     0.02154276,
-     0,
-     -0.0359046,
-     0.02154276,
-     0.02872368,
-     0.02154276,
-     0.01436184,
-     0.01436184,
-     0.04308552,
-     0.01436184,
-     -0.00718092,
-     0.02154276,
-     0.00718092,
-     0.05026644,
-     0.01436184,
-     0.01436184,
-     0.02872368,
-     0.02872368,
-     0.04308552,
-     0.06462828,
-     0.00718092,
-     0.05026644,
-     0.02872368,
-     0.04308552,
-     0.01436184,
-     0.05026644,
-     0.06462828,
-     0.06462828,
-     0.0359046,
-     0.05026644,
-     0.02154276,
-     0.02154276,
-     0.0359046,
-     0.02872368,
-     0.05744736,
-     0.02872368,
-     0.00718092,
-     0.02872368,
-     0.04308552,
-     0.05026644,
-     0.05026644,
-     0.01436184,
-     0.0718092,
-     0.04308552,
-     0.02872368,
-     0.0359046,
-     0.02872368,
-     0.02154276,
-     0.02154276,
-     0.05026644,
-     0.02872368,
-     0.04308552,
-     0.05026644,
-     0.0718092,
-     0.0718092,
-     0.04308552,
-     0.05026644,
-     0.0718092,
-     0.11489472,
-     0.05026644,
-     0.05744736,
-     0.07899012,
-     0.0718092,
-     0.05744736,
-     0.07899012,
-     0.1077138,
-     0.06462828,
-     0.09335196,
-     0.09335196,
-     0.11489472,
-     0.12925656,
-     0.1077138,
-     0.10053288,
-     0.12207564,
-     0.08617104,
-     0.12207564,
-     0.15798024,
-     0.10053288,
-     0.10053288,
-     0.1077138,
-     0.11489472,
-     0.09335196,
-     0.1077138,
-     0.11489472,
-     0.11489472,
-     0.09335196,
-     0.09335196,
-     0.10053288,
-     0.12207564,
-     0.0718092,
-     0.06462828,
-     0.11489472,
-     0.08617104,
-     0.12925656,
-     0.07899012,
-     0.07899012,
-     0.07899012,
-     0.08617104,
-     0.09335196,
-     0.06462828,
-     0.08617104,
-     0.0718092,
-     0.07899012,
-     0.1077138,
-     0.09335196,
-     0.05026644,
-     0.0718092,
-     0.08617104,
-     0.05744736,
-     0.06462828,
-     0.0718092,
-     0.0718092,
-     0.08617104,
-     0.10053288,
-     0.05026644,
-     0.10053288,
-     0.09335196,
-     0.06462828,
-     0.05744736,
-     0.08617104,
-     0.09335196,
-     0.08617104,
-     0.05026644,
-     0.13643748,
-     0.09335196,
-     0.06462828,
-     0.11489472,
-     0.10053288,
-     0.09335196,
-     0.09335196,
-     0.06462828,
-     0.08617104,
-     0.08617104,
-     0.10053288,
-     0.12925656,
-     0.1436184,
-     0.1077138,
-     0.1077138,
-     0.11489472,
-     0.12207564,
-     0.12925656,
-     0.09335196,
-     0.15079932,
-     0.12925656,
-     0.09335196,
-     0.12925656,
-     0.08617104,
-     0.12207564,
-     0.12207564,
-     0.09335196,
-     0.13643748,
-     0.10053288,
-     0.1077138,
-     0.12207564,
-     0.10053288,
-     0.12925656,
-     0.11489472,
-     0.08617104,
-     0.07899012,
-     0.12925656,
-     0.12207564,
-     0.12925656,
-     0.11489472,
-     0.1077138,
-     0.08617104,
-     0.08617104,
-     0.09335196,
-     0.08617104,
-     0.08617104,
-     0.08617104,
-     0.09335196,
-     0.07899012,
-     0.10053288,
-     0.11489472,
-     0.07899012,
-     0.07899012,
-     0.09335196,
-     0.11489472,
-     0.10053288,
-     0.11489472,
-     0.09335196,
-     0.05744736,
-     0.08617104,
-     0.09335196,
-     0.0718092,
-     0.1077138,
-     0.1077138,
-     0.06462828,
-     0.09335196,
-     0.10053288,
-     0.1077138,
-     0.07899012,
-     0.07899012,
-     0.1077138,
-     0.09335196,
-     0.11489472,
-     0.09335196,
-     0.12207564,
-     0.11489472,
-     0.12925656,
-     0.11489472,
-     0.09335196,
-     0.1077138,
-     0.11489472,
-     0.13643748,
-     0.1077138,
-     0.12207564,
-     0.10053288,
-     0.12925656,
-     0.12925656,
-     0.11489472,
-     0.11489472,
-     0.10053288,
-     0.11489472,
-     0.08617104,
-     0.12207564,
-     0.12207564,
-     0.12207564,
-     0.15079932,
-     0.1436184,
-     0.1436184,
-     0.16516116,
-     0.15079932,
-     0.12925656,
-     0.13643748,
-     0.13643748,
-     0.1077138,
-     0.1077138,
-     0.13643748,
-     0.09335196,
-     0.12925656,
-     0.13643748,
-     0.15079932,
-     0.1077138,
-     0.12925656,
-     0.12207564,
-     0.1077138,
-     0.13643748,
-     0.13643748,
-     0.10053288,
-     0.1436184,
-     0.13643748,
-     0.11489472,
-     0.1436184,
-     0.12207564,
-     0.1436184,
-     0.1436184,
-     0.12925656,
-     0.1077138,
-     0.12207564,
-     0.12925656,
-     0.13643748,
-     0.13643748,
-     0.11489472,
-     0.15798024,
-     0.15079932,
-     0.13643748,
-     0.12207564,
-     0.1436184,
-     0.10053288,
-     0.12207564,
-     0.13643748,
-     0.12207564,
-     0.1077138,
-     0.18670392,
-     0.1077138,
-     0.1436184,
-     0.15798024,
-     0.17234208,
-     0.1436184,
-     0.13643748,
-     0.179523,
-     0.15079932,
-     0.15079932,
-     0.16516116,
-     0.15798024,
-     0.18670392,
-     0.179523,
-     0.13643748,
-     0.1436184,
-     0.17234208,
-     0.15798024,
-     0.12925656,
-     0.15798024,
-     0.19388484,
-     0.18670392,
-     0.15079932,
-     0.15079932,
-     0.17234208,
-     0.17234208,
-     0.17234208,
-     0.15798024,
-     0.17234208,
-     0.1436184,
-     0.15079932,
-     0.15798024,
-     0.18670392,
-     0.1436184,
-     0.19388484,
-     0.11489472,
-     0.16516116,
-     0.15079932,
-     0.15079932,
-     0.19388484,
-     0.16516116,
-     0.16516116,
-     0.15798024,
-     0.17234208,
-     0.17234208,
-     0.16516116,
-     0.179523,
-     0.1436184,
-     0.15798024,
-     0.15798024,
-     0.12925656,
-     0.18670392,
-     0.179523,
-     0.20106576,
-     0.16516116,
-     0.20106576,
-     0.15079932,
-     0.16516116,
-     0.1436184,
-     0.17234208,
-     0.18670392,
-     0.20106576,
-     0.18670392,
-     0.16516116,
-     0.16516116,
-     0.15079932,
-     0.15798024,
-     0.1436184,
-     0.15079932,
-     0.1436184,
-     0.1436184,
-     0.15079932,
-     0.179523,
-     0.17234208,
-     0.16516116,
-     0.2154276,
-     0.179523,
-     0.15798024,
-     0.15079932,
-     0.12925656,
-     0.16516116,
-     0.179523,
-     0.17234208,
-     0.15798024,
-     0.18670392,
-     0.15079932,
-     0.18670392,
-     0.17234208,
-     0.16516116,
-     0.17234208,
-     0.179523,
-     0.179523,
-     0.18670392,
-     0.1436184,
-     0.179523,
-     0.18670392,
-     0.19388484,
-     0.23697036,
-     0.20824668,
-     0.1436184,
-     0.18670392,
-     0.179523,
-     0.20824668,
-     0.19388484,
-     0.16516116,
-     0.179523,
-     0.15798024,
-     0.18670392,
-     0.18670392,
-     0.13643748,
-     0.18670392,
-     0.16516116,
-     0.17234208,
-     0.16516116,
-     0.16516116,
-     0.17234208,
-     0.18670392,
-     0.20824668,
-     0.179523,
-     0.179523,
-     0.15079932,
-     0.16516116,
-     0.20106576,
-     0.17234208,
-     0.20106576,
-     0.15798024,
-     0.20106576,
-     0.19388484,
-     0.18670392,
-     0.15798024,
-     0.19388484,
-     0.18670392,
-     0.20106576,
-     0.16516116,
-     0.1436184,
-     0.15079932,
-     0.19388484,
-     0.18670392,
-     0.16516116,
-     0.17234208,
-     0.17234208,
-     0.20824668,
-     0.22260852,
-     0.18670392,
-     0.18670392,
-     0.15079932,
-     0.17234208,
-     0.20106576,
-     0.2154276,
-     0.16516116,
-     0.179523,
-     0.179523,
-     0.20106576,
-     0.18670392,
-     0.20824668,
-     0.20824668,
-     0.19388484,
-     0.19388484,
-     0.15798024,
-     0.18670392,
-     0.20824668,
-     0.18670392,
-     0.15798024,
-     0.18670392,
-     0.20106576,
-     0.20106576,
-     0.2513322,
-     0.20106576,
-     0.179523,
-     0.19388484,
-     0.20106576,
-     0.20106576,
-     0.15798024,
-     0.19388484,
-     0.2154276,
-     0.20824668,
-     0.20106576,
-     0.20106576,
-     0.18670392,
-     0.20824668,
-     0.19388484,
-     0.20106576,
-     0.20106576,
-     0.18670392,
-     0.179523,
-     0.18670392,
-     0.18670392,
-     0.17234208,
-     0.18670392,
-     0.20824668,
-     0.20824668,
-     0.22978944,
-     0.18670392,
-     0.20106576,
-     0.22978944,
-     0.19388484,
-     0.22260852,
-     0.19388484,
-     0.2154276,
-     0.25851312,
-     0.179523,
-     0.22978944,
-     0.20106576,
-     0.22978944,
-     0.22978944,
-     0.2154276,
-     0.24415128,
-     0.2513322,
-     0.22978944,
-     0.23697036,
-     0.22260852,
-     0.22978944,
-     0.2154276,
-     0.2154276,
-     0.23697036,
-     0.22978944,
-     0.22978944,
-     0.26569404,
-     0.22260852,
-     0.27287496,
-     0.17234208,
-     0.20824668,
-     0.2154276,
-     0.20824668,
-     0.23697036,
-     0.22260852,
-     0.26569404,
-     0.24415128,
-     0.23697036,
-     0.24415128,
-     0.26569404,
-     0.22260852,
-     0.20824668,
-     0.2872368,
-     0.22978944,
-     0.24415128,
-     0.20106576,
-     0.23697036,
-     0.2513322,
-     0.25851312,
-     0.2513322,
-     0.2513322,
-     0.27287496,
-     0.24415128,
-     0.2513322,
-     0.26569404,
-     0.23697036,
-     0.28005588,
-     0.25851312,
-     0.2513322,
-     0.25851312,
-     0.26569404,
-     0.29441772,
-     0.23697036,
-     0.23697036,
-     0.28005588,
-     0.24415128,
-     0.27287496,
-     0.2872368,
-     0.27287496,
-     0.22260852,
-     0.26569404,
-     0.27287496,
-     0.28005588,
-     0.27287496,
-     0.2513322,
-     0.25851312,
-     0.2513322,
-     0.24415128,
-     0.26569404,
-     0.28005588,
-     0.27287496,
-     0.2513322,
-     0.26569404,
-     0.2513322,
-     0.25851312,
-     0.24415128,
-     0.28005588,
-     0.2513322,
-     0.2513322,
-     0.24415128,
-     0.27287496,
-     0.29441772,
-     0.25851312,
-     0.26569404,
-     0.25851312,
-     0.2872368,
-     0.2872368,
-     0.24415128,
-     0.28005588,
-     0.2872368,
-     0.26569404,
-     0.25851312,
-     0.2513322,
-     0.28005588,
-     0.27287496,
-     0.31596048,
-     0.29441772,
-     0.25851312,
-     0.30877956,
-     0.27287496,
-     0.30877956,
-     0.29441772,
-     0.28005588,
-     0.29441772,
-     0.29441772,
-     0.30159864,
-     0.3231414,
-     0.29441772,
-     0.31596048,
-     0.28005588,
-     0.27287496,
-     0.31596048,
-     0.29441772,
-     0.33750324,
-     0.30877956,
-     0.31596048,
-     0.27287496,
-     0.31596048,
-     0.30877956,
-     0.31596048,
-     0.31596048,
-     0.33032232,
-     0.29441772,
-     0.30159864,
-     0.3231414,
-     0.31596048,
-     0.3231414,
-     0.29441772,
-     0.3231414,
-     0.31596048,
-     0.3231414,
-     0.34468416,
-     0.33750324,
-     0.33032232,
-     0.29441772,
-     0.34468416,
-     0.33032232,
-     0.3231414,
-     0.33032232,
-     0.33032232,
-     0.33750324,
-     0.33032232,
-     0.3231414,
-     0.33750324,
-     0.3231414,
-     0.28005588,
-     0.30877956,
-     0.31596048,
-     0.3231414,
-     0.33032232,
-     0.37340784,
-     0.33750324,
-     0.34468416,
-     0.33032232,
-     0.3231414,
-     0.3231414,
-     0.3231414,
-     0.35186508,
-     0.2872368,
-     0.31596048,
-     0.35186508,
-     0.34468416,
-     0.34468416,
-     0.36622692,
-     0.34468416,
-     0.38776968,
-     0.359046,
-     0.35186508,
-     0.359046,
-     0.33032232,
-     0.36622692,
-     0.36622692,
-     0.35186508,
-     0.37340784,
-     0.37340784,
-     0.34468416,
-     0.31596048,
-     0.38058876,
-     0.38058876,
-     0.37340784,
-     0.3949506,
-     0.3949506,
-     0.359046,
-     0.38776968,
-     0.33032232,
-     0.38058876,
-     0.37340784,
-     0.35186508,
-     0.38058876,
-     0.35186508,
-     0.36622692,
-     0.40213152,
-     0.42367428,
-     0.359046,
-     0.38776968,
-     0.38776968,
-     0.41649336,
-     0.4308552,
-     0.35186508,
-     0.38058876,
-     0.359046,
-     0.3949506,
-     0.37340784,
-     0.38776968,
-     0.41649336,
-     0.40213152,
-     0.3949506,
-     0.37340784,
-     0.41649336,
-     0.37340784,
-     0.38058876,
-     0.38776968,
-     0.37340784,
-     0.37340784,
-     0.38776968,
-     0.42367428,
-     0.40931244,
-     0.41649336,
-     0.42367428,
-     0.38058876,
-     0.43803612,
-     0.4308552,
-     0.41649336,
-     0.4308552,
-     0.40931244,
-     0.41649336,
-     0.38058876,
-     0.40931244,
-     0.40931244,
-     0.38058876,
-     0.3949506,
-     0.43803612,
-     0.43803612,
-     0.44521704,
-     0.40213152,
-     0.40931244,
-     0.3949506,
-     0.40931244,
-     0.45239796,
-     0.4308552,
-     0.4308552,
-     0.42367428,
-     0.45239796,
-     0.4308552,
-     0.4308552,
-     0.47394072,
-     0.42367428,
-     0.44521704,
-     0.42367428,
-     0.44521704,
-     0.40213152,
-     0.44521704,
-     0.4308552,
-     0.45957888,
-     0.42367428,
-     0.45957888,
-     0.48112164,
-     0.43803612,
-     0.43803612,
-     0.45239796,
-     0.45957888,
-     0.44521704,
-     0.4308552,
-     0.45239796,
-     0.42367428,
-     0.42367428,
-     0.45957888,
-     0.42367428,
-     0.45957888,
-     0.45239796,
-     0.4667598,
-     0.44521704,
-     0.48112164,
-     0.45239796,
-     0.49548348,
-     0.4667598,
-     0.4667598,
-     0.44521704,
-     0.44521704,
-     0.45239796,
-     0.47394072,
-     0.43803612,
-     0.5026644,
-     0.48112164,
-     0.44521704,
-     0.48112164,
-     0.48830256,
-     0.45239796,
-     0.48830256,
-     0.4667598,
-     0.4667598,
-     0.48830256,
-     0.47394072,
-     0.5026644,
-     0.50984532,
-     0.49548348,
-     0.45239796,
-     0.49548348,
-     0.51702624,
-     0.53138808,
-     0.51702624,
-     0.5026644,
-     0.52420716,
-     0.5026644,
-     0.538569,
-     0.51702624,
-     0.538569,
-     0.48830256,
-     0.51702624,
-     0.49548348,
-     0.49548348,
-     0.50984532,
-     0.51702624,
-     0.52420716,
-     0.52420716,
-     0.52420716,
-     0.55293084,
-     0.51702624,
-     0.52420716,
-     0.50984532,
-     0.53138808,
-     0.51702624,
-     0.56011176,
-     0.538569,
-     0.56729268,
-     0.53138808,
-     0.54574992,
-     0.60319728,
-     0.56729268,
-     0.56729268,
-     0.56011176,
-     0.538569,
-     0.56729268,
-     0.55293084,
-     0.59601636,
-     0.55293084,
-     0.56011176,
-     0.56011176,
-     0.5744736,
-     0.60319728,
-     0.5744736,
-     0.56011176,
-     0.60319728,
-     0.60319728,
-     0.56011176,
-     0.58165452,
-     0.60319728,
-     0.61755912,
-     0.59601636,
-     0.59601636,
-     0.56011176,
-     0.62474004,
-     0.61755912,
-     0.6103782,
-     0.6103782,
-     0.58165452,
-     0.63192096,
-     0.6103782,
-     0.59601636,
-     0.6103782,
-     0.62474004,
-     0.6103782,
-     0.63910188,
-     0.58883544,
-     0.62474004,
-     0.60319728,
-     0.61755912,
-     0.59601636,
-     0.60319728,
-     0.61755912,
-     0.58883544,
-     0.63192096,
-     0.63910188,
-     0.6462828,
-     0.62474004,
-     0.63192096,
-     0.59601636,
-     0.65346372,
-     0.65346372,
-     0.63192096,
-     0.6462828,
-     0.6462828,
-     0.63192096,
-     0.65346372,
-     0.66782556,
-     0.66782556,
-     0.62474004,
-     0.65346372,
-     0.63910188,
-     0.66782556,
-     0.66064464,
-     0.66782556,
-     0.6462828,
-     0.63910188,
-     0.63192096,
-     0.68936832,
-     0.63910188,
-     0.68936832,
-     0.67500648,
-     0.6821874,
-     0.6821874,
-     0.67500648,
-     0.70373016,
-     0.66782556,
-     0.68936832,
-     0.68936832,
-     0.68936832,
-     0.70373016,
-     0.718092,
-     0.70373016,
-     0.718092,
-     0.72527292,
-     0.69654924,
-     0.71091108,
-     0.7539966,
-     0.73245384,
-     0.718092,
-     0.72527292,
-     0.73245384,
-     0.73245384,
-     0.72527292,
-     0.6821874,
-     0.718092,
-     0.73245384,
-     0.718092,
-     0.72527292,
-     0.73963476,
-     0.718092,
-     0.76835844,
-     0.73963476,
-     0.73245384,
-     0.70373016,
-     0.74681568,
-     0.72527292,
-     0.78272028,
-     0.73245384,
-     0.77553936,
-     0.7899012,
-     0.76117752,
-     0.78272028,
-     0.7899012,
-     0.78272028,
-     0.77553936,
-     0.7899012,
-     0.76835844,
-     0.80426304,
-     0.81862488,
-     0.7899012,
-     0.78272028,
-     0.85452948,
-     0.7899012,
-     0.78272028,
-     0.78272028,
-     0.83298672,
-     0.77553936,
-     0.7899012,
-     0.81144396,
-     0.81862488,
-     0.80426304,
-     0.76835844,
-     0.84734856,
-     0.81144396,
-     0.81862488,
-     0.84734856,
-     0.83298672,
-     0.84734856,
-     0.8258058,
-     0.84016764,
-     0.85452948,
-     0.84016764,
-     0.8617104,
-     0.83298672,
-     0.85452948,
-     0.87607224,
-     0.85452948,
-     0.86889132,
-     0.88325316,
-     0.86889132,
-     0.8617104,
-     0.86889132,
-     0.84734856,
-     0.87607224,
-     0.87607224,
-     0.8617104,
-     0.90479592,
-     0.84734856,
-     0.91197684,
-     0.87607224,
-     0.87607224,
-     0.87607224,
-     0.88325316,
-     0.8617104,
-     0.90479592,
-     0.90479592,
-     0.90479592,
-     0.897615,
-     0.90479592,
-     0.91197684,
-     0.88325316,
-     0.90479592,
-     0.87607224,
-     0.89043408,
-     0.90479592,
-     0.91197684,
-     0.89043408,
-     0.90479592,
-     0.90479592,
-     0.94070052,
-     0.91915776,
-     0.897615,
-     0.91197684,
-     0.90479592,
-     0.91197684,
-     0.89043408,
-     0.897615,
-     0.91197684,
-     0.95506236,
-     0.94788144,
-     0.9335196,
-     0.91197684,
-     0.95506236,
-     0.9335196,
-     0.9335196,
-     0.90479592,
-     0.9694242,
-     0.9335196,
-     0.91197684,
-     0.96224328,
-     0.94788144,
-     0.91915776,
-     0.96224328,
-     0.94070052,
-     0.9694242,
-     0.97660512,
-     0.94788144,
-     0.95506236,
-     0.94070052,
-     0.90479592,
-     0.94070052,
-     0.9694242,
-     0.9694242,
-     0.96224328,
-     0.95506236,
-     0.95506236,
-     0.97660512,
-     0.96224328,
-     0.99096696,
-     0.9694242,
-     0.96224328,
-     0.98378604,
-     0.98378604,
-     0.97660512,
-     0.97660512,
-     1.02687156,
-     0.96224328,
-     0.9694242,
-     0.9694242,
-     1.01969064,
-     0.99814788,
-     0.98378604,
-     1.01969064,
-     1.02687156,
-     0.9694242,
-     1.01969064,
-     1.01969064,
-     0.99814788,
-     1.0053288,
-     1.0053288,
-     1.04841432,
-     1.02687156,
-     0.99096696,
-     1.06995708,
-     1.02687156,
-     0.99814788,
-     1.02687156,
-     1.0412334,
-     1.04841432,
-     1.08431892,
-     1.08431892,
-     1.03405248,
-     1.077138,
-     1.02687156,
-     1.04841432,
-     1.06995708,
-     1.06995708,
-     1.05559524,
-     1.077138,
-     1.04841432,
-     1.01969064,
-     1.10586168,
-     1.077138,
-     1.1130426,
-     1.02687156,
-     1.08431892,
-     1.06995708,
-     1.05559524,
-     1.08431892,
-     1.06995708,
-     1.06277616,
-     1.1489472,
-     1.08431892,
-     1.077138,
-     1.09868076,
-     1.1130426,
-     1.1130426,
-     1.1130426,
-     1.14176628,
-     1.15612812,
-     1.12740444,
-     1.13458536,
-     1.1130426,
-     1.14176628,
-     1.13458536,
-     1.12740444,
-     1.1489472,
-     1.15612812,
-     1.1130426,
-     1.12740444,
-     1.12740444,
-     1.14176628,
-     1.19203272,
-     1.15612812,
-     1.1489472,
-     1.12740444,
-     1.15612812,
-     1.12740444,
-     1.1489472,
-     1.16330904,
-     1.17048996,
-     1.14176628,
-     1.13458536,
-     1.17767088,
-     1.1489472,
-     1.14176628,
-     1.17767088,
-     1.16330904,
-     1.17767088,
-     1.15612812,
-     1.19203272,
-     1.1848518,
-     1.17767088,
-     1.19203272,
-     1.2207564,
-     1.17048996,
-     1.1848518,
-     1.20639456,
-     1.19203272,
-     1.21357548,
-     1.19921364,
-     1.20639456,
-     1.17048996,
-     1.23511824,
-     1.17767088,
-     1.16330904,
-     1.21357548,
-     1.20639456,
-     1.20639456,
-     1.23511824,
-     1.20639456,
-     1.23511824,
-     1.26384192,
-     1.2207564,
-     1.2207564,
-     1.2207564,
-     1.22793732,
-     1.17767088,
-     1.22793732,
-     1.23511824,
-     1.21357548,
-     1.17767088,
-     1.2207564,
-     1.22793732,
-     1.24948008,
-     1.22793732,
-     1.19203272,
-     1.19921364,
-     1.24229916,
-     1.24948008,
-     1.26384192,
-     1.24229916,
-     1.23511824,
-     1.22793732,
-     1.22793732,
-     1.26384192,
-     1.256661,
-     1.2925656,
-     1.2925656,
-     1.24948008,
-     1.256661,
-     1.23511824,
-     1.24948008,
-     1.27820376,
-     1.24948008,
-     1.26384192,
-     1.24948008,
-     1.26384192,
-     1.24229916,
-     1.23511824,
-     1.24229916,
-     1.24229916,
-     1.256661,
-     1.28538468,
-     1.27820376,
-     1.30692744,
-     1.28538468,
-     1.23511824,
-     1.28538468,
-     1.2925656,
-     1.23511824,
-     1.2925656,
-     1.256661,
-     1.27102284,
-     1.256661,
-     1.256661,
-     1.28538468,
-     1.2925656,
-     1.29974652,
-     1.27102284,
-     1.31410836,
-     1.27102284,
-     1.27820376,
-     1.27102284,
-     1.30692744,
-     1.22793732,
-     1.2925656,
-     1.29974652,
-     1.27102284,
-     1.29974652,
-     1.31410836,
-     1.2925656,
-     1.27820376,
-     1.30692744,
-     1.2925656,
-     1.30692744,
-     1.30692744,
-     1.31410836,
-     1.2925656,
-     1.31410836,
-     1.32128928,
-     1.30692744,
-     1.2925656,
-     1.2925656,
-     1.27102284,
-     1.3284702,
-     1.34283204,
-     1.31410836,
-     1.27102284,
-     1.30692744,
-     1.33565112,
-     1.2925656,
-     1.29974652,
-     1.2925656,
-     1.3284702,
-     1.34283204,
-     1.28538468,
-     1.3284702,
-     1.3284702,
-     1.30692744,
-     1.2925656,
-     1.29974652,
-     1.2925656,
-     1.32128928,
-     1.3284702,
-     1.32128928,
-     1.33565112,
-     1.30692744,
-     1.3643748,
-     1.32128928,
-     1.3643748,
-     1.32128928,
-     1.33565112,
-     1.3284702,
-     1.3284702,
-     1.34283204,
-     1.33565112,
-     1.33565112,
-     1.35719388,
-     1.35719388,
-     1.33565112,
-     1.37873664,
-     1.32128928,
-     1.3643748,
-     1.32128928,
-     1.35001296,
-     1.37155572,
-     1.32128928,
-     1.29974652,
-     1.34283204,
-     1.34283204,
-     1.33565112,
-     1.3643748,
-     1.33565112,
-     1.37873664,
-     1.3643748,
-     1.35001296,
-     1.33565112,
-     1.34283204,
-     1.34283204,
-     1.33565112,
-     1.33565112,
-     1.3643748,
-     1.35719388,
-     1.35719388,
-     1.35001296,
-     1.35001296,
-     1.35719388,
-     1.3643748,
-     1.3643748,
-     1.35001296,
-     1.3643748,
-     1.35001296,
-     1.34283204,
-     1.37155572,
-     1.35719388,
-     1.38591756,
-     1.3643748,
-     1.33565112,
-     1.33565112,
-     1.38591756,
-     1.37873664,
-     1.35001296,
-     1.37155572,
-     1.35719388,
-     1.35719388,
-     1.35719388,
-     1.35001296,
-     1.35001296,
-     1.35719388,
-     1.37873664,
-     1.3643748,
-     1.29974652,
-     1.34283204,
-     1.37873664,
-     1.35719388,
-     1.3643748,
-     1.33565112,
-     1.35719388,
-     1.32128928,
-     1.34283204,
-     1.31410836,
-     1.38591756,
-     1.35719388,
-     1.3643748,
-     1.3643748,
-     1.38591756,
-     1.35719388,
-     1.35001296,
-     1.35719388,
-     1.33565112,
-     1.34283204,
-     1.35719388}};
-
-const float GYROSCOPE_DATA[MOTION_SENSOR_AXIS_NUM][IMU_DATA_SIZE] = {
-    {-0.000152716,
-     0,
-     -0.000305433,
-     0,
-     0,
-     0,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000305433,
-     0,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0,
-     0.000305433,
-     0,
-     -0.000152716,
-     0.000152716,
-     0,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.00122173,
-     0.003054326,
-     0.00412334,
-     0.005650503,
-     0.007177667,
-     0.007788532,
-     0.009315695,
-     0.011301007,
-     0.012675454,
-     0.015424347,
-     0.01695151,
-     0.019394971,
-     0.021685716,
-     0.023976461,
-     0.026114489,
-     0.025961773,
-     0.028710666,
-     0.031764992,
-     0.03436117,
-     0.037415496,
-     0.040469822,
-     0.043065999,
-     0.044135013,
-     0.04550946,
-     0.047342056,
-     0.047036623,
-     0.04841107,
-     0.049938233,
-     0.051770829,
-     0.053450708,
-     0.055130588,
-     0.055894169,
-     0.056199602,
-     0.056352318,
-     0.056352318,
-     0.056352318,
-     0.056810467,
-     0.0571159,
-     0.0571159,
-     0.0571159,
-     0.056352318,
-     0.055588737,
-     0.055130588,
-     0.054367006,
-     0.053450708,
-     0.053450708,
-     0.05253441,
-     0.051770829,
-     0.05131268,
-     0.050701815,
-     0.049785517,
-     0.049174652,
-     0.04841107,
-     0.047494772,
-     0.046731191,
-     0.046883907,
-     0.045967609,
-     0.04550946,
-     0.044440446,
-     0.043524148,
-     0.042455134,
-     0.03970624,
-     0.036957347,
-     0.034666602,
-     0.03145956,
-     0.032070425,
-     0.029168815,
-     0.026572638,
-     0.02443461,
-     0.021838432,
-     0.018784106,
-     0.016340645,
-     0.013744468,
-     0.010842858,
-     0.008552113,
-     0.008552113,
-     0.006108652,
-     0.003207043,
-     0.000610865,
-     -0.001832596,
-     -0.004428773,
-     -0.00702495,
-     -0.009468411,
-     -0.012064588,
-     -0.014813482,
-     -0.014508049,
-     -0.017104227,
-     -0.019700404,
-     -0.022143865,
-     -0.023060163,
-     -0.022296581,
-     -0.021991149,
-     -0.021380283,
-     -0.020922134,
-     -0.020616702,
-     -0.020463985,
-     -0.020005837,
-     -0.019700404,
-     -0.019089539,
-     -0.01863139,
-     -0.018325957,
-     -0.018020525,
-     -0.017409659,
-     -0.016798794,
-     -0.016493361,
-     -0.016340645,
-     -0.016187929,
-     -0.015577064,
-     -0.015118915,
-     -0.014660766,
-     -0.014355333,
-     -0.0140499,
-     -0.013744468,
-     -0.013286319,
-     -0.01282817,
-     -0.013133603,
-     -0.01282817,
-     -0.012217305,
-     -0.011759156,
-     -0.011911872,
-     -0.011759156,
-     -0.010995574,
-     -0.011148291,
-     -0.010231993,
-     -0.010231993,
-     -0.010690142,
-     -0.009621128,
-     -0.009468411,
-     -0.008857546,
-     -0.009010262,
-     -0.008552113,
-     -0.008399397,
-     -0.008246681,
-     -0.008093964,
-     -0.007788532,
-     -0.007788532,
-     -0.007330383,
-     -0.007330383,
-     -0.00702495,
-     -0.006872234,
-     -0.006566801,
-     -0.006261369,
-     -0.006108652,
-     -0.006261369,
-     -0.005650503,
-     -0.00580322,
-     -0.005650503,
-     -0.005345071,
-     -0.005039638,
-     -0.004886922,
-     -0.004886922,
-     -0.004734206,
-     -0.004428773,
-     -0.004581489,
-     -0.004428773,
-     -0.004276057,
-     -0.004276057,
-     -0.003817908,
-     -0.003970624,
-     -0.003970624,
-     -0.003665191,
-     -0.003359759,
-     -0.003207043,
-     -0.003207043,
-     -0.003054326,
-     -0.003054326,
-     -0.00290161,
-     -0.00290161,
-     -0.002748894,
-     -0.002748894,
-     -0.002443461,
-     -0.002290745,
-     -0.002290745,
-     -0.002138028,
-     -0.002138028,
-     -0.002290745,
-     -0.002138028,
-     -0.001832596,
-     -0.001985312,
-     -0.001985312,
-     -0.001832596,
-     -0.001679879,
-     -0.001679879,
-     -0.001374447,
-     -0.001374447,
-     -0.001374447,
-     -0.001374447,
-     -0.001527163,
-     -0.001374447,
-     -0.00122173,
-     -0.00122173,
-     -0.001069014,
-     -0.001069014,
-     -0.000763582,
-     -0.000916298,
-     -0.00122173,
-     -0.00122173,
-     -0.000916298,
-     -0.000916298,
-     -0.000763582,
-     -0.000763582,
-     -0.00122173,
-     -0.000763582,
-     -0.000916298,
-     -0.000305433,
-     -0.000763582,
-     -0.000763582,
-     -0.000763582,
-     -0.000458149,
-     -0.000610865,
-     -0.000305433,
-     -0.000458149,
-     -0.000458149,
-     -0.000458149,
-     -0.000152716,
-     -0.000458149,
-     -0.000610865,
-     -0.000458149,
-     -0.000305433,
-     -0.000458149,
-     -0.000152716,
-     -0.000610865,
-     -0.000305433,
-     -0.000305433,
-     -0.000305433,
-     -0.000305433,
-     -0.000152716,
-     -0.000152716,
-     -0.000305433,
-     -0.000458149,
-     -0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     -0.000305433,
-     -0.000152716,
-     -0.000305433,
-     -0.000458149,
-     -0.000305433,
-     -0.000305433,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     -0.000152716,
-     -0.000305433,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     -0.000305433,
-     0.000152716,
-     -0.000305433,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     -0.000305433,
-     0,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     0,
-     0,
-     0.000152716,
-     -0.000305433,
-     -0.000305433,
-     -0.000152716,
-     0,
-     0,
-     0,
-     0,
-     0,
-     -0.000152716,
-     0,
-     0.000152716,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     -0.000152716,
-     -0.000305433,
-     0,
-     0.000305433,
-     0,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     -0.000152716,
-     -0.000305433,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0,
-     -0.000152716,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0.000458149,
-     -0.000152716,
-     -0.000305433,
-     0,
-     -0.000305433,
-     0,
-     0,
-     -0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000458149,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000305433,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     -0.000305433,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000458149,
-     0,
-     -0.000152716,
-     0,
-     0,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0,
-     0,
-     -0.000152716,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000305433,
-     0,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     -0.000305433,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     -0.000305433,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0,
-     0,
-     -0.000458149,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000305433,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0,
-     0,
-     -0.000152716,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     -0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000610865,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0,
-     -0.000152716,
-     0,
-     -0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     -0.000305433,
-     0,
-     0.000305433,
-     0,
-     -0.000305433,
-     0,
-     0.000152716,
-     0,
-     0,
-     -0.000305433,
-     0,
-     0,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     -0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000305433,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000305433,
-     0,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     -0.000305433,
-     -0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     -0.000305433,
-     0,
-     0,
-     0,
-     0.000305433,
-     -0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0,
-     0,
-     0,
-     0,
-     -0.000152716,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     -0.000305433,
-     0,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     -0.000305433,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0,
-     0,
-     0,
-     0,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0.000458149,
-     0.000152716,
-     -0.000152716,
-     0,
-     -0.000152716,
-     -0.000305433,
-     0,
-     -0.000305433,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0,
-     -0.000152716,
-     -0.000305433,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000305433,
-     0,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     -0.000305433,
-     -0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0,
-     0,
-     -0.000152716,
-     0,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000152716,
-     0,
-     0,
-     -0.000152716,
-     0,
-     0,
-     0.000305433,
-     0,
-     0.000305433,
-     0,
-     0,
-     0,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000458149,
-     0,
-     0,
-     0.000152716,
-     -0.000152716,
-     0,
-     0,
-     -0.000152716,
-     0,
-     -0.000152716,
-     0.000458149,
-     -0.000305433,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000305433,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0,
-     0,
-     -0.000152716,
-     0,
-     -0.000305433,
-     -0.000305433,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     -0.000305433,
-     0,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     -0.000305433,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000305433,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000458149,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     -0.000305433,
-     0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0.000610865,
-     -0.000152716,
-     0.000305433,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     0,
-     0,
-     0.000305433,
-     -0.000152716,
-     -0.000152716,
-     -0.000458149,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000610865,
-     0.000152716,
-     0.000458149,
-     0,
-     0,
-     0.000152716,
-     0,
-     0,
-     -0.000305433,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0,
-     0.000305433,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     -0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     -0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000458149,
-     0,
-     0,
-     0.000152716,
-     0,
-     0.000458149,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0,
-     0,
-     0.000458149,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000763582,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     -0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000610865,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000458149,
-     0,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0.000610865,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000458149,
-     -0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000458149,
-     -0.000152716,
-     0.000305433,
-     0,
-     0,
-     0.000458149,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     -0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000763582,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000610865,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     -0.000305433,
-     -0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000458149,
-     -0.000152716,
-     0.000458149,
-     -0.000305433,
-     0.000458149,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0,
-     0,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000610865,
-     0.000458149,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000610865,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0,
-     0.000305433,
-     0,
-     0,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000610865,
-     0,
-     0.000152716,
-     0.000610865,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0,
-     -0.000152716,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000610865,
-     0.000305433,
-     0,
-     0.000610865,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000610865,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000610865,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000458149,
-     -0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     0,
-     0,
-     0.000305433,
-     0.000305433,
-     -0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000610865,
-     0.000458149,
-     0,
-     0.000305433,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000305433,
-     -0.000152716,
-     0.000458149,
-     0,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     -0.000305433,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000458149,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0.000458149,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000610865,
-     0,
-     0.000610865,
-     0,
-     0,
-     0.000458149,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     -0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000610865,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000458149,
-     -0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000305433,
-     0,
-     0,
-     0,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000610865,
-     0,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000610865,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000610865,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000458149,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000610865,
-     0,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000610865,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000610865,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000610865,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000458149},
-    {-0.000152716,
-     -0.000610865,
-     0,
-     -0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     -0.000152716,
-     0,
-     0,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0,
-     -0.000305433,
-     0,
-     0,
-     0,
-     0.000305433,
-     -0.000152716,
-     -0.000152716,
-     0,
-     -0.000152716,
-     -0.000458149,
-     -0.000152716,
-     0,
-     0.000152716,
-     -0.000305433,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     -0.010079276,
-     -0.023060163,
-     -0.035888333,
-     -0.048716503,
-     -0.062308254,
-     -0.062308254,
-     -0.076052722,
-     -0.089491757,
-     -0.103083509,
-     -0.11667526,
-     -0.130877877,
-     -0.144775061,
-     -0.158824962,
-     -0.171805848,
-     -0.185550316,
-     -0.1853976,
-     -0.198989351,
-     -0.21227567,
-     -0.225256557,
-     -0.238237443,
-     -0.251218329,
-     -0.263435634,
-     -0.27519479,
-     -0.286953946,
-     -0.298254953,
-     -0.29794952,
-     -0.308792378,
-     -0.31948252,
-     -0.329867229,
-     -0.338572058,
-     -0.347582321,
-     -0.355829001,
-     -0.362853951,
-     -0.369573469,
-     -0.375529405,
-     -0.375987554,
-     -0.381485341,
-     -0.386066831,
-     -0.390037455,
-     -0.393244497,
-     -0.395687958,
-     -0.397367837,
-     -0.397978703,
-     -0.397978703,
-     -0.397825986,
-     -0.39767327,
-     -0.396146107,
-     -0.393855362,
-     -0.390953752,
-     -0.386983128,
-     -0.38194349,
-     -0.37614027,
-     -0.369268036,
-     -0.361479505,
-     -0.353080108,
-     -0.352927391,
-     -0.343306264,
-     -0.332157973,
-     -0.320246101,
-     -0.307570647,
-     -0.295353343,
-     -0.284357768,
-     -0.272140464,
-     -0.258701428,
-     -0.244193379,
-     -0.244346095,
-     -0.229074464,
-     -0.211970238,
-     -0.194560578,
-     -0.175929189,
-     -0.156381501,
-     -0.136070232,
-     -0.114689948,
-     -0.0926988,
-     -0.070249502,
-     -0.070249502,
-     -0.047647489,
-     -0.024281893,
-     -0.000458149,
-     0.023365595,
-     0.047494772,
-     0.071013084,
-     0.094531396,
-     0.117591558,
-     0.140040856,
-     0.140193572,
-     0.162337437,
-     0.182801423,
-     0.202959975,
-     0.2209805,
-     0.23793201,
-     0.25366179,
-     0.267100825,
-     0.27931813,
-     0.283899619,
-     0.283899619,
-     0.286953946,
-     0.287870244,
-     0.285884931,
-     0.282525173,
-     0.276721953,
-     0.269086137,
-     0.25946501,
-     0.24785857,
-     0.23380867,
-     0.234114103,
-     0.218537039,
-     0.201280096,
-     0.181732408,
-     0.161268423,
-     0.139429991,
-     0.116064395,
-     0.091935218,
-     0.067195176,
-     0.041844269,
-     0.041996985,
-     0.016035213,
-     -0.009162979,
-     -0.034513886,
-     -0.059406644,
-     -0.083535821,
-     -0.106290551,
-     -0.127823551,
-     -0.147676671,
-     -0.166308061,
-     -0.166002628,
-     -0.182648706,
-     -0.19654589,
-     -0.208610479,
-     -0.21807889,
-     -0.22510384,
-     -0.230143478,
-     -0.232128791,
-     -0.231976074,
-     -0.229379897,
-     -0.229227181,
-     -0.224492975,
-     -0.217162592,
-     -0.206625167,
-     -0.195171444,
-     -0.180968827,
-     -0.165391763,
-     -0.147523955,
-     -0.129045282,
-     -0.109497594,
-     -0.109039445,
-     -0.087811878,
-     -0.066584311,
-     -0.044898595,
-     -0.022602014,
-     -0.00122173,
-     0.019394971,
-     0.039400808,
-     0.05833763,
-     0.075594573,
-     0.075136424,
-     0.090713488,
-     0.104610672,
-     0.116064395,
-     0.12538009,
-     0.132099608,
-     0.136070232,
-     0.138055544,
-     0.136375664,
-     0.133168622,
-     0.133474055,
-     0.127823551,
-     0.119424154,
-     0.109344878,
-     0.097127573,
-     0.082924956,
-     0.067806041,
-     0.051159964,
-     0.033750304,
-     0.016035213,
-     0.015882496,
-     -0.002290745,
-     -0.019547688,
-     -0.037110063,
-     -0.05253441,
-     -0.067806041,
-     -0.08109236,
-     -0.093156949,
-     -0.102319927,
-     -0.110108459,
-     -0.110566608,
-     -0.115911679,
-     -0.118660573,
-     -0.119424154,
-     -0.118049707,
-     -0.114079083,
-     -0.108275863,
-     -0.100181899,
-     -0.090102623,
-     -0.078648899,
-     -0.078954332,
-     -0.065668013,
-     -0.052076262,
-     -0.038026361,
-     -0.023823744,
-     -0.009773844,
-     0.003970624,
-     0.01695151,
-     0.02855795,
-     0.038789943,
-     0.039095375,
-     0.04718934,
-     0.053908857,
-     0.058795779,
-     0.061391956,
-     0.062002822,
-     0.060322942,
-     0.056810467,
-     0.051465396,
-     0.044745879,
-     0.044593162,
-     0.036499198,
-     0.02687807,
-     0.016493361,
-     0.005650503,
-     -0.005345071,
-     -0.015882496,
-     -0.025961773,
-     -0.0355829,
-     -0.043829581,
-     -0.043676865,
-     -0.051007247,
-     -0.056352318,
-     -0.060628375,
-     -0.062460971,
-     -0.063377268,
-     -0.061391956,
-     -0.059101212,
-     -0.054519723,
-     -0.049021935,
-     -0.049021935,
-     -0.04260785,
-     -0.034972035,
-     -0.026725354,
-     -0.01863139,
-     -0.010537425,
-     -0.001985312,
-     0.004581489,
-     0.011301007,
-     0.016187929,
-     0.016187929,
-     0.020463985,
-     0.023212879,
-     0.024892758,
-     0.024740042,
-     0.023365595,
-     0.020616702,
-     0.016798794,
-     0.012522737,
-     0.00702495,
-     0.006872234,
-     0.000916298,
-     -0.005039638,
-     -0.010995574,
-     -0.016646078,
-     -0.022143865,
-     -0.026419922,
-     -0.030390546,
-     -0.032986723,
-     -0.035124751,
-     -0.034666602,
-     -0.0355829,
-     -0.034819319,
-     -0.033139439,
-     -0.031001411,
-     -0.027488936,
-     -0.023823744,
-     -0.019547688,
-     -0.014508049,
-     -0.010690142,
-     -0.010690142,
-     -0.005955936,
-     -0.002290745,
-     0.00122173,
-     0.003665191,
-     0.005650503,
-     0.006872234,
-     0.007330383,
-     0.006566801,
-     0.005192355,
-     0.005345071,
-     0.003512475,
-     0.000763582,
-     -0.002596177,
-     -0.005192355,
-     -0.008552113,
-     -0.011911872,
-     -0.014966198,
-     -0.017256943,
-     -0.019547688,
-     -0.019394971,
-     -0.020922134,
-     -0.021533,
-     -0.022296581,
-     -0.021685716,
-     -0.020769418,
-     -0.019242255,
-     -0.017256943,
-     -0.015577064,
-     -0.013286319,
-     -0.013133603,
-     -0.010690142,
-     -0.008552113,
-     -0.006261369,
-     -0.004581489,
-     -0.00290161,
-     -0.002290745,
-     -0.001527163,
-     -0.001527163,
-     -0.001985312,
-     -0.001985312,
-     -0.002748894,
-     -0.003817908,
-     -0.005345071,
-     -0.006872234,
-     -0.008246681,
-     -0.010079276,
-     -0.011453723,
-     -0.012980886,
-     -0.0140499,
-     -0.013897184,
-     -0.014966198,
-     -0.015271631,
-     -0.01572978,
-     -0.015577064,
-     -0.014966198,
-     -0.014202617,
-     -0.013744468,
-     -0.012217305,
-     -0.011148291,
-     -0.011453723,
-     -0.010079276,
-     -0.008857546,
-     -0.007941248,
-     -0.00702495,
-     -0.006261369,
-     -0.00580322,
-     -0.005650503,
-     -0.005497787,
-     -0.005345071,
-     -0.005497787,
-     -0.005650503,
-     -0.006261369,
-     -0.006872234,
-     -0.007788532,
-     -0.008246681,
-     -0.009315695,
-     -0.010079276,
-     -0.010842858,
-     -0.011301007,
-     -0.010842858,
-     -0.011301007,
-     -0.011911872,
-     -0.012217305,
-     -0.012370021,
-     -0.011301007,
-     -0.011453723,
-     -0.010842858,
-     -0.010384709,
-     -0.010231993,
-     -0.00992656,
-     -0.009315695,
-     -0.00870483,
-     -0.008093964,
-     -0.008246681,
-     -0.007788532,
-     -0.007635815,
-     -0.007941248,
-     -0.007635815,
-     -0.007788532,
-     -0.007635815,
-     -0.007788532,
-     -0.008093964,
-     -0.008552113,
-     -0.009162979,
-     -0.009468411,
-     -0.00992656,
-     -0.00992656,
-     -0.010384709,
-     -0.010384709,
-     -0.010384709,
-     -0.010384709,
-     -0.010537425,
-     -0.010690142,
-     -0.010537425,
-     -0.010690142,
-     -0.010842858,
-     -0.010690142,
-     -0.010537425,
-     -0.010842858,
-     -0.010842858,
-     -0.010690142,
-     -0.01160644,
-     -0.011453723,
-     -0.011911872,
-     -0.011911872,
-     -0.012217305,
-     -0.012217305,
-     -0.012522737,
-     -0.012370021,
-     -0.012370021,
-     -0.012675454,
-     -0.012675454,
-     -0.012675454,
-     -0.012217305,
-     -0.011911872,
-     -0.012217305,
-     -0.012217305,
-     -0.011759156,
-     -0.01160644,
-     -0.011911872,
-     -0.011759156,
-     -0.011759156,
-     -0.011759156,
-     -0.01160644,
-     -0.011453723,
-     -0.011453723,
-     -0.011301007,
-     -0.01160644,
-     -0.01160644,
-     -0.011453723,
-     -0.011911872,
-     -0.011911872,
-     -0.012064588,
-     -0.012064588,
-     -0.012064588,
-     -0.012522737,
-     -0.012217305,
-     -0.012522737,
-     -0.012522737,
-     -0.012522737,
-     -0.012522737,
-     -0.012217305,
-     -0.012522737,
-     -0.012675454,
-     -0.012522737,
-     -0.012217305,
-     -0.012522737,
-     -0.012217305,
-     -0.012064588,
-     -0.012064588,
-     -0.012217305,
-     -0.011453723,
-     -0.01160644,
-     -0.011453723,
-     -0.011148291,
-     -0.010384709,
-     -0.010079276,
-     -0.009773844,
-     -0.009010262,
-     -0.009162979,
-     -0.009315695,
-     -0.00870483,
-     -0.009010262,
-     -0.008857546,
-     -0.00870483,
-     -0.008857546,
-     -0.009162979,
-     -0.009468411,
-     -0.009621128,
-     -0.00992656,
-     -0.009773844,
-     -0.010690142,
-     -0.010842858,
-     -0.010842858,
-     -0.011148291,
-     -0.011148291,
-     -0.011301007,
-     -0.011453723,
-     -0.01160644,
-     -0.011453723,
-     -0.011453723,
-     -0.011301007,
-     -0.011148291,
-     -0.011301007,
-     -0.010842858,
-     -0.010842858,
-     -0.010995574,
-     -0.010384709,
-     -0.010537425,
-     -0.010537425,
-     -0.010079276,
-     -0.010537425,
-     -0.010079276,
-     -0.009773844,
-     -0.009773844,
-     -0.010384709,
-     -0.010079276,
-     -0.010231993,
-     -0.010384709,
-     -0.00992656,
-     -0.010384709,
-     -0.010384709,
-     -0.011148291,
-     -0.010537425,
-     -0.010995574,
-     -0.010995574,
-     -0.010995574,
-     -0.011148291,
-     -0.011301007,
-     -0.01160644,
-     -0.011301007,
-     -0.011148291,
-     -0.011301007,
-     -0.011148291,
-     -0.011301007,
-     -0.011301007,
-     -0.010995574,
-     -0.010995574,
-     -0.010690142,
-     -0.010995574,
-     -0.010384709,
-     -0.011148291,
-     -0.010995574,
-     -0.010842858,
-     -0.010995574,
-     -0.010690142,
-     -0.010690142,
-     -0.010842858,
-     -0.010690142,
-     -0.010995574,
-     -0.010995574,
-     -0.010842858,
-     -0.010995574,
-     -0.010995574,
-     -0.010690142,
-     -0.011301007,
-     -0.010995574,
-     -0.011301007,
-     -0.011453723,
-     -0.011301007,
-     -0.01160644,
-     -0.011301007,
-     -0.011301007,
-     -0.011301007,
-     -0.011301007,
-     -0.01160644,
-     -0.011453723,
-     -0.011453723,
-     -0.011453723,
-     -0.011301007,
-     -0.011911872,
-     -0.011453723,
-     -0.011453723,
-     -0.011453723,
-     -0.011453723,
-     -0.01160644,
-     -0.011301007,
-     -0.011453723,
-     -0.010995574,
-     -0.011301007,
-     -0.011301007,
-     -0.011301007,
-     -0.011453723,
-     -0.011453723,
-     -0.011453723,
-     -0.01160644,
-     -0.01160644,
-     -0.01160644,
-     -0.01160644,
-     -0.01160644,
-     -0.011911872,
-     -0.011759156,
-     -0.011759156,
-     -0.012064588,
-     -0.011759156,
-     -0.01160644,
-     -0.011759156,
-     -0.012064588,
-     -0.011911872,
-     -0.012064588,
-     -0.011759156,
-     -0.011911872,
-     -0.01160644,
-     -0.011759156,
-     -0.011911872,
-     -0.011911872,
-     -0.011759156,
-     -0.011759156,
-     -0.011759156,
-     -0.011911872,
-     -0.011759156,
-     -0.011759156,
-     -0.011911872,
-     -0.011911872,
-     -0.012064588,
-     -0.012064588,
-     -0.011911872,
-     -0.012064588,
-     -0.011911872,
-     -0.012064588,
-     -0.011911872,
-     -0.011911872,
-     -0.012370021,
-     -0.011911872,
-     -0.011911872,
-     -0.012064588,
-     -0.012370021,
-     -0.012217305,
-     -0.012217305,
-     -0.011911872,
-     -0.012370021,
-     -0.012064588,
-     -0.012522737,
-     -0.012064588,
-     -0.012064588,
-     -0.012217305,
-     -0.012370021,
-     -0.012370021,
-     -0.012675454,
-     -0.012217305,
-     -0.012370021,
-     -0.012522737,
-     -0.012370021,
-     -0.012370021,
-     -0.012370021,
-     -0.012522737,
-     -0.012522737,
-     -0.012217305,
-     -0.012370021,
-     -0.012675454,
-     -0.012370021,
-     -0.012370021,
-     -0.012370021,
-     -0.012522737,
-     -0.012675454,
-     -0.012522737,
-     -0.012522737,
-     -0.012217305,
-     -0.012980886,
-     -0.012522737,
-     -0.012522737,
-     -0.012522737,
-     -0.012675454,
-     -0.012522737,
-     -0.012675454,
-     -0.01282817,
-     -0.012675454,
-     -0.01282817,
-     -0.01282817,
-     -0.012980886,
-     -0.012522737,
-     -0.012675454,
-     -0.012675454,
-     -0.012675454,
-     -0.01282817,
-     -0.01282817,
-     -0.012675454,
-     -0.012980886,
-     -0.01282817,
-     -0.01282817,
-     -0.012980886,
-     -0.01282817,
-     -0.013133603,
-     -0.012675454,
-     -0.012980886,
-     -0.012980886,
-     -0.012980886,
-     -0.012675454,
-     -0.01282817,
-     -0.012980886,
-     -0.012980886,
-     -0.012980886,
-     -0.012980886,
-     -0.01282817,
-     -0.01282817,
-     -0.013286319,
-     -0.013286319,
-     -0.012675454,
-     -0.012980886,
-     -0.013286319,
-     -0.013439035,
-     -0.012980886,
-     -0.013133603,
-     -0.013133603,
-     -0.013286319,
-     -0.013591752,
-     -0.012980886,
-     -0.013286319,
-     -0.013439035,
-     -0.013133603,
-     -0.013439035,
-     -0.013286319,
-     -0.013591752,
-     -0.013286319,
-     -0.013591752,
-     -0.013744468,
-     -0.013286319,
-     -0.013591752,
-     -0.013744468,
-     -0.013744468,
-     -0.013439035,
-     -0.013591752,
-     -0.013744468,
-     -0.013897184,
-     -0.0140499,
-     -0.014355333,
-     -0.013897184,
-     -0.0140499,
-     -0.0140499,
-     -0.014202617,
-     -0.014202617,
-     -0.0140499,
-     -0.014202617,
-     -0.014355333,
-     -0.0140499,
-     -0.014202617,
-     -0.014202617,
-     -0.014202617,
-     -0.0140499,
-     -0.014202617,
-     -0.0140499,
-     -0.014202617,
-     -0.014355333,
-     -0.014508049,
-     -0.0140499,
-     -0.014202617,
-     -0.0140499,
-     -0.014202617,
-     -0.014202617,
-     -0.0140499,
-     -0.014508049,
-     -0.014202617,
-     -0.014355333,
-     -0.014355333,
-     -0.014508049,
-     -0.014508049,
-     -0.014355333,
-     -0.014202617,
-     -0.014355333,
-     -0.014355333,
-     -0.0140499,
-     -0.014508049,
-     -0.014355333,
-     -0.014660766,
-     -0.014202617,
-     -0.014813482,
-     -0.014813482,
-     -0.014508049,
-     -0.014355333,
-     -0.014813482,
-     -0.014813482,
-     -0.014813482,
-     -0.014813482,
-     -0.015118915,
-     -0.014660766,
-     -0.014813482,
-     -0.014813482,
-     -0.014660766,
-     -0.015118915,
-     -0.014813482,
-     -0.014813482,
-     -0.015118915,
-     -0.014813482,
-     -0.014966198,
-     -0.014966198,
-     -0.014813482,
-     -0.015118915,
-     -0.014966198,
-     -0.014966198,
-     -0.015118915,
-     -0.014813482,
-     -0.014813482,
-     -0.014813482,
-     -0.014813482,
-     -0.014660766,
-     -0.014966198,
-     -0.014813482,
-     -0.014966198,
-     -0.014813482,
-     -0.015271631,
-     -0.015424347,
-     -0.014966198,
-     -0.014966198,
-     -0.014813482,
-     -0.015118915,
-     -0.015577064,
-     -0.015118915,
-     -0.015118915,
-     -0.015577064,
-     -0.015271631,
-     -0.015271631,
-     -0.015424347,
-     -0.015424347,
-     -0.01572978,
-     -0.015118915,
-     -0.015271631,
-     -0.015424347,
-     -0.015577064,
-     -0.015424347,
-     -0.015577064,
-     -0.015577064,
-     -0.015424347,
-     -0.015882496,
-     -0.015577064,
-     -0.015577064,
-     -0.015882496,
-     -0.016035213,
-     -0.015577064,
-     -0.015424347,
-     -0.01572978,
-     -0.015577064,
-     -0.015882496,
-     -0.015577064,
-     -0.01572978,
-     -0.015882496,
-     -0.015577064,
-     -0.01572978,
-     -0.015882496,
-     -0.015882496,
-     -0.016035213,
-     -0.01572978,
-     -0.015882496,
-     -0.01572978,
-     -0.015882496,
-     -0.016035213,
-     -0.016187929,
-     -0.016340645,
-     -0.016187929,
-     -0.016187929,
-     -0.016035213,
-     -0.016035213,
-     -0.016187929,
-     -0.015882496,
-     -0.015882496,
-     -0.016187929,
-     -0.015882496,
-     -0.016035213,
-     -0.016340645,
-     -0.016187929,
-     -0.016646078,
-     -0.016340645,
-     -0.016646078,
-     -0.016340645,
-     -0.016187929,
-     -0.016187929,
-     -0.016340645,
-     -0.016493361,
-     -0.016187929,
-     -0.016493361,
-     -0.016340645,
-     -0.016493361,
-     -0.016340645,
-     -0.016340645,
-     -0.016493361,
-     -0.016340645,
-     -0.016646078,
-     -0.016340645,
-     -0.016493361,
-     -0.016646078,
-     -0.01695151,
-     -0.016646078,
-     -0.016646078,
-     -0.016798794,
-     -0.016646078,
-     -0.016798794,
-     -0.016340645,
-     -0.016798794,
-     -0.016646078,
-     -0.016798794,
-     -0.01695151,
-     -0.016798794,
-     -0.017104227,
-     -0.016493361,
-     -0.016646078,
-     -0.01695151,
-     -0.01695151,
-     -0.017256943,
-     -0.016798794,
-     -0.016798794,
-     -0.017104227,
-     -0.017104227,
-     -0.017104227,
-     -0.017256943,
-     -0.017256943,
-     -0.017256943,
-     -0.01695151,
-     -0.017104227,
-     -0.01695151,
-     -0.01695151,
-     -0.016798794,
-     -0.017256943,
-     -0.017256943,
-     -0.017256943,
-     -0.017104227,
-     -0.01695151,
-     -0.017104227,
-     -0.017256943,
-     -0.017104227,
-     -0.017256943,
-     -0.017562376,
-     -0.017409659,
-     -0.017562376,
-     -0.017562376,
-     -0.017409659,
-     -0.017409659,
-     -0.017562376,
-     -0.017562376,
-     -0.017715092,
-     -0.017715092,
-     -0.017715092,
-     -0.017715092,
-     -0.017867808,
-     -0.017867808,
-     -0.017562376,
-     -0.017867808,
-     -0.018020525,
-     -0.017715092,
-     -0.017409659,
-     -0.017867808,
-     -0.017715092,
-     -0.018020525,
-     -0.018020525,
-     -0.018173241,
-     -0.018325957,
-     -0.018173241,
-     -0.018020525,
-     -0.018020525,
-     -0.018020525,
-     -0.018020525,
-     -0.018020525,
-     -0.018020525,
-     -0.018020525,
-     -0.018020525,
-     -0.018173241,
-     -0.018173241,
-     -0.018173241,
-     -0.017867808,
-     -0.018325957,
-     -0.018325957,
-     -0.018173241,
-     -0.018020525,
-     -0.018478673,
-     -0.018325957,
-     -0.018173241,
-     -0.018173241,
-     -0.018478673,
-     -0.018173241,
-     -0.01863139,
-     -0.018478673,
-     -0.018478673,
-     -0.018325957,
-     -0.018784106,
-     -0.018478673,
-     -0.018478673,
-     -0.01863139,
-     -0.01863139,
-     -0.01863139,
-     -0.018478673,
-     -0.01863139,
-     -0.018784106,
-     -0.01863139,
-     -0.018784106,
-     -0.018784106,
-     -0.018936822,
-     -0.018936822,
-     -0.018784106,
-     -0.018936822,
-     -0.019089539,
-     -0.018784106,
-     -0.018784106,
-     -0.019089539,
-     -0.019089539,
-     -0.018936822,
-     -0.018936822,
-     -0.019242255,
-     -0.019089539,
-     -0.019089539,
-     -0.019242255,
-     -0.019089539,
-     -0.019089539,
-     -0.019089539,
-     -0.019089539,
-     -0.019089539,
-     -0.018784106,
-     -0.019242255,
-     -0.019242255,
-     -0.019394971,
-     -0.019089539,
-     -0.019242255,
-     -0.019394971,
-     -0.019547688,
-     -0.019242255,
-     -0.019394971,
-     -0.019394971,
-     -0.019547688,
-     -0.019700404,
-     -0.019700404,
-     -0.019547688,
-     -0.01985312,
-     -0.019394971,
-     -0.019394971,
-     -0.019547688,
-     -0.01985312,
-     -0.020005837,
-     -0.01985312,
-     -0.019700404,
-     -0.020005837,
-     -0.020005837,
-     -0.01985312,
-     -0.019700404,
-     -0.020005837,
-     -0.020005837,
-     -0.020158553,
-     -0.020005837,
-     -0.020005837,
-     -0.020311269,
-     -0.020005837,
-     -0.020311269,
-     -0.01985312,
-     -0.020311269,
-     -0.020005837,
-     -0.020311269,
-     -0.020005837,
-     -0.020158553,
-     -0.020311269,
-     -0.020311269,
-     -0.020158553,
-     -0.020005837,
-     -0.020311269,
-     -0.020005837,
-     -0.020463985,
-     -0.020463985,
-     -0.020616702,
-     -0.020463985,
-     -0.020311269,
-     -0.020463985,
-     -0.020311269,
-     -0.020769418,
-     -0.020616702,
-     -0.020616702,
-     -0.020463985,
-     -0.020769418,
-     -0.020463985,
-     -0.020922134,
-     -0.020616702,
-     -0.020616702,
-     -0.020769418,
-     -0.020769418,
-     -0.021074851,
-     -0.020769418,
-     -0.020769418,
-     -0.021074851,
-     -0.020769418,
-     -0.020922134,
-     -0.021227567,
-     -0.021074851,
-     -0.020922134,
-     -0.021227567,
-     -0.021227567,
-     -0.021074851,
-     -0.021380283,
-     -0.021380283,
-     -0.021074851,
-     -0.021074851,
-     -0.021380283,
-     -0.021074851,
-     -0.021685716,
-     -0.020922134,
-     -0.021685716,
-     -0.021380283,
-     -0.021380283,
-     -0.021685716,
-     -0.021685716,
-     -0.021227567,
-     -0.021533,
-     -0.021533,
-     -0.021685716,
-     -0.021838432,
-     -0.021838432,
-     -0.021838432,
-     -0.022143865,
-     -0.021685716,
-     -0.021685716,
-     -0.021991149,
-     -0.021838432,
-     -0.021991149,
-     -0.021685716,
-     -0.021838432,
-     -0.021991149,
-     -0.021685716,
-     -0.022296581,
-     -0.021991149,
-     -0.021991149,
-     -0.022296581,
-     -0.022449298,
-     -0.021838432,
-     -0.021991149,
-     -0.022143865,
-     -0.022143865,
-     -0.022143865,
-     -0.022296581,
-     -0.022602014,
-     -0.022143865,
-     -0.022296581,
-     -0.022449298,
-     -0.022449298,
-     -0.022449298,
-     -0.022143865,
-     -0.022602014,
-     -0.022449298,
-     -0.02275473,
-     -0.02275473,
-     -0.022907446,
-     -0.022602014,
-     -0.02275473,
-     -0.023060163,
-     -0.022296581,
-     -0.022602014,
-     -0.02275473,
-     -0.022602014,
-     -0.023060163,
-     -0.02275473,
-     -0.022907446,
-     -0.02275473,
-     -0.022907446,
-     -0.023060163,
-     -0.023212879,
-     -0.022907446,
-     -0.023060163,
-     -0.023212879,
-     -0.023365595,
-     -0.023365595,
-     -0.023212879,
-     -0.023365595,
-     -0.023365595,
-     -0.023365595,
-     -0.023365595,
-     -0.023671028,
-     -0.023671028,
-     -0.023365595,
-     -0.023212879,
-     -0.023212879,
-     -0.023518312,
-     -0.023518312,
-     -0.023976461,
-     -0.023823744,
-     -0.023671028,
-     -0.023365595,
-     -0.023823744,
-     -0.023823744,
-     -0.023823744,
-     -0.023976461,
-     -0.023671028,
-     -0.023671028,
-     -0.023823744,
-     -0.023823744,
-     -0.024129177,
-     -0.023823744,
-     -0.024281893,
-     -0.024281893,
-     -0.023823744,
-     -0.024129177,
-     -0.023976461,
-     -0.024281893,
-     -0.02443461,
-     -0.024281893,
-     -0.024281893,
-     -0.024281893,
-     -0.024281893,
-     -0.02443461,
-     -0.02443461,
-     -0.024587326,
-     -0.024587326,
-     -0.024740042,
-     -0.02443461,
-     -0.024740042,
-     -0.024740042,
-     -0.024892758,
-     -0.024892758,
-     -0.024892758,
-     -0.024892758,
-     -0.024892758,
-     -0.024587326,
-     -0.025045475,
-     -0.024892758,
-     -0.024892758,
-     -0.024892758,
-     -0.024892758,
-     -0.025045475,
-     -0.02565634,
-     -0.025198191,
-     -0.025198191,
-     -0.025198191,
-     -0.02565634,
-     -0.025350907,
-     -0.025350907,
-     -0.025350907,
-     -0.025503624,
-     -0.025503624,
-     -0.025350907,
-     -0.025350907,
-     -0.025350907,
-     -0.02565634,
-     -0.025809056,
-     -0.025350907,
-     -0.025809056,
-     -0.02565634,
-     -0.025503624,
-     -0.025809056,
-     -0.02565634,
-     -0.025809056,
-     -0.02565634,
-     -0.02565634,
-     -0.025961773,
-     -0.025809056,
-     -0.025961773,
-     -0.026267205,
-     -0.026114489,
-     -0.025961773,
-     -0.026267205,
-     -0.026267205,
-     -0.026114489,
-     -0.026572638,
-     -0.026572638,
-     -0.026419922,
-     -0.026419922,
-     -0.026267205,
-     -0.026572638,
-     -0.026267205,
-     -0.026572638,
-     -0.026419922,
-     -0.02687807,
-     -0.026419922,
-     -0.026267205,
-     -0.026419922,
-     -0.027030787,
-     -0.027030787,
-     -0.027030787,
-     -0.02687807,
-     -0.027030787,
-     -0.026725354,
-     -0.027030787,
-     -0.026725354,
-     -0.027030787,
-     -0.027336219,
-     -0.027030787,
-     -0.027030787,
-     -0.027183503,
-     -0.02687807,
-     -0.027183503,
-     -0.027183503,
-     -0.027030787,
-     -0.027488936,
-     -0.027488936,
-     -0.027183503,
-     -0.027183503,
-     -0.027488936,
-     -0.027183503,
-     -0.027641652,
-     -0.027488936,
-     -0.027641652,
-     -0.027641652,
-     -0.027794368,
-     -0.027947085,
-     -0.027488936,
-     -0.027947085,
-     -0.027794368,
-     -0.027947085,
-     -0.027794368,
-     -0.027947085,
-     -0.028099801,
-     -0.028099801,
-     -0.027794368,
-     -0.028405234,
-     -0.027947085,
-     -0.027947085,
-     -0.028099801,
-     -0.028252517,
-     -0.028252517,
-     -0.028099801,
-     -0.028252517,
-     -0.028252517,
-     -0.028405234,
-     -0.028099801,
-     -0.028099801,
-     -0.028252517,
-     -0.027947085,
-     -0.02855795,
-     -0.028252517,
-     -0.028252517,
-     -0.02855795,
-     -0.028099801,
-     -0.028252517,
-     -0.028405234,
-     -0.028405234,
-     -0.028710666,
-     -0.02855795,
-     -0.02855795,
-     -0.02855795,
-     -0.02855795,
-     -0.02855795,
-     -0.029168815,
-     -0.029016099,
-     -0.028863383,
-     -0.029016099,
-     -0.029016099,
-     -0.028863383,
-     -0.029016099,
-     -0.02855795,
-     -0.029321531,
-     -0.028863383,
-     -0.029321531,
-     -0.029321531,
-     -0.029168815,
-     -0.029168815,
-     -0.029321531,
-     -0.029168815,
-     -0.029626964,
-     -0.029321531,
-     -0.029321531,
-     -0.02977968,
-     -0.02977968,
-     -0.030085113,
-     -0.030237829,
-     -0.030237829,
-     -0.029932397,
-     -0.030237829,
-     -0.030237829,
-     -0.030237829,
-     -0.030390546,
-     -0.030237829,
-     -0.030237829,
-     -0.030085113,
-     -0.030237829,
-     -0.030543262,
-     -0.030543262,
-     -0.030543262,
-     -0.030543262,
-     -0.030695978,
-     -0.030695978,
-     -0.030695978,
-     -0.030543262,
-     -0.030695978,
-     -0.030543262,
-     -0.030848695,
-     -0.031001411,
-     -0.030848695,
-     -0.031306843,
-     -0.031306843,
-     -0.030695978,
-     -0.031001411,
-     -0.031001411,
-     -0.031154127,
-     -0.031306843,
-     -0.031154127,
-     -0.031154127,
-     -0.03145956,
-     -0.03145956,
-     -0.031154127,
-     -0.031154127,
-     -0.031154127,
-     -0.03145956,
-     -0.031154127,
-     -0.031612276,
-     -0.031764992,
-     -0.031764992,
-     -0.031306843,
-     -0.031764992,
-     -0.031764992,
-     -0.032375858,
-     -0.031917709,
-     -0.032070425,
-     -0.031917709,
-     -0.032070425,
-     -0.031764992,
-     -0.032223141,
-     -0.032223141,
-     -0.031764992,
-     -0.032528574,
-     -0.031764992,
-     -0.032375858,
-     -0.032528574,
-     -0.032528574,
-     -0.03268129,
-     -0.032375858,
-     -0.03268129,
-     -0.032834007,
-     -0.03268129,
-     -0.03268129,
-     -0.032834007,
-     -0.032528574,
-     -0.03268129,
-     -0.032986723,
-     -0.033139439,
-     -0.033139439,
-     -0.033139439,
-     -0.033597588,
-     -0.032986723,
-     -0.033139439,
-     -0.032986723,
-     -0.033444872,
-     -0.032986723,
-     -0.033444872,
-     -0.033597588,
-     -0.033444872,
-     -0.033444872,
-     -0.033597588,
-     -0.033597588,
-     -0.033903021,
-     -0.034055737,
-     -0.034208453,
-     -0.033750304,
-     -0.033903021,
-     -0.034208453,
-     -0.033444872,
-     -0.03436117,
-     -0.034055737,
-     -0.034055737,
-     -0.034208453,
-     -0.03436117,
-     -0.034055737,
-     -0.03436117,
-     -0.034513886,
-     -0.034666602,
-     -0.034819319,
-     -0.034513886,
-     -0.034666602,
-     -0.034972035,
-     -0.034666602,
-     -0.034819319,
-     -0.034819319,
-     -0.034819319,
-     -0.034972035,
-     -0.035124751,
-     -0.034972035,
-     -0.035124751,
-     -0.035124751,
-     -0.035277468,
-     -0.035430184,
-     -0.035124751,
-     -0.035430184,
-     -0.035277468,
-     -0.035430184,
-     -0.035888333,
-     -0.035430184,
-     -0.0355829,
-     -0.036041049,
-     -0.0355829,
-     -0.0355829,
-     -0.036193765,
-     -0.035735616,
-     -0.035735616,
-     -0.036193765,
-     -0.036041049,
-     -0.035735616,
-     -0.035888333,
-     -0.036346482,
-     -0.036193765,
-     -0.036346482,
-     -0.036193765,
-     -0.036499198,
-     -0.036499198,
-     -0.036499198,
-     -0.036499198,
-     -0.036499198,
-     -0.036957347,
-     -0.036346482,
-     -0.036957347,
-     -0.03726278,
-     -0.036804631,
-     -0.03726278,
-     -0.037110063,
-     -0.03726278,
-     -0.03726278,
-     -0.03726278,
-     -0.03726278,
-     -0.03726278,
-     -0.037415496,
-     -0.037415496,
-     -0.037568212,
-     -0.037415496,
-     -0.037720928,
-     -0.037720928,
-     -0.037568212,
-     -0.037720928,
-     -0.037873645,
-     -0.038026361,
-     -0.037873645,
-     -0.038331794,
-     -0.038331794,
-     -0.038179077,
-     -0.03848451,
-     -0.038331794,
-     -0.038637226,
-     -0.038331794,
-     -0.038026361,
-     -0.038637226,
-     -0.038637226,
-     -0.038789943,
-     -0.038789943,
-     -0.038789943,
-     -0.038789943,
-     -0.038789943,
-     -0.038942659,
-     -0.038637226,
-     -0.038789943,
-     -0.038942659,
-     -0.039248092,
-     -0.039095375,
-     -0.039095375,
-     -0.039400808,
-     -0.039095375,
-     -0.039553524,
-     -0.039553524,
-     -0.03970624,
-     -0.039553524,
-     -0.039400808,
-     -0.039553524,
-     -0.039553524,
-     -0.039553524,
-     -0.040011673,
-     -0.039858957,
-     -0.040011673,
-     -0.040011673,
-     -0.040164389,
-     -0.040469822,
-     -0.040469822,
-     -0.040164389,
-     -0.040469822,
-     -0.040469822,
-     -0.040469822,
-     -0.040622538,
-     -0.040622538,
-     -0.040775255,
-     -0.040775255,
-     -0.041233404,
-     -0.040775255,
-     -0.040927971,
-     -0.041233404,
-     -0.041233404,
-     -0.041233404,
-     -0.041080687,
-     -0.04138612,
-     -0.041233404,
-     -0.04138612,
-     -0.041538836,
-     -0.041538836,
-     -0.041538836,
-     -0.041844269,
-     -0.041996985,
-     -0.041844269,
-     -0.041996985,
-     -0.041844269,
-     -0.042302418,
-     -0.042149701,
-     -0.042455134,
-     -0.042455134,
-     -0.042455134,
-     -0.042455134,
-     -0.042455134,
-     -0.042455134,
-     -0.04260785,
-     -0.043065999,
-     -0.042760567,
-     -0.042760567,
-     -0.042760567,
-     -0.043065999,
-     -0.043065999,
-     -0.043065999,
-     -0.043065999,
-     -0.043524148,
-     -0.043218716,
-     -0.043218716,
-     -0.043676865,
-     -0.043371432,
-     -0.043676865,
-     -0.043676865,
-     -0.043524148,
-     -0.043982297,
-     -0.043829581,
-     -0.043982297,
-     -0.043982297,
-     -0.043982297,
-     -0.043982297,
-     -0.044135013,
-     -0.044135013,
-     -0.044135013,
-     -0.044593162,
-     -0.044440446,
-     -0.044898595,
-     -0.044745879,
-     -0.044745879,
-     -0.045051311,
-     -0.044745879,
-     -0.044593162,
-     -0.044898595,
-     -0.044898595,
-     -0.044898595,
-     -0.045204028,
-     -0.045204028,
-     -0.045356744,
-     -0.045356744,
-     -0.04550946,
-     -0.045662177,
-     -0.045662177,
-     -0.045662177,
-     -0.045967609,
-     -0.046273042,
-     -0.046120325,
-     -0.045967609,
-     -0.046120325,
-     -0.046425758,
-     -0.046273042,
-     -0.046578474,
-     -0.046273042,
-     -0.046578474,
-     -0.046425758,
-     -0.046425758,
-     -0.046425758,
-     -0.046578474,
-     -0.046731191,
-     -0.046731191,
-     -0.04718934,
-     -0.047342056,
-     -0.046883907,
-     -0.047036623,
-     -0.047342056,
-     -0.047647489,
-     -0.047494772,
-     -0.047647489,
-     -0.047342056,
-     -0.047342056,
-     -0.047647489,
-     -0.047647489,
-     -0.047952921,
-     -0.048258354,
-     -0.04841107,
-     -0.047952921,
-     -0.048258354,
-     -0.048105638,
-     -0.04841107,
-     -0.048716503,
-     -0.048258354,
-     -0.048563786,
-     -0.048869219,
-     -0.048716503,
-     -0.048716503,
-     -0.049174652,
-     -0.048869219,
-     -0.048869219,
-     -0.049174652,
-     -0.049327368,
-     -0.049174652,
-     -0.049174652,
-     -0.049480084,
-     -0.049938233,
-     -0.049632801,
-     -0.049785517,
-     -0.050243666,
-     -0.049632801,
-     -0.050396382,
-     -0.049938233,
-     -0.05009095,
-     -0.050243666,
-     -0.050243666,
-     -0.050396382,
-     -0.050854531,
-     -0.050549098,
-     -0.050854531,
-     -0.050701815,
-     -0.050549098,
-     -0.051007247,
-     -0.051007247,
-     -0.050854531,
-     -0.051159964,
-     -0.05131268,
-     -0.05131268,
-     -0.051159964,
-     -0.05131268,
-     -0.051618113,
-     -0.051770829,
-     -0.051923545,
-     -0.051770829,
-     -0.052381694,
-     -0.052076262,
-     -0.052381694,
-     -0.052381694,
-     -0.052381694,
-     -0.05253441,
-     -0.052228978,
-     -0.052839843,
-     -0.052687127,
-     -0.052992559,
-     -0.052839843,
-     -0.053145276,
-     -0.053145276,
-     -0.052992559,
-     -0.053297992,
-     -0.053603425,
-     -0.053145276,
-     -0.053450708,
-     -0.053603425,
-     -0.053756141,
-     -0.053603425,
-     -0.053756141,
-     -0.053756141,
-     -0.054061574,
-     -0.05421429,
-     -0.054061574,
-     -0.05421429,
-     -0.054519723,
-     -0.054672439,
-     -0.054672439,
-     -0.054519723,
-     -0.054672439,
-     -0.054825155,
-     -0.054672439,
-     -0.055130588,
-     -0.05543602,
-     -0.055130588,
-     -0.055130588,
-     -0.055283304,
-     -0.055283304,
-     -0.05543602,
-     -0.05543602,
-     -0.055741453,
-     -0.055588737,
-     -0.056199602,
-     -0.056199602,
-     -0.056199602,
-     -0.056046886,
-     -0.056199602,
-     -0.056505035,
-     -0.056199602,
-     -0.056352318,
-     -0.056657751,
-     -0.056657751,
-     -0.057268616,
-     -0.056963183,
-     -0.056963183,
-     -0.057268616,
-     -0.057421332,
-     -0.057421332,
-     -0.057574049,
-     -0.057268616,
-     -0.057879481,
-     -0.057726765,
-     -0.057879481,
-     -0.058184914,
-     -0.058490347,
-     -0.058184914,
-     -0.05833763,
-     -0.05833763,
-     -0.058490347,
-     -0.058490347,
-     -0.058490347,
-     -0.058948495,
-     -0.058795779,
-     -0.059101212,
-     -0.059101212,
-     -0.059253928,
-     -0.059253928,
-     -0.059406644,
-     -0.059406644,
-     -0.059253928,
-     -0.059712077,
-     -0.059559361,
-     -0.059864793,
-     -0.060322942,
-     -0.059864793,
-     -0.060475659,
-     -0.060475659,
-     -0.060475659,
-     -0.060475659,
-     -0.060628375,
-     -0.060628375,
-     -0.060781091,
-     -0.06123924,
-     -0.060933808,
-     -0.060933808,
-     -0.06123924,
-     -0.06123924,
-     -0.061391956,
-     -0.061697389,
-     -0.061544673,
-     -0.061850105,
-     -0.061850105,
-     -0.062155538,
-     -0.062308254,
-     -0.061850105,
-     -0.062460971,
-     -0.062460971,
-     -0.062613687,
-     -0.062613687,
-     -0.062766403,
-     -0.063071836,
-     -0.063071836,
-     -0.063071836,
-     -0.063224552,
-     -0.063377268,
-     -0.063377268,
-     -0.063377268,
-     -0.063835417,
-     -0.063988134,
-     -0.063835417,
-     -0.063835417,
-     -0.064293566,
-     -0.064293566,
-     -0.064293566,
-     -0.064446283,
-     -0.064446283,
-     -0.064446283,
-     -0.064904432,
-     -0.065057148,
-     -0.065057148,
-     -0.065209864,
-     -0.065209864,
-     -0.06536258,
-     -0.065820729,
-     -0.06536258,
-     -0.065668013,
-     -0.065820729,
-     -0.065973446,
-     -0.066431595,
-     -0.065973446,
-     -0.066126162,
-     -0.066737027,
-     -0.066431595,
-     -0.066737027,
-     -0.066584311,
-     -0.066431595,
-     -0.066889744,
-     -0.06704246,
-     -0.067347893,
-     -0.06704246,
-     -0.067347893,
-     -0.067500609,
-     -0.067806041,
-     -0.068111474,
-     -0.067500609,
-     -0.068111474,
-     -0.068111474,
-     -0.068416907,
-     -0.068416907,
-     -0.068722339,
-     -0.069027772,
-     -0.068722339,
-     -0.068875056,
-     -0.069485921,
-     -0.069027772,
-     -0.069333205,
-     -0.069485921,
-     -0.069333205,
-     -0.069638637,
-     -0.070249502,
-     -0.070096786,
-     -0.069791353,
-     -0.070096786,
-     -0.070402219,
-     -0.070249502,
-     -0.070402219,
-     -0.070707651,
-     -0.070554935,
-     -0.070707651,
-     -0.0711658,
-     -0.070860368,
-     -0.071318517,
-     -0.071318517,
-     -0.071776665,
-     -0.071318517,
-     -0.072082098,
-     -0.072082098,
-     -0.072082098,
-     -0.072082098,
-     -0.072234814,
-     -0.072540247,
-     -0.072692963,
-     -0.072692963,
-     -0.072540247,
-     -0.072692963,
-     -0.073151112,
-     -0.073303829,
-     -0.073456545,
-     -0.073609261,
-     -0.073456545,
-     -0.073609261,
-     -0.073761978,
-     -0.074220126,
-     -0.074220126,
-     -0.074372843,
-     -0.074525559,
-     -0.074525559,
-     -0.074525559,
-     -0.074678275,
-     -0.075289141,
-     -0.075136424,
-     -0.075136424,
-     -0.075441857,
-     -0.075900006,
-     -0.075594573,
-     -0.075900006,
-     -0.076052722,
-     -0.076205438,
-     -0.075900006,
-     -0.076052722,
-     -0.076510871,
-     -0.076816304,
-     -0.076816304,
-     -0.077121736,
-     -0.077121736,
-     -0.077274453,
-     -0.077274453,
-     -0.077121736,
-     -0.077579885,
-     -0.077885318,
-     -0.077732602,
-     -0.077885318,
-     -0.078038034,
-     -0.078343467,
-     -0.078343467,
-     -0.078648899,
-     -0.078801616,
-     -0.078343467,
-     -0.078801616,
-     -0.079107048,
-     -0.079259765,
-     -0.079107048,
-     -0.079717914,
-     -0.079717914,
-     -0.079717914,
-     -0.080023346,
-     -0.080176063,
-     -0.080328779,
-     -0.080786928,
-     -0.080328779,
-     -0.080634211,
-     -0.081245077,
-     -0.080939644,
-     -0.081245077,
-     -0.08109236,
-     -0.081397793,
-     -0.081550509,
-     -0.081550509,
-     -0.082161375,
-     -0.081855942,
-     -0.082161375,
-     -0.082619523,
-     -0.082619523,
-     -0.082924956,
-     -0.082466807,
-     -0.082924956,
-     -0.082924956,
-     -0.083077672,
-     -0.083383105,
-     -0.083383105,
-     -0.083688538,
-     -0.083688538,
-     -0.084146687,
-     -0.084146687,
-     -0.084299403,
-     -0.084757552,
-     -0.084757552,
-     -0.084757552,
-     -0.085062984,
-     -0.084910268,
-     -0.085215701,
-     -0.085368417,
-     -0.085826566,
-     -0.085826566,
-     -0.085979282,
-     -0.085826566,
-     -0.086284715,
-     -0.086284715,
-     -0.086590148,
-     -0.086742864,
-     -0.086437431,
-     -0.08689558,
-     -0.087506445,
-     -0.087506445,
-     -0.087353729,
-     -0.087659162,
-     -0.087811878,
-     -0.088270027,
-     -0.088270027,
-     -0.088422743,
-     -0.088728176,
-     -0.088728176,
-     -0.088728176,
-     -0.088880892,
-     -0.088422743,
-     -0.089186325,
-     -0.089339041,
-     -0.089644474,
-     -0.089491757,
-     -0.089491757,
-     -0.089949906,
-     -0.090408055,
-     -0.090255339,
-     -0.090713488,
-     -0.090560772,
-     -0.090866204,
-     -0.090713488,
-     -0.091171637,
-     -0.091629786,
-     -0.091782502,
-     -0.091782502,
-     -0.092087935,
-     -0.091782502,
-     -0.0926988,
-     -0.092393367,
-     -0.092393367,
-     -0.092546084,
-     -0.092851516,
-     -0.093156949,
-     -0.093004233,
-     -0.093462381,
-     -0.093309665,
-     -0.093767814,
-     -0.093767814,
-     -0.09392053,
-     -0.094225963,
-     -0.094531396,
-     -0.094531396,
-     -0.094836828,
-     -0.094836828,
-     -0.094836828,
-     -0.095142261,
-     -0.09560041,
-     -0.095753126,
-     -0.09560041,
-     -0.095753126,
-     -0.095753126,
-     -0.096211275,
-     -0.096669424,
-     -0.096974857,
-     -0.09682214,
-     -0.096974857,
-     -0.097280289,
-     -0.097280289,
-     -0.097127573,
-     -0.097433005,
-     -0.097738438,
-     -0.097891154,
-     -0.097891154,
-     -0.09850202,
-     -0.098654736,
-     -0.09850202,
-     -0.098960169,
-     -0.099112885,
-     -0.099265601,
-     -0.099265601,
-     -0.099876466,
-     -0.099265601,
-     -0.099876466,
-     -0.100181899,
-     -0.100181899,
-     -0.100640048,
-     -0.100792764,
-     -0.101250913,
-     -0.100792764,
-     -0.101250913,
-     -0.101098197,
-     -0.101709062,
-     -0.102014495,
-     -0.102014495,
-     -0.102472644,
-     -0.101861778,
-     -0.102472644,
-     -0.102930793,
-     -0.102778076,
-     -0.102778076,
-     -0.103388942,
-     -0.103388942,
-     -0.103388942,
-     -0.10384709,
-     -0.10384709,
-     -0.104305239,
-     -0.104305239,
-     -0.104763388,
-     -0.104763388,
-     -0.104916105,
-     -0.105068821,
-     -0.105374254,
-     -0.10552697,
-     -0.105679686,
-     -0.105679686,
-     -0.106137835,
-     -0.106443268,
-     -0.106595984,
-     -0.106290551,
-     -0.106443268,
-     -0.106901417,
-     -0.107054133,
-     -0.107359566,
-     -0.107664998,
-     -0.107512282,
-     -0.107664998,
-     -0.10842858,
-     -0.10842858,
-     -0.10842858,
-     -0.108886729,
-     -0.108734012,
-     -0.108886729,
-     -0.109497594,
-     -0.109344878,
-     -0.10965031,
-     -0.10965031,
-     -0.109955743,
-     -0.110108459,
-     -0.110108459,
-     -0.110719324,
-     -0.110872041,
-     -0.111024757,
-     -0.111177473,
-     -0.11133019,
-     -0.112093771,
-     -0.111788339,
-     -0.112246488,
-     -0.11255192,
-     -0.112399204,
-     -0.112704636,
-     -0.112857353,
-     -0.112704636,
-     -0.113010069,
-     -0.113468218,
-     -0.113315502,
-     -0.114079083,
-     -0.114079083,
-     -0.113926367,
-     -0.114384516,
-     -0.114689948,
-     -0.114537232,
-     -0.114842665,
-     -0.115148097,
-     -0.115148097,
-     -0.11545353,
-     -0.115758963,
-     -0.115606246,
-     -0.115758963,
-     -0.116064395,
-     -0.116369828,
-     -0.116522544,
-     -0.116522544,
-     -0.116827977,
-     -0.117133409,
-     -0.117133409,
-     -0.117744275,
-     -0.118049707,
-     -0.118049707,
-     -0.117896991,
-     -0.11835514,
-     -0.11835514,
-     -0.118660573,
-     -0.119118721,
-     -0.118966005,
-     -0.119424154,
-     -0.11957687,
-     -0.119882303,
-     -0.120187736,
-     -0.120340452,
-     -0.120035019,
-     -0.120493168,
-     -0.120340452,
-     -0.120798601,
-     -0.12125675,
-     -0.121409466,
-     -0.121867615,
-     -0.122020331,
-     -0.122020331,
-     -0.122325764,
-     -0.12247848,
-     -0.12247848,
-     -0.122936629,
-     -0.123089345,
-     -0.123242062,
-     -0.123700211,
-     -0.123700211,
-     -0.124311076,
-     -0.124311076,
-     -0.124311076,
-     -0.124463792,
-     -0.124769225,
-     -0.125074658,
-     -0.12538009,
-     -0.12538009,
-     -0.12538009,
-     -0.125838239,
-     -0.125990955,
-     -0.126296388,
-     -0.126296388,
-     -0.126601821,
-     -0.126754537,
-     -0.126907253,
-     -0.127518118,
-     -0.127670835,
-     -0.127976267,
-     -0.128128984,
-     -0.1282817,
-     -0.128434416,
-     -0.128434416,
-     -0.128892565,
-     -0.129197998,
-     -0.12950343,
-     -0.12950343,
-     -0.129961579,
-     -0.130114296,
-     -0.130267012,
-     -0.130877877,
-     -0.130725161,
-     -0.13118331,
-     -0.130725161,
-     -0.13118331,
-     -0.131946891,
-     -0.131794175,
-     -0.132252324,
-     -0.132557757,
-     -0.132557757,
-     -0.133015906,
-     -0.132863189,
-     -0.132863189,
-     -0.133015906,
-     -0.133474055,
-     -0.133932203,
-     -0.133932203,
-     -0.134543069,
-     -0.134543069,
-     -0.134848501,
-     -0.135001218,
-     -0.135001218,
-     -0.135459367,
-     -0.13530665,
-     -0.135917515,
-     -0.135764799,
-     -0.136528381,
-     -0.136528381,
-     -0.136833813,
-     -0.137139246,
-     -0.137139246,
-     -0.137291962,
-     -0.137444679,
-     -0.137444679,
-     -0.137750111,
-     -0.138360976,
-     -0.138666409,
-     -0.138819125,
-     -0.138819125,
-     -0.139429991,
-     -0.139582707,
-     -0.139277274,
-     -0.139582707,
-     -0.139735423,
-     -0.140499005,
-     -0.140040856,
-     -0.140346288,
-     -0.140957154,
-     -0.141262586,
-     -0.141262586,
-     -0.141568019,
-     -0.141873452,
-     -0.141720735,
-     -0.141720735,
-     -0.142026168,
-     -0.142484317,
-     -0.142484317,
-     -0.142789749,
-     -0.143247898,
-     -0.143247898,
-     -0.143706047,
-     -0.143706047,
-     -0.143553331,
-     -0.14401148,
-     -0.14401148,
-     -0.144316913,
-     -0.144316913,
-     -0.144622345,
-     -0.145080494,
-     -0.145385927,
-     -0.145385927,
-     -0.145538643,
-     -0.145996792,
-     -0.145691359,
-     -0.146302225,
-     -0.146607657,
-     -0.146607657,
-     -0.146760373,
-     -0.147218522,
-     -0.147371239,
-     -0.147523955,
-     -0.147676671,
-     -0.147829388,
-     -0.147829388,
-     -0.147982104,
-     -0.148287537,
-     -0.148592969,
-     -0.149203834,
-     -0.149051118,
-     -0.149051118,
-     -0.149356551,
-     -0.1498147,
-     -0.149661983,
-     -0.150272849,
-     -0.150272849,
-     -0.150120132,
-     -0.150578281,
-     -0.151189146,
-     -0.15103643,
-     -0.151189146,
-     -0.151494579,
-     -0.151800012,
-     -0.151952728,
-     -0.152105444,
-     -0.151952728,
-     -0.152563593,
-     -0.152410877,
-     -0.152410877,
-     -0.153174458,
-     -0.153327175,
-     -0.153632607,
-     -0.15393804,
-     -0.153632607,
-     -0.15393804,
-     -0.154396189,
-     -0.154090756,
-     -0.154701622,
-     -0.155159771,
-     -0.155312487,
-     -0.154854338,
-     -0.155465203,
-     -0.155770636,
-     -0.155770636,
-     -0.155617919,
-     -0.156381501,
-     -0.156228785,
-     -0.156381501,
-     -0.156686934,
-     -0.156992366,
-     -0.156992366,
-     -0.157603231,
-     -0.157603231,
-     -0.157755948,
-     -0.15806138,
-     -0.15806138,
-     -0.158519529,
-     -0.158519529,
-     -0.158824962,
-     -0.158977678,
-     -0.159130395,
-     -0.159283111,
-     -0.159435827,
-     -0.159283111,
-     -0.159893976,
-     -0.160046692,
-     -0.160199409,
-     -0.160504841,
-     -0.160504841,
-     -0.16096299,
-     -0.160810274,
-     -0.16096299,
-     -0.161421139,
-     -0.161421139,
-     -0.161573856,
-     -0.161879288,
-     -0.162490153,
-     -0.162337437,
-     -0.162490153,
-     -0.162795586,
-     -0.163101019,
-     -0.163101019,
-     -0.163253735,
-     -0.163253735,
-     -0.163559168,
-     -0.163559168,
-     -0.164017316,
-     -0.164170033,
-     -0.164475465,
-     -0.164780898,
-     -0.164933614,
-     -0.164933614,
-     -0.165391763,
-     -0.165239047,
-     -0.165239047,
-     -0.165391763,
-     -0.165697196,
-     -0.166155345,
-     -0.166155345,
-     -0.166613494,
-     -0.166460777,
-     -0.166460777,
-     -0.166613494,
-     -0.16676621,
-     -0.167071643,
-     -0.167682508,
-     -0.167835224,
-     -0.167682508,
-     -0.167682508,
-     -0.168140657,
-     -0.168140657,
-     -0.168293373,
-     -0.168598806,
-     -0.168904238,
-     -0.168751522,
-     -0.168751522,
-     -0.169209671,
-     -0.169362387,
-     -0.169362387,
-     -0.16966782,
-     -0.169973253,
-     -0.169973253,
-     -0.170278685,
-     -0.170278685,
-     -0.170125969,
-     -0.170278685,
-     -0.170584118,
-     -0.170431401,
-     -0.171194983,
-     -0.171042267,
-     -0.171194983,
-     -0.171347699,
-     -0.171500416,
-     -0.171500416,
-     -0.171653132,
-     -0.171805848,
-     -0.172111281,
-     -0.172263997,
-     -0.172263997,
-     -0.172722146,
-     -0.17256943,
-     -0.172874862,
-     -0.173027579,
-     -0.172874862,
-     -0.172874862,
-     -0.173485728,
-     -0.173333011,
-     -0.173638444,
-     -0.173638444,
-     -0.17379116,
-     -0.174096593,
-     -0.174402026,
-     -0.173943877,
-     -0.173943877,
-     -0.174096593,
-     -0.174554742,
-     -0.174707458,
-     -0.174707458,
-     -0.174860174,
-     -0.174860174,
-     -0.175165607,
-     -0.175165607,
-     -0.175318323,
-     -0.175165607,
-     -0.175623756,
-     -0.17547104,
-     -0.175776472,
-     -0.175776472,
-     -0.176081905,
-     -0.176234621,
-     -0.175929189,
-     -0.176387338,
-     -0.176540054,
-     -0.176540054,
-     -0.176540054,
-     -0.176540054,
-     -0.17669277,
-     -0.17669277,
-     -0.177150919,
-     -0.176998203,
-     -0.177150919,
-     -0.177150919,
-     -0.177609068,
-     -0.177456352,
-     -0.177456352,
-     -0.177609068,
-     -0.177609068,
-     -0.177761784,
-     -0.177761784,
-     -0.178067217,
-     -0.178219933,
-     -0.178219933,
-     -0.178525366,
-     -0.178067217,
-     -0.178678082,
-     -0.178830798,
-     -0.178525366,
-     -0.178678082,
-     -0.178525366,
-     -0.178830798,
-     -0.178678082,
-     -0.179288947,
-     -0.178983515,
-     -0.179136231,
-     -0.179288947,
-     -0.178983515,
-     -0.179288947,
-     -0.178983515,
-     -0.179441664,
-     -0.17959438,
-     -0.179747096,
-     -0.179441664,
-     -0.17959438,
-     -0.179899813,
-     -0.179747096,
-     -0.180205245,
-     -0.179747096,
-     -0.180205245,
-     -0.17959438,
-     -0.179899813,
-     -0.180205245,
-     -0.180357962,
-     -0.180357962,
-     -0.180357962,
-     -0.180663394,
-     -0.180510678,
-     -0.180357962,
-     -0.180205245,
-     -0.180510678,
-     -0.180663394,
-     -0.180510678,
-     -0.180816111,
-     -0.180816111,
-     -0.180816111,
-     -0.181121543,
-     -0.180968827,
-     -0.180816111,
-     -0.181274259,
-     -0.180663394,
-     -0.180968827,
-     -0.180663394,
-     -0.181274259,
-     -0.181121543,
-     -0.181274259,
-     -0.181121543,
-     -0.180968827,
-     -0.180968827,
-     -0.180968827,
-     -0.180968827,
-     -0.181274259,
-     -0.181426976,
-     -0.181426976,
-     -0.181274259},
-    {-0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0,
-     -0.000305433,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000305433,
-     0,
-     0,
-     0,
-     0,
-     0.000152716,
-     -0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000763582,
-     0.000763582,
-     0.000763582,
-     0.000763582,
-     0.001069014,
-     0.000916298,
-     0.001069014,
-     0.00122173,
-     0.001527163,
-     0.001832596,
-     0.002443461,
-     0.002290745,
-     0.002596177,
-     0.00290161,
-     0.003359759,
-     0.003512475,
-     0.003665191,
-     0.003970624,
-     0.004581489,
-     0.004886922,
-     0.005497787,
-     0.00580322,
-     0.00580322,
-     0.006719518,
-     0.006872234,
-     0.007330383,
-     0.007635815,
-     0.008246681,
-     0.008552113,
-     0.00870483,
-     0.009621128,
-     0.010079276,
-     0.009621128,
-     0.009773844,
-     0.010690142,
-     0.010842858,
-     0.010995574,
-     0.010995574,
-     0.011301007,
-     0.011453723,
-     0.011759156,
-     0.01160644,
-     0.011301007,
-     0.01160644,
-     0.01160644,
-     0.011453723,
-     0.011301007,
-     0.010995574,
-     0.011148291,
-     0.010842858,
-     0.010537425,
-     0.010384709,
-     0.010690142,
-     0.00992656,
-     0.00992656,
-     0.009010262,
-     0.008857546,
-     0.008093964,
-     0.007483099,
-     0.006719518,
-     0.006108652,
-     0.005345071,
-     0.005192355,
-     0.004276057,
-     0.003359759,
-     0.002443461,
-     0.001527163,
-     0.000763582,
-     -0.000305433,
-     -0.00122173,
-     -0.002138028,
-     -0.002748894,
-     -0.002748894,
-     -0.003970624,
-     -0.004734206,
-     -0.005497787,
-     -0.006108652,
-     -0.006872234,
-     -0.007483099,
-     -0.008399397,
-     -0.008857546,
-     -0.009162979,
-     -0.00870483,
-     -0.009162979,
-     -0.009468411,
-     -0.009621128,
-     -0.009468411,
-     -0.009468411,
-     -0.009468411,
-     -0.009162979,
-     -0.009010262,
-     -0.008857546,
-     -0.00870483,
-     -0.008552113,
-     -0.007788532,
-     -0.007788532,
-     -0.006872234,
-     -0.006719518,
-     -0.00580322,
-     -0.005345071,
-     -0.004581489,
-     -0.003970624,
-     -0.003512475,
-     -0.003207043,
-     -0.002290745,
-     -0.001527163,
-     -0.000610865,
-     0,
-     0.000458149,
-     0.001527163,
-     0.002138028,
-     0.00290161,
-     0.002748894,
-     0.003665191,
-     0.003970624,
-     0.005039638,
-     0.005497787,
-     0.005955936,
-     0.006108652,
-     0.005955936,
-     0.006566801,
-     0.006566801,
-     0.006872234,
-     0.00702495,
-     0.006872234,
-     0.006566801,
-     0.006566801,
-     0.006414085,
-     0.005650503,
-     0.005192355,
-     0.005192355,
-     0.004734206,
-     0.005039638,
-     0.003817908,
-     0.003665191,
-     0.003054326,
-     0.002290745,
-     0.001679879,
-     0.001069014,
-     0.000152716,
-     -0.000458149,
-     -0.000458149,
-     -0.00122173,
-     -0.001374447,
-     -0.001832596,
-     -0.002443461,
-     -0.002748894,
-     -0.003207043,
-     -0.003512475,
-     -0.003512475,
-     -0.003817908,
-     -0.003970624,
-     -0.003665191,
-     -0.00412334,
-     -0.00412334,
-     -0.003817908,
-     -0.003512475,
-     -0.003512475,
-     -0.00290161,
-     -0.002748894,
-     -0.002290745,
-     -0.001832596,
-     -0.001374447,
-     -0.001069014,
-     -0.000610865,
-     -0.000305433,
-     0.000305433,
-     0.001069014,
-     0.001527163,
-     0.001985312,
-     0.001985312,
-     0.002596177,
-     0.002290745,
-     0.003054326,
-     0.003207043,
-     0.003207043,
-     0.003054326,
-     0.003359759,
-     0.003512475,
-     0.003054326,
-     0.003207043,
-     0.00290161,
-     0.002443461,
-     0.002443461,
-     0.002138028,
-     0.001679879,
-     0.001374447,
-     0.000916298,
-     0.000763582,
-     0.000152716,
-     -0.000458149,
-     -0.000305433,
-     -0.000763582,
-     -0.001069014,
-     -0.001374447,
-     -0.00122173,
-     -0.001374447,
-     -0.002290745,
-     -0.002138028,
-     -0.001832596,
-     -0.001832596,
-     -0.001832596,
-     -0.001832596,
-     -0.001527163,
-     -0.001679879,
-     -0.001069014,
-     -0.001069014,
-     -0.000305433,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000610865,
-     0.000763582,
-     0.001069014,
-     0.00122173,
-     0.001527163,
-     0.001832596,
-     0.001679879,
-     0.002138028,
-     0.001679879,
-     0.001985312,
-     0.001527163,
-     0.001679879,
-     0.001527163,
-     0.000916298,
-     0.001527163,
-     0.000610865,
-     0.000916298,
-     0.000305433,
-     0.000152716,
-     -0.000610865,
-     -0.000610865,
-     -0.000305433,
-     -0.000610865,
-     -0.000458149,
-     -0.000763582,
-     -0.000916298,
-     -0.001069014,
-     -0.000763582,
-     -0.000610865,
-     -0.000458149,
-     -0.000305433,
-     -0.000763582,
-     0,
-     -0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000916298,
-     0.000916298,
-     0.000610865,
-     0.00122173,
-     0.000916298,
-     0.001069014,
-     0.000763582,
-     0.000763582,
-     0.000763582,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0,
-     -0.000458149,
-     -0.000305433,
-     -0.000152716,
-     -0.000610865,
-     0,
-     -0.000610865,
-     -0.000610865,
-     -0.000610865,
-     -0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000763582,
-     0.000305433,
-     0.000763582,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000610865,
-     0.000610865,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     -0.000152716,
-     -0.000152716,
-     -0.000305433,
-     0,
-     -0.000458149,
-     0,
-     -0.000152716,
-     0,
-     0,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000610865,
-     0.000763582,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     -0.000305433,
-     0,
-     -0.000152716,
-     0,
-     0.000152716,
-     -0.000152716,
-     0,
-     0,
-     0,
-     0.000305433,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0,
-     0,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     -0.000305433,
-     0.000305433,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000610865,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000458149,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000458149,
-     0,
-     -0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000458149,
-     0,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     0,
-     0,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0,
-     0.000305433,
-     0,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000305433,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0,
-     0,
-     0,
-     0,
-     0.000610865,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000763582,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000305433,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     -0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000305433,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     -0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000763582,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000610865,
-     0.000458149,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000610865,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     -0.000152716,
-     0,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000763582,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000305433,
-     -0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     -0.000152716,
-     0.000610865,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     0,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000610865,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000458149,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000152716,
-     0.000152716,
-     -0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000610865,
-     0,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0,
-     0,
-     0.000152716,
-     -0.000152716,
-     -0.000152716,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0,
-     0,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000610865,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     -0.000152716,
-     0.000458149,
-     0,
-     0.000305433,
-     0,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000763582,
-     0.000610865,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     -0.000152716,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000763582,
-     0,
-     0.000458149,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000610865,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000458149,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000610865,
-     0.000610865,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000458149,
-     0,
-     0,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000305433,
-     0.000458149,
-     0,
-     0.000152716,
-     0,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000458149,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0,
-     0.000763582,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0,
-     0.000458149,
-     0.000305433,
-     0,
-     0.000458149,
-     0.000610865,
-     0,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000763582,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000152716,
-     0.000152716,
-     0.000610865,
-     0.000458149,
-     0.000458149,
-     0,
-     0.000610865,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000305433,
-     0,
-     0.000305433,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000763582,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000763582,
-     0.000610865,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000610865,
-     0.000458149,
-     0.000763582,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000610865,
-     0.000610865,
-     0.000152716,
-     0.000610865,
-     0.000152716,
-     0.000458149,
-     0.000152716,
-     0.000763582,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000610865,
-     0.000610865,
-     0.000610865,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000610865,
-     0.000763582,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000610865,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000610865,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000763582,
-     0.000152716,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000916298,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000152716,
-     0.000152716,
-     0.000610865,
-     0.000305433,
-     0.000305433,
-     0.000763582,
-     0.000152716,
-     0.000458149,
-     0.000610865,
-     0.000458149,
-     0.000152716,
-     0.000610865,
-     0.000305433,
-     0.000305433,
-     0.000152716,
-     0.000763582,
-     0.000152716,
-     0.000610865,
-     0.000458149,
-     0.000458149,
-     0.000763582,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000916298,
-     0.000458149,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0.000610865,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000610865,
-     0.000763582,
-     0.000305433,
-     0.000458149,
-     0.000152716,
-     0.000610865,
-     0.000152716,
-     0.000458149,
-     0.000610865,
-     0.000610865,
-     0.000152716,
-     0.000610865,
-     0.000458149,
-     0.000763582,
-     0.000610865,
-     0.000305433,
-     0.000152716,
-     0.000610865,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000610865,
-     0.000305433,
-     0.000458149,
-     0.000610865,
-     0.000610865,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000763582,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000152716,
-     0,
-     0.000610865,
-     0.000916298,
-     0.000610865,
-     0.000152716,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000610865,
-     0.000305433,
-     0.000458149,
-     0.000610865,
-     0.000610865,
-     0.000610865,
-     0.000305433,
-     0.000763582,
-     0.000610865,
-     0.000152716,
-     0.000763582,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000763582,
-     0.000610865,
-     0.000305433,
-     0.000305433,
-     0.000763582,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000610865,
-     0.000610865,
-     0.000610865,
-     0.000305433,
-     0.000458149,
-     0.000305433,
-     0.000305433,
-     0.000458149,
-     0.000610865,
-     0.000458149,
-     0.000610865,
-     0.000763582,
-     0.000305433,
-     0.000610865,
-     0.000763582,
-     0.000458149,
-     0.000763582,
-     0.000458149,
-     0.000916298,
-     0.000763582,
-     0.000458149,
-     0.000610865,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000458149,
-     0.000916298,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000305433,
-     0.000610865,
-     0.000916298,
-     0.000305433,
-     0.000916298,
-     0.000458149,
-     0.000610865,
-     0.000610865,
-     0.000152716,
-     0.000305433,
-     0.000152716,
-     0.000763582,
-     0.000458149,
-     0.000610865,
-     0.000763582,
-     0.000610865,
-     0.000763582,
-     0.000610865,
-     0.000305433,
-     0.000610865,
-     0.000458149,
-     0.000305433,
-     0.000763582,
-     0.000610865,
-     0.000763582,
-     0.000458149,
-     0.000458149,
-     0.000763582,
-     0.000763582,
-     0.000305433,
-     0.000916298,
-     0.000305433,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000610865,
-     0.000916298,
-     0.000763582,
-     0.000763582,
-     0.000458149,
-     0.000763582,
-     0.000916298,
-     0.000610865,
-     0.000610865,
-     0.000763582,
-     0.000916298,
-     0.000763582,
-     0.000458149,
-     0.000610865,
-     0.000763582,
-     0.000305433,
-     0.000610865,
-     0.000610865,
-     0.000458149,
-     0.000610865,
-     0.000458149,
-     0.000610865,
-     0.000458149,
-     0.000305433,
-     0.000763582,
-     0.000763582,
-     0.000458149,
-     0.000763582,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000763582,
-     0.000763582,
-     0.000916298,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000763582,
-     0.000610865,
-     0.000763582,
-     0.000610865,
-     0.000458149,
-     0.000610865,
-     0.000763582,
-     0.000610865,
-     0.000458149,
-     0.000458149,
-     0.000458149,
-     0.000763582,
-     0.000458149,
-     0.000610865,
-     0.000610865,
-     0.000916298,
-     0.000763582,
-     0.000458149,
-     0.000610865,
-     0.000916298,
-     0.000458149,
-     0.000610865,
-     0.000458149,
-     0.001069014,
-     0.000458149,
-     0.00122173,
-     0.001069014,
-     0.000458149,
-     0.000458149,
-     0.001069014,
-     0.000610865,
-     0.000458149,
-     0.000763582,
-     0.000610865,
-     0.000610865,
-     0.000610865,
-     0.000610865,
-     0.000916298,
-     0.000152716,
-     0.000916298,
-     0.000610865,
-     0.000763582,
-     0.000916298,
-     0.000916298,
-     0.000610865,
-     0.000305433,
-     0.001069014,
-     0.000458149,
-     0.000763582,
-     0.000610865,
-     0.000458149,
-     0.000763582,
-     0.000610865,
-     0.000305433,
-     0.000763582,
-     0.000763582,
-     0.000916298,
-     0.000610865,
-     0.000458149,
-     0.000763582,
-     0.000458149,
-     0.000458149,
-     0.000610865,
-     0.000305433,
-     0.000763582,
-     0.001069014,
-     0.000763582,
-     0.001069014,
-     0.000763582,
-     0.000458149,
-     0.000763582,
-     0.000610865,
-     0.000763582,
-     0.000610865,
-     0.000763582,
-     0.000610865,
-     0.000763582,
-     0.000458149,
-     0.000610865,
-     0.000763582,
-     0.000610865,
-     0.000916298,
-     0.000610865,
-     0.000916298,
-     0.000763582,
-     0.000458149,
-     0.000763582,
-     0.001069014,
-     0.000916298,
-     0.000763582,
-     0.000763582,
-     0.000763582,
-     0.000916298,
-     0.000916298,
-     0.000916298,
-     0.000763582,
-     0.000610865,
-     0.000458149,
-     0.000610865,
-     0.000763582,
-     0.000610865,
-     0.000916298,
-     0.000916298,
-     0.000610865,
-     0.000916298,
-     0.000916298,
-     0.000763582,
-     0.000458149,
-     0.000763582,
-     0.000458149,
-     0.000458149,
-     0.000916298,
-     0.000610865,
-     0.000610865,
-     0.000916298,
-     0.000458149,
-     0.000763582,
-     0.000763582,
-     0.000916298,
-     0.000458149,
-     0.000763582,
-     0.000610865,
-     0.000610865,
-     0.000610865,
-     0.000916298,
-     0.000610865,
-     0.00122173,
-     0.000610865,
-     0.000916298,
-     0.000610865,
-     0.000763582,
-     0.000916298,
-     0.000610865,
-     0.000916298,
-     0.000763582,
-     0.000610865,
-     0.000916298,
-     0.000916298,
-     0.000763582,
-     0.000916298,
-     0.000916298,
-     0.000763582,
-     0.000763582,
-     0.000763582,
-     0.000916298,
-     0.000763582,
-     0.000610865,
-     0.000610865,
-     0.000916298,
-     0.000763582,
-     0.000916298,
-     0.000916298,
-     0.000763582,
-     0.000763582,
-     0.000916298,
-     0.001069014,
-     0.000458149,
-     0.001069014,
-     0.000916298,
-     0.001069014,
-     0.001069014,
-     0.001069014,
-     0.000916298,
-     0.00122173,
-     0.000916298,
-     0.000916298,
-     0.001069014,
-     0.001069014,
-     0.000916298,
-     0.000763582,
-     0.000610865,
-     0.000610865,
-     0.000916298,
-     0.00122173,
-     0.000763582,
-     0.000916298,
-     0.000916298,
-     0.000916298,
-     0.00122173,
-     0.001069014,
-     0.000916298,
-     0.000763582,
-     0.000763582,
-     0.000763582,
-     0.000916298,
-     0.000916298,
-     0.000916298,
-     0.000916298,
-     0.000916298,
-     0.000916298,
-     0.000763582,
-     0.001069014,
-     0.000916298,
-     0.000916298,
-     0.00122173,
-     0.001069014,
-     0.000763582,
-     0.00122173,
-     0.001069014,
-     0.00122173,
-     0.000916298,
-     0.000916298,
-     0.000916298,
-     0.000763582,
-     0.000763582,
-     0.000610865,
-     0.00122173,
-     0.000916298,
-     0.000763582,
-     0.00122173,
-     0.000916298,
-     0.000916298,
-     0.00122173,
-     0.000916298,
-     0.000763582,
-     0.000916298,
-     0.000763582,
-     0.001069014,
-     0.001374447,
-     0.001374447,
-     0.001069014,
-     0.000916298,
-     0.00122173,
-     0.001069014,
-     0.000916298,
-     0.000610865,
-     0.001069014,
-     0.000763582,
-     0.000763582,
-     0.00122173,
-     0.000916298,
-     0.000763582,
-     0.000916298,
-     0.001069014,
-     0.000763582,
-     0.000763582,
-     0.00122173,
-     0.000916298,
-     0.001069014,
-     0.000763582,
-     0.00122173,
-     0.000763582,
-     0.001069014,
-     0.000610865,
-     0.001069014,
-     0.000916298,
-     0.001069014,
-     0.00122173,
-     0.000763582,
-     0.000916298,
-     0.001069014,
-     0.001069014,
-     0.001069014,
-     0.000916298,
-     0.000916298,
-     0.00122173,
-     0.000916298,
-     0.001069014,
-     0.000916298,
-     0.00122173,
-     0.001069014,
-     0.001069014,
-     0.001069014,
-     0.00122173,
-     0.000763582,
-     0.001069014,
-     0.000763582,
-     0.001374447,
-     0.001069014,
-     0.00122173,
-     0.001374447,
-     0.00122173,
-     0.001069014,
-     0.00122173,
-     0.00122173,
-     0.00122173,
-     0.001374447,
-     0.000916298,
-     0.001374447,
-     0.001069014,
-     0.00122173,
-     0.001069014,
-     0.000763582,
-     0.00122173,
-     0.00122173,
-     0.00122173,
-     0.000916298,
-     0.000916298,
-     0.001069014,
-     0.00122173,
-     0.000916298,
-     0.001374447,
-     0.00122173,
-     0.001069014,
-     0.000916298,
-     0.00122173,
-     0.000763582,
-     0.001069014,
-     0.001069014,
-     0.00122173,
-     0.001069014,
-     0.001069014,
-     0.001069014,
-     0.00122173,
-     0.001069014,
-     0.00122173,
-     0.000916298,
-     0.00122173,
-     0.000916298,
-     0.00122173,
-     0.001069014,
-     0.00122173,
-     0.000916298,
-     0.001527163,
-     0.001069014,
-     0.001374447,
-     0.000916298,
-     0.00122173,
-     0.00122173,
-     0.001374447,
-     0.000916298,
-     0.000916298,
-     0.00122173,
-     0.001069014,
-     0.00122173,
-     0.001374447,
-     0.00122173,
-     0.00122173,
-     0.001374447,
-     0.001374447,
-     0.00122173,
-     0.000916298,
-     0.001069014,
-     0.00122173,
-     0.000763582,
-     0.001069014,
-     0.00122173,
-     0.001069014,
-     0.00122173,
-     0.001069014,
-     0.00122173,
-     0.00122173,
-     0.00122173,
-     0.00122173,
-     0.00122173,
-     0.00122173,
-     0.00122173,
-     0.001527163,
-     0.001374447,
-     0.001374447,
-     0.000916298,
-     0.000916298,
-     0.001374447,
-     0.00122173,
-     0.001527163,
-     0.001374447,
-     0.00122173,
-     0.001374447,
-     0.001374447,
-     0.001374447,
-     0.001374447,
-     0.000916298,
-     0.00122173,
-     0.000916298,
-     0.001527163,
-     0.001374447,
-     0.001527163,
-     0.001527163,
-     0.001679879,
-     0.00122173,
-     0.001374447,
-     0.001069014,
-     0.00122173,
-     0.001374447,
-     0.00122173,
-     0.00122173,
-     0.001069014,
-     0.001527163,
-     0.001527163,
-     0.001069014,
-     0.001069014,
-     0.001374447,
-     0.001069014,
-     0.001069014,
-     0.00122173,
-     0.001527163,
-     0.001069014,
-     0.001374447,
-     0.001527163,
-     0.001527163,
-     0.001069014,
-     0.001374447,
-     0.001679879,
-     0.00122173,
-     0.00122173,
-     0.001374447,
-     0.001069014,
-     0.00122173,
-     0.001527163,
-     0.001374447,
-     0.001374447,
-     0.00122173,
-     0.001527163,
-     0.001527163,
-     0.00122173,
-     0.00122173,
-     0.001527163,
-     0.001527163,
-     0.001374447,
-     0.001527163,
-     0.001374447,
-     0.001374447,
-     0.001527163,
-     0.00122173,
-     0.001527163,
-     0.00122173,
-     0.00122173,
-     0.001527163,
-     0.00122173,
-     0.000763582,
-     0.001374447,
-     0.001527163,
-     0.001679879,
-     0.00122173,
-     0.001374447,
-     0.001527163,
-     0.00122173,
-     0.001527163,
-     0.001832596,
-     0.001679879,
-     0.001832596,
-     0.001527163,
-     0.001374447,
-     0.00122173,
-     0.00122173,
-     0.001374447,
-     0.001527163,
-     0.001374447,
-     0.001069014,
-     0.001679879,
-     0.001527163,
-     0.001069014,
-     0.00122173,
-     0.001527163,
-     0.001374447,
-     0.001679879,
-     0.001679879,
-     0.001679879,
-     0.001374447,
-     0.001527163,
-     0.001679879,
-     0.00122173,
-     0.001832596,
-     0.00122173,
-     0.001374447,
-     0.001679879,
-     0.001374447,
-     0.001679879,
-     0.001527163,
-     0.001374447,
-     0.001527163,
-     0.001679879,
-     0.001527163,
-     0.001527163,
-     0.001527163,
-     0.001374447,
-     0.00122173,
-     0.001527163,
-     0.001374447,
-     0.001679879,
-     0.001679879,
-     0.001832596,
-     0.001832596,
-     0.001374447,
-     0.001832596,
-     0.001374447,
-     0.001069014,
-     0.001527163,
-     0.001679879,
-     0.001527163,
-     0.001679879,
-     0.001832596,
-     0.00122173,
-     0.001527163,
-     0.001679879,
-     0.001527163,
-     0.001527163,
-     0.001679879,
-     0.001374447,
-     0.001832596,
-     0.001374447,
-     0.001374447,
-     0.001832596,
-     0.001832596,
-     0.001374447,
-     0.001679879,
-     0.00122173,
-     0.001832596,
-     0.001527163,
-     0.001832596,
-     0.001679879,
-     0.001679879,
-     0.001985312,
-     0.001527163,
-     0.001679879,
-     0.001374447,
-     0.001985312,
-     0.001679879,
-     0.00122173,
-     0.001679879,
-     0.001679879,
-     0.001832596,
-     0.001527163,
-     0.001985312,
-     0.001679879,
-     0.001832596,
-     0.001527163,
-     0.001374447,
-     0.001679879,
-     0.001527163,
-     0.001679879,
-     0.001679879,
-     0.001679879,
-     0.001527163,
-     0.001832596,
-     0.001832596,
-     0.001374447,
-     0.001832596,
-     0.001679879,
-     0.001527163,
-     0.001679879,
-     0.001832596,
-     0.001985312,
-     0.001527163,
-     0.001679879,
-     0.001679879,
-     0.001679879,
-     0.001679879,
-     0.001832596,
-     0.001679879,
-     0.001527163,
-     0.001832596,
-     0.001985312,
-     0.001527163,
-     0.001832596,
-     0.001527163,
-     0.001985312,
-     0.001679879,
-     0.001832596,
-     0.001679879,
-     0.001832596,
-     0.001679879,
-     0.001679879,
-     0.001527163,
-     0.001832596,
-     0.001985312,
-     0.001679879,
-     0.001832596,
-     0.001527163,
-     0.001985312,
-     0.001679879,
-     0.001832596,
-     0.001527163,
-     0.001832596,
-     0.001985312,
-     0.001832596,
-     0.001679879,
-     0.001679879,
-     0.001832596,
-     0.001679879,
-     0.001832596,
-     0.001527163,
-     0.001985312,
-     0.001374447,
-     0.001832596,
-     0.001527163,
-     0.001679879,
-     0.001985312,
-     0.001985312,
-     0.001832596,
-     0.001679879,
-     0.002290745,
-     0.001832596,
-     0.001985312,
-     0.001832596,
-     0.001679879,
-     0.001832596,
-     0.001679879,
-     0.001679879,
-     0.001985312,
-     0.001832596,
-     0.002138028,
-     0.001985312,
-     0.001985312,
-     0.001985312,
-     0.002138028,
-     0.001832596,
-     0.001985312,
-     0.001985312,
-     0.001985312,
-     0.002443461,
-     0.001832596,
-     0.001985312,
-     0.001832596,
-     0.001832596,
-     0.002290745,
-     0.002290745,
-     0.002290745,
-     0.001985312,
-     0.001985312,
-     0.002138028,
-     0.002290745,
-     0.001985312,
-     0.001832596,
-     0.002443461,
-     0.001985312,
-     0.002138028,
-     0.001832596,
-     0.002443461,
-     0.002290745,
-     0.001985312,
-     0.002138028,
-     0.001985312,
-     0.002138028,
-     0.001679879,
-     0.001985312,
-     0.001832596,
-     0.001985312,
-     0.002138028,
-     0.002290745,
-     0.002138028,
-     0.001985312,
-     0.002138028,
-     0.002138028,
-     0.002138028,
-     0.002138028,
-     0.001985312,
-     0.002290745,
-     0.002290745,
-     0.002290745,
-     0.002138028,
-     0.002138028,
-     0.001985312,
-     0.002290745,
-     0.002290745,
-     0.002138028,
-     0.002290745,
-     0.002138028,
-     0.002290745,
-     0.002138028,
-     0.001985312,
-     0.002290745,
-     0.001832596,
-     0.002138028,
-     0.002290745,
-     0.002443461,
-     0.002443461,
-     0.002138028,
-     0.002596177,
-     0.002290745,
-     0.002290745,
-     0.002290745,
-     0.002290745,
-     0.002138028,
-     0.002290745,
-     0.002290745,
-     0.002290745,
-     0.002290745,
-     0.002290745,
-     0.002290745,
-     0.002138028,
-     0.002290745,
-     0.002748894,
-     0.002443461,
-     0.002138028,
-     0.002290745,
-     0.002138028,
-     0.002138028,
-     0.002138028,
-     0.002443461,
-     0.002290745,
-     0.002290745,
-     0.002596177,
-     0.002290745,
-     0.002138028,
-     0.002596177,
-     0.002596177,
-     0.002596177,
-     0.001985312,
-     0.002138028,
-     0.002138028,
-     0.002443461,
-     0.002443461,
-     0.002290745,
-     0.002443461,
-     0.002290745,
-     0.002596177,
-     0.002596177,
-     0.002138028,
-     0.002443461,
-     0.002290745,
-     0.002290745,
-     0.002290745,
-     0.002290745,
-     0.002596177,
-     0.002596177,
-     0.002290745,
-     0.002443461,
-     0.002443461,
-     0.002290745,
-     0.002443461,
-     0.002748894,
-     0.002443461,
-     0.002748894,
-     0.002138028,
-     0.002748894,
-     0.002138028,
-     0.002443461,
-     0.002596177,
-     0.002290745,
-     0.002596177,
-     0.002596177,
-     0.002290745,
-     0.002748894,
-     0.002748894,
-     0.002596177,
-     0.002443461,
-     0.002748894,
-     0.002596177,
-     0.002443461,
-     0.002290745,
-     0.002443461,
-     0.002596177,
-     0.002748894,
-     0.002748894,
-     0.002596177,
-     0.002596177,
-     0.002596177,
-     0.002596177,
-     0.002290745,
-     0.002596177,
-     0.002748894,
-     0.002596177,
-     0.002596177,
-     0.002290745,
-     0.002748894,
-     0.002596177,
-     0.00290161,
-     0.002748894,
-     0.002596177,
-     0.002748894,
-     0.002596177,
-     0.002596177,
-     0.00290161,
-     0.002748894,
-     0.002748894,
-     0.003054326,
-     0.002748894,
-     0.002443461,
-     0.002748894,
-     0.002596177,
-     0.002748894,
-     0.003054326,
-     0.003054326,
-     0.002748894,
-     0.002748894,
-     0.003054326,
-     0.002596177,
-     0.00290161,
-     0.002596177,
-     0.002596177,
-     0.00290161,
-     0.002596177,
-     0.002596177,
-     0.002748894,
-     0.003207043,
-     0.002748894,
-     0.002596177,
-     0.00290161,
-     0.00290161,
-     0.002748894,
-     0.00290161,
-     0.00290161,
-     0.002748894,
-     0.002596177,
-     0.003207043,
-     0.00290161,
-     0.002748894,
-     0.003054326,
-     0.003054326,
-     0.003054326,
-     0.002596177,
-     0.002748894,
-     0.003207043,
-     0.003054326,
-     0.00290161,
-     0.00290161,
-     0.002748894,
-     0.003054326,
-     0.003054326,
-     0.003054326,
-     0.003054326,
-     0.003054326,
-     0.00290161,
-     0.00290161,
-     0.003054326,
-     0.00290161,
-     0.002748894,
-     0.003207043,
-     0.00290161,
-     0.00290161,
-     0.003054326,
-     0.003054326,
-     0.003359759,
-     0.003512475,
-     0.003054326,
-     0.003207043,
-     0.003054326,
-     0.00290161,
-     0.003054326,
-     0.00290161,
-     0.00290161,
-     0.003054326,
-     0.003359759,
-     0.003207043,
-     0.00290161,
-     0.003207043,
-     0.003054326,
-     0.003054326,
-     0.003359759,
-     0.003512475,
-     0.00290161,
-     0.003054326,
-     0.002748894,
-     0.003359759,
-     0.003359759,
-     0.003207043,
-     0.003054326,
-     0.003054326,
-     0.003054326,
-     0.00290161,
-     0.003054326,
-     0.003207043,
-     0.00290161,
-     0.003207043,
-     0.003054326,
-     0.00290161,
-     0.003512475,
-     0.003207043,
-     0.003359759,
-     0.003359759,
-     0.00290161,
-     0.003054326,
-     0.003207043,
-     0.003054326,
-     0.003054326,
-     0.003054326,
-     0.003359759,
-     0.00290161,
-     0.003207043,
-     0.003207043,
-     0.003359759,
-     0.003207043,
-     0.003054326,
-     0.003054326,
-     0.003207043,
-     0.003054326,
-     0.003054326,
-     0.003512475,
-     0.003359759,
-     0.003359759,
-     0.003054326,
-     0.003054326,
-     0.003665191,
-     0.003207043,
-     0.003207043,
-     0.003359759,
-     0.003207043,
-     0.003054326,
-     0.003207043,
-     0.003359759,
-     0.003665191,
-     0.003512475,
-     0.003207043,
-     0.003207043,
-     0.003359759,
-     0.003207043,
-     0.003207043,
-     0.003207043,
-     0.003359759,
-     0.003359759,
-     0.003359759,
-     0.003512475,
-     0.003665191,
-     0.003665191,
-     0.003207043,
-     0.003207043,
-     0.003207043,
-     0.003512475,
-     0.003054326,
-     0.003359759,
-     0.003665191,
-     0.003359759,
-     0.003359759,
-     0.003359759,
-     0.003665191,
-     0.003359759,
-     0.003665191,
-     0.003817908,
-     0.003512475,
-     0.003512475,
-     0.003359759,
-     0.003512475,
-     0.003665191,
-     0.003970624,
-     0.003359759,
-     0.003359759,
-     0.003207043,
-     0.003512475,
-     0.003817908,
-     0.003512475,
-     0.003665191,
-     0.003207043,
-     0.003512475,
-     0.003970624,
-     0.003207043,
-     0.003512475,
-     0.003359759,
-     0.003359759,
-     0.003512475,
-     0.003817908,
-     0.003970624,
-     0.003512475,
-     0.003207043,
-     0.003970624,
-     0.003512475,
-     0.003207043,
-     0.003512475,
-     0.003817908,
-     0.003665191,
-     0.003512475,
-     0.003512475,
-     0.003970624,
-     0.003512475,
-     0.003665191,
-     0.003665191,
-     0.003665191,
-     0.003817908,
-     0.003665191,
-     0.003665191,
-     0.003665191,
-     0.003970624,
-     0.003665191,
-     0.003512475,
-     0.003665191,
-     0.003665191,
-     0.003817908,
-     0.003665191,
-     0.003665191,
-     0.003359759,
-     0.003665191,
-     0.003665191,
-     0.003817908,
-     0.003665191,
-     0.003970624,
-     0.003817908,
-     0.003970624,
-     0.003665191,
-     0.003817908,
-     0.003817908,
-     0.003665191,
-     0.003512475,
-     0.003665191,
-     0.003512475,
-     0.003665191,
-     0.003970624,
-     0.003817908,
-     0.003665191,
-     0.003970624,
-     0.003817908,
-     0.003817908,
-     0.003970624,
-     0.003817908,
-     0.003665191,
-     0.00412334,
-     0.003665191,
-     0.003817908,
-     0.003817908,
-     0.00412334,
-     0.003970624,
-     0.003665191,
-     0.003665191,
-     0.003970624,
-     0.003817908,
-     0.003512475,
-     0.003970624,
-     0.003817908,
-     0.003817908,
-     0.003970624,
-     0.003817908,
-     0.003970624,
-     0.003970624,
-     0.003970624,
-     0.003817908,
-     0.003817908,
-     0.003665191,
-     0.003970624,
-     0.003970624,
-     0.003817908,
-     0.003817908,
-     0.003817908,
-     0.003817908,
-     0.003665191,
-     0.00412334,
-     0.003665191,
-     0.003817908,
-     0.003817908,
-     0.00412334,
-     0.00412334,
-     0.003970624,
-     0.003817908,
-     0.003970624,
-     0.003970624,
-     0.004276057,
-     0.003970624,
-     0.003970624,
-     0.003665191,
-     0.003970624,
-     0.003970624,
-     0.003970624,
-     0.003970624,
-     0.003817908,
-     0.00412334,
-     0.003970624,
-     0.003817908,
-     0.003817908,
-     0.003970624,
-     0.003817908,
-     0.003665191,
-     0.003665191,
-     0.003970624,
-     0.003970624,
-     0.003817908,
-     0.00412334,
-     0.003817908,
-     0.00412334,
-     0.003970624,
-     0.00412334,
-     0.003970624,
-     0.003970624,
-     0.003970624,
-     0.003817908,
-     0.004428773,
-     0.003970624,
-     0.003970624,
-     0.00412334,
-     0.003665191,
-     0.003817908,
-     0.00412334,
-     0.004276057,
-     0.00412334,
-     0.003970624,
-     0.00412334,
-     0.003817908,
-     0.003817908,
-     0.003970624,
-     0.003817908,
-     0.003970624,
-     0.003665191,
-     0.003970624,
-     0.003817908,
-     0.003970624,
-     0.003970624,
-     0.00412334,
-     0.003665191,
-     0.003817908,
-     0.003512475,
-     0.004276057,
-     0.004276057,
-     0.003970624,
-     0.003665191,
-     0.003970624,
-     0.003970624,
-     0.003817908,
-     0.003970624,
-     0.00412334,
-     0.003665191,
-     0.003970624,
-     0.003817908,
-     0.003665191,
-     0.003665191,
-     0.003817908,
-     0.003970624,
-     0.003817908,
-     0.004276057,
-     0.004276057,
-     0.003970624,
-     0.003817908,
-     0.00412334,
-     0.00412334,
-     0.003665191,
-     0.003970624,
-     0.00412334,
-     0.004276057,
-     0.004276057,
-     0.003970624,
-     0.003970624,
-     0.004276057,
-     0.00412334,
-     0.003817908,
-     0.003817908}};
-
-const float MAGNETOMETER_DATA[MOTION_SENSOR_AXIS_NUM][IMU_DATA_SIZE] = {
-    {-32.48,  -32.306, -32.422, -32.596, -32.306, -32.712, -32.712, -32.596,
-     -32.828, -32.712, -32.596, -32.48,  -32.306, -32.828, -32.306, -32.422,
-     -32.306, -32.364, -32.248, -32.306, -32.596, -32.538, -32.828, -32.364,
-     -32.422, -32.422, -32.712, -32.828, -32.538, -32.77,  -32.48,  -32.596,
-     -32.422, -32.538, -32.538, -32.422, -32.306, -32.596, -33.002, -32.248,
-     -32.364, -32.77,  -32.48,  -32.48,  -32.132, -32.306, -32.306, -32.074,
-     -32.016, -31.842, -32.074, -31.784, -32.132, -32.074, -31.842, -31.958,
-     -31.726, -31.552, -31.494, -31.436, -31.088, -31.32,  -31.32,  -31.32,
-     -30.914, -30.856, -31.03,  -30.972, -30.74,  -30.508, -30.682, -30.218,
-     -30.16,  -30.16,  -29.696, -29.754, -29.696, -29.174, -29.464, -29.348,
-     -28.826, -28.942, -29.174, -28.942, -28.362, -28.246, -28.304, -28.014,
-     -28.246, -28.304, -27.898, -27.608, -27.434, -27.434, -26.68,  -27.144,
-     -27.144, -27.086, -27.318, -26.68,  -27.434, -26.912, -26.564, -26.912,
-     -26.216, -26.448, -26.332, -26.158, -25.984, -26.332, -25.81,  -26.216,
-     -26.1,   -26.39,  -26.158, -25.81,  -26.39,  -26.274, -26.042, -26.622,
-     -26.332, -26.506, -26.39,  -26.564, -26.39,  -26.796, -26.448, -26.796,
-     -26.854, -26.738, -27.434, -27.028, -27.086, -27.434, -28.014, -27.666,
-     -27.724, -27.898, -27.782, -27.898, -28.246, -28.42,  -27.898, -28.188,
-     -28.072, -28.594, -28.594, -28.362, -28.652, -28.362, -28.594, -28.42,
-     -28.652, -28.768, -28.652, -28.304, -28.71,  -28.768, -28.652, -28.71,
-     -28.13,  -28.826, -28.478, -28.188, -28.188, -28.478, -27.84,  -28.246,
-     -28.014, -27.898, -27.724, -27.724, -27.608, -27.434, -27.028, -26.97,
-     -26.97,  -27.028, -26.912, -26.738, -26.854, -26.912, -26.622, -27.086,
-     -26.68,  -27.202, -27.086, -26.912, -26.912, -27.202, -27.144, -26.738,
-     -26.912, -26.796, -26.738, -27.202, -27.086, -27.202, -27.318, -27.492,
-     -27.666, -27.434, -27.55,  -27.492, -27.434, -27.434, -27.608, -27.318,
-     -27.376, -27.434, -27.666, -27.84,  -28.072, -27.724, -27.724, -27.666,
-     -27.434, -27.55,  -27.608, -27.608, -27.434, -27.26,  -27.492, -27.434,
-     -27.144, -27.434, -27.376, -27.26,  -26.97,  -27.028, -27.028, -26.68,
-     -27.26,  -26.796, -27.086, -26.97,  -26.912, -26.68,  -26.854, -26.39,
-     -26.97,  -26.796, -27.028, -27.028, -27.376, -27.26,  -27.086, -27.028,
-     -27.434, -27.55,  -27.608, -27.724, -27.782, -27.086, -27.086, -27.086,
-     -27.492, -27.086, -27.202, -27.086, -27.144, -27.26,  -27.55,  -27.318,
-     -27.55,  -27.028, -27.26,  -27.318, -27.028, -27.144, -26.796, -27.028,
-     -27.028, -27.086, -26.97,  -27.318, -27.434, -26.97,  -27.028, -26.97,
-     -26.854, -26.912, -26.912, -26.912, -27.144, -26.912, -27.086, -27.492,
-     -27.086, -27.028, -27.086, -27.086, -27.318, -27.376, -26.97,  -27.202,
-     -27.318, -27.144, -27.144, -26.796, -27.376, -27.144, -27.26,  -27.028,
-     -27.434, -27.26,  -27.26,  -27.144, -26.97,  -27.144, -27.144, -26.738,
-     -26.796, -26.68,  -26.912, -27.202, -26.912, -26.97,  -26.68,  -26.854,
-     -27.55,  -27.144, -27.086, -27.202, -27.028, -27.086, -27.26,  -26.796,
-     -26.796, -27.028, -26.854, -26.912, -27.434, -27.086, -26.622, -27.318,
-     -26.912, -27.144, -26.796, -26.912, -26.796, -27.086, -26.506, -26.796,
-     -26.448, -27.028, -26.854, -26.738, -26.796, -27.028, -27.144, -26.68,
-     -26.564, -27.26,  -27.144, -27.028, -26.912, -26.912, -26.622, -27.028,
-     -26.97,  -26.39,  -27.028, -27.086, -26.854, -26.796, -26.68,  -26.506,
-     -26.68,  -26.448, -26.506, -26.506, -26.622, -26.97,  -26.854, -26.854,
-     -27.028, -26.448, -26.738, -26.738, -26.622, -26.274, -26.796, -26.854,
-     -26.912, -26.68,  -26.854, -26.506, -26.68,  -26.738, -26.854, -26.506,
-     -26.738, -26.622, -26.39,  -27.144, -26.68,  -26.506, -26.564, -26.97,
-     -26.448, -26.622, -26.332, -26.622, -26.39,  -26.564, -26.796, -26.912,
-     -26.506, -26.448, -26.622, -26.738, -26.39,  -26.332, -26.564, -26.854,
-     -26.274, -26.448, -26.68,  -26.506, -26.332, -26.506, -26.332, -26.39,
-     -26.738, -26.39,  -26.332, -26.274, -26.506, -26.216, -26.506, -26.042,
-     -26.332, -26.564, -26.216, -26.042, -26.216, -26.68,  -26.738, -26.39,
-     -26.564, -26.738, -26.39,  -26.274, -26.216, -26.448, -25.81,  -26.158,
-     -25.926, -26.274, -26.216, -26.216, -26.39,  -26.332, -26.274, -26.216,
-     -26.216, -26.1,   -26.158, -26.39,  -26.39,  -26.1,   -26.39,  -26.274,
-     -26.216, -26.158, -25.81,  -26.216, -26.158, -26.506, -26.274, -26.448,
-     -26.332, -26.274, -26.1,   -26.1,   -26.158, -26.042, -26.216, -26.216,
-     -26.042, -26.216, -26.332, -26.274, -26.042, -26.332, -26.274, -26.216,
-     -26.1,   -26.448, -25.81,  -25.984, -26.216, -26.39,  -26.158, -26.564,
-     -25.694, -25.926, -25.868, -26.158, -26.1,   -25.984, -25.984, -26.506,
-     -26.39,  -26.042, -26.042, -25.984, -25.81,  -26.216, -25.81,  -26.39,
-     -25.984, -25.984, -26.332, -25.868, -26.158, -26.1,   -26.042, -25.636,
-     -26.39,  -26.1,   -26.1,   -25.868, -26.216, -25.984, -26.332, -25.868,
-     -26.158, -26.506, -26.042, -25.694, -25.926, -26.1,   -25.752, -25.868,
-     -26.216, -25.926, -26.216, -25.984, -25.81,  -25.81,  -26.332, -25.868,
-     -25.926, -25.984, -26.1,   -25.81,  -26.39,  -25.636, -26.332, -25.984,
-     -25.926, -25.868, -25.868, -25.694, -26.042, -26.274, -25.636, -25.81,
-     -25.984, -25.984, -26.1,   -25.868, -26.1,   -26.042, -26.042, -25.636,
-     -25.81,  -26.042, -26.042, -25.52,  -26.042, -25.694, -25.694, -25.752,
-     -26.1,   -25.868, -26.1,   -25.752, -25.984, -25.52,  -25.984, -25.52,
-     -25.636, -25.81,  -25.926, -25.288, -25.462, -25.404, -25.52,  -25.926,
-     -25.752, -25.694, -25.462, -25.52,  -25.636, -25.81,  -25.752, -25.984,
-     -25.81,  -25.636, -25.694, -25.462, -25.752, -25.984, -25.868, -25.462,
-     -25.636, -25.578, -25.404, -25.346, -25.52,  -25.926, -25.694, -25.578,
-     -25.346, -25.636, -25.462, -25.404, -25.81,  -25.52,  -25.52,  -25.346,
-     -25.636, -25.636, -25.462, -25.404, -25.172, -25.868, -25.056, -25.578,
-     -25.288, -25.114, -25.462, -25.404, -25.52,  -25.404, -25.52,  -25.404,
-     -25.462, -25.288, -25.868, -25.578, -25.346, -25.636, -25.694, -25.288,
-     -25.52,  -25.346, -25.462, -25.404, -25.52,  -25.056, -25.636, -25.23,
-     -25.578, -25.462, -25.23,  -25.694, -25.462, -25.23,  -25.462, -25.23,
-     -25.056, -25.462, -25.23,  -25.114, -25.172, -25.346, -25.52,  -25.288,
-     -25.288, -25.578, -25.404, -25.636, -25.288, -25.52,  -25.288, -25.462,
-     -25.346, -25.462, -25.23,  -25.636, -25.52,  -25.23,  -25.288, -25.288,
-     -24.882, -25.346, -25.056, -25.23,  -25.346, -24.998, -25.172, -25.172,
-     -24.998, -24.708, -24.882, -24.998, -25.114, -24.998, -25.23,  -24.766,
-     -24.882, -24.94,  -24.94,  -25.056, -25.23,  -25.172, -25.404, -24.94,
-     -24.708, -24.708, -24.94,  -24.824, -24.882, -24.65,  -24.824, -24.708,
-     -24.998, -24.998, -24.824, -24.882, -25.056, -24.766, -24.998, -25.056,
-     -24.65,  -25.172, -25.288, -24.882, -25.172, -24.94,  -24.766, -24.708,
-     -25.056, -24.708, -24.708, -24.824, -25.114, -24.708, -24.65,  -24.766,
-     -24.94,  -25.172, -25.056, -24.65,  -24.882, -24.998, -25.346, -24.824,
-     -25.114, -24.824, -24.882, -25.056, -24.65,  -24.766, -24.534, -24.534,
-     -24.824, -24.882, -24.824, -25.056, -24.824, -24.766, -24.592, -24.476,
-     -24.882, -24.94,  -24.824, -24.766, -24.94,  -24.766, -24.766, -24.94,
-     -24.65,  -24.708, -24.65,  -24.766, -24.65,  -24.882, -24.592, -24.94,
-     -24.766, -24.592, -24.534, -24.824, -24.418, -25.114, -24.708, -24.65,
-     -24.882, -24.882, -24.882, -24.824, -24.94,  -24.36,  -24.882, -24.824,
-     -24.824, -24.882, -24.766, -24.418, -24.592, -24.36,  -24.418, -24.128,
-     -24.882, -24.766, -24.882, -24.534, -24.244, -24.186, -24.592, -24.65,
-     -24.766, -24.708, -24.592, -24.708, -24.766, -24.592, -24.302, -24.186,
-     -24.36,  -24.534, -24.65,  -24.592, -24.708, -24.418, -24.186, -24.418,
-     -24.418, -24.476, -24.244, -24.128, -24.766, -24.36,  -24.128, -24.534,
-     -24.418, -24.244, -24.244, -24.244, -24.36,  -24.476, -24.36,  -24.36,
-     -24.244, -24.534, -24.418, -24.244, -23.896, -24.244, -24.07,  -23.664,
-     -23.954, -24.244, -23.896, -24.36,  -24.302, -24.36,  -23.896, -24.302,
-     -24.592, -24.418, -24.012, -24.07,  -23.838, -24.36,  -24.186, -24.708,
-     -24.186, -23.838, -23.954, -24.07,  -24.244, -24.07,  -24.244, -24.186,
-     -24.186, -24.186, -24.186, -24.244, -23.722, -23.896, -23.664, -24.07,
-     -24.012, -24.012, -23.722, -24.302, -24.07,  -23.896, -23.548, -24.186,
-     -23.49,  -24.302, -23.954, -23.838, -23.954, -24.012, -23.78,  -23.954,
-     -23.896, -24.012, -23.896, -23.954, -23.78,  -23.722, -24.07,  -23.954,
-     -23.49,  -23.954, -23.838, -24.07,  -24.07,  -23.548, -23.664, -23.78,
-     -23.722, -23.954, -23.78,  -23.432, -24.128, -23.78,  -23.722, -23.432,
-     -23.896, -23.374, -23.316, -23.606, -24.012, -23.722, -23.49,  -23.78,
-     -23.49,  -23.78,  -23.432, -23.664, -23.78,  -23.664, -23.78,  -23.374,
-     -23.258, -23.722, -23.374, -23.49,  -23.432, -23.316, -23.316, -23.606,
-     -23.2,   -23.548, -23.78,  -23.664, -23.548, -23.606, -23.896, -23.432,
-     -23.258, -23.432, -23.316, -23.664, -23.432, -23.258, -23.258, -23.258,
-     -23.258, -23.316, -23.49,  -23.258, -23.664, -23.374, -23.374, -23.432,
-     -23.142, -23.2,   -23.084, -23.258, -23.142, -23.026, -22.272, -22.794,
-     -23.026, -22.91,  -23.142, -23.374, -22.91,  -22.968, -23.2,   -22.794,
-     -23.316, -22.968, -23.432, -23.2,   -22.794, -23.142, -23.026, -23.258,
-     -22.678, -22.91,  -23.316, -22.736, -23.2,   -22.62,  -23.084, -23.316,
-     -22.91,  -23.026, -22.562, -23.026, -23.084, -23.084, -23.2,   -22.794,
-     -23.142, -22.736, -23.142, -23.026, -22.678, -23.316, -23.258, -22.968,
-     -22.794, -22.91,  -22.62,  -22.736, -22.736, -23.026, -22.794, -22.91,
-     -22.736, -22.736, -22.678, -22.446, -22.678, -23.084, -23.142, -22.562,
-     -23.084, -22.794, -22.504, -23.142, -22.852, -23.026, -22.388, -22.736,
-     -22.794, -22.562, -22.446, -22.852, -22.272, -22.91,  -22.272, -22.794,
-     -22.736, -22.562, -22.678, -22.33,  -22.736, -22.388, -22.446, -22.33,
-     -22.736, -22.33,  -22.098, -22.388, -22.388, -22.156, -22.446, -22.272,
-     -22.272, -22.272, -22.214, -22.504, -22.156, -22.156, -22.62,  -22.156,
-     -22.214, -22.214, -22.446, -22.504, -22.446, -22.156, -22.562, -22.446,
-     -22.736, -22.562, -22.33,  -22.388, -22.388, -22.446, -22.388, -22.62,
-     -22.62,  -22.388, -22.446, -22.504, -22.214, -22.272, -22.388, -22.272,
-     -22.272, -21.982, -22.678, -22.04,  -22.214, -22.33,  -22.156, -22.156,
-     -22.388, -22.562, -22.214, -22.33,  -22.33,  -22.04,  -22.388, -22.33,
-     -22.33,  -22.504, -22.156, -22.214, -22.388, -22.214, -21.866, -22.098,
-     -22.04,  -21.924, -22.504, -22.678, -22.62,  -22.214, -22.156, -22.04,
-     -22.562, -22.214, -22.156, -22.156, -21.866, -22.098, -22.388, -21.692,
-     -22.388, -21.808, -21.75,  -22.04,  -22.098, -21.866, -21.576, -22.156,
-     -22.098, -22.272, -21.808, -22.04,  -22.04,  -21.518, -21.866, -21.866,
-     -21.982, -21.866, -22.272, -22.04,  -21.692, -21.808, -21.576, -22.04,
-     -21.576, -21.924, -21.692, -21.46,  -21.576, -22.098, -21.866, -21.634,
-     -21.402, -21.518, -21.576, -21.634, -21.402, -21.75,  -21.576, -21.576,
-     -21.75,  -21.576, -21.692, -21.75,  -21.634, -21.924, -21.46,  -21.866,
-     -21.866, -21.402, -21.344, -21.402, -21.518, -21.634, -21.692, -21.576,
-     -21.808, -21.402, -21.634, -21.286, -21.46,  -21.402, -21.46,  -21.344,
-     -21.344, -21.402, -21.344, -21.75,  -21.286, -21.344, -21.112, -21.402,
-     -21.402, -21.112, -21.17,  -21.286, -21.228, -21.344, -21.286, -21.576,
-     -21.344, -21.17,  -21.344, -20.938, -21.46,  -21.344, -20.764, -20.938,
-     -21.344, -20.938, -21.112, -20.996, -21.054, -21.402, -21.17,  -20.938,
-     -21.054, -21.112, -21.054, -20.996, -20.938, -21.054, -21.286, -20.822,
-     -21.344, -20.938, -20.764, -20.996, -20.996, -20.938, -21.344, -20.706,
-     -21.112, -20.764, -20.706, -20.764, -20.764, -20.706, -20.764, -20.648,
-     -20.88,  -20.822, -20.648, -20.532, -20.648, -20.996, -20.648, -20.358,
-     -20.88,  -20.822, -20.822, -20.59,  -20.88,  -20.764, -20.416, -20.706,
-     -20.764, -20.242, -20.706, -20.532, -20.706, -20.648, -20.416, -20.648,
-     -20.59,  -20.416, -20.416, -20.59,  -20.938, -20.706, -20.648, -20.474,
-     -20.3,   -20.88,  -20.416, -20.416, -20.474, -20.474, -20.532, -20.242,
-     -20.474, -20.416, -20.416, -20.532, -20.532, -20.648, -20.532, -20.706,
-     -20.184, -20.822, -20.416, -20.358, -20.648, -20.184, -20.3,   -20.126,
-     -20.474, -20.822, -20.764, -20.184, -20.3,   -20.416, -20.416, -20.358,
-     -20.3,   -20.474, -20.59,  -20.532, -20.184, -20.358, -19.836, -20.242,
-     -20.358, -20.01,  -19.894, -20.358, -20.242, -20.358, -20.3,   -20.242,
-     -20.532, -20.474, -20.01,  -20.184, -20.242, -20.3,   -20.3,   -20.358,
-     -20.01,  -20.3,   -20.3,   -19.72,  -20.126, -20.126, -20.126, -20.416,
-     -20.068, -19.778, -19.894, -20.01,  -19.662, -19.894, -19.952, -20.068,
-     -19.836, -19.546, -19.778, -19.604, -20.068, -20.01,  -19.836, -20.126,
-     -19.72,  -19.662, -19.72,  -20.242, -19.952, -19.72,  -20.184, -19.546,
-     -20.01,  -19.662, -19.082, -19.894, -19.662, -19.604, -19.778, -19.778,
-     -19.952, -19.778, -19.662, -19.488, -19.894, -19.314, -19.894, -19.43,
-     -19.256, -19.372, -19.488, -19.662, -19.488, -19.604, -18.966, -19.43,
-     -19.43,  -19.43,  -19.314, -19.836, -19.372, -19.256, -19.43,  -19.488,
-     -19.43,  -19.43,  -19.256, -19.43,  -19.604, -19.198, -18.966, -19.198,
-     -18.966, -19.372, -19.082, -19.198, -19.314, -19.314, -19.024, -19.314,
-     -19.488, -18.85,  -19.256, -19.14,  -19.662, -18.966, -18.85,  -19.082,
-     -19.14,  -19.024, -19.198, -19.198, -18.85,  -19.082, -18.85,  -18.792,
-     -19.256, -19.082, -18.966, -19.256, -18.502, -18.676, -18.212, -19.024,
-     -18.676, -18.734, -18.27,  -18.734, -18.676, -18.676, -18.966, -18.444,
-     -18.212, -18.792, -18.328, -18.618, -18.734, -18.56,  -18.502, -18.444,
-     -18.56,  -18.676, -18.27,  -18.676, -18.56,  -18.212, -18.444, -18.56,
-     -18.502, -18.27,  -18.502, -18.444, -18.386, -18.328, -18.038, -18.27,
-     -18.154, -18.212, -18.444, -18.328, -18.27,  -18.038, -18.038, -18.444,
-     -18.27,  -18.328, -18.096, -18.038, -18.27,  -17.98,  -18.444, -17.806,
-     -18.038, -18.27,  -18.038, -17.748, -18.212, -18.154, -17.806, -17.922,
-     -18.096, -17.98,  -17.864, -17.922, -18.038, -17.806, -17.458, -17.864,
-     -17.632, -17.922, -17.69,  -17.69,  -17.922, -17.574, -17.98,  -17.69,
-     -17.748, -17.748, -17.516, -17.632, -17.69,  -17.69,  -17.4,   -17.516,
-     -17.69,  -17.4,   -17.574, -17.458, -17.226, -17.806, -17.226, -17.284,
-     -16.762, -17.052, -17.11,  -17.458, -17.052, -17.226, -17.284, -17.574,
-     -17.284, -17.574, -17.226, -17.4,   -17.632, -17.226, -17.226, -17.284,
-     -17.052, -17.748, -16.704, -17.11,  -17.4,   -17.4,   -17.052, -17.168,
-     -17.284, -17.11,  -16.936, -16.704, -16.646, -17.11,  -17.284, -16.878,
-     -16.588, -16.878, -16.994, -16.878, -16.762, -16.704, -17.11,  -16.414,
-     -16.704, -17.226, -16.24,  -16.646, -16.762, -16.472, -16.414, -16.82,
-     -16.588, -16.646, -16.53,  -16.414, -16.182, -16.878, -16.356, -16.414,
-     -16.53,  -16.124, -16.182, -16.414, -16.182, -16.472, -16.182, -16.646,
-     -16.124, -16.182, -15.66,  -15.834, -16.356, -16.356, -16.298, -15.892,
-     -16.066, -16.182, -16.24,  -15.892, -15.95,  -16.008, -15.66,  -15.95,
-     -15.95,  -15.834, -15.95,  -15.718, -15.486, -16.356, -15.718, -15.834,
-     -15.834, -15.602, -15.66,  -15.95,  -16.008, -15.312, -15.718, -15.892,
-     -15.37,  -15.776, -15.544, -15.544, -15.602, -15.544, -15.428, -15.544,
-     -15.544, -15.544, -15.428, -15.022, -15.08,  -15.254, -14.906, -15.312,
-     -15.254, -15.312, -15.254, -15.08,  -15.254, -15.138, -15.37,  -15.022,
-     -15.254, -14.732, -14.964, -15.196, -15.138, -14.964, -15.196, -15.312,
-     -15.08,  -15.022, -14.79,  -14.964, -14.848, -14.906, -14.674, -14.848,
-     -14.906, -14.616, -14.732, -14.5,   -14.964, -15.08,  -14.674, -14.268,
-     -14.906, -14.21,  -14.674, -14.384, -14.558, -14.732, -14.616, -14.5,
-     -14.268, -14.326, -14.152, -14.21,  -14.616, -14.616, -14.384, -13.862,
-     -14.442, -14.094, -14.094, -14.094, -13.862, -13.862, -14.036, -13.978,
-     -13.688, -13.746, -13.862, -13.978, -13.862, -14.036, -13.746, -13.978,
-     -13.688, -13.688, -13.63,  -13.92,  -14.094, -13.804, -13.63,  -14.094,
-     -13.804, -13.34,  -13.34,  -13.862, -13.398, -13.398, -13.804, -13.398,
-     -13.804, -13.804, -13.34,  -13.572, -13.166, -13.572, -13.108, -13.572,
-     -13.398, -13.224, -13.398, -13.282, -13.514, -13.05,  -12.876, -13.34,
-     -13.166, -13.688, -13.34,  -13.108, -12.992, -12.818, -13.05,  -12.644,
-     -12.992, -13.282, -12.818, -12.528, -12.47,  -12.702, -12.238, -12.76,
-     -12.47,  -12.354, -12.934, -12.702, -12.412, -12.702, -12.528, -12.644,
-     -12.702, -12.76,  -12.47,  -13.05,  -12.47,  -12.238, -12.238, -12.818,
-     -12.354, -12.238, -12.18,  -12.238, -12.76,  -12.18,  -12.064, -12.296,
-     -12.006, -12.238, -12.064, -12.006, -12.122, -11.89,  -12.064, -12.122,
-     -11.89,  -11.774, -12.006, -12.006, -11.542, -11.89,  -12.064, -11.774,
-     -11.948, -11.716, -11.658, -11.6,   -11.716, -11.484, -11.89,  -11.6,
-     -11.774, -11.368, -11.426, -11.6,   -11.6,   -11.774, -11.368, -11.832,
-     -11.368, -11.31,  -11.542, -11.542, -11.31,  -11.252, -11.136, -11.6,
-     -11.194, -11.252, -11.078, -11.426, -11.078, -11.194, -11.02,  -10.73,
-     -11.31,  -10.846, -11.02,  -10.672, -10.962, -11.02,  -10.846, -11.136,
-     -11.194, -10.788, -10.904, -10.208, -10.44,  -10.672, -10.962, -10.788,
-     -10.208, -10.672, -11.078, -10.962, -10.382, -10.672, -10.498, -10.44,
-     -11.02,  -10.092, -10.44,  -10.672, -10.15,  -10.324, -10.266, -10.324,
-     -10.266, -10.614, -10.382, -10.556, -9.976,  -10.034, -9.802,  -10.15,
-     -9.802,  -9.918,  -9.976,  -9.744,  -9.976,  -9.976,  -10.15,  -10.15,
-     -9.918,  -9.86,   -9.454,  -9.86,   -9.628,  -9.86,   -9.744,  -9.512,
-     -9.628,  -9.512,  -9.454,  -9.686,  -9.57,   -9.512,  -9.57,   -9.106,
-     -8.99,   -9.106,  -9.28,   -8.932,  -8.7,    -8.7,    -9.048,  -8.932,
-     -8.584,  -9.048,  -8.99,   -9.222,  -9.106,  -8.816,  -8.874,  -8.99,
-     -8.874,  -8.99,   -8.874,  -8.874,  -8.816,  -8.41,   -8.642,  -8.352,
-     -8.178,  -8.468,  -8.236,  -8.004,  -8.642,  -8.294,  -8.236,  -8.41,
-     -8.294,  -8.41,   -8.468,  -7.888,  -8.352,  -7.772,  -7.656,  -7.888,
-     -7.714,  -7.83,   -7.772,  -8.178,  -8.178,  -7.888,  -7.656,  -7.366,
-     -7.946,  -7.714,  -7.54,   -7.83,   -7.656,  -7.482,  -7.482,  -7.598,
-     -7.076,  -7.192,  -7.424,  -7.308,  -7.25,   -7.018,  -7.192,  -6.844,
-     -6.902,  -7.076,  -6.844,  -6.96,   -6.554,  -6.612,  -6.844,  -6.844,
-     -6.438,  -6.612,  -6.67,   -7.134,  -6.612,  -6.496,  -6.612,  -6.496,
-     -6.38,   -6.612,  -5.974,  -6.496,  -6.322,  -6.148,  -6.264,  -5.916,
-     -6.032,  -5.8,    -6.38,   -6.148,  -6.09,   -6.206,  -5.858,  -5.568,
-     -5.974,  -5.858,  -5.974,  -5.916,  -5.916,  -5.626,  -5.858,  -5.51,
-     -5.974,  -5.568,  -5.22,   -5.452,  -5.22,   -5.51,   -5.278,  -5.278,
-     -5.336,  -5.22,   -5.278,  -5.336,  -5.046,  -5.22,   -4.814,  -5.104,
-     -4.988,  -4.872,  -5.104,  -4.756,  -4.814,  -4.64,   -4.756,  -4.756,
-     -4.524,  -4.466,  -4.756,  -4.408,  -4.176,  -4.118,  -4.234,  -4.176,
-     -4.35,   -4.35,   -4.118,  -4.118,  -4.234,  -4.524,  -4.292,  -4.118,
-     -4.06,   -4.118,  -3.944,  -4.234,  -3.596,  -3.712,  -3.828,  -3.596,
-     -3.654,  -3.886,  -3.654,  -3.538,  -3.364,  -3.48,   -3.886,  -3.248,
-     -3.422,  -3.074,  -3.19,   -2.9,    -3.248,  -2.958,  -3.364,  -2.958,
-     -3.132,  -2.784,  -2.9,    -2.494,  -2.9,    -2.9,    -2.9,    -2.494,
-     -2.668,  -2.436,  -2.436,  -2.61,   -2.204,  -2.494,  -2.32,   -2.262,
-     -2.668,  -1.798,  -2.204,  -2.262,  -1.682,  -1.624,  -1.856,  -1.624,
-     -1.45,   -1.508,  -1.392,  -1.334,  -1.392,  -1.218,  -1.218,  -1.508,
-     -1.102,  -1.566,  -1.392,  -1.334,  -1.45,   -0.986,  -1.218,  -0.986,
-     -1.45,   -1.334,  -0.986,  -0.464,  -0.638,  -0.812,  -0.638,  -0.406,
-     -0.87,   -0.58,   -0.58,   -0.638,  -0.58,   -0.174,  -0.406,  0.058,
-     -0.406,  -0.116,  -0.174,  -0.116,  -0.174,  -0.232,  0,       0.174,
-     -0.058,  -0.058,  -0.058,  0.29,    0.406,   0.29,    0.812,   0.696,
-     0.348,   0.522,   0.638,   0.87,    0.696,   0.754,   0.696,   0.812,
-     0.522,   0.986,   0.986,   0.812,   0.87,    1.044,   1.276,   1.334,
-     1.276,   1.566,   1.392,   1.45,    1.566,   1.45,    1.392,   1.45,
-     1.856,   1.74,    1.682,   1.566,   1.566,   2.03,    2.146,   1.914,
-     2.03,    2.204,   2.494,   2.436,   2.03,    2.436,   2.842,   2.436,
-     2.32,    2.204,   2.552,   2.9,     2.668,   2.958,   2.842,   2.726,
-     2.842,   3.074,   2.9,     3.19,    3.074,   2.61,    3.19,    3.596,
-     3.422,   3.48,    3.422,   3.48,    3.48,    3.364,   3.886,   4.002,
-     3.828,   3.944,   4.002,   4.176,   4.118,   4.002,   4.35,    4.118,
-     4.176,   4.756,   4.176,   4.466,   4.698,   4.814,   4.988,   4.988,
-     4.698,   4.872,   4.93,    4.872,   5.162,   4.756,   4.988,   4.93,
-     5.104,   5.278,   5.22,    5.22,    5.452,   5.51,    5.278,   5.684,
-     5.974,   5.626,   5.742,   5.626,   5.8,     5.8,     5.858,   5.858,
-     6.09,    6.148,   5.858,   6.206,   6.786,   6.554,   6.496,   6.438,
-     6.67,    6.902,   6.96,    6.496,   6.786,   6.96,    7.076,   7.192,
-     6.96,    7.134,   6.612,   7.25,    7.192,   7.54,    7.772,   7.25,
-     7.598,   7.772,   7.946,   7.54,    8.236,   7.888,   7.772,   8.004,
-     8.004,   8.004,   8.062,   8.294,   8.642,   8.41,    8.468,   8.526,
-     8.178,   8.352,   8.932,   8.7,     8.7,     8.7,     9.106,   9.106,
-     9.106,   9.222,   9.164,   9.396,   9.512,   9.222,   9.454,   9.338,
-     9.628,   9.686,   9.628,   9.686,   9.628,   9.57,    10.034,  10.034,
-     9.686,   10.034,  9.976,   10.092,  10.324,  10.034,  10.556,  10.556,
-     10.672,  10.382,  10.788,  10.962,  10.672,  10.846,  10.904,  10.904,
-     11.078,  10.788,  11.31,   11.658,  11.252,  11.426,  11.252,  11.252,
-     11.542,  11.368,  11.716,  11.948,  12.006,  11.658,  11.542,  12.064,
-     12.238,  11.774,  12.47,   12.122,  12.122,  12.528,  12.122,  12.354,
-     12.644,  12.47,   12.818,  12.818,  12.702,  12.934,  12.818,  12.47,
-     13.166,  12.876,  13.224,  13.398,  13.34,   13.514,  12.818,  13.224,
-     13.92,   13.456,  13.688,  13.862,  13.92,   13.804,  14.152,  14.152,
-     14.036,  14.268,  14.268,  14.152,  14.21,   14.442,  14.5,    14.558,
-     14.326,  14.558,  14.616,  14.848,  14.616,  14.674,  14.848,  15.08,
-     14.79,   15.254,  15.196,  15.312,  15.254,  15.428,  15.602,  15.718,
-     15.486,  15.776,  15.776,  15.892,  15.602,  15.66,   16.066,  15.834,
-     16.124,  16.298,  16.298,  16.24,   16.82,   16.704,  16.646,  16.356,
-     16.588,  16.356,  16.82,   17.11,   16.936,  16.878,  17.4,    17.458,
-     17.168,  17.284,  17.458,  17.342,  17.574,  17.516,  17.516,  17.574,
-     17.806,  18.386,  18.038,  17.516,  17.922,  18.154,  18.154,  18.328,
-     18.444,  18.212,  18.676,  18.56,   18.502,  18.502,  18.85,   18.676,
-     18.676,  18.85,   19.198,  19.198,  19.314,  19.024,  19.256,  19.314,
-     19.256,  19.256,  19.72,   19.43,   20.126,  20.3,    19.72,   19.488,
-     19.836,  20.242,  19.952,  20.126,  20.068,  20.706,  20.358,  20.532,
-     20.532,  20.242,  20.59,   20.474,  20.706,  20.764,  21.112,  21.054,
-     21.286,  21.402,  21.286,  21.344,  21.17,   21.228,  21.46,   21.402,
-     21.518,  21.402,  21.402,  21.402,  22.214,  22.098,  22.156,  22.214,
-     22.098,  21.808,  22.156,  22.272,  22.388,  22.214,  22.678,  22.33,
-     22.562,  22.736,  22.736,  22.794,  22.736,  22.968,  22.852,  23.084,
-     23.084,  23.026,  23.084,  23.49,   23.432,  23.49,   23.722,  23.374,
-     23.896,  23.49,   23.432,  23.722,  23.78,   23.838,  23.954,  24.186,
-     24.128,  24.476,  24.186,  24.534,  24.186,  24.418,  24.65,   24.418,
-     24.824,  24.824,  24.882,  24.94,   24.824,  25.404,  24.708,  25.056,
-     25.346,  25.23,   24.882,  25.288,  25.694,  25.23,   25.578,  25.636,
-     25.694,  25.462,  25.984,  26.042,  26.216,  26.1,    26.042,  26.274,
-     26.1,    26.274,  26.332,  26.39,   26.796,  26.506,  26.68,   26.448,
-     26.564,  26.796},
-    {-0.406, -0.406, -0.87,  -1.044, -0.464, -0.58,  -0.348, -0.58,  -0.58,
-     0.116,  -0.986, -0.406, -0.638, -0.754, -0.696, -0.696, -0.464, -0.406,
-     -0.696, -0.986, -0.638, -0.754, -0.522, -0.696, -0.58,  -0.406, -0.812,
-     -0.87,  -0.522, -0.812, -0.232, -0.696, -0.348, -0.812, -0.638, -0.812,
-     -0.522, -0.754, -0.754, -0.696, -0.464, -0.29,  -0.348, -0.58,  -0.522,
-     -0.58,  -0.348, -0.174, -0.696, -0.638, -0.464, -0.928, -0.406, -0.58,
-     -0.348, -0.29,  -0.348, -0.522, 0,      -0.464, -0.232, -0.232, -0.29,
-     -0.174, 0,      -0.58,  -0.058, -0.348, -0.638, -0.116, 0,      -0.29,
-     -0.058, -0.406, 0.058,  -0.232, 0,      -0.29,  -0.232, -0.232, -0.116,
-     -0.116, -0.29,  -0.232, 0.174,  0.174,  -0.058, -0.116, 0.522,  -0.174,
-     0.232,  -0.232, -0.058, 0.116,  0.116,  0.174,  0.638,  0.58,   0.464,
-     0.522,  0.348,  0.058,  0.058,  0.406,  0,      0.29,   0.116,  0.232,
-     0.696,  0,      0.638,  0.348,  0.29,   0.29,   0.406,  0.696,  0.464,
-     0.29,   0.29,   0.406,  0.174,  0.406,  0.116,  0.348,  0.58,   0.464,
-     0.058,  0.406,  0.174,  0.638,  -0.058, 0.522,  0.464,  0.464,  0.29,
-     0.348,  -0.174, 0.174,  0.29,   0.29,   0.348,  0.058,  0.058,  -0.116,
-     -0.058, 0.29,   0,      0.116,  0.232,  0.116,  -0.29,  0.058,  0.116,
-     0.406,  0.174,  0.174,  -0.116, 0,      0,      -0.058, -0.116, 0.058,
-     0.174,  0.116,  0.348,  0.232,  -0.058, 0.116,  0.174,  0.464,  0.116,
-     -0.174, -0.232, 0.116,  -0.174, 0.116,  0.348,  -0.116, -0.116, 0.29,
-     -0.116, -0.058, 0.232,  -0.116, 0.174,  0,      0.406,  0.29,   0.232,
-     -0.174, -0.29,  0.232,  -0.116, -0.116, 0.29,   0.174,  0.116,  0.29,
-     0.116,  0,      0.058,  0.058,  -0.174, 0.058,  0.29,   -0.116, 0.116,
-     0.058,  -0.058, 0.348,  0.29,   0,      0.058,  -0.232, -0.058, -0.232,
-     -0.174, 0.116,  -0.116, -0.174, -0.174, 0.116,  -0.058, -0.29,  -0.348,
-     0.116,  0.116,  0.116,  0.116,  0.116,  -0.058, 0.116,  -0.058, 0,
-     -0.174, 0.058,  -0.522, -0.638, -0.058, -0.058, -0.174, 0.116,  0,
-     0.348,  -0.29,  -0.406, -0.29,  -0.29,  -0.058, -0.058, -0.058, -0.29,
-     -0.232, -0.232, -0.232, 0,      -0.406, 0.116,  0.29,   0.058,  0.174,
-     -0.232, 0,      0.232,  -0.232, -0.174, 0.232,  0.174,  0.116,  0.174,
-     -0.116, 0,      -0.058, -0.464, -0.058, 0.232,  0,      -0.232, 0,
-     -0.174, -0.058, 0.058,  -0.116, -0.116, -0.232, 0.116,  -0.348, 0.464,
-     0.058,  -0.116, -0.232, -0.058, 0.058,  0.174,  0.174,  0.232,  0.058,
-     0.232,  -0.116, 0,      -0.406, 0,      0.058,  -0.116, 0.232,  -0.058,
-     0.116,  -0.058, -0.174, -0.058, -0.232, -0.464, 0.058,  -0.232, -0.116,
-     -0.174, 0.116,  -0.232, -0.29,  -0.116, -0.058, -0.406, -0.174, 0.058,
-     -0.058, 0.116,  0.174,  0.174,  -0.058, -0.29,  -0.29,  -0.058, -0.406,
-     -0.058, -0.116, -0.058, -0.348, 0.232,  0.406,  -0.058, 0.058,  -0.174,
-     -0.058, -0.29,  -0.116, -0.116, 0.174,  0.116,  -0.348, -0.348, -0.058,
-     -0.58,  -0.232, -0.116, 0,      0.058,  -0.058, 0,      0.29,   -0.232,
-     -0.174, -0.464, -0.232, -0.232, -0.174, -0.232, -0.754, -0.464, -0.29,
-     -0.174, -0.29,  -0.232, -0.058, -0.232, -0.58,  -0.116, -0.174, -0.348,
-     -0.348, 0,      -0.348, -0.29,  -0.174, -0.348, -0.116, -0.406, -0.638,
-     -0.232, -0.174, -0.29,  -0.116, -0.29,  0,      -0.406, -0.522, -0.116,
-     -0.406, -0.348, -0.348, -0.464, -0.348, -0.464, -0.638, -0.522, -0.522,
-     0.058,  -0.174, -0.116, -0.232, -0.464, -0.464, -0.696, -0.348, -0.232,
-     -0.464, -0.058, -0.29,  -0.348, 0,      -0.348, -0.116, -0.638, -0.232,
-     -0.29,  -0.29,  -0.58,  -0.232, -0.696, -0.754, -0.232, -0.406, -0.754,
-     -0.58,  -0.116, -0.464, 0.232,  -0.638, -0.522, -0.464, -0.174, -0.522,
-     -0.116, -0.174, 0.058,  -0.464, -0.232, -0.232, -0.406, -0.464, 0.174,
-     -0.29,  -0.406, 0.174,  -0.174, -0.29,  -0.116, -0.348, -0.348, -0.406,
-     -0.406, -0.174, 0.116,  -0.174, -0.348, -0.522, 0.058,  -0.058, -0.58,
-     -0.348, 0.348,  -0.232, -0.29,  -0.406, -0.348, -0.116, 0.174,  0.058,
-     0,      -0.174, -0.058, 0,      -0.174, 0.116,  0.406,  -0.348, -0.348,
-     0.058,  0,      0.116,  -0.348, 0.058,  -0.174, -0.174, 0.406,  0.174,
-     0,      0.116,  0.058,  -0.116, -0.116, 0,      -0.29,  -0.116, 0.058,
-     0.058,  0.29,   0.638,  0,      -0.232, 0.058,  -0.174, -0.232, 0,
-     -0.116, 0.174,  -0.464, -0.522, -0.058, -0.174, 0,      0.29,   -0.174,
-     -0.464, -0.464, -0.348, -0.116, -0.58,  -0.116, 0,      -0.058, -0.058,
-     0,      0.232,  -0.406, -0.348, -0.174, 0.174,  -0.29,  0.174,  0,
-     0,      0.232,  -0.058, 0.116,  0.058,  -0.058, -0.058, 0.29,   0.29,
-     0.116,  0,      0,      -0.058, 0.058,  0.116,  -0.116, 0.116,  0.232,
-     0.29,   0.406,  0.406,  0.348,  0.116,  0.116,  -0.058, 0.174,  0.29,
-     0,      0.232,  0,      0.174,  -0.174, 0.232,  -0.058, 0.116,  0.116,
-     0.522,  0.174,  0.348,  0.232,  0.348,  0.116,  0.174,  -0.058, 0.232,
-     -0.174, -0.116, 0.058,  0.522,  -0.232, 0.232,  0.174,  0.058,  -0.058,
-     0.116,  0.058,  0.174,  -0.058, -0.058, -0.174, 0.116,  -0.058, -0.116,
-     0.29,   0.174,  0.174,  0,      0.058,  0.058,  0.058,  0.232,  0.29,
-     -0.116, -0.116, -0.29,  0.116,  -0.232, -0.058, -0.29,  0.348,  0.058,
-     0.116,  0.29,   0.058,  -0.116, 0.29,   0.406,  0.058,  0.348,  0.058,
-     0.174,  0.116,  -0.174, 0.116,  -0.058, -0.29,  -0.29,  -0.058, 0.406,
-     -0.29,  -0.058, -0.058, 0.29,   -0.174, 0.29,   0,      0.58,   -0.058,
-     -0.174, -0.29,  0.29,   0.232,  0.348,  0.058,  0.116,  0.29,   0.348,
-     -0.29,  -0.116, 0.406,  0.522,  0.174,  0,      -0.058, -0.116, 0.464,
-     -0.058, 0.058,  0.464,  0.058,  0.174,  0.29,   0.406,  0,      0.29,
-     0.116,  0.232,  0.348,  0.406,  0.464,  0.174,  0.174,  0.232,  0.058,
-     0.29,   -0.058, 0.406,  -0.116, 0.174,  0,      0.058,  0.406,  0.174,
-     0.058,  0.522,  0.116,  0.058,  0.29,   -0.116, 0.116,  0.116,  0.406,
-     -0.058, 0.464,  -0.058, 0.116,  0,      0.232,  -0.058, 0.174,  0.116,
-     -0.232, 0.058,  -0.174, 0.116,  -0.058, -0.116, 0.058,  -0.29,  -0.116,
-     -0.116, 0.116,  0.116,  -0.174, 0.29,   0.116,  0.348,  0.232,  -0.174,
-     0,      0.058,  0.29,   0.464,  0.174,  -0.174, 0,      0.058,  0.058,
-     -0.232, 0.174,  -0.058, 0.116,  -0.232, 0.29,   0.29,   -0.174, 0.174,
-     0.29,   0.174,  0.116,  0,      0.29,   0.232,  0.232,  0.174,  0.116,
-     0.58,   0.406,  0.406,  -0.116, 0.232,  0.058,  -0.174, -0.348, 0.29,
-     -0.058, -0.116, 0,      0.116,  0.232,  0.116,  -0.406, -0.116, -0.29,
-     -0.29,  0,      -0.116, 0.116,  -0.174, -0.058, 0.116,  -0.464, -0.174,
-     0,      -0.058, -0.058, 0,      0.058,  0.174,  -0.058, 0.116,  0,
-     0.232,  0.406,  -0.058, -0.29,  -0.29,  -0.174, -0.232, 0.058,  -0.058,
-     -0.116, -0.58,  -0.29,  -0.29,  -0.174, 0.058,  0.058,  0,      -0.348,
-     0,      -0.406, -0.522, 0,      0,      0,      0.232,  0.058,  -0.232,
-     -0.696, -0.232, -0.232, -0.29,  -0.058, -0.174, 0.058,  -0.522, -0.116,
-     -0.464, -0.232, 0,      -0.232, -0.348, -0.406, -0.406, -0.174, -0.058,
-     -0.116, -0.174, -0.116, 0.058,  -0.29,  -0.174, -0.116, -0.522, -0.174,
-     -0.232, -0.522, 0.058,  -0.232, 0.116,  -0.754, -0.116, -0.348, 0.29,
-     -0.464, -0.116, -0.812, -0.174, 0,      -0.406, 0.058,  -0.29,  -0.348,
-     -0.29,  -0.522, -0.116, -0.464, -0.406, -0.232, -0.58,  -0.058, 0.116,
-     -0.464, 0,      -0.29,  -0.116, 0.058,  -0.406, -0.058, -0.058, -0.696,
-     -0.522, -0.232, -0.406, -0.232, -0.174, -0.116, 0.116,  -0.058, -0.406,
-     0.058,  -0.174, -0.174, -0.406, -0.116, -0.29,  -0.116, -0.116, -0.174,
-     0.116,  -0.406, -0.116, -0.406, -0.174, -0.464, 0.058,  -0.348, 0,
-     -0.232, -0.174, -0.058, -0.232, -0.348, 0.116,  -0.058, 0,      0.058,
-     -0.116, -0.174, -0.174, -0.116, -0.116, -0.232, -0.058, -0.522, -0.29,
-     0.174,  -0.29,  -0.348, -0.406, -0.348, -0.232, -0.174, -0.058, -0.116,
-     -0.174, -0.174, 0.058,  0.174,  -0.174, -0.058, 0,      0.406,  -0.058,
-     -0.522, -0.58,  0,      -0.174, 0.058,  0.116,  -0.29,  0.058,  0.116,
-     0.232,  -0.058, 0.058,  0,      0,      -0.116, -0.058, 0.174,  0.116,
-     0.058,  0.174,  0.058,  0.406,  -0.058, -0.406, 0.116,  0.058,  0.116,
-     0.29,   -0.29,  -0.058, -0.116, -0.116, -0.29,  0,      -0.058, -0.406,
-     -0.232, -0.116, 0.232,  -0.232, 0,      0,      -0.29,  -0.058, -0.058,
-     0.522,  -0.174, 0.174,  0.058,  -0.232, -0.116, 0.29,   0,      0.116,
-     0.174,  0.348,  0.116,  -0.058, -0.116, 0.116,  0.174,  0.116,  0.232,
-     -0.29,  0.29,   0.174,  0.174,  0,      0.174,  0.116,  0.174,  -0.058,
-     -0.058, 0.116,  0.174,  0.174,  -0.058, -0.058, 0.406,  -0.058, -0.29,
-     -0.348, -0.174, -0.29,  -0.29,  0.348,  -0.058, -0.348, -0.232, -0.174,
-     -0.058, -0.522, -0.058, 0.058,  0.116,  -0.232, 0.58,   -0.29,  0,
-     0.058,  0,      0.058,  0.174,  0.174,  0.464,  0,      -0.116, -0.058,
-     -0.058, -0.116, -0.116, -0.058, -0.058, 0.058,  -0.058, 0,      0.116,
-     -0.232, 0.058,  -0.232, 0,      0.058,  0.406,  0.116,  0.174,  -0.116,
-     0.232,  0,      -0.116, -0.29,  -0.116, 0.232,  -0.058, 0.174,  0.174,
-     -0.058, -0.232, -0.116, 0.116,  0.232,  0.058,  0.174,  0.348,  0.29,
-     -0.174, 0.058,  0.58,   0.058,  0.464,  0.232,  0,      -0.116, 0.29,
-     0.116,  0.058,  0.348,  0.29,   0.29,   0,      0.29,   0.348,  0.116,
-     -0.058, 0.406,  -0.174, -0.174, -0.058, 0.058,  0.522,  0.116,  0.232,
-     0,      0.058,  0.116,  -0.29,  0,      -0.174, 0.348,  0.116,  0,
-     0,      0.348,  0.406,  0.406,  0.174,  0.232,  -0.29,  0.058,  0.464,
-     0.058,  0.29,   -0.406, 0.29,   -0.232, -0.232, 0.058,  -0.232, 0.406,
-     0.174,  0.058,  0,      0.174,  0.174,  0.29,   -0.232, 0.174,  0.174,
-     0.058,  0.348,  0.116,  0.29,   0.058,  0,      0.348,  -0.058, 0.058,
-     0.406,  0.232,  0.058,  0.116,  0.174,  0.174,  -0.174, 0.058,  -0.232,
-     0.29,   0.058,  0.232,  0,      -0.348, 0.174,  0.232,  0.174,  0.232,
-     0.406,  0.174,  -0.174, -0.116, 0.058,  0.058,  0.058,  0.232,  -0.116,
-     0.464,  0,      0.29,   0,      -0.116, -0.058, -0.29,  0.232,  0.174,
-     0.058,  0.232,  -0.116, -0.058, 0.116,  -0.232, -0.174, 0.116,  0.348,
-     0.116,  0.116,  0.232,  -0.174, 0.116,  0.232,  0,      -0.058, -0.232,
-     0.232,  0.116,  -0.058, 0.174,  0.29,   0.232,  0.058,  0.174,  -0.058,
-     0.174,  0.174,  -0.116, 0.116,  -0.174, 0.058,  -0.058, 0,      0.464,
-     -0.29,  0.174,  0,      0.464,  -0.058, 0.058,  0.058,  -0.116, 0.058,
-     0.058,  -0.174, -0.174, 0,      -0.29,  0.174,  0.348,  0.174,  0,
-     -0.464, 0.058,  0.348,  -0.58,  -0.232, -0.174, 0,      -0.116, 0.116,
-     0.174,  -0.29,  -0.232, -0.058, 0.058,  -0.232, 0.058,  0.058,  0.058,
-     -0.116, -0.696, -0.348, 0.174,  0.174,  0.116,  -0.116, 0.232,  -0.464,
-     -0.29,  0.174,  -0.058, -0.116, -0.116, -0.058, -0.058, 0,      0.174,
-     -0.29,  0.29,   -0.174, 0.174,  -0.116, 0.174,  -0.116, 0.116,  -0.058,
-     0.348,  -0.174, -0.058, -0.174, -0.348, -0.348, 0.116,  0.174,  0.116,
-     -0.058, 0.116,  0.232,  0.174,  -0.464, -0.232, -0.058, 0.174,  -0.058,
-     0,      0.058,  -0.174, -0.116, 0.058,  0,      -0.232, -0.058, -0.348,
-     0.058,  -0.058, -0.174, -0.058, -0.116, 0.116,  -0.464, -0.174, -0.232,
-     -0.058, -0.058, -0.058, -0.116, 0.116,  -0.348, -0.58,  -0.232, 0.29,
-     -0.464, 0.058,  0.174,  -0.464, -0.406, -0.232, -0.29,  -0.058, 0.232,
-     -0.464, -0.174, -0.058, -0.116, -0.29,  0.348,  -0.638, -0.058, -0.29,
-     -0.058, 0,      0.232,  0.058,  0,      0,      -0.29,  -0.174, -0.174,
-     -0.116, -0.116, 0.174,  0.232,  -0.116, -0.29,  -0.174, -0.116, 0,
-     0.348,  -0.174, 0,      0.116,  -0.29,  -0.174, 0.232,  0,      0,
-     -0.116, -0.116, 0.058,  0.58,   0.348,  -0.174, -0.116, -0.116, -0.464,
-     -0.406, -0.232, -0.174, 0.058,  -0.29,  -0.174, -0.058, -0.174, -0.174,
-     0.174,  -0.058, -0.348, 0.116,  -0.406, -0.058, -0.116, -0.29,  0.116,
-     0.058,  -0.058, -0.232, 0.116,  -0.58,  -0.116, 0.058,  -0.116, -0.638,
-     -0.232, 0.058,  0,      -0.232, -0.058, 0.232,  0.058,  0.116,  -0.058,
-     -0.232, -0.116, -0.29,  -0.058, 0.058,  0.116,  0.058,  -0.29,  0,
-     0.058,  -0.29,  -0.058, 0.058,  0,      0.29,   0,      -0.348, -0.058,
-     0.348,  -0.232, 0.058,  0.116,  -0.29,  0,      -0.232, -0.058, 0.174,
-     -0.058, 0.058,  -0.348, 0,      -0.058, -0.058, 0.116,  0.174,  0.058,
-     -0.174, -0.116, -0.232, 0,      -0.29,  -0.174, -0.116, 0,      -0.174,
-     -0.232, 0.058,  0.174,  0.29,   0.232,  -0.058, -0.174, 0.116,  -0.058,
-     0.348,  -0.348, -0.116, 0.058,  -0.522, 0,      -0.116, 0.116,  -0.464,
-     -0.058, 0.058,  -0.29,  -0.116, 0,      -0.058, 0.174,  -0.174, -0.174,
-     -0.174, -0.29,  0.058,  -0.174, -0.406, -0.406, 0,      -0.29,  -0.232,
-     0.174,  0,      -0.29,  -0.232, -0.116, -0.116, -0.29,  -0.116, -0.522,
-     -0.232, -0.29,  -0.29,  -0.464, -0.174, 0,      -0.638, -0.058, 0.058,
-     0.174,  -0.29,  0.116,  -0.174, -0.116, -0.29,  -0.116, -0.116, -0.464,
-     -0.348, -0.29,  -0.406, 0.29,   0.232,  0.058,  0,      -0.232, -0.406,
-     -0.116, 0.058,  0.29,   0,      -0.058, -0.116, 0.406,  0.058,  0.232,
-     0.522,  0.174,  -0.174, 0,      -0.232, -0.174, 0.116,  0.406,  -0.116,
-     0.174,  0,      0.116,  0.29,   0.232,  -0.116, -0.174, 0,      0.29,
-     -0.174, 0.174,  0.058,  0,      0,      -0.116, -0.348, 0.116,  -0.058,
-     -0.058, 0.232,  0.29,   0.348,  0.348,  0.058,  0.232,  -0.058, -0.058,
-     -0.116, -0.406, 0.29,   0.174,  0.058,  0,      -0.116, 0.406,  -0.29,
-     0.58,   -0.058, -0.116, 0.29,   0.116,  0.348,  0,      -0.058, -0.232,
-     0.116,  0,      -0.058, -0.058, 0.174,  0.174,  0.058,  0,      -0.232,
-     0.058,  0.058,  0.058,  -0.058, 0.058,  0,      0.058,  -0.058, 0,
-     0.058,  0.116,  0,      0.116,  -0.058, 0.232,  0,      -0.174, 0.406,
-     -0.29,  -0.116, 0.058,  -0.058, 0.058,  0.174,  0.116,  0.058,  -0.058,
-     0.174,  0,      0.116,  0.464,  0.174,  0.174,  0.29,   0.348,  0.29,
-     0.232,  0.174,  0.232,  0.232,  0.116,  0.232,  0.348,  0,      0.522,
-     0.174,  0.29,   0.29,   0.348,  0.58,   0.464,  0,      0.522,  0.29,
-     0.116,  0.406,  0.232,  0.348,  0.29,   0.174,  0.754,  0.232,  0.464,
-     0.406,  0.232,  0.29,   0.232,  0.464,  0.696,  0.522,  0.29,   0.638,
-     0.232,  0.522,  0.754,  0.406,  0.464,  0.29,   0.29,   0.406,  0.232,
-     0.638,  0.58,   0.29,   0.232,  0.232,  0.058,  0.232,  0.058,  0.406,
-     0.522,  0.174,  0.058,  0.232,  0.522,  0.174,  0.29,   0.116,  0.348,
-     0.696,  0.464,  0.29,   0.29,   0.232,  0.464,  0.29,   0.348,  0.406,
-     0.348,  0.058,  0.522,  0.638,  0.464,  0.29,   0.232,  0,      -0.058,
-     0,      0,      -0.232, 0,      0.116,  0.348,  0.116,  0.116,  0.116,
-     -0.058, -0.116, 0.58,   0.116,  0.232,  0.058,  0.29,   0.232,  0.522,
-     0.174,  -0.116, 0.058,  0.406,  0.058,  0.116,  0.058,  0.232,  0.58,
-     0,      0.348,  0.406,  0.174,  0,      0.29,   0.174,  0.638,  0,
-     0.812,  0.29,   0.638,  0.29,   0.058,  0.29,   0.058,  0.29,   -0.058,
-     0.29,   -0.116, 0,      0.522,  0.406,  -0.116, 0.174,  0.406,  0.522,
-     -0.058, 0.058,  0.406,  0.638,  0.174,  -0.116, 0.232,  0.29,   0.058,
-     0.174,  -0.232, 0.348,  0.696,  0.232,  0.348,  0.58,   0.29,   0.406,
-     0.232,  0.174,  0.29,   0.464,  0.058,  0.232,  0.232,  0.406,  0.29,
-     0.29,   0.464,  0.29,   0.348,  0.348,  0.464,  0.174,  0.696,  0.464,
-     0.116,  0.116,  0.058,  0.406,  0.29,   0.058,  -0.116, 0.29,   0.464,
-     0.174,  0.232,  0,      0.464,  0.174,  0.58,   0.058,  0.116,  0.522,
-     0.348,  0.232,  0.638,  0.522,  0.29,   0.348,  0.232,  0.522,  0.174,
-     0.638,  0.116,  0.116,  0.638,  0.29,   0.232,  0.29,   0.348,  0.406,
-     0.29,   0.232,  0,      0.638,  0.058,  0.174,  0.116,  0.58,   0.58,
-     0.812,  0.406,  0,      0.232,  0.29,   0.174,  0.522,  0.232,  -0.058,
-     0.406,  0.232,  0.232,  0.232,  0,      0.232,  0.174,  0.58,   0.232,
-     -0.174, 0.232,  0.232,  0.058,  0.29,   -0.058, 0.058,  -0.29,  0.174,
-     0.116,  0.232,  0.406,  0.174,  -0.058, 0.58,   0.58,   0.174,  0.406,
-     -0.116, 0.348,  0.58,   0,      0.29,   0.174,  0.29,   0.348,  0.348,
-     0.464,  0.58,   0.58,   0.058,  0.464,  0,      0.522,  0.406,  0.29,
-     0.232,  0.058,  0.406,  0.464,  0.232,  0.058,  0.174,  0.116,  0.232,
-     0.174,  0.232,  0.406,  0.406,  0.058,  0.058,  0.232,  0.058,  0.29,
-     -0.058, -0.174, 0.348,  0.638,  0.174,  0.232,  0.29,   0.232,  0.522,
-     0.406,  0.116,  0.29,   0.174,  0.348,  0.29,   0,      0.522,  0.348,
-     0.406,  0.174,  0.464,  0.232,  0.464,  0.232,  0.058,  0.058,  0.058,
-     0.29,   0,      0.464,  -0.116, 0.116,  0.58,   0.058,  0.348,  0.29,
-     0.638,  0.058,  0.058,  0,      0.406,  0.29,   0.58,   0.232,  0.348,
-     0.174,  0.116,  -0.058, -0.174, 0.232,  0.174,  0.232,  0.406,  0.348,
-     -0.058, 0.232,  0.638,  0.29,   0.406,  0.232,  0.29,   0,      -0.232,
-     0.348,  0,      0.522,  0.174,  0.464,  0.232,  0.116,  0.406,  0.406,
-     0.638,  0.29,   0.232,  0.116,  0.406,  0.464,  0.116,  0.348,  0.406,
-     0.29,   0.232,  -0.232, 0.058,  0.116,  -0.174, 0,      0.29,   0.29,
-     0.232,  -0.232, -0.116, -0.29,  0.116,  0,      0.174,  0.232,  0.116,
-     0.232,  -0.058, -0.116, 0.058,  0,      0.638,  0.174,  0.116,  0.406,
-     0.522,  0.348,  0.348,  0.116,  0.464,  0.232,  0.116,  0.174,  0,
-     0.174,  0.464,  0.406,  -0.058, 0.406,  0.29,   0.348,  0.058,  0.174,
-     0.232,  0.348,  0.116,  0.174,  0.406,  0,      0.464,  0.522,  0.174,
-     0.29,   0.174,  0.58,   -0.232, 0.232,  0.058,  0.058,  0.406,  0.348,
-     0.348,  0.174,  0.058,  0.29,   0.406,  0.174,  -0.116, 0.464,  0.58,
-     0.522,  0.58,   0.464,  0.174,  0.522,  0.464,  0.58,   0.232,  0.638,
-     0.232,  0.348,  0.232,  0.696,  0.58,   0.232,  0.406,  0.116,  0.406,
-     0.348,  0.174,  0.464,  0.348,  0.232,  0.58,   0.522,  0.406,  0.29,
-     0.174,  0.812,  0.696,  0.406,  0.406,  0.232,  0.406,  0.406,  0.348,
-     -0.058, 0.406,  0.696,  -0.174, 0.058,  0,      0.406,  0.464,  0.406,
-     0.638,  0.058,  0.232,  0.638,  0.058,  0.116,  0.232,  0.29,   0.522,
-     0.29,   0.29,   0.406,  0.232,  0.638,  0.406,  0.464,  0.348,  0.232,
-     0.058,  -0.116, 0.58,   0.58,   0.638,  0.348,  0.174,  0.174,  0.174,
-     0.058,  0.348,  0.232,  0.754,  0.464,  0.174,  0.348,  0.58,   0.638,
-     0.406,  0.29,   0.174,  0.232,  0.232,  0.522,  0.348,  0.464,  0.348,
-     0.522,  0.696,  0.058,  0.29,   -0.058, 0.464,  0.29,   0.58,   0.406,
-     -0.174, -0.116, 0.058,  0.058,  0.348,  0,      0.232,  0.232,  0.29,
-     0.754,  0.58,   0.116,  0.29,   0.348,  0.464,  0.232,  0.522,  0.58,
-     0.058,  0.348,  0.58,   0.174,  0.058,  0.174,  0.29,   0.232,  0.174,
-     0.522,  0.232,  0.348,  0.116,  0.348,  -0.174, 0.29,   0.348,  0.348,
-     0.116,  -0.29,  0.058,  0.058,  0.29,   0,      0.406,  0.232,  0.29,
-     -0.348, 0.464,  0.522,  0.174,  0.116,  0.348,  0.406,  0.116,  0.348,
-     0.522,  0.638,  0.406,  0.464,  0.348,  0.348,  0.29,   0.116,  0.522,
-     0.174,  0.348,  0.116,  0.232,  0.406,  0,      0.116,  -0.058, 0,
-     -0.116, 0,      0.406,  0.116,  0.29,   0.58,   0.464,  0.232,  0.406,
-     0.29,   0.638,  0.638,  0.29,   0.464,  -0.116, 0.696,  0.406,  0.406,
-     0.174,  0.232,  0.754,  0.464,  0.232,  0.58,   0.058,  0.522,  0.522,
-     0.406,  0.232,  0.406,  0,      0.174,  0.174,  0.406,  0.464,  0.464,
-     0.464,  0.406,  0.174,  0.174,  0.464,  -0.058, 0.29,   0.464,  0.812,
-     0.464,  0.638,  0.406,  0.232,  0.232,  0.522,  0.29,   0.696,  0.348,
-     0.058,  0.812,  0.174,  0.58,   0.058,  0.174,  0.696,  0.232,  0.348,
-     0.464,  0.116,  0.174,  0.58,   0.406,  0.232,  0.174,  0.406,  0.116,
-     0.638,  0.406,  0.348,  0.406,  0.29,   0.58,   0.348,  0.522,  0.522,
-     0.29,   0.464,  0.058,  0.58,   0.232,  0.174,  0.174,  0.58,   0.406,
-     0.058,  0.232,  0.638,  0.522,  0.58,   0.696,  0.29,   0.348,  0.348,
-     0.348,  0.348,  0.754,  0.348,  0.232,  0.29,   0.174,  0.754,  0.232,
-     0.812,  0.58,   0.58,   0.174,  0.116,  0.174,  0.464,  0.464,  0.232,
-     0,      0.638,  0.116,  0.406,  0.522,  0.29,   0.116,  0.174,  0,
-     0.174,  0.232,  0.058,  0.348,  0.29,   0.232,  0,      0.522,  0.406,
-     0.232,  0.232,  0.116,  0.522,  0.232,  0.174,  0,      0,      -0.348,
-     0.406,  0.464,  0.58,   0.174,  0.174,  0.406,  -0.116, 0.232,  0.348,
-     0.464,  0.174,  0.348,  0.58,   0.696,  0.464,  0.29,   0.232,  0.058,
-     0.058,  0.116,  0.638,  0.058,  0.232,  0.174,  -0.232, 0.638,  0.522,
-     -0.174, 0.058,  0,      0.058,  0.174,  0.29,   0.29,   0,      0.232,
-     -0.29,  0.116,  -0.058, 0.174,  -0.058, 0.058,  -0.232, -0.116, -0.058,
-     0.058,  -0.174, 0.116,  0.232,  -0.058, 0.29,   0.232,  0.638,  0.232,
-     -0.174, 0.232,  0,      0.058,  0.232,  0.116,  -0.232, 0,      0.348,
-     0,      0,      0.174,  -0.058, 0.29,   0.406,  0.116,  0.174,  0.174,
-     0.174,  0,      -0.232, 0.522,  0.348,  0,      0.116,  0.348,  0.174,
-     0.174,  0.29,   0.232,  0.348,  -0.406, 0.174,  0.464,  -0.116, 0.29,
-     0.232,  -0.058, -0.116, 0.174,  0.174,  0.116,  -0.348, 0.174,  0.116,
-     0.348,  -0.29,  -0.058, 0.406,  0.116,  0.232,  0.58,   0.058,  -0.116,
-     0.116,  0.058,  0.116,  -0.406, 0.174,  0.058,  0.406,  0.174,  0.174,
-     0.058,  0.406,  -0.058, -0.174, 0.232,  -0.058, 0,      0.058,  0.116,
-     -0.116, -0.116, 0.29,   -0.116, 0.232,  0.174,  0.232,  0.522,  0.116,
-     0.116,  -0.464, 0.116,  0.522,  -0.058, 0.174,  -0.232, 0,      -0.058,
-     0,      0.232,  0,      0.58,   0.174,  -0.232, 0.29,   0.058,  0.464,
-     0.116,  0,      0.174,  0.406,  0.348},
-    {29.87,  30.16,  30.044, 29.986, 30.16,  30.044, 29.928, 30.044, 29.812,
-     29.928, 30.044, 30.044, 30.16,  29.928, 30.044, 30.276, 30.218, 30.16,
-     29.986, 29.928, 30.102, 29.87,  30.276, 30.334, 29.928, 30.102, 29.928,
-     29.928, 30.102, 29.87,  29.87,  30.16,  29.754, 30.102, 30.16,  30.276,
-     30.276, 30.334, 29.87,  30.218, 30.16,  30.276, 30.16,  30.218, 30.102,
-     30.276, 30.392, 30.624, 30.392, 30.218, 30.856, 30.566, 30.74,  31.03,
-     30.856, 31.146, 31.204, 31.204, 31.378, 31.088, 31.378, 31.436, 31.494,
-     31.552, 31.61,  32.132, 31.726, 32.132, 32.654, 32.248, 32.48,  32.712,
-     32.712, 32.77,  32.77,  32.944, 33.234, 33.118, 33.118, 33.524, 33.814,
-     33.988, 34.22,  33.466, 34.046, 33.988, 33.988, 34.568, 34.394, 35.032,
-     34.568, 34.684, 35.264, 34.568, 35.09,  35.032, 35.322, 35.206, 35.612,
-     35.728, 35.67,  35.264, 35.612, 35.554, 35.612, 35.728, 36.018, 35.554,
-     35.786, 35.844, 35.902, 36.076, 35.786, 35.902, 35.96,  36.018, 35.902,
-     35.902, 36.018, 35.438, 35.612, 35.902, 35.67,  35.554, 35.728, 35.67,
-     35.612, 35.38,  35.438, 35.09,  35.438, 35.322, 34.8,   34.684, 34.916,
-     34.974, 34.8,   34.684, 34.626, 34.684, 34.452, 33.988, 34.742, 34.336,
-     34.104, 34.104, 33.872, 34.278, 34.104, 33.988, 33.93,  33.93,  33.93,
-     34.51,  33.698, 33.756, 34.104, 34.046, 34.22,  34.046, 34.394, 34.22,
-     34.336, 34.278, 33.988, 34.336, 34.452, 34.8,   34.916, 34.8,   34.8,
-     34.684, 34.858, 35.032, 35.032, 35.09,  35.032, 35.322, 35.264, 35.206,
-     35.38,  35.554, 35.67,  35.38,  35.148, 35.438, 35.148, 35.554, 35.032,
-     35.438, 35.09,  35.264, 35.206, 34.974, 35.09,  35.032, 35.09,  35.09,
-     35.38,  35.148, 35.148, 35.09,  34.626, 34.858, 34.858, 35.322, 35.032,
-     34.8,   34.858, 34.858, 34.626, 34.626, 34.626, 34.51,  34.626, 34.568,
-     34.974, 34.626, 34.452, 34.974, 35.09,  34.8,   35.09,  34.8,   35.438,
-     35.148, 35.09,  35.206, 35.612, 35.496, 35.032, 35.148, 35.206, 35.264,
-     35.206, 35.206, 35.438, 35.496, 35.264, 35.09,  35.206, 35.206, 35.728,
-     34.452, 35.09,  35.148, 35.206, 35.206, 34.974, 34.974, 35.206, 34.858,
-     35.148, 34.8,   34.684, 34.742, 34.742, 34.8,   35.322, 34.974, 35.148,
-     35.322, 34.8,   35.38,  35.438, 35.032, 35.148, 35.264, 35.148, 35.264,
-     35.264, 35.032, 35.148, 35.496, 35.148, 34.974, 34.974, 35.09,  35.496,
-     35.554, 35.264, 35.09,  35.496, 35.206, 34.916, 34.742, 35.148, 35.09,
-     34.8,   35.09,  34.8,   35.148, 34.858, 34.974, 35.264, 35.09,  35.264,
-     35.148, 35.38,  34.8,   35.032, 35.148, 34.974, 34.974, 34.974, 34.974,
-     34.916, 34.858, 35.322, 35.438, 35.38,  35.206, 34.858, 35.322, 35.09,
-     35.032, 35.264, 35.496, 35.206, 35.554, 35.032, 35.09,  35.38,  35.09,
-     35.148, 35.438, 35.148, 35.206, 35.032, 35.322, 35.438, 35.554, 35.206,
-     35.264, 35.264, 35.264, 34.8,   35.496, 35.554, 35.322, 35.09,  35.496,
-     35.206, 35.032, 35.322, 35.09,  35.38,  35.264, 35.322, 35.09,  35.554,
-     35.322, 35.264, 35.38,  35.032, 35.322, 35.554, 35.032, 35.612, 35.496,
-     35.206, 35.264, 35.67,  35.206, 35.38,  35.264, 35.322, 35.322, 35.206,
-     35.264, 35.032, 35.264, 35.438, 35.728, 34.8,   35.206, 35.554, 35.264,
-     35.148, 35.264, 35.206, 35.264, 35.322, 35.38,  34.858, 35.322, 35.032,
-     35.148, 35.496, 35.206, 35.032, 35.09,  35.38,  35.322, 35.612, 35.264,
-     34.974, 34.916, 35.206, 34.916, 35.206, 35.496, 35.09,  35.322, 35.322,
-     35.09,  35.206, 35.438, 34.916, 35.148, 35.148, 35.438, 35.38,  35.148,
-     35.38,  35.322, 35.438, 35.496, 35.032, 35.496, 35.206, 35.438, 35.264,
-     34.974, 35.322, 35.206, 35.554, 35.322, 35.496, 35.264, 35.322, 35.148,
-     35.438, 35.322, 35.438, 34.916, 35.032, 35.38,  35.264, 35.322, 35.496,
-     35.322, 35.438, 35.612, 35.206, 35.322, 35.554, 35.438, 35.438, 35.38,
-     35.264, 35.206, 35.38,  35.496, 35.496, 35.496, 35.264, 35.496, 35.496,
-     35.612, 35.09,  35.554, 35.38,  35.206, 35.496, 35.554, 35.67,  35.206,
-     35.206, 35.032, 35.206, 35.438, 35.264, 35.438, 35.38,  35.148, 35.206,
-     35.206, 35.206, 35.148, 34.974, 35.264, 35.206, 34.916, 35.554, 35.264,
-     35.612, 35.206, 35.438, 35.612, 35.206, 35.496, 35.554, 35.496, 35.554,
-     34.916, 35.496, 35.38,  35.728, 35.264, 35.032, 35.612, 35.322, 35.38,
-     35.206, 35.902, 35.67,  35.38,  35.322, 35.438, 35.264, 35.032, 35.322,
-     35.38,  35.322, 35.554, 35.786, 35.264, 35.496, 35.322, 35.612, 35.67,
-     35.148, 35.844, 35.38,  35.786, 35.554, 35.322, 35.554, 35.438, 35.844,
-     35.38,  35.728, 35.38,  35.728, 35.612, 36.134, 35.786, 35.438, 35.38,
-     35.496, 35.612, 35.322, 35.728, 35.438, 35.38,  35.554, 35.38,  35.496,
-     35.728, 36.018, 35.67,  35.322, 35.612, 35.67,  35.67,  35.496, 35.786,
-     35.612, 35.902, 35.612, 35.728, 35.728, 35.844, 35.554, 35.786, 35.496,
-     35.902, 36.018, 35.554, 35.786, 35.67,  35.728, 35.67,  35.67,  35.728,
-     35.902, 35.902, 35.67,  35.67,  35.612, 35.786, 35.496, 35.67,  35.902,
-     35.728, 35.96,  35.67,  35.67,  35.554, 36.134, 35.96,  35.496, 35.786,
-     35.67,  35.96,  35.902, 35.496, 35.612, 35.844, 35.728, 35.786, 35.554,
-     35.554, 35.902, 35.902, 35.38,  35.322, 35.438, 35.554, 35.902, 35.554,
-     35.844, 36.018, 36.018, 35.612, 35.96,  36.134, 35.728, 35.554, 35.844,
-     35.67,  35.902, 35.496, 36.192, 35.902, 35.438, 35.496, 35.496, 35.844,
-     36.018, 35.96,  36.192, 35.786, 35.902, 35.786, 35.844, 35.612, 35.902,
-     36.192, 35.96,  35.96,  35.554, 35.902, 36.018, 36.076, 36.134, 35.902,
-     35.844, 36.018, 36.25,  35.786, 36.076, 35.902, 35.96,  35.902, 35.554,
-     35.902, 35.728, 35.554, 36.192, 35.612, 35.844, 35.96,  36.018, 35.67,
-     35.67,  35.844, 35.844, 35.67,  35.728, 35.438, 35.728, 35.728, 35.844,
-     35.844, 35.844, 36.134, 36.076, 36.018, 35.728, 36.018, 35.554, 36.018,
-     36.018, 36.134, 36.308, 36.366, 35.612, 35.902, 35.902, 35.844, 36.134,
-     36.018, 36.018, 35.902, 35.96,  35.67,  35.844, 36.192, 36.366, 35.96,
-     35.96,  35.902, 36.54,  36.076, 36.076, 36.018, 36.076, 36.308, 35.844,
-     36.308, 36.25,  36.076, 36.134, 36.25,  36.076, 36.134, 36.308, 36.366,
-     36.018, 36.076, 36.25,  36.25,  36.076, 36.018, 36.192, 36.076, 36.54,
-     36.25,  36.134, 36.134, 36.134, 36.076, 36.192, 36.25,  36.25,  36.424,
-     36.076, 35.96,  36.54,  36.482, 35.844, 36.482, 36.308, 36.598, 35.96,
-     35.96,  36.018, 36.598, 36.308, 36.772, 36.424, 36.54,  36.366, 36.308,
-     36.424, 36.656, 36.308, 36.772, 36.598, 36.366, 36.424, 36.25,  36.482,
-     36.656, 36.54,  36.25,  36.424, 36.25,  36.424, 36.192, 36.192, 36.482,
-     36.482, 36.192, 36.366, 36.424, 36.366, 36.598, 36.192, 36.424, 36.308,
-     36.25,  36.54,  36.482, 36.656, 36.482, 36.308, 36.54,  36.598, 36.25,
-     36.482, 36.308, 36.424, 36.598, 36.714, 36.366, 36.54,  36.54,  36.424,
-     36.308, 36.656, 36.25,  36.54,  36.482, 36.772, 36.772, 36.54,  36.54,
-     36.714, 36.54,  36.424, 36.366, 36.598, 36.134, 36.656, 36.888, 36.366,
-     36.598, 36.888, 36.366, 36.134, 36.424, 36.482, 36.888, 36.656, 36.482,
-     36.598, 36.25,  36.888, 36.656, 36.54,  36.656, 36.598, 36.54,  36.424,
-     36.366, 36.134, 36.366, 36.482, 36.714, 36.424, 36.308, 36.83,  36.424,
-     37.004, 36.714, 36.946, 36.424, 36.714, 37.12,  36.946, 36.888, 36.946,
-     36.482, 36.656, 36.366, 36.482, 36.192, 36.598, 36.946, 36.54,  36.54,
-     36.888, 36.482, 36.656, 37.004, 36.134, 36.424, 36.83,  36.366, 36.772,
-     36.656, 37.12,  36.424, 36.772, 36.714, 37.12,  36.482, 36.656, 37.004,
-     37.004, 36.83,  36.772, 36.656, 37.004, 36.888, 37.062, 36.656, 36.598,
-     36.772, 36.54,  36.598, 36.54,  36.83,  36.714, 36.714, 36.54,  36.83,
-     36.714, 37.12,  36.656, 36.83,  36.714, 36.656, 36.714, 36.656, 36.714,
-     36.54,  36.54,  36.714, 36.598, 37.062, 36.598, 36.424, 36.83,  36.482,
-     36.83,  36.25,  36.598, 36.888, 36.714, 36.192, 36.656, 36.888, 36.714,
-     36.714, 37.062, 36.598, 36.888, 36.656, 37.178, 37.12,  36.83,  36.54,
-     36.888, 36.714, 36.83,  36.83,  37.004, 36.714, 36.83,  36.888, 36.598,
-     37.062, 36.482, 36.888, 36.656, 36.424, 36.888, 37.004, 36.83,  36.772,
-     36.888, 37.062, 37.062, 37.294, 36.714, 36.888, 37.004, 37.062, 37.178,
-     37.12,  37.004, 36.83,  36.83,  37.178, 37.178, 36.714, 36.714, 36.946,
-     37.236, 37.294, 37.236, 37.352, 36.888, 37.12,  37.12,  37.004, 36.946,
-     36.83,  37.062, 36.946, 37.294, 37.12,  37.004, 36.946, 37.294, 37.178,
-     37.294, 37.062, 37.062, 37.062, 37.468, 36.888, 36.946, 36.888, 36.888,
-     37.178, 36.946, 37.352, 37.12,  36.83,  37.236, 36.888, 37.12,  36.598,
-     37.004, 36.946, 37.004, 37.062, 37.294, 37.12,  37.178, 37.236, 37.062,
-     36.888, 37.12,  37.12,  37.352, 37.41,  37.004, 37.178, 37.236, 37.062,
-     36.946, 36.946, 37.062, 37.178, 36.772, 36.946, 36.772, 37.352, 37.062,
-     36.772, 37.178, 36.946, 37.236, 37.12,  37.294, 37.236, 37.468, 36.83,
-     36.83,  37.468, 37.236, 37.584, 37.352, 37.468, 37.12,  37.12,  37.236,
-     37.236, 36.714, 37.236, 37.062, 36.83,  37.178, 37.236, 37.468, 37.178,
-     37.236, 37.12,  37.12,  37.12,  37.062, 37.178, 37.004, 37.178, 37.236,
-     37.352, 37.352, 37.236, 37.352, 37.062, 36.946, 37.004, 37.352, 37.062,
-     37.004, 37.062, 37.12,  37.004, 37.062, 37.236, 37.178, 37.178, 37.642,
-     37.12,  37.41,  37.12,  37.178, 37.468, 37.352, 37.236, 37.352, 37.352,
-     37.236, 37.352, 37.584, 37.294, 37.294, 37.062, 37.12,  37.236, 37.004,
-     37.062, 36.714, 37.294, 37.12,  37.758, 37.41,  37.584, 37.294, 37.236,
-     37.062, 37.294, 37.062, 37.178, 37.41,  37.352, 37.41,  37.526, 37.352,
-     37.526, 37.874, 37.004, 37.526, 37.178, 37.294, 37.584, 37.642, 37.41,
-     37.178, 37.352, 36.946, 37.41,  37.584, 37.584, 37.236, 37.41,  37.41,
-     37.352, 37.41,  37.41,  37.236, 37.41,  37.294, 37.236, 37.352, 37.642,
-     37.352, 37.874, 37.178, 37.468, 37.352, 37.468, 37.41,  37.468, 37.468,
-     37.41,  37.468, 37.584, 37.352, 38.106, 37.584, 37.584, 37.642, 37.236,
-     37.874, 37.932, 37.178, 37.526, 37.468, 37.468, 37.584, 37.99,  37.526,
-     37.584, 37.642, 37.874, 37.816, 37.41,  37.526, 37.7,   37.526, 37.236,
-     37.12,  37.932, 37.468, 37.7,   37.352, 37.7,   37.584, 37.932, 37.584,
-     37.816, 37.99,  37.932, 37.758, 37.758, 37.352, 37.642, 37.816, 37.816,
-     37.99,  37.758, 38.048, 37.932, 37.874, 37.7,   38.106, 37.584, 37.7,
-     37.758, 37.7,   37.584, 37.758, 37.642, 37.468, 37.584, 37.932, 37.99,
-     37.526, 37.584, 37.642, 37.816, 37.758, 37.758, 37.816, 37.642, 37.99,
-     37.526, 38.222, 37.7,   37.758, 37.816, 37.584, 37.758, 37.874, 37.816,
-     37.816, 37.816, 37.99,  37.7,   37.41,  37.816, 37.758, 37.7,   37.758,
-     37.468, 37.526, 37.932, 37.874, 37.526, 37.584, 37.41,  37.874, 37.7,
-     37.7,   37.584, 37.468, 37.758, 37.7,   37.874, 37.758, 37.642, 37.584,
-     38.048, 37.874, 37.758, 37.584, 38.048, 37.642, 37.932, 37.99,  38.338,
-     37.874, 37.874, 37.874, 37.99,  37.99,  38.222, 38.048, 38.048, 38.222,
-     37.932, 38.106, 37.99,  37.816, 37.816, 38.048, 38.454, 37.932, 38.048,
-     38.164, 37.758, 38.396, 38.164, 38.222, 38.164, 37.932, 37.874, 38.106,
-     38.164, 38.106, 38.57,  38.28,  38.106, 37.99,  37.932, 37.99,  38.222,
-     37.99,  38.164, 38.28,  38.396, 38.28,  38.338, 37.932, 37.874, 38.222,
-     38.512, 38.164, 38.28,  38.28,  38.628, 38.28,  38.164, 38.512, 38.512,
-     38.512, 37.874, 38.686, 38.57,  38.86,  38.106, 38.222, 38.396, 38.28,
-     38.222, 38.628, 38.338, 38.164, 38.454, 38.512, 38.628, 38.512, 38.512,
-     38.802, 38.86,  38.628, 38.57,  38.628, 38.048, 38.918, 38.686, 38.57,
-     38.802, 38.512, 38.57,  39.034, 38.744, 38.454, 38.802, 38.802, 39.092,
-     38.976, 38.976, 38.802, 38.628, 38.802, 38.396, 38.744, 38.802, 38.686,
-     38.918, 38.744, 38.222, 38.86,  38.628, 38.744, 38.686, 38.918, 38.628,
-     39.034, 38.57,  38.802, 38.686, 38.86,  38.744, 38.86,  38.86,  38.396,
-     38.628, 38.918, 38.57,  38.976, 38.57,  38.976, 38.628, 38.86,  39.092,
-     38.744, 38.918, 38.86,  38.918, 38.976, 39.034, 38.976, 39.382, 38.976,
-     39.382, 39.034, 38.454, 39.266, 39.324, 38.918, 39.266, 38.918, 38.976,
-     38.512, 39.324, 38.976, 39.034, 38.918, 38.86,  39.382, 38.918, 38.686,
-     39.092, 38.802, 39.092, 39.208, 38.918, 38.86,  39.034, 39.034, 39.034,
-     39.034, 38.976, 39.15,  39.092, 38.918, 39.208, 39.034, 39.208, 39.092,
-     39.034, 39.324, 39.208, 39.266, 39.498, 39.034, 39.266, 39.208, 39.208,
-     39.092, 39.208, 38.976, 38.976, 39.266, 39.208, 38.976, 39.034, 39.15,
-     39.092, 38.802, 39.034, 39.034, 39.15,  39.092, 39.672, 39.324, 39.092,
-     39.44,  39.15,  39.44,  39.556, 39.44,  39.324, 39.614, 39.382, 38.86,
-     39.498, 39.208, 39.092, 38.976, 38.976, 38.976, 39.266, 39.498, 38.976,
-     39.034, 39.382, 39.382, 39.382, 39.498, 39.324, 39.266, 39.266, 39.324,
-     39.034, 39.208, 39.382, 39.73,  39.266, 39.498, 39.208, 39.556, 39.208,
-     39.498, 39.672, 39.44,  39.324, 39.324, 39.614, 39.44,  39.324, 39.44,
-     39.556, 39.092, 39.382, 39.324, 39.208, 39.556, 39.44,  39.324, 39.266,
-     39.324, 39.44,  39.672, 39.382, 39.382, 39.15,  39.324, 39.556, 39.672,
-     39.556, 39.44,  39.498, 39.498, 39.44,  39.382, 39.498, 39.44,  39.44,
-     39.788, 39.382, 39.266, 39.266, 39.44,  39.324, 39.788, 39.962, 39.614,
-     39.556, 39.614, 39.556, 39.382, 39.614, 39.672, 39.672, 39.73,  39.672,
-     39.672, 39.962, 39.44,  39.44,  39.788, 39.672, 39.44,  39.382, 39.556,
-     39.382, 39.614, 39.556, 39.556, 39.498, 39.556, 39.614, 39.73,  40.02,
-     39.672, 39.44,  39.614, 39.788, 39.614, 40.02,  39.788, 39.498, 39.672,
-     40.02,  39.382, 39.904, 39.44,  39.788, 39.846, 39.962, 40.078, 39.556,
-     39.672, 39.556, 40.02,  39.614, 39.788, 40.02,  39.614, 39.73,  39.73,
-     39.846, 40.078, 39.846, 39.614, 39.498, 39.788, 39.73,  39.904, 39.846,
-     40.02,  39.672, 39.962, 39.788, 40.078, 40.078, 39.788, 39.846, 39.846,
-     40.136, 40.078, 40.078, 40.02,  39.788, 40.02,  40.194, 40.136, 40.426,
-     39.962, 40.252, 40.252, 40.368, 39.904, 40.02,  40.426, 40.194, 40.02,
-     40.194, 40.02,  39.904, 40.484, 40.02,  40.136, 40.542, 40.194, 40.484,
-     40.194, 40.078, 40.31,  40.31,  40.426, 40.02,  40.368, 40.368, 40.89,
-     40.542, 40.716, 40.368, 40.6,   40.136, 40.6,   40.89,  40.194, 40.832,
-     40.774, 40.426, 40.194, 40.426, 40.658, 40.716, 40.6,   40.6,   40.484,
-     40.426, 40.542, 40.658, 40.774, 40.484, 40.6,   40.6,   40.774, 40.948,
-     40.89,  40.832, 40.716, 40.774, 40.484, 40.89,  40.774, 41.006, 40.658,
-     41.064, 40.31,  40.542, 40.774, 40.716, 40.832, 40.658, 40.484, 40.832,
-     40.89,  40.89,  41.006, 40.832, 40.716, 40.948, 40.774, 40.774, 40.716,
-     41.354, 41.006, 40.832, 41.412, 41.18,  40.716, 41.18,  41.18,  40.948,
-     41.006, 41.122, 41.122, 41.18,  40.716, 40.948, 41.18,  41.122, 41.064,
-     41.238, 41.238, 40.774, 41.354, 40.89,  40.832, 41.47,  41.18,  41.354,
-     41.412, 41.354, 41.122, 41.238, 41.064, 41.122, 41.238, 41.238, 40.948,
-     41.586, 41.238, 41.064, 41.296, 41.354, 41.586, 41.47,  41.354, 41.296,
-     41.296, 41.122, 41.122, 41.354, 41.876, 41.528, 41.586, 41.528, 41.354,
-     41.644, 41.296, 41.47,  41.354, 41.354, 41.18,  41.644, 41.354, 41.528,
-     41.412, 41.702, 41.296, 41.876, 41.354, 41.528, 41.818, 41.47,  41.876,
-     41.644, 41.528, 42.108, 41.76,  41.818, 41.818, 41.76,  41.702, 41.412,
-     41.644, 41.354, 41.818, 41.47,  41.76,  41.876, 42.108, 41.354, 41.992,
-     41.586, 41.876, 41.586, 41.76,  41.644, 42.224, 42.05,  41.818, 41.76,
-     42.108, 41.876, 41.992, 41.528, 41.992, 41.644, 41.876, 41.876, 41.644,
-     42.166, 41.76,  41.992, 41.818, 41.76,  42.108, 41.876, 41.876, 42.63,
-     41.76,  41.702, 41.876, 42.108, 41.586, 42.224, 41.876, 41.876, 42.108,
-     42.108, 41.76,  41.76,  41.76,  42.05,  42.05,  42.224, 41.934, 42.224,
-     41.934, 41.992, 42.05,  41.876, 41.934, 41.992, 42.34,  41.876, 42.34,
-     42.05,  42.108, 42.224, 42.224, 42.05,  42.05,  42.224, 42.108, 42.34,
-     42.166, 42.05,  42.282, 42.108, 42.282, 42.108, 42.282, 41.992, 42.108,
-     42.108, 42.224, 42.108, 42.456, 41.934, 42.456, 42.514, 41.992, 42.398,
-     42.572, 42.166, 42.108, 42.05,  42.05,  42.282, 42.282, 42.34,  42.166,
-     42.166, 42.05,  42.572, 42.05,  42.108, 42.224, 42.166, 42.224, 42.514,
-     42.166, 42.282, 42.746, 42.63,  42.34,  42.63,  42.108, 42.63,  42.456,
-     42.34,  42.34,  42.572, 42.282, 42.456, 42.63,  42.63,  42.282, 42.166,
-     42.514, 42.572, 42.34,  42.862, 42.398, 42.572, 42.746, 42.688, 42.746,
-     42.688, 42.862, 42.862, 43.094, 42.456, 42.456, 42.63,  42.63,  42.746,
-     42.34,  42.456, 42.688, 42.514, 42.978, 42.63,  42.804, 42.572, 42.514,
-     42.688, 42.978, 42.862, 42.804, 42.398, 42.63,  43.442, 42.456, 42.688,
-     42.63,  42.746, 43.094, 42.92,  42.63,  42.63,  42.688, 42.63,  42.398,
-     42.746, 42.978, 42.63,  42.63,  42.92,  42.978, 43.094, 43.384, 43.036,
-     43.21,  42.746, 42.978, 42.804, 42.804, 43.384, 42.978, 42.92,  42.92,
-     43.036, 42.862, 43.442, 42.688, 43.094, 43.21,  42.978, 43.036, 42.978,
-     42.978, 43.036, 42.456, 43.036, 43.036, 43.036, 43.21,  43.094, 42.862,
-     42.804, 43.384, 43.21,  43.268, 43.094, 43.036, 43.442, 42.978, 43.152,
-     42.688, 43.442, 43.036, 43.036, 43.094, 42.978, 43.094, 42.746, 42.978,
-     42.862, 43.094, 42.978, 43.094, 43.5,   43.442, 43.384, 43.21,  43.036,
-     43.268, 43.094, 43.268, 43.5,   43.094, 43.268, 42.92,  42.978, 43.094,
-     43.268, 43.674, 42.978, 42.978, 43.21,  43.442, 43.5,   43.268, 43.326,
-     43.268, 43.5,   43.442, 43.384, 43.384, 43.21,  43.21,  43.558, 43.848,
-     42.978, 43.442, 43.268, 43.21,  43.5,   43.268, 43.732, 43.384, 43.384,
-     43.21,  43.5,   43.674, 43.326, 43.79,  43.674, 43.558, 43.21,  43.442,
-     43.268, 43.268, 43.384, 43.616, 43.268, 43.442, 43.152, 43.848, 43.558,
-     43.21,  43.5,   43.442, 43.558, 43.674, 43.558, 43.326, 44.022, 43.268,
-     43.79,  43.732, 43.384, 43.848, 43.384, 43.79,  43.152, 43.384, 43.732,
-     43.558, 43.21,  43.558, 43.558, 43.5,   43.442, 43.442, 43.5,   43.906,
-     43.732, 43.558, 43.674, 43.442, 43.848, 43.732, 43.732, 43.326, 43.964,
-     43.674, 43.558, 43.79,  43.268, 43.616, 43.848, 43.732, 43.326, 43.384,
-     43.848, 43.848, 43.384, 43.442, 43.442, 43.732, 43.442, 43.5,   43.616,
-     43.674, 43.384, 43.442, 43.674, 43.384, 43.616, 43.616, 43.616, 43.268,
-     43.5,   43.5,   43.326, 43.384, 43.906, 43.558, 43.5,   43.21,  43.442,
-     43.558, 44.022, 43.906, 43.268, 43.558, 43.616, 43.732, 43.674, 43.442,
-     43.384, 43.558, 43.5,   43.442, 43.674, 43.442, 43.79,  43.442, 43.268,
-     43.732, 43.906, 43.326, 43.326, 43.616, 43.616, 43.79,  43.5,   43.79,
-     43.384, 43.674, 43.616, 43.558, 43.616, 43.674, 43.326, 43.906, 43.558,
-     43.79,  43.558, 43.558, 43.21,  43.674, 43.152, 43.442, 43.094, 43.616,
-     43.674, 43.616, 43.442, 43.674, 43.732, 43.558, 43.5,   42.688, 43.616,
-     43.5,   43.442, 43.616, 43.326, 43.558, 43.906, 43.152, 43.384, 43.384,
-     43.5,   43.384, 43.094, 43.442, 43.616, 43.152, 43.152, 43.5,   43.558,
-     43.616, 43.152, 43.326, 43.732, 43.326, 43.152, 43.152, 43.5,   43.326,
-     43.036, 43.5,   43.268, 43.326, 43.616, 43.326, 43.326, 43.036, 43.036,
-     43.152, 43.094, 43.152, 42.572, 42.92,  43.152, 42.978, 43.094, 43.036,
-     42.804, 43.21,  42.92,  42.92,  42.688, 42.92,  42.688, 43.036, 43.384,
-     42.804, 43.036, 42.862, 43.094, 43.268, 42.804, 43.268, 42.92,  42.746,
-     42.572, 42.746, 42.92,  43.094, 42.978, 42.456, 42.862, 42.978, 42.92,
-     42.862, 42.688, 42.862, 42.63,  42.746, 42.804, 42.572, 42.92,  42.862,
-     42.572, 42.92,  42.746, 42.746, 42.746, 42.746, 42.804, 42.978, 42.92,
-     42.746, 42.572, 42.746, 42.63,  42.804, 42.804, 42.456, 42.224, 42.688,
-     42.63,  42.63,  42.862, 42.572, 42.514, 42.572, 42.572, 42.514, 42.224,
-     42.34,  42.108, 42.456, 42.34,  42.224, 42.456, 42.746, 42.398, 42.398,
-     42.398, 42.166, 42.514, 42.456, 41.876, 42.108, 42.514, 41.934, 42.282,
-     42.166, 42.398, 42.108, 42.282, 42.108, 41.702, 42.108, 42.05,  42.108,
-     42.166, 41.818, 41.876, 41.76,  41.992, 41.818, 42.05,  41.992, 41.76,
-     42.34,  41.876, 42.166, 41.934, 41.702, 41.76,  41.586, 41.76,  41.76,
-     41.644, 41.528, 41.702, 41.818, 41.354, 41.934, 41.18,  41.586, 41.586,
-     41.586, 41.18,  41.412, 41.644, 41.528, 41.412, 41.18,  41.238, 41.354,
-     41.296, 41.354, 41.18,  41.412, 41.528, 41.122, 41.18,  41.122, 41.238,
-     41.122, 41.238, 41.064, 40.948, 40.832, 41.122, 40.832, 41.006, 40.89,
-     40.89,  40.484, 40.658, 40.716, 40.89,  40.89,  40.658, 40.89,  41.18,
-     41.064, 40.542, 40.658, 40.832, 40.89,  40.484, 40.6,   40.368, 40.658,
-     40.774, 40.542, 40.194, 40.078, 39.73,  40.31,  40.02,  40.252, 40.484,
-     40.252, 40.136, 40.252, 39.73,  39.846, 40.02,  39.788, 39.73,  39.788,
-     39.962, 39.324, 39.672, 39.904, 39.846, 39.788, 39.15,  39.556, 39.846,
-     39.266, 39.382, 39.614, 39.44,  39.904, 39.556, 39.324, 39.324, 39.44,
-     39.208, 38.976, 39.324, 38.976, 39.034, 39.15,  39.092, 39.208, 38.86,
-     39.324, 39.034, 38.628, 38.454, 38.802, 38.86,  39.208, 38.338, 38.744,
-     38.628, 38.57,  38.396, 38.164, 38.802, 37.99,  38.338, 38.396, 38.222,
-     38.106, 38.57,  38.28,  38.454, 38.164, 38.222, 38.222, 37.7,   38.106,
-     37.7,   37.99,  37.932, 37.758, 37.7,   37.758, 37.584, 37.816, 37.352,
-     37.352, 37.7,   37.584, 37.41,  37.584, 37.236, 37.642, 37.004, 37.526,
-     37.12,  37.236, 37.294, 36.772, 37.004, 36.598, 36.714, 36.714, 36.656,
-     36.482, 36.598, 36.946, 36.482, 36.946, 36.482, 36.54,  36.366, 36.308,
-     36.424, 36.308, 36.308, 35.902, 36.424, 35.96,  36.192, 36.018, 36.076,
-     35.902, 35.902, 35.786, 35.67,  35.728, 35.612, 35.902, 35.96,  35.554,
-     35.786, 35.612, 35.612, 35.496, 35.322, 35.496, 35.264, 35.148, 35.438,
-     34.742, 35.496, 35.322, 34.916, 35.38,  34.974, 34.858, 34.626, 34.916,
-     34.858, 34.742, 34.626, 34.8,   34.162}};
diff --git a/src/boards/Parafoil/mocksensors/mock_data/test-mock-data.h b/src/boards/Parafoil/mocksensors/mock_data/test-mock-data.h
deleted file mode 100644
index 191c01884..000000000
--- a/src/boards/Parafoil/mocksensors/mock_data/test-mock-data.h
+++ /dev/null
@@ -1,38 +0,0 @@
-/* Copyright (c) 2019 Skyward Experimental Rocketry
- * Author: Luca Mozzarelli
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-static const unsigned PRESSURE_DATA_SIZE = 2570;
-extern const float SIMULATED_PRESSURE[PRESSURE_DATA_SIZE];
-
-static const unsigned GPS_DATA_SIZE = 2570;
-extern const float SIMULATED_LAT[GPS_DATA_SIZE];
-extern const float SIMULATED_LON[GPS_DATA_SIZE];
-extern const float SIMULATED_VNORD[GPS_DATA_SIZE];
-extern const float SIMULATED_VEAST[GPS_DATA_SIZE];
-
-static const unsigned IMU_DATA_SIZE          = 2570;
-static const unsigned MOTION_SENSOR_AXIS_NUM = 3;
-extern const float ACCELEROMETER_DATA[MOTION_SENSOR_AXIS_NUM][IMU_DATA_SIZE];
-extern const float GYROSCOPE_DATA[MOTION_SENSOR_AXIS_NUM][IMU_DATA_SIZE];
-extern const float MAGNETOMETER_DATA[MOTION_SENSOR_AXIS_NUM][IMU_DATA_SIZE];
\ No newline at end of file
diff --git a/src/boards/Parafoil/mocksensors/mock_data/test-mock-sensors.cpp b/src/boards/Parafoil/mocksensors/mock_data/test-mock-sensors.cpp
deleted file mode 100644
index d21fa7b4e..000000000
--- a/src/boards/Parafoil/mocksensors/mock_data/test-mock-sensors.cpp
+++ /dev/null
@@ -1,82 +0,0 @@
-/* Copyright (c) 2020 Skyward Experimental Rocketry
- * Author: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#include <Common.h>
-#include <mocksensors/MockSensors.h>
-
-using namespace DeathStackBoard;
-
-int main()
-{
-    TimestampTimer::enableTimestampTimer();
-
-    MockGPS gps;
-    MockPressureSensor p_sensor;
-    MockIMU imu;
-    TestSensor test_sensor;
-
-    int i = 0;
-
-    while (true)
-    {
-
-        if (i == 10)
-        {
-            gps.signalLiftoff();
-            p_sensor.signalLiftoff();
-            TRACE("---------- LIFTOFF !!! ----------\n\n");
-        }
-
-        gps.sample();
-        GPSData gps_data = gps.getLastSample();
-        TRACE("GPS SAMPLE: \n");
-        TRACE("lat = %f \n", gps_data.latitude);
-        TRACE("lon = %f \n\n", gps_data.longitude);
-
-        p_sensor.sample();
-        PressureData pressure = p_sensor.getLastSample();
-        TRACE("PRESSURE SAMPLE: \n");
-        TRACE("pressure = %f \n\n", pressure.press);
-
-        imu.sample();
-        MockIMUData imu_data = imu.getLastSample();
-        TRACE("IMU SAMPLE: \n");
-        TRACE("accel x = %f \n", imu_data.accel_x);
-        TRACE("accel y = %f \n", imu_data.accel_y);
-        TRACE("accel z = %f \n", imu_data.accel_z);
-        TRACE("gyro x = %f \n", imu_data.gyro_x);
-        TRACE("gyro y = %f \n", imu_data.gyro_y);
-        TRACE("gyro z = %f \n", imu_data.gyro_z);
-        TRACE("magneto x = %f \n", imu_data.mag_x);
-        TRACE("magneto y = %f \n", imu_data.mag_y);
-        TRACE("magneto z = %f \n\n", imu_data.mag_z);
-
-        test_sensor.sample();
-        TestData test_data = test_sensor.getLastSample();
-        TRACE("TEST SAMPLE: \n");
-        TRACE("value = %f \n\n", test_data.value);
-
-        miosix::Thread::sleep(1000);
-
-        i++;
-    }
-}
\ No newline at end of file
diff --git a/src/boards/Payload/Main/Sensors.h b/src/boards/Payload/Main/Sensors.h
index 0841df4d2..dd3a8cc9d 100644
--- a/src/boards/Payload/Main/Sensors.h
+++ b/src/boards/Payload/Main/Sensors.h
@@ -70,23 +70,24 @@ public:
             Boardcore::TaskScheduler* scheduler);
 
     /**
-     * @brief Destroy the Sensors object and all its sensors
+     * @brief Destroy the Sensors object and all its sensors.
      */
     ~Sensors();
 
     /**
      * @brief Starts all the calibration procedures regarding some of the most
-     * critical sensors
+     * critical sensors.
      */
     void calibrate();
 
     /**
-     * @brief Starts the sensor manager and the task scheduler
-     * @return true If all goes correctly
-     * @return false If something fails
+     * @brief Starts the sensor manager and the task scheduler.
+     * @return True if all goes correctly.
      */
     bool start();
 
+    bool isStarted();
+
     // Kernel lock getters
     Boardcore::InternalADCData getInternalAdcLastSample();
     Boardcore::BatteryVoltageSensorData getBatteryVoltageLastSample();
@@ -157,4 +158,4 @@ private:
      */
     void updateSensorsStatus();
 };
-}  // namespace Payload
\ No newline at end of file
+}  // namespace Payload
diff --git a/src/boards/common/Algorithm.h b/src/boards/common/Algorithm.h
deleted file mode 100644
index 7f8ace5e3..000000000
--- a/src/boards/common/Algorithm.h
+++ /dev/null
@@ -1,65 +0,0 @@
-/* Copyright (c) 2020 Skyward Experimental Rocketry
- * Author: Luca Conterio
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-class Algorithm
-{
-public:
-    /**
-     * @brief Initializes the Algorithm object, must be called as soon as the
-     * object is created.
-     * */
-    virtual bool init() = 0;
-
-    /**
-     * @brief Starts the execution of the algorithm and set the running flag to
-     * true.
-     * */
-    void begin() { running = true; }
-
-    /**
-     * @brief Terminates the algorithm's execution and sets the running flag to
-     * false.
-     * */
-    void end() { running = false; }
-
-    /**
-     * @brief Checks wether the algorithm is in a running state or not, and
-     * eventually calls the @see{step} routine.
-     * */
-    void update()
-    {
-        if (running)
-        {
-            step();
-        }
-    }
-
-protected:
-    /**
-     * @brief The actual algorithm step.
-     */
-    virtual void step() = 0;
-
-    bool running = false;
-};
diff --git a/src/boards/Parafoil/TelemetriesTelecommands/Mavlink.h b/src/boards/common/Mavlink.h
similarity index 78%
rename from src/boards/Parafoil/TelemetriesTelecommands/Mavlink.h
rename to src/boards/common/Mavlink.h
index 6b768ab2f..780856af1 100644
--- a/src/boards/Parafoil/TelemetriesTelecommands/Mavlink.h
+++ b/src/boards/common/Mavlink.h
@@ -1,5 +1,5 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Luca Erbetta
+/* Copyright (c) 2022 Skyward Experimental Rocketry
+ * Author: Alberto Nidasio
  *
  * Permission is hereby granted, free of charge, to any person obtaining a copy
  * of this software and associated documentation files (the "Software"), to deal
@@ -20,22 +20,10 @@
  * THE SOFTWARE.
  */
 
-#pragma once
-
-// Ignore warnings as these are auto-generated headers made with third party
-// tools
+// Ignore warnings as these are auto-generated headers made by a third party
 #pragma GCC diagnostic push
 #pragma GCC diagnostic ignored "-Wcast-align"
 #pragma GCC diagnostic ignored "-Waddress-of-packed-member"
+#pragma GCC diagnostic ignored "-Wmaybe-uninitialized"
 #include <mavlink_lib/pyxis/mavlink.h>
 #pragma GCC diagnostic pop
-
-#include <Parafoil/Configs/MavlinkConfig.h>
-#include <radio/MavlinkDriver/MavlinkDriver.h>
-
-namespace Parafoil
-{
-
-using MavDriver = Boardcore::MavlinkDriver<MAV_PKT_SIZE, MAV_OUT_QUEUE_LEN>;
-
-}
diff --git a/src/boards/common/ServoInterface.h b/src/boards/common/ServoInterface.h
deleted file mode 100644
index e549b35b1..000000000
--- a/src/boards/common/ServoInterface.h
+++ /dev/null
@@ -1,154 +0,0 @@
-/* Copyright (c) 2021 Skyward Experimental Rocketry
- * Author: Vincenzo Santomarco
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-/**
- * @brief Class for interfacing with 180° servo motors, works in degrees.
- *
- * This class provides all the methods for enabling/disabling servo
- * communication as well as methods for testing it (like reset, setMaxPosition
- * and selftest).
- * The function set(float) is used to send data to the servo and calls, in
- * sequence, the preprocessPosition() and the setPosition() functions. This
- * function must not be overridden and all the logic of preprocessing and
- * sending position to the actual servo must be implemented via those two
- * methods.
- * */
-class ServoInterface
-{
-public:
-    /**
-     * @brief Class constructor.
-     *
-     * @param minPosition The minimum position possible for the Servo
-     * @param maxPosition The maximum position possible for the Servo
-     */
-    ServoInterface(float minPosition, float maxPosition)
-        : MIN_POS(minPosition), MAX_POS(maxPosition), RESET_POS(minPosition)
-    {
-    }
-
-    /**
-     * @brief Class constructor.
-     *
-     * @param minPosition The minimum position possible for the Servo
-     * @param maxPosition The maximum position possible for the Servo
-     * @param resetPosition The reset position for the Servo
-     */
-    ServoInterface(float minPosition, float maxPosition, float resetPosition)
-        : MIN_POS(minPosition), MAX_POS(maxPosition), RESET_POS(resetPosition)
-    {
-    }
-
-    virtual ~ServoInterface() {}
-
-    /**
-     * @brief Enables the communication with the servo and sets it to its reset
-     * position.
-     */
-    virtual void enable() = 0;
-
-    /**
-     * @brief Disables the communication with the servo.
-     */
-    virtual void disable() = 0;
-
-    /**
-     * @brief Sends the given input to the Servo.
-     *
-     * Before sending data the input is preprocessed in order to have a physical
-     * consistent position to send to the servo. Do not override this method,
-     * but use @see{setPosition} and @see{preprocessPosition}.
-     *
-     * @param angle The input to be sent to the Servo
-     */
-    void set(float angle, bool preprocess = false)
-    {
-        if (angle > MAX_POS)
-        {
-            angle = MAX_POS;
-        }
-        else if (angle < MIN_POS)
-        {
-            angle = MIN_POS;
-        }
-
-        if (preprocess)
-        {
-            setPosition(preprocessPosition(angle));
-        }
-        else
-        {
-            setPosition(angle);
-        }
-    }
-
-    /**
-     * @brief Sends the Servo the highest input possible
-     */
-    void setMaxPosition() { setPosition(MAX_POS); }
-
-    /**
-     * @brief Sends the Servo the lowest input possible
-     */
-    void setMinPosition() { setPosition(MIN_POS); }
-
-    /**
-     * @brief Sets servo to its reset position
-     */
-    void reset() { setPosition(RESET_POS); }
-
-    /**
-     * @return current actuator position (in degrees)
-     */
-    float getCurrentPosition() { return currentPosition; }
-
-    virtual void selfTest() = 0;
-
-    const float MIN_POS   = 0;
-    const float MAX_POS   = 0;
-    const float RESET_POS = 0;
-
-protected:
-    /**
-     * @brief Sends the data to the servo.
-     *
-     * @param angle Data to be sent to servo.
-     */
-    virtual void setPosition(float angle) = 0;
-
-    /**
-     * @brief Applies any transformation needed to the data before actually
-     * sending it to the servo.
-     *
-     * @param angle Non normalized input position.
-     *
-     * @returns Normalized input position.
-     */
-    virtual float preprocessPosition(float angle) { return angle; };
-
-    /**
-     * @brief Actuator's current position.
-     */
-    float currentPosition = 0;
-};
diff --git a/src/boards/common/SystemData.h b/src/boards/common/SystemData.h
deleted file mode 100644
index f4253d251..000000000
--- a/src/boards/common/SystemData.h
+++ /dev/null
@@ -1,51 +0,0 @@
-/* Copyright (c) 2019 Skyward Experimental Rocketry
- * Author: Luca Erbetta
- *
- * Permission is hereby granted, free of charge, to any person obtaining a copy
- * of this software and associated documentation files (the "Software"), to deal
- * in the Software without restriction, including without limitation the rights
- * to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
- * copies of the Software, and to permit persons to whom the Software is
- * furnished to do so, subject to the following conditions:
- *
- * The above copyright notice and this permission notice shall be included in
- * all copies or substantial portions of the Software.
- *
- * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
- * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
- * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
- * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
- * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
- * OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN
- * THE SOFTWARE.
- */
-
-#pragma once
-
-#include <ostream>
-#include <string>
-
-struct SystemData
-{
-    long long timestamp  = 0;
-    float cpu_usage      = 0.0f;
-    float cpu_usage_min  = 0.0f;
-    float cpu_usage_max  = 0.0f;
-    float cpu_usage_mean = 0.0f;
-
-    float free_heap     = 0.0f;
-    float min_free_heap = 0.0f;
-
-    static std::string header()
-    {
-        return "timestamp,cpu_usage,cpu_usage_min,cpu_usage_max,cpu_usage_mean,"
-               "free_heap,min_free_heap\n";
-    }
-
-    void print(std::ostream& os) const
-    {
-        os << timestamp << "," << cpu_usage << "," << cpu_usage_min << ","
-           << cpu_usage_max << "," << cpu_usage_mean << "," << free_heap << ","
-           << min_free_heap << "\n";
-    }
-};
diff --git a/src/entrypoints/Parafoil/parafoil-entry.cpp b/src/entrypoints/Parafoil/parafoil-entry.cpp
index ba18445ff..b742cba47 100644
--- a/src/entrypoints/Parafoil/parafoil-entry.cpp
+++ b/src/entrypoints/Parafoil/parafoil-entry.cpp
@@ -20,98 +20,51 @@
  * THE SOFTWARE.
  */
 
+#include <Parafoil/Actuators/Actuators.h>
+#include <Parafoil/BoardScheduler.h>
 #include <Parafoil/Configs/SensorsConfig.h>
-#include <Parafoil/Configs/XbeeConfig.h>
-#include <Parafoil/ParafoilTest.h>
 #include <Parafoil/Configs/WingConfig.h>
-#include <common/SystemData.h>
+#include <Parafoil/NASController/NASController.h>
+#include <Parafoil/Radio/Radio.h>
+#include <Parafoil/Sensors/Sensors.h>
+#include <Parafoil/Wing/WingController.h>
 #include <diagnostic/CpuMeter/CpuMeter.h>
+#include <events/EventBroker.h>
 #include <miosix.h>
 
 using namespace miosix;
-using namespace Parafoil;
 using namespace Boardcore;
+using namespace Parafoil;
 
-void enablePin()
+int main()
 {
-    // GPS_CS.mode(miosix::Mode::OUTPUT);
-    IMU_CS.mode(miosix::Mode::OUTPUT);
-    PRESS_CS.mode(miosix::Mode::OUTPUT);
-
-    SCK.mode(miosix::Mode::ALTERNATE);
-    MISO.mode(miosix::Mode::ALTERNATE);
-    MOSI.mode(miosix::Mode::ALTERNATE);
-    GPS_TX.mode(miosix::Mode::ALTERNATE);
-    GPS_RX.mode(miosix::Mode::ALTERNATE);
-
-    SCK.alternateFunction(5);
-    MISO.alternateFunction(5);
-    MOSI.alternateFunction(5);
-    GPS_TX.alternateFunction(7);
-    GPS_RX.alternateFunction(7);
-
-    XBEE_SCK.mode(miosix::Mode::ALTERNATE);
-    XBEE_SCK.alternateFunction(5);
-    XBEE_MISO.mode(miosix::Mode::ALTERNATE);
-    XBEE_MISO.alternateFunction(5);
-    XBEE_MOSI.mode(miosix::Mode::ALTERNATE);
-    XBEE_MOSI.alternateFunction(5);
-
-    XBEE_CS.mode(miosix::Mode::OUTPUT);
-    XBEE_CS.high();
-
-    XBEE_ATTN.mode(miosix::Mode::INPUT);
-
-    XBEE_RESET.mode(miosix::Mode::OUTPUT);
-
-    SERVO1PIN.mode(miosix::Mode::ALTERNATE);
-    SERVO1PIN.alternateFunction(2);
+    Logger::getInstance().start();
+    EventBroker::getInstance().start();
 
-    SERVO2PIN.mode(miosix::Mode::ALTERNATE);
-    SERVO2PIN.alternateFunction(3);
+    // Initialize the servo outputs
+    Actuators::getInstance().enableServo(PARAFOIL_SERVO1);
+    Actuators::getInstance().enableServo(PARAFOIL_SERVO2);
 
-    // GPS_CS.high();
-    IMU_CS.high();
-    PRESS_CS.high();
-}
+    // Start the radio
+    Radio::getInstance().start();
 
-int main()
-{
-    Stats cpu_stat;
-    StatsResult cpu_stat_res;
-    SystemData system_data;
+    // Start algorithms
+    NASController::getInstance().start();
+    WingController::getInstance().start();
 
-    RCC->APB2ENR |= RCC_APB2ENR_SPI1EN;  // Enable SPI1 bus
-    RCC->APB2ENR |= RCC_APB2ENR_SPI4EN;  // Enable SPI4 bus
-    enablePin();
+    // Start the sensors sampling
+    Sensors::getInstance().start();
 
-    // TODO integrate all the logging stuff
-    ParafoilTest::getInstance().start();
+    // Start the board task scheduler
+    BoardScheduler::getInstance().getScheduler().start();
 
-    Logger* logger_service = &Logger::getInstance();
-
-    for (;;)
+    // Periodically statistics
+    while (true)
     {
         Thread::sleep(1000);
-        logger_service->log(logger_service->getStats());
-
-        StackLogger::getInstance().updateStack(THID_ENTRYPOINT);
-
-        system_data.timestamp = miosix::getTick();
-        system_data.cpu_usage = CpuMeter::getCpuStats().mean;
-        cpu_stat.add(system_data.cpu_usage);
-
-        cpu_stat_res               = cpu_stat.getStats();
-        system_data.cpu_usage_min  = cpu_stat_res.minValue;
-        system_data.cpu_usage_max  = cpu_stat_res.maxValue;
-        system_data.cpu_usage_mean = cpu_stat_res.mean;
-
-        system_data.min_free_heap = MemoryProfiling::getAbsoluteFreeHeap();
-        system_data.free_heap     = MemoryProfiling::getCurrentFreeHeap();
-
-        logger_service->log(system_data);
-
-        StackLogger::getInstance().log();
+        Logger::getInstance().log(CpuMeter::getCpuStats());
+        CpuMeter::resetCpuStats();
+        Logger::getInstance().logStats();
+        Radio::getInstance().logStatus();
     }
-    return 0;
 }
-- 
GitLab