From 7c3b1f0f0db26ac2fc7ea4a2e802d6029a1e00ed Mon Sep 17 00:00:00 2001 From: Frank Dellaert Date: Wed, 16 Apr 2025 15:48:14 -0400 Subject: [PATCH] Add range SLAM example --- .../examples/RangeSLAMExample_plaza2.ipynb | 17841 ++++++++++++++++ 1 file changed, 17841 insertions(+) create mode 100644 python/gtsam/examples/RangeSLAMExample_plaza2.ipynb diff --git a/python/gtsam/examples/RangeSLAMExample_plaza2.ipynb b/python/gtsam/examples/RangeSLAMExample_plaza2.ipynb new file mode 100644 index 000000000..4fea60c14 --- /dev/null +++ b/python/gtsam/examples/RangeSLAMExample_plaza2.ipynb @@ -0,0 +1,17841 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# Range SLAM with Batch Optimization\n", + "\n", + "A 2D Range SLAM example using batch optimization (Levenberg-Marquardt) on the Plaza2 dataset.\n", + "\n", + "This notebook mirrors the functionality of the MATLAB batch SLAM script, adapted using Python and GTSAM, drawing structural elements from the iSAM example.\n", + "\n", + "Author: Frank Dellaert (adapted for batch by AI)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "source": [ + "GTSAM Copyright 2010-2022, Georgia Tech Research Corporation,\n", + "Atlanta, Georgia 30332-0415\n", + "All Rights Reserved\n", + "\n", + "Authors: Frank Dellaert, et al. (see THANKS for the full author list)\n", + "\n", + "See LICENSE for the license information" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Data is second UWB ranging dataset, B2 or \"plaza 2\", from\n", + "\n", + "> \"Navigating with Ranging Radios: Five Data Sets with Ground Truth\", by Joseph Djugash, Bradley Hamner, and Stephan Roth, available at https://www.ri.cmu.edu/pub_files/2009/9/Final_5datasetsRangingRadios.pdf\n", + "\n" + ] + }, + { + "cell_type": "code", + "execution_count": 21, + "metadata": { + "tags": [ + "remove-cell" + ], + "vscode": { + "languageId": "markdown" + } + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\u001b[31mERROR: Could not find a version that satisfies the requirement gtsam-develop (from versions: none)\u001b[0m\u001b[31m\n", + "\u001b[0m\u001b[31mERROR: No matching distribution found for gtsam-develop\u001b[0m\u001b[31m\n", + "\u001b[0mNote: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam-develop" + ] + }, + { + "cell_type": "code", + "execution_count": 34, + "metadata": {}, + "outputs": [], + "source": [ + "# pylint: disable=invalid-name, E1101\n", + "\n", + "import gtsam\n", + "from gtsam import Point2, Pose2, symbol\n", + "import numpy as np\n", + "import math\n", + "import time \n", + "import plotly.express as px\n", + "\n", + "from gtsam.utils import plot # Needs matplotlib\n", + "from numpy.random import default_rng\n", + "\n", + "rng = default_rng()\n", + "\n", + "NM = gtsam.noiseModel" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Load Data" + ] + }, + { + "cell_type": "code", + "execution_count": 35, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Read 4090 odometry entries.\n" + ] + } + ], + "source": [ + "# load the odometry\n", + "# DR: Odometry Input (delta distance traveled and delta heading change)\n", + "# Time (sec) Delta Distance Traveled (m) Delta Heading (rad)\n", + "odometry_data = {}\n", + "data_file_dr = gtsam.findExampleDataFile(\"Plaza2_DR.txt\")\n", + "odo_times_list = []\n", + "for row in np.loadtxt(data_file_dr):\n", + " t, distance_traveled, delta_heading = row\n", + " odometry_data[t] = Pose2(distance_traveled, 0, delta_heading)\n", + " odo_times_list.append(t)\n", + "\n", + "odo_times_list.sort() # Ensure times are sorted\n", + "M = len(odometry_data)\n", + "print(f\"Read {M} odometry entries.\")" + ] + }, + { + "cell_type": "code", + "execution_count": 36, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Read 1816 range triples for 4 unique landmarks.\n" + ] + } + ], + "source": [ + "# load the ranges from TD\n", + "# Time (sec) Sender / Antenna ID Receiver Node ID Range (m)\n", + "triples = []\n", + "landmark_ids = set()\n", + "data_file_td = gtsam.findExampleDataFile(\"Plaza2_TD.txt\")\n", + "for row in np.loadtxt(data_file_td):\n", + " t, sender, receiver, _range = row\n", + " landmark_id = int(receiver)\n", + " triples.append((t, landmark_id, _range))\n", + " landmark_ids.add(landmark_id)\n", + "\n", + "K = len(triples)\n", + "sorted_landmark_ids = sorted(list(landmark_ids))\n", + "print(f\"Read {K} range triples for {len(landmark_ids)} unique landmarks.\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Set Parameters and Noise Models" + ] + }, + { + "cell_type": "code", + "execution_count": 37, + "metadata": {}, + "outputs": [], + "source": [ + "# parameters\n", + "sigmaR = 50 # range standard deviation (matches MATLAB)\n", + "sigmaInitialLandmark = 1.0 # Stddev for random landmark init (matches MATLAB)\n", + "robust = True" + ] + }, + { + "cell_type": "code", + "execution_count": 38, + "metadata": {}, + "outputs": [], + "source": [ + "# Set Noise parameters (mirrors MATLAB script)\n", + "priorSigmas = gtsam.Point3(1, 1, math.pi) # Prior on Pose 0\n", + "pointPriorSigmas = gtsam.Point2(1, 1) # Loose prior on landmarks\n", + "odoSigmas = gtsam.Point3(0.05, 0.01, 0.2) # Odometry noise\n", + "\n", + "priorNoise = NM.Diagonal.Sigmas(priorSigmas) # prior on pose 0\n", + "pointPriorNoise = NM.Diagonal.Sigmas(pointPriorSigmas) # loose LM prior\n", + "odoNoise = NM.Diagonal.Sigmas(odoSigmas) # odometry\n", + "\n", + "# Range noise\n", + "gaussian = NM.Isotropic.Sigma(1, sigmaR) # non-robust\n", + "base = NM.mEstimator.Tukey(15) # Tukey M-estimator like MATLAB\n", + "tukey = NM.Robust.Create(base, gaussian) # robust\n", + "rangeNoise = tukey if robust else gaussian" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Build Factor Graph and Initial Estimate" + ] + }, + { + "cell_type": "code", + "execution_count": 39, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Initializing Landmarks...\n", + "Initialized 4 landmarks.\n" + ] + } + ], + "source": [ + "# Initialize Factor Graph and Initial Values\n", + "graph = gtsam.NonlinearFactorGraph()\n", + "initial = gtsam.Values()\n", + "\n", + "# Add prior on first pose\n", + "# Estimate pose0 from the first odometry time's neighborhood or use a fixed reasonable guess.\n", + "# Using the same value as the iSAM example for consistency.\n", + "pose0 = Pose2(-34.2086489999201, 45.3007639991120, math.pi - 2.021089)\n", + "graph.add(gtsam.PriorFactorPose2(0, pose0, priorNoise))\n", + "initial.insert(0, pose0)\n", + "\n", + "# Initialize Landmarks (similar to MATLAB approach)\n", + "print(\"Initializing Landmarks...\")\n", + "for j in sorted_landmark_ids:\n", + " landmark_key = symbol('L', j)\n", + " # Initialize randomly around origin (adjust scale if needed)\n", + " initial_point = Point2(sigmaInitialLandmark * rng.normal(), sigmaInitialLandmark * rng.normal())\n", + " initial.insert(landmark_key, initial_point)\n", + " # Optional: Add a loose prior to help localization if landmarks are poorly constrained\n", + " # graph.add(gtsam.PriorFactorPoint2(landmark_key, Point2(0,0), pointPriorNoise))\n", + "print(f\"Initialized {len(sorted_landmark_ids)} landmarks.\")" + ] + }, + { + "cell_type": "code", + "execution_count": 40, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Building Pose Chain and Odometry Factors...\n", + "Added 4090 odometry factors and initial pose estimates.\n" + ] + } + ], + "source": [ + "print(\"\\nBuilding Pose Chain and Odometry Factors...\")\n", + "lastPose = pose0\n", + "pose_times = [odo_times_list[0]] # Approximate time for pose 0\n", + "# Loop over odometry measurements\n", + "for i, t in enumerate(odo_times_list, 1):\n", + " # get odometry measurement for this time step\n", + " odometry = odometry_data[t]\n", + "\n", + " # add odometry factor\n", + " graph.add(gtsam.BetweenFactorPose2(i - 1, i, odometry, odoNoise))\n", + "\n", + " # predict pose and add as initial estimate\n", + " predictedPose = lastPose.compose(odometry)\n", + " lastPose = predictedPose\n", + " initial.insert(i, predictedPose)\n", + " pose_times.append(t)\n", + "\n", + "print(f\"Added {M} odometry factors and initial pose estimates.\")" + ] + }, + { + "cell_type": "code", + "execution_count": 41, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Adding Range Factors...\n", + "Added 1816 range factors.\n" + ] + } + ], + "source": [ + "print(\"\\nAdding Range Factors...\")\n", + "# Convert pose_times to numpy array for efficient search\n", + "pose_times_np = np.array(pose_times)\n", + "\n", + "# Add range factors\n", + "range_factors_added = 0\n", + "for t_range, landmark_id, measured_range in triples:\n", + " # Find the pose index active at the time of the range measurement\n", + " # Get the index of the *last* pose time that is <= t_range\n", + " pose_index = np.searchsorted(pose_times_np, t_range, side='right') - 1\n", + " \n", + " # Ensure pose_index is valid (it might be -1 if t_range is before the first odometry time)\n", + " if pose_index < 0:\n", + " # print(f\"Warning: Range measurement at time {t_range} is before the first pose time {pose_times_np[0]}. Skipping.\")\n", + " pose_index = 0 # Or skip the measurement\n", + "\n", + " landmark_key = symbol('L', landmark_id)\n", + " graph.add(gtsam.RangeFactor2D(pose_index, landmark_key, measured_range, rangeNoise))\n", + " range_factors_added += 1\n", + "\n", + "print(f\"Added {range_factors_added} range factors.\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Optimize the Factor Graph" + ] + }, + { + "cell_type": "code", + "execution_count": 42, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Optimizing the factor graph...\n", + "Initial error: 2.9e+02, values: 4095\n", + "iter cost cost_change lambda success iter_time\n", + " 0 1.4e+05 -1.4e+05 1e-05 1 0.03\n", + "iter cost cost_change lambda success iter_time\n", + " 0 9.1e+03 -8.8e+03 0.0001 1 0.03\n", + "iter cost cost_change lambda success iter_time\n", + " 0 1.9e+02 1e+02 0.001 1 0.03\n", + " 1 2.7e+03 -2.5e+03 0.0001 1 0.03\n", + " 1 1.1e+02 86 0.001 1 0.02\n", + " 2 1.7e+03 -1.6e+03 0.0001 1 0.02\n", + " 2 85 22 0.001 1 0.03\n", + " 3 6.3e+02 -5.5e+02 0.0001 1 0.03\n", + " 3 76 8.4 0.001 1 0.02\n", + " 4 3.1e+02 -2.3e+02 0.0001 1 0.02\n", + " 4 68 8.6 0.001 1 0.03\n", + " 5 1.9e+02 -1.2e+02 0.0001 1 0.03\n", + " 5 55 13 0.001 1 0.03\n", + " 6 2.6e+02 -2e+02 0.0001 1 0.02\n", + " 6 39 16 0.001 1 0.02\n", + " 7 1.4e+02 -99 0.0001 1 0.04\n", + " 7 26 13 0.001 1 0.03\n", + " 8 94 -68 0.0001 1 0.03\n", + " 8 21 5.5 0.001 1 0.03\n", + " 9 63 -43 0.0001 1 0.02\n", + " 9 19 2.1 0.001 1 0.02\n", + " 10 46 -27 0.0001 1 0.02\n", + " 10 17 1.8 0.001 1 0.03\n", + " 11 35 -18 0.0001 1 0.03\n", + " 11 15 1.5 0.001 1 0.03\n", + " 12 27 -12 0.0001 1 0.03\n", + " 12 14 1.3 0.001 1 0.02\n", + " 13 22 -7.9 0.0001 1 0.02\n", + " 13 13 1.2 0.001 1 0.03\n", + " 14 18 -5.2 0.0001 1 0.03\n", + " 14 12 1 0.001 1 0.03\n", + " 15 15 -3.3 0.0001 1 0.03\n", + " 15 11 0.9 0.001 1 0.02\n", + " 16 13 -2 0.0001 1 0.02\n", + " 16 10 0.79 0.001 1 0.04\n", + " 17 11 -1.1 0.0001 1 0.03\n", + " 17 9.3 0.7 0.001 1 0.03\n", + " 18 9.8 -0.44 0.0001 1 0.03\n", + " 18 8.7 0.62 0.001 1 0.02\n", + " 19 8.7 0.023 0.0001 1 0.02\n", + " 20 67 -58 1e-05 1 0.02\n", + " 20 5 3.7 0.0001 1 0.03\n", + " 21 23 -18 1e-05 1 0.03\n", + " 21 3.5 1.4 0.0001 1 0.03\n", + " 22 9.4 -5.9 1e-05 1 0.03\n", + " 22 3 0.57 0.0001 1 0.03\n", + " 23 5 -2 1e-05 1 0.03\n", + " 23 2.6 0.34 0.0001 1 0.02\n", + " 24 3.3 -0.71 1e-05 1 0.02\n", + " 24 2.4 0.26 0.0001 1 0.03\n", + " 25 2.6 -0.19 1e-05 1 0.03\n", + " 25 2.2 0.21 0.0001 1 0.03\n", + " 26 2.1 0.034 1e-05 1 0.03\n", + " 27 3.7 -1.5 1e-06 1 0.03\n", + " 27 1.1 1 1e-05 1 0.02\n", + " 28 1.4 -0.24 1e-06 1 0.04\n", + " 28 0.93 0.2 1e-05 1 0.03\n", + " 29 0.96 -0.031 1e-06 1 0.04\n", + " 29 0.88 0.048 1e-05 1 0.09\n", + " 30 0.88 0.00063 1e-06 1 0.03\n", + "Optimization complete in 1.93 seconds.\n", + "Initial Error: 294.2927831483431\n", + "Final Error: 0.8771120075818397\n" + ] + } + ], + "source": [ + "# Graph built, optimize!\n", + "print(\"\\nOptimizing the factor graph...\")\n", + "start_time = time.time()\n", + "\n", + "params = gtsam.LevenbergMarquardtParams()\n", + "params.setRelativeErrorTol(1e-3) # Convergence tolerance\n", + "params.setVerbosityLM(\"SUMMARY\") # Print LM progress\n", + "optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initial, params)\n", + "result = optimizer.optimize()\n", + "\n", + "end_time = time.time()\n", + "print(f\"Optimization complete in {end_time - start_time:.2f} seconds.\")\n", + "\n", + "print(f\"Initial Error: {graph.error(initial)}\")\n", + "print(f\"Final Error: {graph.error(result)}\")" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Print and Visualize Results" + ] + }, + { + "cell_type": "code", + "execution_count": 43, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Optimized Landmark Locations:\n", + " L0: [-48.11741249 31.92467992]\n", + " L1: [-80.92811295 53.95372591]\n", + " L5: [-47.60339748 -19.97294509]\n", + " L6: [-17.70157972 66.35356579]\n" + ] + } + ], + "source": [ + "# Print optimized landmarks:\n", + "print(\"\\nOptimized Landmark Locations:\")\n", + "for j in [0, 1, 5, 6]: # Print specific landmarks like MATLAB example\n", + " if j in sorted_landmark_ids:\n", + " landmark_key = gtsam.symbol('L', j)\n", + " try:\n", + " p = result.atPoint2(landmark_key)\n", + " print(f\" L{j}: {p}\")\n", + " except Exception as e:\n", + " print(f\" L{j}: Not found in result ({e})\")\n", + " else:\n", + " print(f\" L{j}: Not present in TD data.\")" + ] + }, + { + "cell_type": "code", + "execution_count": 44, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "Extracted 4091 final poses and 4 landmarks.\n" + ] + } + ], + "source": [ + "# Extract poses and landmarks for plotting\n", + "poses_result = gtsam.utilities.allPose2s(result)\n", + "landmarks_result = gtsam.utilities.extractPoint2(result)\n", + "positions_result = np.array([poses_result.atPose2(key).translation() \n", + " for key in range(M + 1)]) # Poses 0 to M\n", + "\n", + "# Also extract initial estimate poses (dead reckoning)\n", + "poses_initial = gtsam.utilities.allPose2s(initial)\n", + "positions_initial = np.array([poses_initial.atPose2(key).translation() \n", + " for key in range(M + 1)])\n", + "\n", + "print(f\"\\nExtracted {positions_result.shape[0]} final poses and {landmarks_result.shape[0]} landmarks.\")" + ] + }, + { + "cell_type": "code", + "execution_count": 45, + "metadata": {}, + "outputs": [ + { + "data": { + "application/vnd.plotly.v1+json": { + "config": { + "plotlyServerURL": "https://plot.ly" + }, + "data": [ + { + "hovertemplate": "x=%{x}
y=%{y}", + "legendgroup": "", + "line": { + "color": "orange", + "dash": "dash" + }, + "marker": { + "symbol": "circle" + }, + "mode": "lines", + "name": "Initial (Odometry)", + "showlegend": true, + "type": "scattergl", + "x": [ + -34.2086489999201, + -34.20836979114683, + -34.20803935150894, + -34.20769664906428, + -34.20745757618519, + -34.2072636737919, + -34.206871418836954, + -34.20652199326485, + -34.20607696027076, + -34.205693383659714, + -34.20533156377815, + -34.204892040863555, + -34.20443556553866, + -34.20406134318224, + -34.20369032546497, + -34.20324242046013, + -34.2028270923351, + -34.202401863245235, + -34.20211269566228, + -34.20181979427049, + -34.201513804257694, + -34.20117029955497, + -34.20088007284221, + -34.20055009106879, + -34.200260116503095, + -34.19994897517169, + -34.19965523173816, + -34.1994029041421, + -34.19916888715277, + -34.19891245015342, + -34.198715504014366, + -34.198516605035955, + -34.198300798597955, + -34.19809721116232, + -34.197847106023076, + -34.197616437411, + -34.19741625511224, + -34.19724568345311, + -34.19704074569196, + -34.196818813999705, + -34.19666639679551, + -34.196460828100484, + -34.19619001400819, + -34.19604445943367, + -34.195910099362145, + -34.195755878773745, + -34.195558457347744, + -34.19541386029135, + -34.19525845476768, + -34.195067762056134, + -34.19489202116206, + -34.194681037789806, + -34.19447308653113, + -34.194309983073204, + -34.194140694618234, + -34.193972484438326, + -34.19377363038148, + -34.19360766124274, + -34.193492948625305, + -34.193314314602674, + -34.19319298281816, + -34.193028166699094, + -34.192849816083694, + -34.192715762273835, + -34.19257117294791, + -34.192404794783975, + -34.19224973021514, + -34.19189970002379, + -34.19142560164526, + -34.19099330407322, + -34.19057835092971, + -34.19007616240848, + -34.18953374612769, + -34.189050443833295, + -34.18859249871435, + -34.18808208875446, + -34.1875097433046, + -34.187116421986346, + -34.186701972454124, + -34.18624728134878, + -34.185900489807125, + -34.18548519298773, + -34.18497648157919, + -34.184570210732886, + -34.18418266111367, + -34.18366528807, + -34.183184605808485, + -34.182655318225876, + -34.18204098183132, + -34.181444224279026, + -34.1808558113075, + -34.180306857899545, + -34.17974224332086, + -34.179135613546975, + -34.17856989124421, + -34.178002666401895, + -34.17746545979827, + -34.17695023904937, + -34.17657966394335, + -34.17624797721639, + -34.175808057015416, + -34.17538755257384, + -34.1750932929447, + -34.17476769039568, + -34.174492745418206, + -34.174075265157256, + -34.17359930392376, + -34.173248293211714, + -34.17282818575748, + -34.172410770058576, + -34.17200077254057, + -34.1715057852681, + -34.17104567882294, + -34.170667399995736, + -34.17025167380646, + -34.16980106362279, + -34.16931404150385, + -34.16882563482927, + -34.16847743114282, + -34.16813510653869, + -34.16769314049209, + -34.167227624631856, + -34.166829863331756, + -34.1664785535197, + -34.16604401130713, + -34.165566556343066, + -34.165109316771826, + -34.16476249923186, + -34.16450996370322, + -34.16408493938013, + -34.16363029112971, + -34.163331385529496, + -34.16296198386089, + -34.162463869803254, + -34.16214816634397, + -34.161631085622886, + -34.161302187143136, + -34.16100137657189, + -34.160822134943274, + -34.160415997863666, + -34.159983933185096, + -34.1597828337861, + -34.15945735797657, + -34.159069758030675, + -34.15866974752631, + -34.15819360352863, + -34.1577795637878, + -34.15746363077512, + -34.157007863571756, + -34.156346569946464, + -34.156033467642835, + -34.15572418456727, + -34.15529562345149, + -34.15483426815585, + -34.15444066159739, + -34.15415165343272, + -34.153924092755815, + -34.15374222490916, + -34.15333378170154, + -34.152980543941716, + -34.15275576775464, + -34.15250878222005, + -34.15210234719164, + -34.15158887094889, + -34.150879094911026, + -34.150549449264666, + -34.15023150221575, + -34.14965775724086, + -34.14878283559801, + -34.147538049517955, + -34.14667809897801, + -34.14597214139117, + -34.1449514164539, + -34.14387983516139, + -34.142902780048296, + -34.141937345351444, + -34.14095717101974, + -34.140035894746084, + -34.13911887932081, + -34.138148130768094, + -34.13724796551392, + -34.13636077183942, + -34.135412316421636, + -34.13442167349488, + -34.133499345275744, + -34.132509291074356, + -34.13151555638633, + -34.13072016437912, + -34.13006697028636, + -34.12932258882978, + -34.128457114669565, + -34.12757891903413, + -34.12675241902658, + -34.126139745144805, + -34.125424802483835, + -34.12458065380563, + -34.123798126920676, + -34.123098810690834, + -34.12257935830928, + -34.121925358944544, + -34.12105307672232, + -34.12049814794496, + -34.11987641787605, + -34.119130646124795, + -34.11816619787505, + -34.11659424160666, + -34.115608399386204, + -34.11412505344007, + -34.112756498364945, + -34.11143146952295, + -34.10740970711347, + -34.09949525754063, + -34.085656725623295, + -34.064029399092696, + -34.03368048175308, + -33.99553758936172, + -33.95340379062459, + -33.91236348602576, + -33.87800850917465, + -33.85056141800388, + -33.83058697132261, + -33.81565087648537, + -33.8049444491882, + -33.79752120559333, + -33.79099347717986, + -33.783043586462696, + -33.771410205893524, + -33.75224737940923, + -33.724723788759974, + -33.68828786358715, + -33.64238941373633, + -33.58724581318574, + -33.52341612905129, + -33.45038760071136, + -33.36755811978665, + -33.27374271186554, + -33.16795942535702, + -33.05070864404693, + -32.923962785451714, + -32.78888634928476, + -32.64315675634603, + -32.48367840897058, + -32.31441810159456, + -32.13596313043152, + -31.949435410057255, + -31.75114254781883, + -31.543629748980248, + -31.329411925613236, + -31.09992094177584, + -30.864274315589554, + -30.623736251301526, + -30.367808967460086, + -30.105392697296736, + -29.83578637866801, + -29.56230885492452, + -29.27975885528539, + -28.992999595104262, + -28.71312459191392, + -28.42724633519638, + -28.137767487979648, + -27.851560922928158, + -27.566770900225954, + -27.278683483004144, + -26.99787632255226, + -26.724396432763083, + -26.455175707897624, + -26.188565191864626, + -25.930075902409982, + -25.689501249129936, + -25.448340743431032, + -25.211526485546386, + -25.009803441735496, + -24.807447165750766, + -24.610989417765634, + -24.42995646453449, + -24.257893036665816, + -24.0962655892048, + -23.939813766971866, + -23.785188463141555, + -23.64708304417443, + -23.512520266968043, + -23.376751262029757, + -23.254752370972582, + -23.13742752911834, + -23.01995921198726, + -22.910574875820885, + -22.809344622794356, + -22.71317181234873, + -22.619507532029218, + -22.531519207941866, + -22.449978646212163, + -22.373832177497228, + -22.304127240580957, + -22.23823689915115, + -22.17693091756414, + -22.124225918965703, + -22.07695602632899, + -22.031931398110828, + -21.989307820101615, + -21.950083211647588, + -21.910462943189394, + -21.867609092975304, + -21.82625754897879, + -21.78646587326728, + -21.746208522646977, + -21.705243463354428, + -21.667515584399062, + -21.62887810665828, + -21.586339021035123, + -21.54498217834841, + -21.50613878979132, + -21.46468713528134, + -21.422628128270116, + -21.381494411838712, + -21.338363098912186, + -21.295671232801663, + -21.2517648377332, + -21.209440777853917, + -21.16629088618545, + -21.12212193411109, + -21.079305963402135, + -21.035026940876488, + -20.988806156340544, + -20.938972364221645, + -20.890580380571773, + -20.840388844467203, + -20.78615161846691, + -20.729836241071755, + -20.670402780757634, + -20.609787505781618, + -20.546402957679422, + -20.480120171609556, + -20.41198830792046, + -20.341235516317333, + -20.268538456087622, + -20.194194955267772, + -20.117301900801706, + -20.036731061186252, + -19.95468505013031, + -19.868699134763833, + -19.77462426493531, + -19.67986282301832, + -19.581995761257062, + -19.47466325395279, + -19.36273362009527, + -19.248791232362585, + -19.12450696171867, + -18.995796013658993, + -18.862174198065357, + -18.72074076298342, + -18.576806843799996, + -18.4249629947287, + -18.262822742914462, + -18.098040162588983, + -17.92699900601009, + -17.743514170132606, + -17.560493449686934, + -17.372015377233666, + -17.17238149097355, + -16.97541110912954, + -16.776237703761932, + -16.568977338492545, + -16.36389486671192, + -16.159994671884743, + -15.947954387898216, + -15.735828175092163, + -15.530840738447175, + -15.322367537110173, + -15.114473275527201, + -14.908864616675404, + -14.703632643001981, + -14.493620207990459, + -14.283429922868448, + -14.073735470071078, + -13.864882478884011, + -13.653542855632638, + -13.446157017298724, + -13.240450308445956, + -13.03254888534216, + -12.82879238721366, + -12.625931022837921, + -12.420423880877294, + -12.218858416409285, + -12.022165537372443, + -11.825676906596087, + -11.634856193821676, + -11.451732356842388, + -11.247230541528497, + -11.060952984643725, + -10.880935755346197, + -10.702858414999122, + -10.525433949694676, + -10.351124648376633, + -10.181752064538339, + -10.012534030906886, + -9.848038552982812, + -9.686901678027139, + -9.526765307236076, + -9.371758097898878, + -9.215264971070289, + -9.059261042177, + -8.906756953593783, + -8.755843071943021, + -8.605294735699728, + -8.463275783481409, + -8.329190931335454, + -8.19369233294814, + -8.0692156189969, + -7.957216438928777, + -7.847220752904937, + -7.747069786469661, + -7.660310444789812, + -7.579305780836443, + -7.509036127875443, + -7.452017387410774, + -7.405222753283836, + -7.372073035485067, + -7.351642614806359, + -7.343177466094715, + -7.347361197476441, + -7.365735556099691, + -7.399156885256334, + -7.445360657763755, + -7.508776765471713, + -7.5927583213542436, + -7.691455380855894, + -7.807186907221394, + -7.940512252030794, + -8.093125828074614, + -8.269604259222355, + -8.473507609030213, + -8.684597260765347, + -8.90762400264664, + -9.158369270369137, + -9.414517782519223, + -9.676485984615962, + -9.969182915609869, + -10.266655713459462, + -10.55807520953602, + -10.866789682755009, + -11.18402793906773, + -11.502005862565333, + -11.825750159204869, + -12.149457350470596, + -12.471233265292803, + -12.798585381492586, + -13.122099173279063, + -13.443047334476752, + -13.76471032475758, + -14.083597315288468, + -14.398595030817017, + -14.715489513179412, + -15.024865561808635, + -15.33263427801308, + -15.640571566341688, + -15.941612412184652, + -16.24040289031909, + -16.539924732517363, + -16.83590412247988, + -17.131319977153872, + -17.428339650906224, + -17.72867730697316, + -18.029332598697753, + -18.33273157445459, + -18.638847939348018, + -18.949488962162466, + -19.26412009371686, + -19.586822101861458, + -19.923017274196553, + -20.261872661811843, + -20.603947245474316, + -20.958966844932917, + -21.314551872621777, + -21.667166798469715, + -22.032699596753904, + -22.411522053759192, + -22.776362008833686, + -23.15208156156842, + -23.546676852918527, + -23.92067875520956, + -24.308761843228947, + -24.71190798064512, + -25.09792435154741, + -25.497564826276022, + -25.90868675985076, + -26.29742349166464, + -26.694454583952325, + -27.099808943673086, + -27.47666241999062, + -27.855645950507423, + -28.260841892246933, + -28.65141831699363, + -29.02798499263422, + -29.429967515377168, + -29.828877112257004, + -30.20623374775589, + -30.60346100788182, + -31.00593668328393, + -31.39048611841581, + -31.782926405143584, + -32.17868413738589, + -32.55977264296768, + -32.94512410748157, + -33.330915742264054, + -33.712635519621315, + -34.097676707286155, + -34.482474934446415, + -34.86477834110895, + -35.25316252077966, + -35.63979801719962, + -36.02925966667758, + -36.42024268506567, + -36.81612541766959, + -37.208494830948204, + -37.59953258183762, + -37.98948836224458, + -38.373589535086744, + -38.749522301219656, + -39.124013397388076, + -39.49760288322387, + -39.87450057054848, + -40.258518113709755, + -40.648739126828815, + -41.03870038319137, + -41.42704450655007, + -41.81274057712025, + -42.19515301354295, + -42.58488833284426, + -42.97668394398382, + -43.364210178023065, + -43.739919223387076, + -44.11079386997858, + -44.48257316394245, + -44.85321160432007, + -45.22495996659519, + -45.59262925672443, + -45.96279446238195, + -46.33399343312924, + -46.69162151604925, + -47.05013773412914, + -47.41892127042934, + -47.77831689057106, + -48.136030253455665, + -48.49888236769298, + -48.86349611699248, + -49.22108678260273, + -49.57570642648424, + -49.92947036109773, + -50.274706538797254, + -50.614965488147575, + -50.964947802491984, + -51.309516044623926, + -51.64395595262953, + -51.98688538713852, + -52.325034614501384, + -52.64536286364738, + -52.97776600605042, + -53.305485485769815, + -53.622106066193076, + -53.951384822826775, + -54.28100594529425, + -54.59527919871606, + -54.92252186474323, + -55.2477175995997, + -55.560303894522775, + -55.88723007893267, + -56.20939312176507, + -56.517615020186284, + -56.83462644280102, + -57.14058455681063, + -57.44433310644948, + -57.755042297251784, + -58.06127286099091, + -58.365787223773054, + -58.67240778062577, + -58.97278734814268, + -59.27134758243663, + -59.57953972712718, + -59.87675130379625, + -60.17840020009142, + -60.479121813545, + -60.76066281110613, + -61.04257603044654, + -61.32028234240231, + -61.571288303886206, + -61.82421304542558, + -62.07176949083373, + -62.29703239472938, + -62.514855841875956, + -62.72351165643634, + -62.91782612832176, + -63.09626044458709, + -63.265265498296955, + -63.42286360637691, + -63.566943502258184, + -63.700676684767984, + -63.82163068824623, + -63.93594093491176, + -64.04396315960943, + -64.1399152615282, + -64.22602688025769, + -64.3032687295051, + -64.37286672176609, + -64.4351265593657, + -64.48754224501491, + -64.53452306913441, + -64.57779542218493, + -64.61262474702409, + -64.63642641850628, + -64.65019798608247, + -64.65498179041354, + -64.6497146978355, + -64.6326206448963, + -64.60518713668186, + -64.56885384104137, + -64.52097117513405, + -64.45955652984058, + -64.38451814775523, + -64.29060293682289, + -64.17992812807096, + -64.05966390630117, + -63.925508546901916, + -63.77516028982094, + -63.61034033759696, + -63.4293737384692, + -63.23581452479093, + -63.031021619411845, + -62.81225115151607, + -62.583839788194865, + -62.34866864499496, + -62.09789634574366, + -61.83290019315182, + -61.56162483680962, + -61.28536659815268, + -60.99522104250729, + -60.69968775906392, + -60.42085119471336, + -60.1283188169592, + -59.819008645838885, + -59.53076491571798, + -59.23751466372139, + -58.91497230190822, + -58.60748762278332, + -58.30400734584279, + -57.97467245220812, + -57.654106742048384, + -57.33625888903485, + -57.00259227257815, + -56.674841483157955, + -56.35305374687847, + -56.02553718554206, + -55.702262112283556, + -55.3814721540694, + -55.05688954508452, + -54.73009699822438, + -54.406255577449514, + -54.08167634282728, + -53.76221867258252, + -53.44485768106943, + -53.13219728048551, + -52.81457574298221, + -52.503015569422374, + -52.189251770484056, + -51.87343074646113, + -51.56389404627859, + -51.26344155270778, + -50.95358319162299, + -50.66424018599097, + -50.384498177485725, + -50.09160927167098, + -49.812435968513945, + -49.532124266908106, + -49.238984228217916, + -48.95738046395134, + -48.67661571585529, + -48.35937981335118, + -48.076640185916744, + -47.79767229534073, + -47.50863977716664, + -47.21210993114214, + -46.9237025968253, + -46.634090376746094, + -46.336014867755594, + -46.04330953357996, + -45.75715272138405, + -45.46276075279872, + -45.16733514294459, + -44.87774275444449, + -44.58033268485854, + -44.28107050649222, + -43.99194096366448, + -43.70134796782298, + -43.412659024856765, + -43.13559484747741, + -42.85286754474855, + -42.574171057790586, + -42.2980238735172, + -42.01551175653316, + -41.72762840582466, + -41.433042978584986, + -41.14015786685668, + -40.84172003708187, + -40.53104176574113, + -40.213813602199096, + -39.89309565909701, + -39.57014806376517, + -39.244171495856754, + -38.915987784882, + -38.58934801406164, + -38.272128932215665, + -37.9574687989562, + -37.63743254921885, + -37.32073864769026, + -37.00818203440748, + -36.68917419502268, + -36.366818137408664, + -36.04611012514127, + -35.72653438453104, + -35.408492517158194, + -35.073714926966915, + -34.746377234386735, + -34.42955066989188, + -34.09223102852332, + -33.75484965456418, + -33.445829076672325, + -33.11552897191394, + -32.77037994873269, + -32.44992703279743, + -32.12502826021245, + -31.778207451202064, + -31.447701203771487, + -31.14246155537935, + -30.80809149890923, + -30.466156203951886, + -30.14728339242797, + -29.807374072655794, + -29.45731418587252, + -29.12235329034721, + -28.776342357177302, + -28.432661774193978, + -28.093522680701145, + -27.75150758606779, + -27.40818939678314, + -27.07608526011534, + -26.737157023012063, + -26.406410594476682, + -26.08971609110852, + -25.75672148863116, + -25.423141857524186, + -25.105838163229688, + -24.787731148602155, + -24.46920132865978, + -24.159634778771718, + -23.86297868393125, + -23.566174282178487, + -23.28606418943286, + -23.022583879609392, + -22.761391232675397, + -22.5071206699873, + -22.27328754880599, + -22.042892722522282, + -21.816476176435494, + -21.605541375580295, + -21.39690581411838, + -21.20139429916033, + -21.018535678533095, + -20.842962364245956, + -20.681382851286852, + -20.53259405197908, + -20.395943983475348, + -20.270092149571834, + -20.15678453921385, + -20.054496019842436, + -19.96021401192574, + -19.87451420907953, + -19.796616008695267, + -19.72654075407966, + -19.664238258442694, + -19.6070255660196, + -19.555416051879025, + -19.510398075787894, + -19.47009575583654, + -19.43334999192826, + -19.400534848988084, + -19.369130813601668, + -19.339743557596968, + -19.313852629320575, + -19.28879200496297, + -19.263592162642702, + -19.241102160584422, + -19.220401767732763, + -19.19955127727777, + -19.17789277396974, + -19.157745103413344, + -19.13944712783892, + -19.12140771540347, + -19.104128716144565, + -19.087530801150898, + -19.071959241824285, + -19.056826020635853, + -19.041259733635773, + -19.025089282415408, + -19.008470458905915, + -18.992073479289715, + -18.975470727857175, + -18.958654544359934, + -18.94150962275529, + -18.923880162808086, + -18.905630551124812, + -18.88867845388129, + -18.87195186841717, + -18.855656173513683, + -18.838576376643513, + -18.821760920458527, + -18.80507873057346, + -18.786936283588805, + -18.768366418163772, + -18.751573547862648, + -18.7356535042555, + -18.721027682078418, + -18.708265908634843, + -18.697327682769227, + -18.68811769529859, + -18.682554474080927, + -18.680346272120985, + -18.680177332852963, + -18.68265591665324, + -18.69014605814047, + -18.701475586703168, + -18.71521800274297, + -18.732826158150633, + -18.75601256492638, + -18.78365036264507, + -18.8154452722153, + -18.852149822657232, + -18.89369469436917, + -18.934430685455094, + -18.977897048149778, + -19.02228713257116, + -19.066346439718593, + -19.111481910157305, + -19.157756815679925, + -19.2043070603169, + -19.249380310411922, + -19.295460499803077, + -19.3393994393193, + -19.38141214866904, + -19.425552390510045, + -19.473016557213317, + -19.52186987369341, + -19.569739838061423, + -19.61794840606325, + -19.6679099624962, + -19.71844726490396, + -19.771637738164948, + -19.82470445124085, + -19.879312172256398, + -19.934177990580114, + -19.986597680985927, + -20.039480863754484, + -20.09230662741227, + -20.14534830578189, + -20.19798657030222, + -20.251622289749257, + -20.306095188670973, + -20.363846306660687, + -20.414516043851275, + -20.465518298521012, + -20.515465566980836, + -20.561836183562683, + -20.603053318393517, + -20.641846957654924, + -20.67675711657683, + -20.707382977366915, + -20.733585257799767, + -20.754546746502523, + -20.769722502433204, + -20.77746589489218, + -20.779074056307735, + -20.774396629799046, + -20.764224608688664, + -20.75026863278645, + -20.732003495366133, + -20.710344145930513, + -20.68469101797568, + -20.654597128865635, + -20.622065177647716, + -20.58665237991359, + -20.5454917546794, + -20.5009018255594, + -20.453813816927212, + -20.3999210465216, + -20.34278601093995, + -20.284286124896127, + -20.218975731612954, + -20.152708559242253, + -20.088978293827637, + -20.01323095299503, + -19.939426652328745, + -19.86739686010645, + -19.79247723956603, + -19.708606351768413, + -19.626406400347683, + -19.54240362614865, + -19.453693918647424, + -19.365521774108203, + -19.27650134867682, + -19.18510298124001, + -19.09212417154239, + -18.997033635222746, + -18.900438430035134, + -18.802858904701715, + -18.702046619281894, + -18.598910212516117, + -18.495508656721444, + -18.39072501995874, + -18.28447531955079, + -18.178582345736874, + -18.076410428925655, + -17.97165282444552, + -17.86765844756164, + -17.76545154440105, + -17.661242458286257, + -17.557836728725114, + -17.454912303802896, + -17.353945706767032, + -17.25537006259427, + -17.160229526963754, + -17.065919351409473, + -16.971618903822495, + -16.878661620156794, + -16.78779282169796, + -16.698497862155378, + -16.61077079014498, + -16.525904850869782, + -16.442780550088887, + -16.360498988663544, + -16.281534726796973, + -16.206802340143952, + -16.133778928416323, + -16.062264166852707, + -15.993049059317531, + -15.92822979090142, + -15.863879618921702, + -15.799875703306611, + -15.736119217937642, + -15.674630374813349, + -15.614840434623366, + -15.547444349619692, + -15.487395638825438, + -15.432527121648045, + -15.381583812586285, + -15.334598123540111, + -15.293450115453636, + -15.259856994555934, + -15.233690619946962, + -15.21494153246387, + -15.203634558837665, + -15.201154380910786, + -15.209078670416062, + -15.225359092081764, + -15.250002036936612, + -15.284649538139242, + -15.327522593153994, + -15.380709985912155, + -15.44573848269761, + -15.519353051247695, + -15.604559990183146, + -15.702240879132068, + -15.811527701771865, + -15.933654783769107, + -16.071140021074356, + -16.221391811186244, + -16.389188603052308, + -16.570479788727262, + -16.764117128990062, + -16.9692948221372, + -17.189413386956197, + -17.432762157106843, + -17.681107670345288, + -17.932541135233734, + -18.21091660629076, + -18.498191364237368, + -18.78330636844814, + -19.08406975623124, + -19.393422112588933, + -19.698910108159087, + -20.01584816113684, + -20.33382844384227, + -20.64163741949853, + -20.955675612409408, + -21.2687763371419, + -21.566485067367573, + -21.859561974408624, + -22.1502341727436, + -22.42348529997479, + -22.69551795661861, + -22.96438927676706, + -23.215573834652048, + -23.46244839926611, + -23.704584665809353, + -23.930505606997098, + -24.150451705189653, + -24.365190008980353, + -24.5699314676053, + -24.76780132169323, + -24.9620925332786, + -25.152068297062918, + -25.336977122245695, + -25.520267517466507, + -25.702857737051826, + -25.886034594401092, + -26.07282477580728, + -26.263584887429488, + -26.46099862005774, + -26.661902468778145, + -26.866393400065217, + -27.075049483206225, + -27.285808865637744, + -27.50052801073749, + -27.71933669622049, + -27.941760780363364, + -28.171142171861774, + -28.403646992785575, + -28.63741550040471, + -28.88240210565768, + -29.12706791493376, + -29.372781377653563, + -29.62024863079779, + -29.88034754011355, + -30.14178729354976, + -30.396276067264644, + -30.669073320253485, + -30.946319514409478, + -31.21186178660606, + -31.488190575329675, + -31.779675322644817, + -32.06103461148627, + -32.34824070984298, + -32.65050665257917, + -32.9430373739719, + -33.23319583733999, + -33.535798533110025, + -33.83685624268183, + -34.13320508363247, + -34.4353164638501, + -34.744494359853, + -35.05140883901183, + -35.3582604085396, + -35.66826458626864, + -35.983572628096425, + -36.294097318226406, + -36.605853544426914, + -36.926992330684705, + -37.24610367189432, + -37.560138397490675, + -37.87888945497262, + -38.20281110243761, + -38.51529346900825, + -38.82348631293479, + -39.1382453334092, + -39.44136154185805, + -39.74276489287358, + -40.04702673125926, + -40.34663653188699, + -40.64638782270767, + -40.94445094060477, + -41.23703448331536, + -41.53229260851288, + -41.830827041690725, + -42.12370450766311, + -42.416638243414454, + -42.709962427881, + -42.99753716100533, + -43.282364958524965, + -43.56671769411638, + -43.84306194611597, + -44.111269220469495, + -44.38328890038548, + -44.645007505848994, + -44.906834025243484, + -45.17353352395579, + -45.439187669545255, + -45.70266112832891, + -45.97349090158788, + -46.24170051178181, + -46.501858146120476, + -46.76200338762441, + -47.02328154783815, + -47.27692660393374, + -47.53078240405272, + -47.78599818368028, + -48.03098356520449, + -48.26909335009252, + -48.5082370295951, + -48.745697031594425, + -48.97781630309095, + -49.21609489615746, + -49.453754710454845, + -49.684993713303136, + -49.91756206913763, + -50.14892747822964, + -50.37055342338956, + -50.59324272015816, + -50.816585275357596, + -51.03522073520233, + -51.24834950164259, + -51.46127850930465, + -51.673863210934066, + -51.88460858481911, + -52.09273802026191, + -52.30054630881307, + -52.50850356230636, + -52.71424803446304, + -52.917419956162234, + -53.122994929547055, + -53.3309545468346, + -53.53399739045991, + -53.73599752841803, + -53.939986289299156, + -54.140533778272065, + -54.332037144773864, + -54.52668695660694, + -54.72146496905921, + -54.90905918977328, + -55.0981800450627, + -55.29026683617076, + -55.47771589077422, + -55.66216999199799, + -55.851364138906796, + -56.03585121878141, + -56.214831744774074, + -56.39995271236985, + -56.58363705134989, + -56.75950712573621, + -56.93740769051402, + -57.1168915145049, + -57.289572253638504, + -57.46225504210772, + -57.636166015598185, + -57.805786473358964, + -57.9741856105167, + -58.14490703259626, + -58.313466825129346, + -58.47824702472428, + -58.64230433592689, + -58.8079734251042, + -58.97014353929205, + -59.131911927271204, + -59.296136920002354, + -59.45520359036883, + -59.60741516527753, + -59.76135339865153, + -59.912205614653175, + -60.05150857415546, + -60.18664716926364, + -60.317502418270905, + -60.43957092631385, + -60.55499322597076, + -60.667636157341946, + -60.768427018784784, + -60.86241918672804, + -60.95030085618347, + -61.024580932148645, + -61.09090587621887, + -61.14914079411982, + -61.19924314482764, + -61.243621863530386, + -61.27924651122599, + -61.308987736621866, + -61.33646385694965, + -61.356871064629736, + -61.36829243965916, + -61.37162056962145, + -61.36834045637813, + -61.358295497544134, + -61.33973503069145, + -61.31174474146187, + -61.27589148248306, + -61.23023836809319, + -61.17731596195805, + -61.113512138554405, + -61.028649750219785, + -60.93001045593834, + -60.82384294482543, + -60.69624251216949, + -60.55972314880028, + -60.433607471193234, + -60.29474747995763, + -60.14437680918496, + -59.98755662017712, + -59.81625232872422, + -59.630092005090916, + -59.4384879071594, + -59.23985580283991, + -59.03086544552774, + -58.810565355578, + -58.56645955067877, + -58.31358558746552, + -58.05126619125516, + -57.77794229365562, + -57.492628781303466, + -57.196442861836466, + -56.904475931304425, + -56.60044398559001, + -56.28964708300861, + -55.97015556762816, + -55.643628494242414, + -55.31709111332235, + -54.97954037887618, + -54.64790045365633, + -54.317651966708176, + -53.982465937851956, + -53.64334996358776, + -53.312591895660155, + -52.971111887687975, + -52.6257337142858, + -52.29357659127428, + -51.95586437945262, + -51.60919991098627, + -51.26137741673533, + -50.91082793198764, + -50.55143459403899, + -50.191092358689446, + -49.828981026510405, + -49.46307985264355, + -49.100211002516204, + -48.72549656212283, + -48.344906692079725, + -47.96754912365586, + -47.582986526218306, + -47.1931479496242, + -46.805680961076334, + -46.417212011564004, + -46.02552259840897, + -45.639080269092474, + -45.24927459176417, + -44.8657141286857, + -44.48264988590599, + -44.091341587388044, + -43.70440152496862, + -43.326371335081944, + -42.93756005495286, + -42.55803152824457, + -42.1903664745427, + -41.80740101201049, + -41.438957033848, + -41.07750854574851, + -40.70295329029283, + -40.33943578167989, + -39.980772947505955, + -39.608478599421666, + -39.24615187109048, + -38.901931747594546, + -38.53476931078258, + -38.16549338446798, + -37.81401858826104, + -37.44533559265203, + -37.07068585727125, + -36.71589596720581, + -36.35336140466468, + -35.983587424183376, + -35.62689074078295, + -35.26379595055595, + -34.891830326257534, + -34.537016008039586, + -34.1874053880579, + -33.83597714224507, + -33.49500373020275, + -33.158504284874226, + -32.8288894003938, + -32.493755184990235, + -32.159574972343606, + -31.818825301923898, + -31.475467812069407, + -31.136281289512674, + -30.78935523168383, + -30.431421999563444, + -30.072031137636504, + -29.71609282391668, + -29.347830919658357, + -28.98622890885428, + -28.634312915719445, + -28.276106222720692, + -27.932279655314392, + -27.59773395312081, + -27.24587215336978, + -26.881798072009286, + -26.540917457373784, + -26.197509286650266, + -25.83553656836154, + -25.478593377686654, + -25.12989298445228, + -24.774320695924626, + -24.401670454355557, + -24.037421652994762, + -23.687067506611392, + -23.32705878057707, + -22.950423811741636, + -22.59592183223668, + -22.237037367621134, + -21.847983918721674, + -21.46939605343931, + -21.112800781158175, + -20.737673349532134, + -20.358806694038343, + -20.02009580585816, + -19.68095609086906, + -19.315993464740046, + -18.96930321847797, + -18.6307647327169, + -18.268324190475546, + -17.91788963138427, + -17.57342500397895, + -17.222244756522777, + -16.879332363613543, + -16.541466620741822, + -16.202772464928938, + -15.880068764244909, + -15.557220259294553, + -15.24072952564827, + -14.94019159380588, + -14.636066417794233, + -14.338861264876103, + -14.058549792275725, + -13.787132756761189, + -13.521315821055818, + -13.27643510934198, + -13.04636834840875, + -12.823762818203749, + -12.628358179469453, + -12.449217283160127, + -12.273583188616836, + -12.123268061812093, + -11.98703435908888, + -11.859319390730313, + -11.74861724994712, + -11.6512153114971, + -11.561833526473844, + -11.484745698728178, + -11.421838965178488, + -11.369843955080263, + -11.327488766542356, + -11.296131900010426, + -11.274797050244334, + -11.261901596663778, + -11.256313185591026, + -11.259614281391523, + -11.272134050044054, + -11.29400034356385, + -11.32230236191854, + -11.357576702821278, + -11.400628066401854, + -11.450635413938164, + -11.50520105835824, + -11.563180837625433, + -11.629685655187425, + -11.698675124714063, + -11.769936504488717, + -11.848240358620831, + -11.929867369897622, + -12.010760050168534, + -12.097512482866327, + -12.183385608408717, + -12.270780511880975, + -12.36365572795244, + -12.456489639953709, + -12.549005368335774, + -12.646141765232894, + -12.743051089847395, + -12.836905193032365, + -12.9345487600994, + -13.02984022921658, + -13.12291907495958, + -13.2174132710384, + -13.310069692007449, + -13.399205328955079, + -13.48773882522301, + -13.575833194274283, + -13.665087379027295, + -13.75291775229126, + -13.842459027864933, + -13.932315756903538, + -14.02184667456172, + -14.110717417770104, + -14.202385755977145, + -14.296337079503425, + -14.392231580873847, + -14.490265070609134, + -14.592781481421335, + -14.710021643707668, + -14.820510826764014, + -14.937318734613797, + -15.059614394723365, + -15.18468965697846, + -15.317302524132579, + -15.453820183251077, + -15.593608196508068, + -15.743427487693591, + -15.897111059648413, + -16.05149836661001, + -16.21660840683516, + -16.384021062618345, + -16.54230076541489, + -16.709550275147727, + -16.877126464877946, + -17.037462017848203, + -17.20263057702021, + -17.373701002666728, + -17.532423389450074, + -17.69101434767841, + -17.853090007971023, + -18.008745583263284, + -18.16424551966732, + -18.327362883142065, + -18.48893391110862, + -18.64435899971885, + -18.80399840054474, + -18.96525149129647, + -19.12749442059322, + -19.289228895757486, + -19.45741279118992, + -19.624518082031788, + -19.789264290616078, + -19.957217899632273, + -20.12554320365396, + -20.291535359651412, + -20.45661741374188, + -20.624900762742314, + -20.792490384542983, + -20.955721909462937, + -21.120630439016022, + -21.2870585386575, + -21.444982130001627, + -21.598863656561335, + -21.750643479669705, + -21.896438373808422, + -22.03910849233606, + -22.17636904208855, + -22.30540175462884, + -22.42542341135726, + -22.539146956257788, + -22.644016031622645, + -22.740484152312717, + -22.836514716343093, + -22.92764295559613, + -23.012012970289483, + -23.095118556658033, + -23.17077480859399, + -23.240066409121205, + -23.305515989393733, + -23.361728466694164, + -23.412337074856616, + -23.46037371829752, + -23.50306443829218, + -23.543747054539534, + -23.58499815473238, + -23.62041704711707, + -23.654493695511366, + -23.689535348467874, + -23.719767272254945, + -23.750525646015646, + -23.779927190012543, + -23.805992317431624, + -23.829555186808896, + -23.853796381897105, + -23.876081246940547, + -23.89663360763789, + -23.916418952165216, + -23.933755094216373, + -23.94812616839284, + -23.960289014763017, + -23.97027853066918, + -23.979346440291494, + -23.988601818959726, + -23.99748673065064, + -24.00746230432093, + -24.01957645060076, + -24.033380097808386, + -24.048066397906844, + -24.063321226370473, + -24.08014814477246, + -24.09751014798169, + -24.115132668007714, + -24.134855522500235, + -24.157898249969136, + -24.184071663509478, + -24.21053352668448, + -24.236998685094562, + -24.26325365204827, + -24.289106883822285, + -24.316311335503762, + -24.34603774911967, + -24.37588825465715, + -24.407686256573594, + -24.441138420094155, + -24.477407778640487, + -24.515457326758536, + -24.557349688165694, + -24.601587495378162, + -24.64748235127934, + -24.69755047368866, + -24.75077809488096, + -24.80578761517861, + -24.873895518769565, + -24.94448774858941, + -25.019008543138536, + -25.09892525500434, + -25.185604718885763, + -25.27307780410482, + -25.364576689331386, + -25.46244295885574, + -25.558943346151434, + -25.65575028695536, + -25.759876023316302, + -25.864454463336454, + -25.96961375458354, + -26.079170181308427, + -26.18634383147922, + -26.29915145418115, + -26.41859651341646, + -26.536725175124598, + -26.661264026478797, + -26.793935149400237, + -26.92695335525144, + -27.06890445470459, + -27.223066003407094, + -27.387049201077836, + -27.564426325664687, + -27.747572176016874, + -27.93471931049071, + -28.13436605320347, + -28.343737508465473, + -28.56782487399333, + -28.790516962230615, + -29.014180773919982, + -29.264963800505228, + -29.514241258752172, + -29.7507494894846, + -29.999709328402282, + -30.25566379689364, + -30.509285098859056, + -30.767976423346198, + -31.030391781940747, + -31.292404341267684, + -31.555709870094105, + -31.812829165823533, + -32.06157084192572, + -32.31126090315761, + -32.55430156850084, + -32.7874250918752, + -33.013204134689765, + -33.228245201726686, + -33.45056213359985, + -33.64115367671727, + -33.823531279904536, + -33.994139037296264, + -34.15613190979066, + -34.31141144239608, + -34.456150439498195, + -34.59114376810545, + -34.71902504617575, + -34.83792158668946, + -34.94790477840534, + -35.050416574223746, + -35.14510074675099, + -35.23517737454116, + -35.32256305773505, + -35.40517143426763, + -35.48535672371655, + -35.57405311539677, + -35.65501447059158, + -35.738099251115855, + -35.822642876840526, + -35.90917545965357, + -36.00047594326388, + -36.09321222872469, + -36.18752861473809, + -36.284240303576944, + -36.3836798712461, + -36.48809319057018, + -36.59313018240287, + -36.700604561550676, + -36.81453474991191, + -36.93311730567894, + -37.05309845188107, + -37.17928359079711, + -37.31323857749552, + -37.44761451769284, + -37.588284057073025, + -37.73227708031916, + -37.88325501482355, + -38.04140478248731, + -38.20044180813364, + -38.37094435449853, + -38.55112897531844, + -38.72710070636912, + -38.90885426980683, + -39.104773756264535, + -39.301469076443794, + -39.50092913661933, + -39.71551269943364, + -39.93246932757636, + -40.14419470742514, + -40.36403088471037, + -40.61237982379394, + -40.837449775604206, + -41.064227857947046, + -41.296263191665865, + -41.53250161080576, + -41.77005786741688, + -42.00642155578498, + -42.245692909403644, + -42.48615083355477, + -42.72627120320868, + -42.967784276973255, + -43.210838389998216, + -43.454905027997754, + -43.69656572062917, + -43.939071522217255, + -44.17748578944402, + -44.40877356683387, + -44.63746220975535, + -44.86686969668305, + -45.087741067713004, + -45.30470116652954, + -45.526841861896855, + -45.74381477345993, + -45.9582240033877, + -46.17520740545471, + -46.38988522520938, + -46.60260269830783, + -46.815076231505415, + -47.0306596826408, + -47.246494086527896, + -47.45431443616966, + -47.66179794852654, + -47.869890858231095, + -48.07051691276318, + -48.26658740305062, + -48.45822715782399, + -48.637913969054864, + -48.81847286901816, + -48.9981089964212, + -49.168131845598005, + -49.33503788461863, + -49.502372581737816, + -49.664890882012045, + -49.82532662495358, + -49.985368463902745, + -50.141289377818886, + -50.29445671935501, + -50.44537527216848, + -50.595209995241746, + -50.73987131413586, + -50.880321205825396, + -51.02053233594645, + -51.15862052568441, + -51.29209638461525, + -51.423227850287695, + -51.554193325480924, + -51.682263827662155, + -51.80818966783331, + -51.933267353127604, + -52.05329760709906, + -52.16949175990998, + -52.28678490748444, + -52.39775833318429, + -52.50647880540683, + -52.61359443602876, + -52.71846518731468, + -52.82032291602857, + -52.92044824595632, + -53.017292305290745, + -53.113265566743245, + -53.20682483440556, + -53.29549837615724, + -53.38050501526027, + -53.463008615655816, + -53.54278518028811, + -53.620062293650314, + -53.69609395213598, + -53.77152277654935, + -53.84653840152321, + -53.92166157519881, + -53.996279591142375, + -54.06956555485206, + -54.13976662425757, + -54.21010790595168, + -54.281335950198425, + -54.34868707516771, + -54.41624017478141, + -54.48455688045824, + -54.551068776349425, + -54.61574435450012, + -54.6819684659621, + -54.74687315211124, + -54.80981745893463, + -54.87483829002289, + -54.9400734205884, + -55.00410148869024, + -55.069917202635196, + -55.136939217187624, + -55.201861944524815, + -55.266327934074646, + -55.3317541238993, + -55.39720755610121, + -55.463251249573375, + -55.53183612633831, + -55.600815659007544, + -55.66866888302588, + -55.73855766178132, + -55.81094806659809, + -55.88274360338026, + -55.954410878287604, + -56.02335995616113, + -56.08653911246893, + -56.14528801778404, + -56.19830731489368, + -56.24522663731658, + -56.28597955798271, + -56.32190276823193, + -56.3519461383363, + -56.37527715778535, + -56.396000943071016, + -56.410295107175, + -56.41748415160509, + -56.41511941982913, + -56.40461982918199, + -56.383780435378, + -56.35053751793998, + -56.308371808596924, + -56.25699922373871, + -56.190261226826806, + -56.11489109327586, + -56.028361132762754, + -55.93528832066313, + -55.841011086953536, + -55.73248273941255, + -55.60947684380252, + -55.485133563840606, + -55.34974633710588, + -55.199200316763275, + -55.0485683988637, + -54.88546118863054, + -54.71185208986849, + -54.53821924360358, + -54.33865137751723, + -54.12676993446414, + -53.917672564784866, + -53.687481928798, + -53.45247952617786, + -53.224167600110626, + -52.979675778149875, + -52.722402522782346, + -52.46592382551485, + -52.197801370097416, + -51.92043424125247, + -51.6485256498487, + -51.367855919960384, + -51.07225456512394, + -50.77220138000718, + -50.46125676473004, + -50.13988620861913, + -49.81387251704995, + -49.4738458398497, + -49.12946373042813, + -48.785439747863265, + -48.43348449840709, + -48.07354271016477, + -47.71001644719917, + -47.340243406625554, + -46.975552243235605, + -46.606976228357844, + -46.22669179650427, + -45.86232697645387, + -45.50328789610202, + -45.12665413967861, + -44.755393662619745, + -44.398697318781515, + -44.0201703619642, + -43.637921578937195, + -43.26707798347966, + -42.88661844403491, + -42.49221634638106, + -42.10257554309159, + -41.70620510737677, + -41.30404826516985, + -40.9024725592768, + -40.49695324808783, + -40.094203832165476, + -39.69326197760276, + -39.28467981906957, + -38.87706873985989, + -38.466767667351284, + -38.05063278221215, + -37.63793009967038, + -37.22773802824038, + -36.81081745582405, + -36.39950435349942, + -35.98740807079116, + -35.564018296971405, + -35.148622793218735, + -34.72901355973301, + -34.298855382619536, + -33.881001233161356, + -33.4693413907427, + -33.04501771609204, + -32.63845031857292, + -32.232698830429094, + -31.82058640190152, + -31.416293177928125, + -31.005664782491984, + -30.59279361029727, + -30.187209070318314, + -29.7785167447167, + -29.36659548355264, + -28.975365030880102, + -28.57445136808079, + -28.163977619406293, + -27.767587830956874, + -27.373414255606882, + -26.968516842274514, + -26.576998991782002, + -26.187220189614244, + -25.788177672808217, + -25.396856976222026, + -25.001445620704846, + -24.603457091701628, + -24.219371761407537, + -23.841161581728375, + -23.470260057496493, + -23.108014999801455, + -22.750004117400216, + -22.395414135020793, + -22.042610659048606, + -21.681270616376256, + -21.27553134551176, + -20.913105879888324, + -20.545781587335025, + -20.165478262334542, + -19.78378104021787, + -19.400186955075686, + -19.016874466607028, + -18.63313242754503, + -18.254355086592316, + -17.896259493530156, + -17.552332572435873, + -17.213033571797308, + -16.875962974781757, + -16.541937239717203, + -16.206102587589175, + -15.87676286308467, + -15.511972688126127, + -15.17600829607498, + -14.83721674879326, + -14.490093131839615, + -14.12861908582576, + -13.757097672089284, + -13.401345155840602, + -13.04533635724029, + -12.670252886350644, + -12.302212745396481, + -11.953371368277988, + -11.585828201277513, + -11.214590856602351, + -10.88435258245321, + -10.559012936539022, + -10.228991082741462, + -9.91140558037379, + -9.602436805693412, + -9.300126927048481, + -8.986836483092265, + -8.678457907452758, + -8.379091726896203, + -8.069251023296742, + -7.754712908155948, + -7.448270919620779, + -7.147601267393443, + -6.8583619753513405, + -6.5769804042732485, + -6.307367057079339, + -6.05631914282536, + -5.813724319815339, + -5.5814076355931626, + -5.368911812062815, + -5.192783199868777, + -5.026022995334309, + -4.868573670790678, + -4.724075731613454, + -4.592754795067297, + -4.4657171934561175, + -4.355142645668079, + -4.2596546851801955, + -4.173412975318418, + -4.0955037984464555, + -4.024808370968408, + -3.968051835537542, + -3.9241973889923254, + -3.891067199301055, + -3.869707371482235, + -3.860122070435745, + -3.862495398975393, + -3.8775151213606383, + -3.9073570620714304, + -3.950451835597978, + -4.005461239337054, + -4.071208160032066, + -4.143380125248869, + -4.2255319121017045, + -4.3171473076338565, + -4.413934691448962, + -4.521982882453739, + -4.639687833005884, + -4.760098636788015, + -4.887110188807535, + -5.0261006886480075, + -5.1661996110564985, + -5.309491523231896, + -5.468176571958472, + -5.622253537883207, + -5.777285976835671, + -5.946373579698685, + -6.111283969646562, + -6.2717260228459395, + -6.444205063808137, + -6.609813145526646, + -6.773720264899113, + -6.946045975631996, + -7.118808272128241, + -7.291485921054185, + -7.470831606503378, + -7.6533696746314686, + -7.830199685370139, + -8.013377255497419, + -8.199564393590066, + -8.384530603791417, + -8.57276708100062, + -8.764092264635837, + -8.952026334503474, + -9.13889061141238, + -9.32698380261516, + -9.513847103890624, + -9.706681451985856, + -9.894284923289993, + -10.085215369996689, + -10.27397743810571, + -10.46183393625287, + -10.647675203668975, + -10.83098793418853, + -11.0184310312165, + -11.205597764385988, + -11.392168810711311, + -11.58054114554603, + -11.770043530402754, + -11.961243643568931, + -12.1545095518784, + -12.355773155038113, + -12.561455602769636, + -12.765464418300763, + -12.978933786165262, + -13.194811307411582, + -13.407949114803971, + -13.630138801875, + -13.857851236022755, + -14.085204476989372, + -14.321819793004368, + -14.575182510486046, + -14.817720769469934, + -15.059573005267572, + -15.319242183165702, + -15.568876804424663, + -15.818823975065168, + -16.08258642563926, + -16.34223874940074, + -16.594629894743363, + -16.849567870978728, + -17.10579657033175, + -17.353681398093396, + -17.60653299805298, + -17.85999035414474, + -18.115673612600467, + -18.364967465806743, + -18.614438650252584, + -18.86587359078524, + -19.12120535304735, + -19.374476650515412, + -19.63153293056934, + -19.89687143489585, + -20.15350283626709, + -20.408118024224827, + -20.6622972824969, + -20.9206815476821, + -21.170248923250337, + -21.419776681362926, + -21.67249004929207, + -21.919020154425592, + -22.1637044896756, + -22.410109019447614, + -22.657707212892188, + -22.900690166227275, + -23.144291468724422, + -23.386332664981293, + -23.619115263115102, + -23.857131862490455, + -24.09024445190506, + -24.30498132329061, + -24.517780954673, + -24.7221849723308, + -24.921015255880473, + -25.114219513598446, + -25.302940490263403, + -25.488321719857403, + -25.672226604487538, + -25.85034856713363, + -26.025582336955623, + -26.197591896228154, + -26.367651795131177, + -26.533327549794155, + -26.687755042423557, + -26.84055578832506, + -26.99019647315873, + -27.13144868285428, + -27.27161008377521, + -27.41667790440846, + -27.55109559756212, + -27.68300506668926, + -27.82638961081035, + -27.961846992981275, + -28.091233357668013, + -28.230263054923775, + -28.36639169618012, + -28.499690495293102, + -28.639337022166554, + -28.78225615330068, + -28.925094595024095, + -29.074026903283965, + -29.22403424232948, + -29.36953502485965, + -29.514981072534624, + -29.65695376722536, + -29.79644485744043, + -29.933882283035597, + -30.071653917496093, + -30.20816723332997, + -30.343842071599965, + -30.479793962838674, + -30.613787436791135, + -30.748708557112543, + -30.881033307151984, + -31.0138450544275, + -31.146690908358817, + -31.279007427202927, + -31.41167946785834, + -31.546737361526997, + -31.68530424271964, + -31.824093766050275, + -31.960275171462246, + -32.09844380117443, + -32.23595195995335, + -32.3676118801337, + -32.49858677699923, + -32.63402351098039, + -32.759013349903206, + -32.88413080127819, + -33.010907599257344, + -33.133380285877834, + -33.252723920535594, + -33.36996619896849, + -33.48668704809511, + -33.603491435704406, + -33.716355338377284, + -33.8314707763821, + -33.953498808178054, + -34.07512651098753, + -34.19538041646202, + -34.32816727584279, + -34.46144232930978, + -34.59423893382527, + -34.742769721067916, + -34.895522536009594, + -35.044393623940934, + -35.2073585096373, + -35.37265462129525, + -35.53867091655266, + -35.71943923683007, + -35.88801817525376, + -36.06067544629365, + -36.247107654796665, + -36.42679064269483, + -36.60985158483766, + -36.80783599136066, + -37.00587038488824, + -37.208502067013846, + -37.422226501665655, + -37.639281013634104, + -37.86121207151336, + -38.09646877474403, + -38.34092748182813, + -38.590685452105404, + -38.848909520509714, + -39.11534274278885, + -39.39261077527654, + -39.67639588567982, + -39.96087646625901, + -40.25329494474936, + -40.54763068668886, + -40.83297928839565, + -41.129295480945906, + -41.421726408290645, + -41.70723149140203, + -41.990465458619425, + -42.2651421955693, + -42.530352843379895, + -42.786404516998175, + -43.03274648205944, + -43.26590034036846, + -43.481356339301776, + -43.686525766160955, + -43.8759252958635, + -44.04559167635969, + -44.19806839619527, + -44.33188127186157, + -44.44866487897621, + -44.551215280360594, + -44.63752047436132, + -44.707535091993755, + -44.76388811729896, + -44.81173765941115, + -44.843079376071046, + -44.86580402296306, + -44.881708484165394, + -44.890293460786985, + -44.892259994242096, + -44.888906890095846, + -44.87985243749461, + -44.86664418299311, + -44.850639535998425, + -44.832439078434206, + -44.81307697045818, + -44.79364821576541, + -44.77503496468325, + -44.75793184471923, + -44.74349179460754, + -44.73134203405788, + -44.72030702815232, + -44.69249268903152, + -44.6996869826273, + -44.71391958127997, + -44.735883976569475, + -44.765254335205896, + -44.80170001153461, + -44.84530831853433, + -44.895772991062024, + -44.95219263712336, + -45.01473332775103, + -45.08399352928447, + -45.15996747740505, + -45.24347836402794, + -45.33845839365368, + -45.43750344941558, + -45.536366746199725, + -45.643487327307824, + -45.75842306715362, + -45.87238738167741, + -45.994168329078256, + -46.12390089910052, + -46.25115217236301, + -46.38101718408689, + -46.517506831728014, + -46.6550714716193, + -46.794282173775485, + -46.93871939461475, + -47.08870503777707, + -47.24106231918847, + -47.39492903767727, + -47.552106407831616, + -47.71069482163378, + -47.86833471880161, + -48.02825171483278, + -48.19088735949445, + -48.35367350272166, + -48.5164819191643, + -48.681022375298, + -48.84166040674982, + -48.998435418748194, + -49.15419224791821, + -49.30854843717438, + -49.45737026800353, + -49.60656826089752, + -49.75758195482167, + -49.902628690297306, + -50.04873698515476, + -50.19615653120516, + -50.33994110158995, + -50.480549863079794, + -50.622008878640365, + -50.76133541333833, + -50.8929643832669, + -51.02233515820244, + -51.14895945137354, + -51.2680988597582, + -51.38051322461153, + -51.484596065755014, + -51.57966171816269, + -51.67284228761277, + -51.759502972305945, + -51.83940366411082, + -51.91587332061889, + -51.98798567467568, + -52.055661050170094, + -52.119569779834634, + -52.179991988245625, + -52.236473421664535, + -52.290181235386555, + -52.33967545133591, + -52.38385351938186, + -52.42412489048871, + -52.46170592983039, + -52.496379272571275, + -52.52794835091763, + -52.55640817046599, + -52.58053487776926, + -52.600000458811806, + -52.613722002239975, + -52.62350810992837, + -52.62996018638715, + -52.63343479455111, + -52.633980907247164, + -52.630943992008476, + -52.62467450630691, + -52.61612382426644, + -52.60476322398838, + -52.59057986977051, + -52.574046200361074, + -52.555570291267216, + -52.535628720336824, + -52.51400646619419, + -52.48791643702848, + -52.45849939065624, + -52.426490217563206, + -52.39189322700984, + -52.35474224440913, + -52.31584925846777, + -52.27685866076428, + -52.23899018369706, + -52.20150409459526, + -52.162776399484635, + -52.12304343355836, + -52.08512991409284, + -52.0461224656918, + -52.00514312276096, + -51.96440843197896, + -51.92084551384291, + -51.87287870672525, + -51.82307010778093, + -51.772298034008365, + -51.72023068227053, + -51.667030281223816, + -51.61417873608414, + -51.56225592335788, + -51.509952259223745, + -51.458071560477855, + -51.408907919267264, + -51.36289940655628, + -51.318446525474, + -51.27513817666198, + -51.23343081073004, + -51.192150494659984, + -51.14880593328901, + -51.10552068083719, + -51.06348656722617, + -51.022793497279615, + -50.98218273023084, + -50.942458104881574, + -50.90333209393517, + -50.86399556579007, + -50.82371783660683, + -50.78285149382917, + -50.74063371446675, + -50.69590802453579, + -50.64616604322733, + -50.59426317388249, + -50.54021665142166, + -50.48125913923025, + -50.4159489221181, + -50.34573461699959, + -50.27601953353696, + -50.19607363984064, + -50.1091936597282, + -50.020274412215954, + -49.92751626418495, + -49.83029165712424, + -49.72593195712166, + -49.613775234690515, + -49.50052865968491, + -49.379349222896074, + -49.25032717896444, + -49.119444992439774, + -48.98069563185496, + -48.829240981162926, + -48.68317797721376, + -48.524230507127044, + -48.357094358307926, + -48.18913215749813, + -48.00296609363351, + -47.813956589409116, + -47.62526973423658, + -47.4202582006301, + -47.211026671998845, + -47.00100327179271, + -46.77265217918488, + -46.54583321854025, + -46.31148139389012, + -46.048383374484736, + -45.786075026934384, + -45.51444151562943, + -45.22318886053367, + -44.94310777165705, + -44.66655916779887, + -44.37079048660445, + -44.07328916933107, + -43.77760952714714, + -43.46228592311404, + -43.14300318049824, + -42.8299257989286, + -42.50778530170045, + -42.18033867939624, + -41.84944077635536, + -41.51096936196984, + -41.171839551467016, + -40.82660420735386, + -40.472401955940995, + -40.11561997539666, + -39.764207205288514, + -39.40585787372262, + -39.041387040642384, + -38.675513535158515, + -38.31160371356203, + -37.95185106102344, + -37.583940709792145, + -37.21400006015976, + -36.862613482193815, + -36.51330918301553, + -36.15141824953603, + -35.800358567377984, + -35.459571629845264, + -35.09943945327148, + -34.74059028489571, + -34.39428050806257, + -34.036348280582615, + -33.66769338599005, + -33.3061227815726, + -32.93681771785011, + -32.558864420188826, + -32.184908142543804, + -31.80646051263562, + -31.428248350729074, + -31.057021006462573, + -30.680559309450924, + -30.29930409057992, + -29.924490614829747, + -29.54454141384704, + -29.162933575628614, + -28.784312689581878, + -28.408811023483157, + -28.02957905323498, + -27.65748997836576, + -27.278908053004926, + -26.900956821644524, + -26.527388781437157, + -26.14438945089141, + -25.763103298989105, + -25.390813823245367, + -25.015638730734423, + -24.635898301341562, + -24.277690192581534, + -23.909719258693144, + -23.540331987477405, + -23.186638603304758, + -22.82197620132539, + -22.45300542515495, + -22.097185015213235, + -21.737532249434736, + -21.371056921395777, + -21.012577134921433, + -20.666636844946296, + -20.307038412830885, + -19.948720373033876, + -19.597577281640667, + -19.246936206017725, + -18.89159592676133, + -18.545277410556288, + -18.20121162170815, + -17.851966325494715, + -17.508052562998092, + -17.167770769304795, + -16.821076220366233, + -16.47946607988687, + -16.145744793266836, + -15.814228922530297, + -15.491805258234203, + -15.179677523464361, + -14.8633627512647, + -14.557037617349037, + -14.253843341729306, + -13.944987813427646, + -13.635629095741681, + -13.322281360388635, + -13.012004316164749, + -12.698719522178457, + -12.375354008410984, + -12.046641556605602, + -11.712787415317722, + -11.376614517001714, + -11.040394907385506, + -10.702720618533457, + -10.362559867057287, + -10.03061645103251, + -9.707980959615293, + -9.38440903905259, + -9.059834976066892, + -8.734203012823148, + -8.41805821291957, + -8.100012267881002, + -7.773826376060623, + -7.447778200975354, + -7.1184738164268335, + -6.795318826940068, + -6.456722035195495, + -6.117266938576435, + -5.7866646071535675, + -5.452889040131884, + -5.101611510399121, + -4.764240990674404, + -4.436876820100168, + -4.087136277317069, + -3.7418598571742168, + -3.4241903364665935, + -3.103473435967006, + -2.7788705640082556, + -2.485939087116193, + -2.2092911445964023, + -1.9102302910029092, + -1.6173485489608996, + -1.346405576436552, + -1.0670108169783246, + -0.7977185809825318, + -0.5484779523677786, + -0.29859945955637024, + -0.061841161178086995, + 0.16448661684993626, + 0.3841144497276622, + 0.5867262104084506, + 0.7707135775219899, + 0.9446706703707425, + 1.1018653867297192, + 1.2443708560725106, + 1.3837252634150707, + 1.5096321328587712, + 1.6158006419000692, + 1.707777574760611, + 1.7869280304255042, + 1.8499632932751935, + 1.8943460035923738, + 1.9212024056325951, + 1.9282960145211037, + 1.917817362532113, + 1.8864847970915535, + 1.8374243200313785, + 1.7741355270940877, + 1.6897934949524558, + 1.5912510242380387, + 1.4802031868357792, + 1.3515261774411509, + 1.203421348234305, + 1.0448401000523437, + 0.873293391818103, + 0.6845743378337061, + 0.48831273855358437, + 0.28777000970844396, + 0.07933697037023946, + -0.13688849636368336, + -0.35883808203806244, + -0.5824375509874291, + -0.8098234100091103, + -1.043231861384742, + -1.2817768081554781, + -1.520391387343699, + -1.76571433172012, + -2.017623614445508, + -2.267746428346875, + -2.5171593167391517, + -2.780965140001806, + -3.0374773839757703, + -3.2879731480628536, + -3.5511411050417214, + -3.812005961062005, + -4.062173802661583, + -4.3241936020579885, + -4.584631865759376, + -4.838889944192866, + -5.103219898911103, + -5.3860529376514785, + -5.67653719234623, + -5.975693892712216, + -6.279804512355977, + -6.576325874713259, + -6.8789860937068905, + -7.188447734974245, + -7.492947550366757, + -7.799447499143733, + -8.111691199367367, + -8.40422873334024, + -8.68505581379873, + -8.96735922985983, + -9.247395022849393, + -9.532148029176163, + -9.811745409174838, + -10.09695940223443, + -10.382500903677133, + -10.665319975781946, + -10.946664751406837, + -11.237903100529563, + -11.541335122632427, + -11.844730606419335, + -12.147499968901313, + -12.458264678458884, + -12.768826734965083, + -13.082203961327481, + -13.395786454899332, + -13.719506417967747, + -14.043151773165096, + -14.351713746912496, + -14.660910477428597, + -14.965990758885457, + -15.27002094724147, + -15.585344209431796, + -15.898666411115586, + -16.209075784159566, + -16.533446215676193, + -16.864127276059868, + -17.174480366931117, + -17.4684255916292, + -17.75305947463326, + -18.018662261851215, + -18.28817989298486, + -18.570346264010272, + -18.837537510652222, + -19.097866518194827, + -19.371515472780914, + -19.63946804818005, + -19.901653887969136, + -20.192591710752406, + -20.496584416781534, + -20.80453937159835, + -21.106293859934464, + -21.40740926541604, + -21.71235840809054, + -22.022894799656644, + -22.325192821906608, + -22.625615940203158, + -22.94236583559797, + -23.24129787830059, + -23.5297764922627, + -23.820261712351282, + -24.114438784228476, + -24.40505482803702, + -24.69024388532251, + -24.980994512419564, + -25.2662303956687, + -25.55521384575851, + -25.842454884994655, + -26.13866400472831, + -26.436809303890584, + -26.728314163166203, + -27.024496327804812, + -27.313159457627815, + -27.595955846558883, + -27.88173449603556, + -28.15927234762725, + -28.432499269756363, + -28.706573461440055, + -28.97165345463406, + -29.24091483378553, + -29.513117955874556, + -29.777739955927895, + -30.045782300939948, + -30.31930157945917, + -30.586529277498784, + -30.85294189001411, + -31.124288832352487, + -31.388692671859268, + -31.64526886462561, + -31.91066119942439, + -32.164018041278524, + -32.412152720246944, + -32.66492625526931, + -32.92390382094429, + -33.16281383558861, + -33.4031736766098, + -33.6620600313757, + -33.90006089539899, + -34.143799184675665, + -34.400591909596464, + -34.64662141364417, + -34.889028061874605, + -35.13660210260092, + -35.385863748383926, + -35.62891602906219, + -35.876861842075805, + -36.12230259571905, + -36.36165468512135, + -36.597918705609075, + -36.8305393027967, + -37.061513262028065, + -37.29367944609783, + -37.53013267649586, + -37.761760565043296, + -37.99867332980302, + -38.23503373913347, + -38.47257909285061, + -38.71522076192912, + -38.95468842645664, + -39.19600129828062, + -39.44281759022477, + -39.689096679733495, + -39.935277150649554, + -40.185340621989184, + -40.44270012327779, + -40.69700686925106, + -40.947604704997126, + -41.20357316572996, + -41.45874687175612, + -41.705575390757986, + -41.950407032641735, + -42.2057428328899, + -42.44484924723598, + -42.68167380825259, + -42.924384541809914, + -43.15453416835302, + -43.38447302893445, + -43.618030375520874, + -43.85006631917921, + -44.082708269384824, + -44.31670989633449, + -44.547957923265855, + -44.78630139238495, + -45.02791171860808, + -45.26382763836701, + -45.512312043293115, + -45.7543493885623, + -45.99292295377146, + -46.240180231005276, + -46.48476619484078, + -46.72583368767717, + -46.97000561210904, + -47.215377647267445, + -47.45722013201295, + -47.70323221192097, + -47.941871473538235, + -48.17756106845346, + -48.41923672459774, + -48.65393415152999, + -48.88709752111466, + -49.12767628102655, + -49.369436237810774, + -49.61340333337116, + -49.860886129774926, + -50.11424063264458, + -50.373259092667546, + -50.639647444283, + -50.911504562297914, + -51.18945881614874, + -51.47353348374666, + -51.75583442446818, + -52.0468763170805, + -52.344808366209335, + -52.6320520795149, + -52.90692873021462, + -53.19002579230331, + -53.469100992392214, + -53.730143535404515, + -53.98894162744045, + -54.23764698050932, + -54.469555428785576, + -54.688008998443244, + -54.89019073834005, + -55.07186501266503, + -55.23165307667545, + -55.3732870634124, + -55.49378057002766, + -55.590710360531396, + -55.66532866871269, + -55.717525811303936, + -55.75066885955313, + -55.76481512072593, + -55.759891092974605, + -55.73724106254656, + -55.69729589255787, + -55.64060541527604, + -55.56834567111792, + -55.48177187454085, + -55.383542300915664, + -55.27491394895366, + -55.15645320520226, + -55.03284645498123, + -54.90260828196945, + -54.767051200225715, + -54.629698754699795, + -54.48874693444187, + -54.346638011117626, + -54.20731475330449, + -54.07363022510151, + -53.93196722252462, + -53.80831329558492, + -53.69114650339178, + -53.57786601284826, + -53.469043869138225, + -53.3657755501066, + -53.2670069393885, + -53.17308914387623, + -53.08615017251135, + -53.00551961166567, + -52.93392858581801, + -52.87073627139909, + -52.812357963286885, + -52.76213472629049, + -52.717720751099606, + -52.67911497873581, + -52.64225787403717, + -52.61330178705449, + -52.594676919791304, + -52.58082521513664, + -52.571383870721235, + -52.56542523904344, + -52.5630785770816, + -52.565592370876516, + -52.57291237735343, + -52.58616924586441, + -52.603678154010616, + -52.62296230917877, + -52.644724206431114, + -52.67165037532843, + -52.702284323820884, + -52.737154780288485, + -52.77689231566481, + -52.82004447580215, + -52.86531443987108, + -52.91387719640536, + -52.96428709593051, + -53.01436406118113, + -53.06484444653372, + -53.117922809677495, + -53.171181093997106, + -53.22458916017944, + -53.279133522095115, + -53.33052337704517, + -53.378733418019564, + -53.42607164702704, + -53.4714046698874, + -53.51481297136362, + -53.557944350815504, + -53.598259257367445, + -53.636102223438186, + -53.67274066725741, + -53.70648333263322, + -53.7354858649595, + -53.761058642241586, + -53.78300186441062, + -53.79922034263283, + -53.809134573170724, + -53.81419992696705, + -53.812247757428295, + -53.80373956340987, + -53.78878642993154, + -53.769409349898694, + -53.74473539493373, + -53.71516183313104, + -53.678488530788805, + -53.63643698267936, + -53.590771397281955, + -53.538796494073715, + -53.47975676217477, + -53.41637368491696, + -53.3497085120415, + -53.27559987391911, + -53.19991727447366, + -53.1208453439042, + -53.03571923129624, + -52.949456604697666, + -52.86298781084249, + -52.770943878812425, + -52.67350404144981, + -52.577987350008115, + -52.47545301673853, + -52.36682885794369, + -52.25597378162846, + -52.14208990752695, + -52.024303232727576, + -51.90702509388509, + -51.787273710472974, + -51.66571118214049, + -51.54266789484829, + -51.41738781292871, + -51.28946596887473, + -51.16052080253384, + -51.02866508449045, + -50.8967711691289, + -50.76261493370004, + -50.624378145049164, + -50.484817041196, + -50.34337387757248, + -50.20008854303476, + -50.0538283194695, + -49.906382587265696, + -49.76005205696314, + -49.61522890373951, + -49.46798359797079, + -49.32205414306024, + -49.18168893804091, + -49.03706712113395, + -48.88939627432503, + -48.73172291378426, + -48.5841774399688, + -48.43013737911197, + -48.276852452440046, + -48.124153931719825, + -47.966186745995046, + -47.80676532177742, + -47.65060753173576, + -47.49206214765714, + -47.32980473958183, + -47.17081699044504, + -47.013375283800286, + -46.85609451728255, + -46.69841323654441, + -46.54233532256226, + -46.38772590626042, + -46.23045540429578, + -46.072997353744526, + -45.91985572568633, + -45.767809867773444, + -45.59778214886511, + -45.4471504016637, + -45.29859410580334, + -45.14745006215438, + -44.994958896543324, + -44.84172223777462, + -44.685277819059, + -44.5221124740435, + -44.35867921694125, + -44.195839378625294, + -44.03100821053184, + -43.85770043495074, + -43.6831017161419, + -43.51147692747272, + -43.324363683492656, + -43.1341969492792, + -42.943091506016266, + -42.7474159172583, + -42.547946375969765, + -42.343132635624364, + -42.120768303065276, + -41.897350622455434, + -41.66325160495242, + -41.426558639232404, + -41.18934403635728, + -40.93616529212884, + -40.6957372459493, + -40.44246504964155, + -40.18163899920708, + -39.92434735393384, + -39.668231026113034, + -39.41623766824345, + -39.1671557592698, + -38.90258881561719, + -38.639796655670395, + -38.37732500748666, + -38.0969814389229, + -37.825939649866726, + -37.54664444117788, + -37.24150585378087, + -36.945436630283055, + -36.63431425760449, + -36.31069019186036, + -36.00875720739604, + -35.70803315122114, + -35.388528637443244, + -35.07167294493991, + -34.763215751620464, + -34.43838892399438, + -34.11452048772369, + -33.78971758156607, + -33.46110006712418, + -33.132339748723815, + -32.80562116904536, + -32.47674906483984, + -32.15090406653988, + -31.82626137880774, + -31.492741870296136, + -31.161963129353094, + -30.839768089453276, + -30.493129347388155, + -30.146136230801716, + -29.807844869758554, + -29.4740387069343, + -29.150738082622137, + -28.82972569412432, + -28.497130844013107, + -28.177648099772572, + -27.86433405088853, + -27.54673240484818, + -27.23888274655231, + -26.936622708354275, + -26.63489587492054, + -26.32161000472169, + -26.012277100129033, + -25.704170704376644, + -25.387665290561017, + -25.06487794695087, + -24.742397351130883, + -24.41396499075897, + -24.081677491641894, + -23.749454082284778, + -23.414062490360944, + -23.07733604145589, + -22.745188337458533, + -22.40847179134633, + -22.067639686268684, + -21.729226908949432, + -21.386769694136664, + -21.040769559214397, + -20.694471211981465, + -20.34868723300353, + -19.999851501289555, + -19.62008189513422, + -19.27100073905224, + -18.92638531991459, + -18.588161684266517, + -18.248324614771455, + -17.91893082771564, + -17.602343056242095, + -17.283595867368387, + -16.971013855715412, + -16.682724384619622, + -16.387549568085664, + -16.09399970814327, + -15.819904351598758, + -15.53622841716392, + -15.244803010467109, + -14.96153412920028, + -14.674097730402414, + -14.384325343204667, + -14.092251264932358, + -13.794057665870046, + -13.50353877170297, + -13.21132811898712, + -12.90482099173236, + -12.60392219447869, + -12.306052288733733, + -12.000349963580295, + -11.697178124530476, + -11.39923804691345, + -11.093392111059817, + -10.785357285246695, + -10.486092890232523, + -10.18038877531292, + -9.870093857162523, + -9.569145551116153, + -9.270163101591091, + -8.971689287343583, + -8.684948555769086, + -8.396638712403725, + -8.110775480521541, + -7.828626245102295, + -7.541759274591084, + -7.25185419221323, + -6.958716363996231, + -6.667624138672746, + -6.370607582327201, + -6.064973734697458, + -5.755738511435491, + -5.444859257882132, + -5.130587935937114, + -4.817118437273158, + -4.502311861517167, + -4.192532975929694, + -3.892115508842604, + -3.592360289199098, + -3.292157005112628, + -2.994028767949145, + -2.7072234297897504, + -2.4156418234712964, + -2.118372881667491, + -1.826027837138399, + -1.5372850622183543, + -1.2428298103384017, + -0.9422224484891255, + -0.6552049888848881, + -0.3802417472927005, + -0.09499173291949081, + 0.18178537509938686, + 0.4336700157143668, + 0.6966730029626242, + 0.9665684353036693, + 1.216039652762898, + 1.4546975043632169, + 1.6925505536190624, + 1.9253051372526606, + 2.137269757080463, + 2.3348868282274555, + 2.541653755138296, + 2.7436144600862598, + 2.928477839467786, + 3.111118767816139, + 3.28909610967536, + 3.451869183628742, + 3.6096664019301143, + 3.757841920030514, + 3.893329687530655, + 4.019577932052728, + 4.13396385921677, + 4.229525363128095, + 4.311309889766212, + 4.380327916900443, + 4.432965936768186, + 4.475875460034202, + 4.507316137177971, + 4.521693504913679, + 4.519895939932456, + 4.50496611397356, + 4.47645575885916, + 4.43384802277373, + 4.374209266732488, + 4.296899117358691, + 4.210015616578304, + 4.104579242640396, + 3.9778396686966366, + 3.8420915834690517, + 3.692770841811775, + 3.5188157991922537, + 3.3386652503098957, + 3.145436982917815, + 2.933423991239192, + 2.7053988088309047, + 2.4672041042324535, + 2.2142547679138094, + 1.9470620857968879, + 1.6744119224200058, + 1.3940728617136626, + 1.1077367848826238, + 0.8120134386012675, + 0.5064169801305209, + 0.19600550427888197, + -0.11519481997323494, + -0.4348907632773606, + -0.7601506912480445, + -1.0811114512597637, + -1.4113228395034298, + -1.7520690288938887, + -2.089199872100345, + -2.4199960462935155, + -2.754382843526987, + -3.085879387873012, + -3.403722679223684, + -3.7287647344026817, + -4.059303691707763, + -4.371617495489478, + -4.691167708791514, + -5.0153341110063065, + -5.325481016885064, + -5.64444861472565, + -5.973274399135193, + -6.293507204356354, + -6.622157004465535, + -6.956470047111187, + -7.285131106061637, + -7.612929557778126, + -7.952666481858264, + -8.287211747780118, + -8.619125852721707, + -8.960351479197719, + -9.292576089398906, + -9.619806590711063, + -9.949330091312321, + -10.276437166767955, + -10.605874630556425, + -10.93603593512243, + -11.260949741870894, + -11.594693548760064, + -11.926840393309933, + -12.258285619429644, + -12.59003510316944, + -12.922628757236783, + -13.25719101937559, + -13.590107125337209, + -13.925225829744729, + -14.25991204836196, + -14.596589257102645, + -14.933226361922141, + -15.30144852419057, + -15.636389410093038, + -15.951465822668757, + -16.26585755696513, + -16.582588739409395, + -16.892811876290097, + -17.208594370272603, + -17.530849393175526, + -17.844037896976886, + -18.160160886264045, + -18.490299225060138, + -18.827149085965367, + -19.159434910010802, + -19.506458932281532, + -19.86983306245915, + -20.213055271598076, + -20.558906850608093, + -20.919337987116812, + -21.268587445881664, + -21.60575183614417, + -21.94737843516884, + -22.290350506575955, + -22.60631395835898, + -22.926389663624114, + -23.241421946220758, + -23.558718610991047, + -23.877227033839514, + -24.185953968542123, + -24.496543399324647, + -24.812914018277183, + -25.129316218894648, + -25.437705379813718, + -25.76791426055, + -26.1086499912129, + -26.433932575197215, + -26.762693636241615, + -27.08976080996914, + -27.41676910984239, + -27.744558650908523, + -28.06317597782058, + -28.38813917833264, + -28.709236052185172, + -29.03603566656552, + -29.364349086205472, + -29.691810303017913, + -30.0264406286328, + -30.357478895900417, + -30.690090074649092, + -31.028524673395534, + -31.359309213008196, + -31.693658807808653, + -32.0401146220198, + -32.375413954350854, + -32.711758407980135, + -33.05302629626409, + -33.386399455267714, + -33.7226646869726, + -34.05219298383436, + -34.384159436675425, + -34.71809821319222, + -35.048326605006764, + -35.38348081271346, + -35.71592154712338, + -36.03978343545733, + -36.36951368666786, + -36.69594528914535, + -37.007635122277186, + -37.32698354487897, + -37.642807531478454, + -37.94444818295919, + -38.26191451116631, + -38.58141482245345, + -38.88234262194125, + -39.20242173895554, + -39.53072157932119, + -39.83643879368301, + -40.15298632538702, + -40.47876182238641, + -40.792606913290555, + -41.1074698471274, + -41.43679969125798, + -41.756266158769215, + -42.07473564083749, + -42.43571142561871, + -42.75501157154936, + -43.069437724007486, + -43.388043613914235, + -43.7056555519817, + -44.01925886767052, + -44.34176130009067, + -44.65919378166218, + -44.98100341360274, + -45.30894152180402, + -45.639459898123164, + -45.9704224177619, + -46.30154149107646, + -46.637379498865016, + -46.97508382476037, + -47.31025528614293, + -47.64712673241311, + -47.98848581612999, + -48.32932923027304, + -48.66487042474649, + -49.004949800619414, + -49.3396609641448, + -49.6718517241719, + -50.00484932992559, + -50.335227267131884, + -50.66062751044557, + -50.98582505252587, + -51.3167308698585, + -51.637442071225024, + -51.95570950852133, + -52.27129218259571, + -52.584435674414934, + -52.89639499584523, + -53.19971360181313, + -53.50369647943074, + -53.80834417268652, + -54.11140527787669, + -54.40502807821798, + -54.701318235476705, + -54.98525140774505, + -55.254107245235, + -55.53004044424332, + -55.814750152120915, + -56.090155152115344, + -56.36012384614532, + -56.64580452906922, + -56.923991960855936, + -57.19372426201853, + -57.48081992941508, + -57.769617907982806, + -58.052444667673626, + -58.34450638218545, + -58.622731900421755, + -58.89581824639618, + -59.17753436912586, + -59.456076332077735, + -59.731547374587414, + -60.009710603685875, + -60.27995006956179, + -60.54464623557332, + -60.81164928851323, + -61.07602994161075, + -61.34739147355955, + -61.62268296221908, + -61.894212716288116, + -62.16547747770566, + -62.43832654566834, + -62.70532729639679, + -62.962695980546336, + -63.2143876797705, + -63.461203433044105, + -63.68835902448967, + -63.8982607904228, + -64.0962428848378, + -64.27117255867775, + -64.42841844864822, + -64.56614957216128, + -64.67858233116108, + -64.77163961435572, + -64.84051860783873, + -64.88591786395241, + -64.91131741211484, + -64.91549497820269, + -64.89762703337516, + -64.85853702847986, + -64.80054349323746, + -64.72698328290869, + -64.63545030544971, + -64.52517528059961, + -64.40049610221821, + -64.26059236617407, + -64.10506466173719, + -63.937213654748135, + -63.75678927164039, + -63.566809058558924, + -63.36855105170832, + -63.16123402630231, + -62.94899136212532, + -62.7301268465736, + -62.5010241731829, + -62.268705925559715, + -62.03552164453808, + -61.79876253720458, + -61.56032905398105, + -61.32510911069667, + -61.0931423778431, + -60.86006864423852, + -60.633165719755844, + -60.40872004894628, + -60.18144368966343, + -59.9611175572778, + -59.7431854887936, + -59.530374496683955, + -59.32409536373215, + -59.12345612818583, + -58.931749710025315, + -58.75193958763854, + -58.57387741062418, + -58.407209398167865, + -58.25198632291714, + -58.1041520483058, + -57.95533131417458, + -57.81408123244753, + -57.68934364100779, + -57.564041888593884, + -57.44353670581038, + -57.33216616877852, + -57.22201936354363, + -57.112527066628445, + -57.012938936329114, + -56.916896982928364, + -56.821757929588095, + -56.73343779055994, + -56.646253679527824, + -56.55991805279086, + -56.479779242775436, + -56.40156040638177, + -56.32495433240671, + -56.251541148571604, + -56.181363015815705, + -56.111733055739855, + -56.04237249323248, + -55.97368189380239, + -55.90358060583399, + -55.834298170582414, + -55.765239957288266, + -55.69592049313019, + -55.62617783716715, + -55.55531715660172, + -55.48356508809312, + -55.40993232303179, + -55.33489601485874, + -55.26098970759312, + -55.186464063122216, + -55.108746628010195, + -55.03182396839522, + -54.95389538313502, + -54.87405565820421, + -54.792608408457966, + -54.70986707115987, + -54.62217191944274, + -54.53004390698982, + -54.436522239332184, + -54.336283692677746, + -54.22972088121484, + -54.120932249394386, + -54.00617719260835, + -53.887186620743236, + -53.766120059154034, + -53.63909351802302, + -53.507983948645915, + -53.37215650217293, + -53.22543118442101, + -53.07496935031896, + -52.919581290765684, + -52.753803225539556, + -52.582938902895734, + -52.41165765968816, + -52.23312422864181, + -52.04858353335398, + -51.865090921062176, + -51.673240496672385, + -51.47490696095621, + -51.28024641755678, + -51.08386770926707, + -50.87936304185, + -50.67401180525247, + -50.46888651295372, + -50.250591510455315, + -50.02824419922022, + -49.805578279975435, + -49.574271202122475, + -49.345507768204705, + -49.11341840103734, + -48.87591231390753, + -48.637064128921075, + -48.39688987931705, + -48.15138373981382, + -47.905253414505076, + -47.658117279444504, + -47.41254890041668, + -47.16761946594974, + -46.917886867711196, + -46.66774286714823, + -46.418794773678584, + -46.1662341543551, + -45.90919209440135, + -45.65125126255571, + -45.39839301930402, + -45.14891097286928, + -44.89664578573406, + -44.64640141712189, + -44.40625758300676, + -44.16035936869182, + -43.91056736596237, + -43.66787246329435, + -43.42242805003103, + -43.16835770344952, + -42.91030981050776, + -42.63774219963873, + -42.358778181537346, + -42.078747610712725, + -41.80338575521076, + -41.52490687245359, + -41.24279741097451, + -40.96427756356151, + -40.685733453661385, + -40.40558054494515, + -40.130254405942274, + -39.86757389533995, + -39.60707938272576, + -39.34475540998937, + -39.07842460842025, + -38.81931690041337, + -38.562686853389096, + -38.30266366588122, + -38.04834798564219, + -37.79954777962222, + -37.55290773968637, + -37.31669283965531, + -37.08125179328632, + -36.8423985289406, + -36.59647282827979, + -36.35043306474415, + -36.107384064935566, + -35.86479595362636, + -35.61483890947434, + -35.331083604078735, + -35.08467593081306, + -34.82106257777353, + -34.54556572052031, + -34.27460110941142, + -34.003822190109645, + -33.7234802213776, + -33.44179473270728, + -33.15404639354219, + -32.87050327610256, + -32.58059006720925, + -32.27863778989865, + -31.974910828643875, + -31.625261336959714, + -31.313387822712656, + -30.99594893231147, + -30.638295150715958, + -30.307294264613517, + -29.96915980473817, + -29.630218779293614, + -29.287615725836904, + -28.949722701606397, + -28.61214299684073, + -28.263324125658396, + -27.925086770255056, + -27.568292044437335, + -27.200004161191206, + -26.841930786622143, + -26.469623578292122, + -26.10526166402949, + -25.7633482883371, + -25.412957223371198, + -25.06886569338142, + -24.73944990787778, + -24.39985551461764, + -24.06358432487452, + -23.745255496146143, + -23.426525335201283, + -23.105885895095795, + -22.799767638116997, + -22.49727514661846, + -22.191512596579802, + -21.891550729953174, + -21.590555095391352, + -21.299800506744486, + -21.007459721050708, + -20.712505682578513, + -20.417676359856692, + -20.1288424114053, + -19.846110724116734, + -19.557595214382083, + -19.28022537410284, + -19.014449312268486, + -18.750918995967762, + -18.491107639453244, + -18.235664351288477, + -17.9795877790416, + -17.721819734208616, + -17.46897854981269, + -17.214611409109313, + -16.956473654155083, + -16.695196476177763, + -16.434045992582917, + -16.167492560565577, + -15.89800943709457, + -15.6307679353881, + -15.361289112735683, + -15.092818270382255, + -14.829004930418265, + -14.562877850354946, + -14.294519724502058, + -14.030585803536798, + -13.765237969926819, + -13.497923111167285, + -13.234891933479595, + -12.97316886875696, + -12.711808717546162, + -12.454194391119383, + -12.19602507631081, + -11.935528952308767, + -11.67958978903822, + -11.421997715558938, + -11.164448947544308, + -10.911949175795565, + -10.663612992465232, + -10.410357865899986, + -10.165148682321933, + -9.924962021390026, + -9.673653052987477, + -9.432629859989227, + -9.195342670726596, + -8.948062321990827, + -8.706241410623509, + -8.47032010334807, + -8.225928280604439, + -7.978389168827798, + -7.73736140804471, + -7.497250189318121, + -7.245795004371036, + -6.9987034327101325, + -6.757151653913929, + -6.508834203192692, + -6.263672595978965, + -6.028150849844641, + -5.78800386578519, + -5.546046282574258, + -5.314001026202576, + -5.079433067953793, + -4.841429196618071, + -4.612694155697623, + -4.388707178010669, + -4.164553150775704, + -3.9478262838874354, + -3.7311509071527325, + -3.522314335342655, + -3.3124060115933043, + -3.102505607858443, + -2.893933689356671, + -2.6813165678067397, + -2.4716573725450317, + -2.259457809256232, + -2.0416601442580937, + -1.820530332249989, + -1.6011434418342279, + -1.3792924671975615, + -1.1573692093907881, + -0.937683749914177, + -0.7157838335096527, + -0.5025761859928053, + -0.29572698607465064, + -0.06875462801314372, + 0.13916910940614716, + 0.3356064932076778, + 0.5254223494192539, + 0.7225861750073419, + 0.9174020765641653, + 1.109507283467813, + 1.296704119216514, + 1.4897693873692912, + 1.6818811947252001, + 1.8675234036787325, + 2.0493392212722954, + 2.237983491726821, + 2.426333618040964, + 2.603518075701454, + 2.785109481579425, + 2.971950526820138, + 3.146522955940648, + 3.308071412513028, + 3.466892579623205, + 3.6202023899320186, + 3.7542339221224283, + 3.8745624026034355, + 3.9968835226577486, + 4.111193097788245, + 4.210625589643177, + 4.303847746654786, + 4.389589899802569, + 4.463272747942096, + 4.527925739270417, + 4.581620827121556, + 4.623653373638112, + 4.653243214668194, + 4.667554863346527, + 4.66236752050303, + 4.638794262618646, + 4.598753633693416, + 4.545381036871401, + 4.476700932513723, + 4.389812718332553, + 4.287809094218327, + 4.169078151417449, + 4.0337891175561085, + 3.8853931955825773, + 3.7272593542819386, + 3.5507043988790468, + 3.358102237811909, + 3.1651740198986325, + 2.9526530684725723, + 2.7178985062406245, + 2.487766711156026, + 2.239010205724702, + 1.9697694841508335, + 1.7039840386279805, + 1.4275718050197304, + 1.1269846739476312, + 0.8222887596704817, + 0.5162959892493844, + 0.19558762207302433, + -0.13345092285786847, + -0.46220243878085393, + -0.7929708493107742, + -1.1214811859868086, + -1.456120346240359, + -1.7972115272559916, + -2.1310910955781144, + -2.4638837448918935, + -2.8079759788362644, + -3.1456326294461148, + -3.4827274783486786, + -3.8314926086555965, + -4.180313251704143, + -4.520758302292919, + -4.865420412184198, + -5.224967284992722, + -5.56453732752588, + -5.9000908168059025, + -6.252465322458136, + -6.5942883841183555, + -6.92437217125159, + -7.271789519182661, + -7.612759287706714, + -7.946660687609742, + -8.294083993961767, + -8.639737061587114, + -8.980986481932046, + -9.33242642784403, + -9.689355404980818, + -10.037825131094943, + -10.39336751538966, + -10.758525809216103, + -11.119472443660197, + -11.483530509935356, + -11.855400525589813, + -12.222370212220225, + -12.587414867333706, + -12.955518706677944, + -13.32048479640778, + -13.691787789490027, + -14.054563710141634, + -14.424951195143885, + -14.79773534478032, + -15.168355733815776, + -15.537795644316514, + -15.902878177737989, + -16.276519065567175, + -16.64688244976087, + -17.0139208030353, + -17.38706483478301, + -17.76046386720403, + -18.131722380813656, + -18.49787495018238, + -18.873141193368053, + -19.245771525145923, + -19.614272276698706, + -19.987316216657533, + -20.352476543605828, + -20.71995251601444, + -21.095355790849915, + -21.460159884003456, + -21.824294732196023, + -22.208134791712077, + -22.58507999968541, + -22.94399072775922, + -23.330385819325496, + -23.718247852077766, + -24.08400847274188, + -24.463124366592318, + -24.853688572998212, + -25.22004139330868, + -25.584441873185398, + -25.97197836307736, + -26.3415213744268, + -26.709330811425424, + -27.083419073826352, + -27.458918687547662, + -27.826383345452186, + -28.19391321807642, + -28.565180461751968, + -28.94195519023841, + -29.311238083351725, + -29.670078650853863, + -30.043955801452864, + -30.41005097901917, + -30.768999928936818, + -31.12817167201201, + -31.495659793925526, + -31.85135437527981, + -32.203436764856825, + -32.56265543064982, + -32.91970803545725, + -33.28614455149576, + -33.657117080737514, + -34.03312542473182, + -34.40593757281209, + -34.782089260964156, + -35.160448048017756, + -35.52942898963792, + -35.90658951585313, + -36.284053145426775, + -36.65476451632372, + -36.99338940652855, + -37.31210512684125, + -37.63256930076928, + -37.95244255152422, + -38.2709995018038, + -38.58830911084204, + -38.90980292751436, + -39.235710648118946, + -39.5546493082041, + -39.87375706460377, + -40.22544316311305, + -40.57636295198425, + -40.92522886226912, + -41.28364128623022, + -41.62892987418175, + -41.970592060306906, + -42.332885121171934, + -42.67804885782773, + -43.01166281162483, + -43.375288715268354, + -43.70690286515323, + -44.008154174490784, + -44.33506079856576, + -44.65807088043407, + -44.96768244597823, + -45.288473768435516, + -45.616746242978365, + -45.933603882916564, + -46.25187139875348, + -46.57454038621962, + -46.90195673044048, + -47.22911341441135, + -47.55895709510095, + -47.88997094675314, + -48.21724850096846, + -48.55122209291605, + -48.88107824579509, + -49.21569403871265, + -49.54830345030725, + -49.87465148645359, + -50.2482872738873, + -50.63216666433026, + -51.01770219311104, + -51.408769520926064, + -51.797045291793914, + -52.182119321516225, + -52.568239582219334, + -52.96108097928673, + -53.35864888770875, + -53.743459675795584, + -54.102767939216626, + -54.455600512326306, + -54.80455211942588, + -55.14372277795312, + -55.49048522118435, + -55.83989862934475, + -56.17283974521251, + -56.509396280707804, + -56.84710967750188, + -57.178233711388586, + -57.52201949730945, + -57.86756983068868, + -58.21043608090959, + -58.55772556251277, + -58.908923038684364, + -59.24408415654623, + -59.589903375851506, + -59.94478017125559, + -60.28357890305282, + -60.63399208769079, + -60.9731898197203, + -61.29241026263995, + -61.61964823476025, + -61.95298842315661, + -62.27627181706702, + -62.5982102760029, + -62.92827500718808, + -63.24779025502591, + -63.57145526795926, + -63.89032831139089, + -64.19491538820286, + -64.50695213099198, + -64.81103198074504, + -65.1021460453941, + -65.38943664388782, + -65.6736319905866, + -65.95378645640052, + -66.22419961020843, + -66.4921635787646, + -66.75574304226045, + -67.01586461508562, + -67.27312869486198, + -67.52359827175695, + -67.7743086078551, + -68.01961465088993, + -68.25347517935884, + -68.48392426068527, + -68.70910795234815, + -68.91660496285618, + -69.10380651804887, + -69.28870781075972, + -69.4631131754671, + -69.61347619161562, + -69.74508298029102, + -69.86119938523795, + -69.95423129069756, + -70.02826179975484, + -70.08163908860483, + -70.1130964313865, + -70.12406173747227, + -70.11449531852482, + -70.08527048680838, + -70.0357871620045, + -69.96704934908234, + -69.87914884190009, + -69.7715476923107, + -69.64734699805649, + -69.50868769106724, + -69.35431046377643, + -69.18477993135747, + -68.99810414688947, + -68.80065957254445, + -68.58837086091653, + -68.36380960860161, + -68.13169619807452, + -67.88819323818844, + -67.63919346575103, + -67.38659256982382, + -67.12398807645634, + -66.85931265224333, + -66.59212419167349, + -66.31643857753708, + -66.04154184320969, + -65.76644043859847, + -65.48613485778944, + -65.20650996423714, + -64.92831577820456, + -64.65198350368452, + -64.37789680037756, + -64.1026474637757, + -63.83162052468435, + -63.56478657311441, + -63.29809115448759, + -63.03285372895792, + -62.77113047902272, + -62.511150613610795, + -62.25531030031971, + -62.003569456359344, + -61.75343602598804, + -61.51444115870572, + -61.278160381960305, + -61.03960593492409, + -60.81211536578428, + -60.58713621924456, + -60.36845116830578, + -60.14320916898169, + -59.92599679132155, + -59.722507648154654, + -59.511007719999085, + -59.30449060217959, + -59.108094248879965, + -58.909046332347636, + -58.70709589577023, + -58.514498044683, + -58.32689049259974, + -58.136921933462474, + -57.95387982162923, + -57.77564527268614, + -57.59574244302279, + -57.421640918906036, + -57.25399349987955, + -57.0854261112508, + -56.92234990475461, + -56.75739418005345, + -56.592720559580044, + -56.429140883894625, + -56.2626723178267, + -56.094430525928125, + -55.92663954394565, + -55.76148150353939, + -55.593551787433505, + -55.42826123286333, + -55.26383930916287, + -55.09709569041535, + -54.931617802966855, + -54.76662284619, + -54.600978613694224, + -54.434320971781176, + -54.27070783416176, + -54.10205341065748, + -53.930716891663565, + -53.76328356334991, + -53.58789387372266, + -53.41189431824663, + -53.23543668445821, + -53.05269326341237, + -52.86449025571554, + -52.66952255601094, + -52.4738294200348, + -52.27044917585209, + -52.05456234100216, + -51.8355622979325, + -51.60622529641284, + -51.370920331434654, + -51.13371546847616, + -50.886162616523286, + -50.6315265389719, + -50.36893799545237, + -50.095614436016305, + -49.81196376832589, + -49.5227464249609, + -49.217725714497774, + -48.90304716069872, + -48.584201604977814, + -48.252161304898735, + -47.911745591341145, + -47.56879187606734, + -47.22700323391149, + -46.83281146669143, + -46.4702410093277, + -46.11140104044296, + -45.73978993127088, + -45.36042460604, + -44.98814678361028, + -44.60845482629428, + -44.22232453802405, + -43.838346213926805, + -43.45483175254206, + -43.06529180331909, + -42.67508983308675, + -42.283880578380746, + -41.890348995386525, + -41.49409899762718, + -41.09933547771172, + -40.7021126832968, + -40.30653402976841, + -39.91086956691768, + -39.514410149881066, + -39.113402797902, + -38.71511783247079, + -38.31347119525082, + -37.915177450093324, + -37.51144414939198, + -37.12041432120927, + -36.731854876747136, + -36.336325178616725, + -35.94738466193311, + -35.56846448153699, + -35.17909068319027, + -34.79419173563531, + -34.41634416534482, + -34.04013866541881, + -33.66933543732716, + -33.29934467389773, + -32.946700682106496, + -32.595723103600804, + -32.23970053142105, + -31.89297875313497, + -31.54939915826174, + -31.209228000500847, + -30.874644803505756, + -30.54571209305497, + -30.24150487426131, + -29.941264679434493, + -29.65556353940081, + -29.396640317655304, + -29.13561070283149, + -28.894534748036087, + -28.669200199339638, + -28.447210808479557, + -28.24514897894562, + -28.065695478182626, + -27.884178456594803, + -27.72121466335784, + -27.580385557745, + -27.441025464257606, + -27.318037332251123, + -27.213431769426453, + -27.112569153891087, + -27.02684243142981, + -26.952040560013934, + -26.89015793311576, + -26.841657897848393, + -26.799178365802046, + -26.7623332112538, + -26.73118256922781, + -26.701813054921814, + -26.672511431232987, + -26.642687322170968, + -26.61371163900235, + -26.604725534031797, + -26.597101359440742, + -26.590344058134974, + -26.583528825064608, + -26.577574260168863, + -26.572385492278176, + -26.567331155802318, + -26.562668454945392, + -26.558620470762342, + -26.555283737753275, + -26.524395630462394, + -26.490009498431338, + -26.455113095080918, + -26.419571657826847, + -26.38342996200929, + -26.346678757884227, + -26.309309285749165, + -26.271418137912175, + -26.232468054980703, + -26.192622671193412, + -26.182885579595844, + -26.176561889525477, + -26.170019220735703, + -26.163518676255148, + -26.157031284645136, + -26.15037816272362, + -26.143791394631844, + -26.137149470624433, + -26.130435039069834, + -26.12369410297835, + -26.100864735902903, + -26.0762011588705, + -26.051429206960446, + -26.026699805734967, + -26.001949247406344, + -25.977174709685514, + -25.95241373081624, + -25.927620255904582, + -25.90281436231869, + -25.87792048986312, + -25.86912552068418, + -25.861938869545675, + -25.854678826415526, + -25.847514306923753, + -25.84043267225333, + -25.833185235135094, + -25.825912260874038, + -25.818712461828877, + -25.811343661510133, + -25.804032062722534, + -25.76327200353828, + -25.71816951961668, + -25.67309950738135, + -25.6282189769851, + -25.58362563075885, + -25.539095963918186, + -25.494459405581956, + -25.45004414705182, + -25.40584975898497, + -25.361193146420717, + -25.35176083098965, + -25.346356673412064, + -25.341087701934505, + -25.33606270204788, + -25.331045020776386, + -25.326051648671193, + -25.321001702151786, + -25.315407894826496, + -25.310270117846283, + -25.305238426422218, + -25.30388068436576, + -25.302596981996626, + -25.301515761725618, + -25.300424963503286, + -25.299121605821288, + -25.29786948141474, + -25.29672765150048, + -25.295533260114343, + -25.294258667253228 + ], + "xaxis": "x", + "y": [ + 45.300763999112, + 45.301341573551824, + 45.30202395222192, + 45.3027304682885, + 45.30322237079558, + 45.30362067496451, + 45.304425203332364, + 45.30514048380767, + 45.30604976529649, + 45.306832191191525, + 45.30756898223068, + 45.30846231208834, + 45.30938864992191, + 45.310146673033415, + 45.31089687456964, + 45.31180081847361, + 45.312637714650506, + 45.31349301157287, + 45.314073695195525, + 45.3146608251378, + 45.31527304638943, + 45.31595919671405, + 45.31653792238171, + 45.317194737096244, + 45.317770872862425, + 45.318388003341866, + 45.31896967467463, + 45.31946843250839, + 45.319930227441446, + 45.32043543954677, + 45.32082272659343, + 45.32121324116136, + 45.32163620609007, + 45.32203450106808, + 45.32252305614339, + 45.32297280120289, + 45.32336242467605, + 45.32369386666636, + 45.32409141971895, + 45.32452122201855, + 45.324815845330846, + 45.32521256200015, + 45.32573437392582, + 45.32601426487314, + 45.326272186092524, + 45.32656776983637, + 45.32694553337056, + 45.327221708071704, + 45.32751804238648, + 45.32788106789423, + 45.328215034350976, + 45.328615342235956, + 45.3290091977588, + 45.32931759406239, + 45.329637175733765, + 45.32995418467703, + 45.33032833395729, + 45.33064009395056, + 45.330855206546445, + 45.33118968061984, + 45.331416453200255, + 45.33172398395247, + 45.332056224367435, + 45.33230550243798, + 45.33257395929481, + 45.3328823693904, + 45.33316931701505, + 45.33381599455605, + 45.334690400214996, + 45.33548640314393, + 45.33624919080267, + 45.33717076976769, + 45.33816451158525, + 45.3390484876764, + 45.3398846550109, + 45.340815079256465, + 45.34185668623101, + 45.34257141177747, + 45.34332312698853, + 45.344146460405405, + 45.34477346199053, + 45.345522978248866, + 45.346439532787365, + 45.347170382318076, + 45.347866414668964, + 45.348793914547244, + 45.349654386282666, + 45.350600302806356, + 45.351696416438095, + 45.35275943072291, + 45.35380572241721, + 45.35478027689853, + 45.35578104718409, + 45.356854446587434, + 45.35785394410009, + 45.35885438676964, + 45.359800413158574, + 45.36070616051463, + 45.361356618172934, + 45.36193783590679, + 45.36270764202978, + 45.36344215343657, + 45.36395524598705, + 45.36452216407602, + 45.36500010695263, + 45.36572464375114, + 45.366549414871706, + 45.36715644301529, + 45.36788206871917, + 45.36860188969828, + 45.369307664419, + 45.370158507472766, + 45.37094808765331, + 45.371596244630965, + 45.37230734145343, + 45.373077006469224, + 45.37390746412289, + 45.374738978946525, + 45.37533094086246, + 45.375911926393584, + 45.376660790566646, + 45.37744844505151, + 45.378120337993614, + 45.37871281301936, + 45.37944455726284, + 45.38024740126725, + 45.3810150092614, + 45.38159616835665, + 45.38201869243848, + 45.38272884241276, + 45.383487249053935, + 45.38398497519398, + 45.3845992105842, + 45.38542582840918, + 45.385949363001984, + 45.38680492486659, + 45.387348537977445, + 45.38784484606646, + 45.3881401319806, + 45.3888083451927, + 45.38951797313852, + 45.389847682969375, + 45.39038062223386, + 45.39101432104074, + 45.39166716937402, + 45.39244323096255, + 45.39311681660571, + 45.393629975075534, + 45.39436923588978, + 45.39544047566005, + 45.395946607659376, + 45.39644577388547, + 45.397136851800866, + 45.39787944394874, + 45.39851183408501, + 45.39897565687679, + 45.399340275298286, + 45.39963115185406, + 45.40028360093086, + 45.40084689773852, + 45.40120478758708, + 45.40159750972863, + 45.40224271477849, + 45.403056398790575, + 45.4041792694118, + 45.4047000889682, + 45.40520158629604, + 45.406105313965924, + 45.40748144561115, + 45.40943529834741, + 45.4107837640198, + 45.4118891588229, + 45.41348431974955, + 45.41515658983633, + 45.41667919460014, + 45.41818121451507, + 45.419703865894896, + 45.42113282745641, + 45.422553061774046, + 45.42405415464268, + 45.42544418832713, + 45.4268120040987, + 45.42827202741131, + 45.42979469260146, + 45.43121034271308, + 45.43272739895048, + 45.43424778583486, + 45.43546298459962, + 45.43645932152596, + 45.437592945562, + 45.43890910745662, + 45.44024249061596, + 45.44149552216681, + 45.44242302356497, + 45.44350379303764, + 45.44477792418805, + 45.445957075912965, + 45.447009319383746, + 45.44778973119988, + 45.4487710307042, + 45.45007783625308, + 45.45090763042639, + 45.45183603800033, + 45.452948351405226, + 45.45438467008537, + 45.456721755917506, + 45.45818512008324, + 45.46038379692406, + 45.462409788324116, + 45.46436920738667, + 45.47031123502449, + 45.48198682975995, + 45.50236060450161, + 45.53412777155301, + 45.57865482102878, + 45.63461195057368, + 45.69618820418663, + 45.75575362855735, + 45.805235963722915, + 45.844574314502026, + 45.87319009501468, + 45.89457350099864, + 45.90985702727797, + 45.920426784645194, + 45.929714314741986, + 45.94102433941112, + 45.95754900248294, + 45.984717098417015, + 46.02364689867042, + 46.074959813766874, + 46.1392187367292, + 46.21581309604001, + 46.303513964077254, + 46.402348322939716, + 46.51232170450343, + 46.63443683273643, + 46.769414650239135, + 46.91620833647572, + 47.072472510197336, + 47.23593432263914, + 47.40689313834542, + 47.58589559174276, + 47.76674702509741, + 47.94743119221877, + 48.12661549200032, + 48.306004856275344, + 48.48083176129356, + 48.64841047310979, + 48.813218898197654, + 48.96797914345479, + 49.11114843563967, + 49.24810402015948, + 49.373442983020205, + 49.48679746006202, + 49.586225276514554, + 49.67486678418323, + 49.75045581871038, + 49.80942562458604, + 49.85397554296133, + 49.88507842427781, + 49.90085090313507, + 49.8988757650409, + 49.87742261138937, + 49.83738247164229, + 49.77929693160578, + 49.70297245886327, + 49.60700749450082, + 49.49412270164788, + 49.36899891548721, + 49.22287365957846, + 49.0576477713906, + 48.89487209314991, + 48.706037434197974, + 48.49781142868888, + 48.28055252354111, + 48.04992989325078, + 47.8121765846866, + 47.559256286586965, + 47.28776340821796, + 47.02643650298985, + 46.75156963194857, + 46.45689980375514, + 46.17250442856052, + 45.880475804042035, + 45.57019228703469, + 45.260523105678715, + 44.94878994030538, + 44.62878206191175, + 44.299830325210415, + 43.969893204712456, + 43.63593348642329, + 43.29485327305683, + 42.95872002652995, + 42.61912286071814, + 42.26607771350164, + 41.918973232819475, + 41.57098241775734, + 41.214255254373604, + 40.8400237615168, + 40.48499485985969, + 40.123055774101914, + 39.741634268528905, + 39.369172624470124, + 39.003215264536074, + 38.62717062932619, + 38.24212774832719, + 37.877598836186976, + 37.504685485908134, + 37.117251461184125, + 36.74198424369736, + 36.37754675140968, + 35.99923365132266, + 35.6264236219529, + 35.266323625486265, + 34.894081708392854, + 34.52563453098432, + 34.15414418512981, + 33.78913023990528, + 33.41842289323424, + 33.0435961836081, + 32.679323999198324, + 32.31371279496165, + 31.95437866296702, + 31.580268678266055, + 31.229479177704786, + 30.877781472263738, + 30.508994931523873, + 30.150488891931595, + 29.796302517436125, + 29.44027879747006, + 29.074791931980396, + 28.712191780253157, + 28.35823855229896, + 27.99879545077412, + 27.640204060378316, + 27.28388283528901, + 26.92919627599728, + 26.56984937023628, + 26.21602342567307, + 25.863629406629126, + 25.49790648584417, + 25.149619176401096, + 24.804710592355164, + 24.445104311412454, + 24.09022404913823, + 23.745532269319668, + 23.3857846839867, + 23.03166683343009, + 22.683762062252573, + 22.329872038849924, + 21.989574640144735, + 21.64845920134522, + 21.3049796381533, + 20.97282416491729, + 20.64203158943567, + 20.30090176762072, + 19.973057305957397, + 19.645640435661452, + 19.30615980903741, + 18.980915208503788, + 18.65644862255679, + 18.324743966065398, + 18.00053865051007, + 17.6797624591609, + 17.34690612817321, + 17.01408542910839, + 16.689982779726076, + 16.358375758321905, + 16.028560988784907, + 15.705030884331155, + 15.38325393302482, + 15.057322482131829, + 14.731575851703301, + 14.405003248468422, + 14.078159797923878, + 13.74599436158187, + 13.415915683022071, + 13.085144947087308, + 12.74771355257983, + 12.414912886241646, + 12.079091946567505, + 11.738366338724818, + 11.402272003387672, + 11.069875069462155, + 10.72966346850544, + 10.39148332303563, + 10.064162846394513, + 9.69618110173987, + 9.35931374486956, + 9.033307291371546, + 8.70745863235564, + 8.37898415672725, + 8.056761112476863, + 7.739709332572376, + 7.421201950111207, + 7.105714426783437, + 6.792744303735408, + 6.476676019972183, + 6.16768207838867, + 5.852895579209107, + 5.532391193871351, + 5.218912864659064, + 4.900400654136906, + 4.569876849158174, + 4.243970598084207, + 3.924903130447823, + 3.587176721825192, + 3.258867782658453, + 2.942791882605584, + 2.6042377728092205, + 2.2705783121379435, + 1.9487151348600342, + 1.6112175295461257, + 1.2761688946705378, + 0.9508632327376363, + 0.6175763442038749, + 0.299787417162958, + -0.015741272825973762, + -0.3367256025240243, + -0.6371876578615306, + -0.9383847043225775, + -1.2456306620029711, + -1.534783750817155, + -1.824882339729615, + -2.1213194813266765, + -2.401357524525755, + -2.6794150779470147, + -2.9543812881729097, + -3.2198376847186516, + -3.4748461696052937, + -3.7234681836955463, + -3.9416898458483063, + -4.140137812307389, + -4.335503896360229, + -4.506983229102717, + -4.653251207477817, + -4.785819888437005, + -4.892279273068619, + -4.971537682661272, + -5.030458988709827, + -5.0658188226727106, + -5.076422764936061, + -5.06262634071044, + -5.026330897488161, + -4.969686300691085, + -4.891492372832748, + -4.794552814995628, + -4.679509821705779, + -4.547120899746603, + -4.399614625795304, + -4.2381700837055165, + -4.060430777530634, + -3.872435638632237, + -3.6710308450176057, + -3.455488028949548, + -3.231469231772502, + -2.9966344842292423, + -2.750927800489316, + -2.500916583739034, + -2.2463141385572807, + -1.9876805600808203, + -1.7266430581510566, + -1.467889712456801, + -1.2097227199180942, + -0.9528219875076482, + -0.6979055196300923, + -0.44600551231092733, + -0.19535390779521317, + 0.0541737457367337, + 0.29400326611414, + 0.5246764581160047, + 0.7539626589974129, + 0.9736166714470532, + 1.183989511360528, + 1.3937315750387254, + 1.6019416405285407, + 1.7895440011700536, + 1.973619328412509, + 2.1577995839358044, + 2.325366460938859, + 2.4929312307479226, + 2.6590554482926407, + 2.8080533697417174, + 2.9546256424311856, + 3.09969079163285, + 3.2335468937711505, + 3.3675130495414747, + 3.4992067476044464, + 3.6153651176217334, + 3.7264172791652688, + 3.8410242036315507, + 3.9478917310532426, + 4.049599274189725, + 4.156343028680598, + 4.258484815993488, + 4.35249002831893, + 4.450333333872016, + 4.5488629889563565, + 4.644884540423524, + 4.7460562127469785, + 4.849951616982029, + 4.955035466070503, + 5.066187722650232, + 5.179325060094688, + 5.2933875761899545, + 5.409626084324819, + 5.525889405780967, + 5.642460132379497, + 5.7631433440158, + 5.8852648342585745, + 6.011591942119079, + 6.144150940208226, + 6.284841345766752, + 6.431223582187876, + 6.583792196588058, + 6.743078809517763, + 6.9092906576273, + 7.0803177541799975, + 7.259502022852225, + 7.445945586695279, + 7.640928060221949, + 7.843238411397529, + 8.053057626660687, + 8.268415734705762, + 8.490396816861495, + 8.71891837463856, + 8.951769237822816, + 9.193218471325817, + 9.442594924647457, + 9.696365138125932, + 9.951458576255341, + 10.2120316761229, + 10.47864708607293, + 10.74647204211657, + 11.018385315278776, + 11.29279184675726, + 11.574945542225109, + 11.863286704760498, + 12.142861947700974, + 12.424984275096996, + 12.717908216058275, + 13.006249798999773, + 13.298788519143722, + 13.598894208518637, + 13.900405695370429, + 14.197368082720658, + 14.495312996367689, + 14.796948313285007, + 15.097945170890185, + 15.401355532178915, + 15.717805881010413, + 16.031520095830437, + 16.339101788283934, + 16.660392023315495, + 16.98159027411665, + 17.292653640261246, + 17.62171122712807, + 17.94892979037467, + 18.26922667115353, + 18.607125469156045, + 18.947401080835, + 19.276079319682413, + 19.623698553925163, + 19.96987188612568, + 20.304282776178955, + 20.656754005979543, + 21.0056343233842, + 21.339355562931917, + 21.684092928221315, + 22.01573036490737, + 22.348805633718737, + 22.6912983917052, + 23.02687460807076, + 23.356656517438864, + 23.684969813497123, + 24.003146095679078, + 24.321778792664468, + 24.651032913031717, + 24.969136693301518, + 25.29591867506696, + 25.62612936076743, + 25.94017776058608, + 26.26113290602105, + 26.588280217576173, + 26.895463290126933, + 27.222442340904838, + 27.55559214430204, + 27.87267187562141, + 28.197921036197673, + 28.525211405628266, + 28.844795525491932, + 29.15258188034745, + 29.466937726573722, + 29.776639528891486, + 30.079641033751738, + 30.382562678840582, + 30.67124595352575, + 30.958424296196142, + 31.247475362821486, + 31.528198961981687, + 31.80750159283566, + 32.080281832540074, + 32.35177729430272, + 32.62700611360116, + 32.89722613195348, + 33.17331291032348, + 33.460902140624334, + 33.73481415623733, + 34.02158170641768, + 34.32815902776748, + 34.625095195773504, + 34.931117235726944, + 35.26233505594226, + 35.57873292326579, + 35.877764386430236, + 36.20052486048117, + 36.52870849117942, + 36.840537392162716, + 37.1641226831591, + 37.49705722422052, + 37.81708695838772, + 38.13578681251307, + 38.457874553223824, + 38.775614575292884, + 39.093632399009046, + 39.411178747966616, + 39.7306961729037, + 40.05736051603555, + 40.38362133088337, + 40.703220569224996, + 41.02848519872867, + 41.35634815781767, + 41.67736377855218, + 41.995194193616534, + 42.318129957180716, + 42.634178551730514, + 42.922966851131626, + 43.21012264796641, + 43.5040655962893, + 43.76851481772789, + 44.02912724506593, + 44.305809205144826, + 44.5622250376899, + 44.807167150442936, + 45.06652071998439, + 45.31847297765649, + 45.566011133706276, + 45.826348969099065, + 46.08277850217597, + 46.33411551433679, + 46.58967771135485, + 46.84386762530234, + 47.09700246169205, + 47.35236193546806, + 47.60960216206434, + 47.86561418904249, + 48.123268741192796, + 48.37724558753112, + 48.63188397938058, + 48.88512811945823, + 49.143508878831206, + 49.39835903392802, + 49.656066115959796, + 49.91621165051497, + 50.17140426357718, + 50.41941225470457, + 50.674403029351495, + 50.91252439281616, + 51.14230275477052, + 51.379739937707136, + 51.60407313386915, + 51.8252709936769, + 52.05510728411453, + 52.27507903289203, + 52.49084093094618, + 52.734194896018536, + 52.954018978760715, + 53.170265300558725, + 53.391621328731794, + 53.61890214033733, + 53.83936786363542, + 54.05733100184072, + 54.27972415894159, + 54.49766515626916, + 54.71125855539906, + 54.92970282110391, + 55.147510230894326, + 55.357281099974635, + 55.57150256122695, + 55.78735713927546, + 55.994838066916536, + 56.20139326980965, + 56.40601719777533, + 56.60065735462683, + 56.79619626417855, + 56.98765507374571, + 57.17496351274691, + 57.36379561508075, + 57.552068230944016, + 57.742561532166434, + 57.93062053298537, + 58.12005092905921, + 58.315121889807656, + 58.51253401279553, + 58.71188199346526, + 58.911383893579085, + 59.11169764875003, + 59.31360008885097, + 59.5135060053731, + 59.7092070119636, + 59.90291608059877, + 60.0988785380776, + 60.293137574580925, + 60.48408287785949, + 60.67705457418497, + 60.872691351526996, + 61.06911697752726, + 61.26693973907211, + 61.463619659666705, + 61.67057237188686, + 61.873395305031416, + 62.06994071190517, + 62.2763117136212, + 62.48288569573003, + 62.670433806439334, + 62.86599398885605, + 63.06484624294453, + 63.23994309585581, + 63.404790257604844, + 63.5683951546275, + 63.71266402266976, + 63.833313673297184, + 63.957343197384354, + 64.07253337240147, + 64.16632664101635, + 64.25151881995679, + 64.32572991848842, + 64.38285729196312, + 64.42834672854003, + 64.46234364646841, + 64.48363245449228, + 64.48974560572483, + 64.47974511722353, + 64.45367193180653, + 64.41272649008886, + 64.35915170182273, + 64.29585728147505, + 64.21908416931414, + 64.12905525277463, + 64.02759206304033, + 63.91155210481026, + 63.783250461016685, + 63.645608893204916, + 63.49812769160795, + 63.33528536342317, + 63.16492904610628, + 62.98892398285202, + 62.795741138748994, + 62.58970387725575, + 62.38259767718872, + 62.160179037963886, + 61.923620482714576, + 61.68293145375927, + 61.42330628791671, + 61.15519230296776, + 60.876331872212845, + 60.579762295680354, + 60.275645768282175, + 59.960507387483716, + 59.63703073309107, + 59.30850704074147, + 58.9757028791477, + 58.63870745665814, + 58.29540932396677, + 57.95444873224277, + 57.61173711178277, + 57.267852354424896, + 56.92859530487275, + 56.590442033230566, + 56.25305986809595, + 55.912764342101134, + 55.56525941998776, + 55.21658153469502, + 54.879889471452486, + 54.53606114761929, + 54.184080384793454, + 53.85109730890776, + 53.50880070604252, + 53.15899468183553, + 52.814462304514855, + 52.48064377041907, + 52.13777724028534, + 51.79654702573489, + 51.46687954964362, + 51.1266105774489, + 50.784511846951915, + 50.451770742434185, + 50.111797708303484, + 49.76748946434314, + 49.425916171246854, + 49.08613195209399, + 48.736427537896795, + 48.3856070070895, + 48.04055301139471, + 47.68508895813121, + 47.33024274544863, + 46.98171587327677, + 46.633615480805815, + 46.2880205583211, + 45.94400735137217, + 45.59217569410682, + 45.25079461473036, + 44.90637087473837, + 44.55294148523616, + 44.205832777584554, + 43.85722484736744, + 43.50834110350364, + 43.1621088257624, + 42.81560345410025, + 42.46566436746404, + 42.118339414714214, + 41.77312931554235, + 41.41987859061167, + 41.073298559779715, + 40.72837872280661, + 40.3770253694961, + 40.02904833041153, + 39.68835985233569, + 39.34439804680693, + 39.009829973197114, + 38.671687745887205, + 38.323374457630734, + 37.98897010516161, + 37.65242926201179, + 37.304928825636814, + 36.95080862383974, + 36.61504655523721, + 36.26367204319447, + 35.89855452154007, + 35.544102364865196, + 35.19010380073074, + 34.83320667240535, + 34.46870627907129, + 34.120882613512286, + 33.771363807673204, + 33.41198798673348, + 33.06219420676293, + 32.712277566591176, + 32.36035455047789, + 32.00757065696203, + 31.661419421657694, + 31.315557458592334, + 30.9647625575405, + 30.617965955180733, + 30.265302718072977, + 29.919287077307345, + 29.571155743794343, + 29.216495853346082, + 28.878197989565503, + 28.536667325767418, + 28.190942579958637, + 27.845283287699914, + 27.513155173991645, + 27.179098623728564, + 26.83502343895677, + 26.46103637376922, + 26.124888471057403, + 25.779048125633576, + 25.42333823469573, + 25.069760328006527, + 24.72118898254519, + 24.36798861523095, + 24.015711997513932, + 23.668584379139066, + 23.315293198737912, + 22.961272806670213, + 22.610807753387963, + 22.2674733006515, + 21.91722673210496, + 21.567342437432803, + 21.233823479248375, + 20.892896771613447, + 20.544384009259172, + 20.20672800387583, + 19.866889099097538, + 19.512059752683733, + 19.170635603647817, + 18.836611494522998, + 18.484065621800763, + 18.143236322521165, + 17.81514553870242, + 17.469667809468664, + 17.131528575343008, + 16.809030674807882, + 16.466696872242288, + 16.1214317762364, + 15.799733330298245, + 15.42877363811099, + 15.073792858668515, + 14.747406156504846, + 14.414222581446774, + 14.063486594190591, + 13.729510593899505, + 13.395417648581581, + 13.048103444311565, + 12.706091630874697, + 12.364460809725964, + 12.015689641799408, + 11.669290615538904, + 11.324334069605856, + 10.979868486367371, + 10.640546596943121, + 10.298037572697554, + 9.953989503168742, + 9.612220302018773, + 9.267630755042081, + 8.921786546643382, + 8.575497419945757, + 8.237742897424031, + 7.88943212755558, + 7.5431838368751745, + 7.201932616872471, + 6.851825258506718, + 6.5029603902480995, + 6.154858315440672, + 5.803513795390799, + 5.448087318478452, + 5.096922909884843, + 4.7471486112752075, + 4.394007854240869, + 4.040519825603647, + 3.690172063167879, + 3.3392603502264295, + 2.9851205498345794, + 2.6333955725056244, + 2.288299469792739, + 1.9398064120443241, + 1.5997071035704864, + 1.2659347793408662, + 0.934825270517099, + 0.6058723220959414, + 0.28230350527672887, + -0.03629015797928825, + -0.36071636564953935, + -0.6819547254777746, + -1.007643085546778, + -1.330066825079602, + -1.6492567694716918, + -2.0104130703536005, + -2.339223859536039, + -2.6558284693529974, + -2.9752868315982397, + -3.3033092125038506, + -3.6322167726085306, + -3.950657289158474, + -4.274167227651788, + -4.601383622381596, + -4.915750468997668, + -5.23600751664346, + -5.555412012664591, + -5.847173310532583, + -6.142911390226606, + -6.444978920109589, + -6.72613985268185, + -7.001156311358316, + -7.279213081058419, + -7.544352527749074, + -7.804971727588198, + -8.061597996276314, + -8.310382291110322, + -8.554022006119533, + -8.797213336289916, + -9.03321605866088, + -9.26882078620251, + -9.497978440377171, + -9.719132779090145, + -9.931711355256954, + -10.134639615353883, + -10.327031589724083, + -10.49394959295115, + -10.638262924931626, + -10.769628023409727, + -10.879246376242422, + -10.964817519121414, + -11.032428862255294, + -11.079372097718194, + -11.102912315321094, + -11.103191905368893, + -11.079244514526284, + -11.032721627638416, + -10.961261277617764, + -10.865196952237048, + -10.74901918697948, + -10.61000961740642, + -10.449652153407792, + -10.278802388244747, + -10.086174464728362, + -9.874521154196852, + -9.65770029887742, + -9.423675235606092, + -9.174134318110932, + -8.921988604113233, + -8.656989114942014, + -8.380594650253201, + -8.098963878941928, + -7.8108678727576075, + -7.514900432821215, + -7.214406717186254, + -6.91193496707461, + -6.60380849731807, + -6.293174592930257, + -5.982330019792183, + -5.672116824982232, + -5.3652697050718325, + -5.058392164619464, + -4.75748769823338, + -4.459446086908367, + -4.161658500314655, + -3.868079626007064, + -3.576863053064497, + -3.286606466411095, + -3.001645623116065, + -2.718640927432209, + -2.4422744920606325, + -2.1746787881673773, + -1.9016214411074897, + -1.6379852872735574, + -1.3794056948426807, + -1.1263237319579624, + -0.8645465683249527, + -0.6089902795573999, + -0.3723638395152906, + -0.12509393518272546, + 0.12003648106456932, + 0.3505740876000286, + 0.5846856719358533, + 0.8244867863742374, + 1.0491993902429702, + 1.2699963556370675, + 1.496821911062356, + 1.712503717279573, + 1.9248968578725032, + 2.1418482701366557, + 2.3505439599106426, + 2.5523825862884832, + 2.7531995300117607, + 2.9541553860330523, + 3.148465256215704, + 3.3398151305240726, + 3.5299514440337405, + 3.720296770847451, + 3.9053071456439357, + 4.088881914933927, + 4.276781445025462, + 4.462576188309582, + 4.646870384206813, + 4.835697821217075, + 5.029821917521804, + 5.221367644332071, + 5.415360946106958, + 5.615232463589128, + 5.8090913345269435, + 6.004986928654759, + 6.203827654982399, + 6.4006922122688, + 6.600285224867596, + 6.801033264701665, + 6.999531515865841, + 7.202487639332157, + 7.410785615382285, + 7.618194445673296, + 7.8305529639776355, + 8.048794527824265, + 8.269230040416549, + 8.494515105781907, + 8.726845100344663, + 8.961369651981645, + 9.1967088366889, + 9.440421022370094, + 9.682894032455827, + 9.932018824589539, + 10.192585984206067, + 10.45695130453579, + 10.725620750180626, + 11.009196295992373, + 11.295492970999367, + 11.582235534121276, + 11.878578270279743, + 12.182832393582968, + 12.479401710417404, + 12.782775167320377, + 13.094100571366237, + 13.400245911423351, + 13.70514648225263, + 14.017984705260282, + 14.33212251738247, + 14.639618146964136, + 14.95767547988323, + 15.278803640425702, + 15.596193195655003, + 15.922162557440148, + 16.251956920872253, + 16.57167234279722, + 16.89829409490034, + 17.232586891473908, + 17.566312071722997, + 17.899789800152938, + 18.242636362853847, + 18.5874319540848, + 18.930956278371266, + 19.271359875226974, + 19.61471393570453, + 19.96071653519306, + 20.305240607722805, + 20.648476213008024, + 21.000160129295892, + 21.357801222709778, + 21.707692400950048, + 22.056525876511053, + 22.415288221263225, + 22.771383305433954, + 23.116170563384895, + 23.473800779097594, + 23.83402006978679, + 24.184389383985415, + 24.543669015913185, + 24.911485261810032, + 25.27403401822014, + 25.635177289261257, + 26.01004795898074, + 26.378335243972316, + 26.738358933747435, + 27.113709043417835, + 27.49072739057218, + 27.8531538233007, + 28.221658491015777, + 28.595727293922245, + 28.95637169156403, + 29.32204101295745, + 29.69621141381072, + 30.060466513854657, + 30.423735098723874, + 30.787978494030376, + 31.145739588431468, + 31.493882032695705, + 31.842876111156787, + 32.197179154784145, + 32.54672086652207, + 32.8969536154289, + 33.25853532862679, + 33.609723337002855, + 33.94989446641682, + 34.30025212183056, + 34.65264409337346, + 34.98888831453011, + 35.32804279011438, + 35.67547524302361, + 36.00724974720602, + 36.331694431613094, + 36.66466942998067, + 36.98040335169968, + 37.298097905182736, + 37.61034756605825, + 37.90347642595841, + 38.199572829167074, + 38.48304663331545, + 38.758875029184075, + 39.05150458495746, + 39.3213311417734, + 39.58277083626067, + 39.8598149615599, + 40.13442464859941, + 40.40846823880898, + 40.687878257587755, + 40.96034686903057, + 41.2423625928913, + 41.531887678961525, + 41.823000836541055, + 42.108567927464875, + 42.41160627488574, + 42.710933013990775, + 42.99896832353256, + 43.305438515642486, + 43.61473659522926, + 43.9075228194131, + 44.2195852489998, + 44.52088858915054, + 44.775271618516086, + 45.038717568139646, + 45.3065147252586, + 45.558644558606005, + 45.806638154774696, + 46.05744570682455, + 46.297726955338895, + 46.53007589812538, + 46.75860788541654, + 46.98314649371935, + 47.21337823270735, + 47.43538870321986, + 47.65098488001414, + 47.86296819613546, + 48.07196452474747, + 48.27752789194195, + 48.4727917742563, + 48.671171000903946, + 48.870510506147575, + 49.068556827284254, + 49.26864223170053, + 49.4664655137866, + 49.66602445581489, + 49.85699306272575, + 50.04159151962469, + 50.22139204221718, + 50.39857397772692, + 50.56968175498876, + 50.743227400695744, + 50.914436488115655, + 51.07572512908874, + 51.2374188274606, + 51.400640247005846, + 51.56264390234506, + 51.72376071170347, + 51.887448023861666, + 52.050670372454405, + 52.21163653428425, + 52.37272718456936, + 52.530928525770655, + 52.69368258186714, + 52.85693113087273, + 53.01673973310257, + 53.175978871665535, + 53.33413338044323, + 53.488898307705625, + 53.641953059592616, + 53.794997423257534, + 53.94614986829016, + 54.09821763981167, + 54.24763872281109, + 54.39556974514787, + 54.544857009530865, + 54.69225454746054, + 54.835183549144034, + 54.98236898689759, + 55.12719972160686, + 55.270212383949016, + 55.41779180396307, + 55.5595721429318, + 55.697081292243176, + 55.83914094804922, + 55.97736523650002, + 56.111534879278764, + 56.25020498403974, + 56.38645900735883, + 56.51367827978848, + 56.64776222024372, + 56.78251438442593, + 56.909366023198594, + 57.040318993678504, + 57.17158153518691, + 57.29455922325618, + 57.41781775745749, + 57.542017283887716, + 57.65890884103764, + 57.775994080951975, + 57.894729838987416, + 58.00725661901747, + 58.116829449580685, + 58.22776725082642, + 58.335101438886184, + 58.44103590043717, + 58.545141641703005, + 58.650076352618015, + 58.75373246759643, + 58.85807811202025, + 58.96276072138144, + 59.06704747335343, + 59.17367855214936, + 59.28262777708285, + 59.392323874391046, + 59.499333882845356, + 59.60825783531494, + 59.71530206217485, + 59.819876706411286, + 59.92659593363098, + 60.02791787166093, + 60.122374329154006, + 60.217767571857614, + 60.311784964210005, + 60.39631897828489, + 60.47765047529153, + 60.56130950611345, + 60.643002314951374, + 60.71927567435813, + 60.79446933642293, + 60.872170250747125, + 60.94843642367266, + 61.01909456115377, + 61.0901889752132, + 61.1644313222098, + 61.23440900169365, + 61.301808753309, + 61.37124894988424, + 61.43205217258117, + 61.48007162806713, + 61.52087454747573, + 61.55268056257392, + 61.57033794523745, + 61.57967333535705, + 61.58123261799172, + 61.57006687229265, + 61.543951930475444, + 61.50101671375109, + 61.443577187180125, + 61.37177551007202, + 61.284344876552744, + 61.186407860721836, + 61.07364102809763, + 60.94148279358354, + 60.7947987289158, + 60.628772512865936, + 60.44807794113385, + 60.26022406482096, + 60.05428806671372, + 59.83236113594278, + 59.600819019064595, + 59.35483808704782, + 59.092657464317774, + 58.83026684654099, + 58.55672615133106, + 58.26491473000322, + 57.98173409242346, + 57.68944967785447, + 57.37211030881352, + 57.065809140174515, + 56.74713234501805, + 56.41122980633165, + 56.08215437372467, + 55.747268511748246, + 55.39019286938688, + 55.033145683768126, + 54.67964840612432, + 54.31199650127023, + 53.93933597616171, + 53.57322727179192, + 53.2088619419737, + 52.841202673940835, + 52.46752251759267, + 52.0920565467725, + 51.71929275257745, + 51.34383573646989, + 50.965414975173125, + 50.592039278483, + 50.21360665858586, + 49.82624288051308, + 49.44608107791579, + 49.073072096355226, + 48.68484008220616, + 48.31211375553175, + 47.95458871554521, + 47.58063883752528, + 47.2153466136471, + 46.867906773775225, + 46.50467714820476, + 46.149094202608886, + 45.801557912220005, + 45.44249150449991, + 45.08611015073263, + 44.73382850434776, + 44.371005246721474, + 44.00688512625639, + 43.65144174700234, + 43.28081489390871, + 42.90953975452277, + 42.54493878237917, + 42.16822904180096, + 41.79544680953694, + 41.42848455489019, + 41.0569993185093, + 40.684784571572024, + 40.311666830515044, + 39.946076102256484, + 39.57015425007888, + 39.19333837881301, + 38.82104700025099, + 38.44906853875514, + 38.07753529033888, + 37.70453294888627, + 37.33650472765199, + 36.97085062240488, + 36.602577447663975, + 36.19554793947306, + 35.836765679249915, + 35.472631217829154, + 35.10559550585509, + 34.74778256601126, + 34.38818681402771, + 34.03296686912532, + 33.68179901785343, + 33.32388162152203, + 32.97244564883373, + 32.62906622284139, + 32.27022652984324, + 31.910448589408816, + 31.57046358561761, + 31.207735566984358, + 30.840143538282717, + 30.490098702470352, + 30.13236394494525, + 29.757784668208508, + 29.407585765733774, + 29.05478277754968, + 28.684160144331962, + 28.32768425612499, + 27.980344111444065, + 27.62038291400361, + 27.265631676199437, + 26.922935248991845, + 26.57214733668604, + 26.218275301379094, + 25.86892713900485, + 25.525130751460914, + 25.17270247346353, + 24.820851901061474, + 24.479141590368958, + 24.13227361836511, + 23.784312416529406, + 23.445501267289572, + 23.11108379645721, + 22.769838631959008, + 22.42729129524143, + 22.088481558984395, + 21.7425621059889, + 21.386782669371648, + 21.037810565939633, + 20.686155558984794, + 20.32909523607062, + 19.976520951459147, + 19.61785401656065, + 19.254572972223155, + 18.892936676247537, + 18.530943889940545, + 18.162213685962982, + 17.795607207771546, + 17.43709267306614, + 17.064876487452445, + 16.69286255937941, + 16.323836228081472, + 15.93439991314548, + 15.550624617509252, + 15.169587009951547, + 14.777798962571978, + 14.39327652990857, + 14.010164666176923, + 13.620053313641371, + 13.240472869863268, + 12.855649660386884, + 12.457656460717581, + 12.087309596379711, + 11.709082269627443, + 11.305617505125515, + 10.930042676161868, + 10.552853859191243, + 10.153555819327073, + 9.765876715173547, + 9.385816477220772, + 8.98506470516248, + 8.600912941591435, + 8.2472130090847, + 7.883430395603922, + 7.523330710997504, + 7.174807110242863, + 6.818133961648295, + 6.458287936440017, + 6.1055557477686495, + 5.744899707929617, + 5.384899242974408, + 5.016762180625916, + 4.639514089040035, + 4.259448767562861, + 3.8799250689214406, + 3.5066850650037455, + 3.130571960102859, + 2.7545390538483923, + 2.381519482004951, + 2.011549784417578, + 1.636819093126453, + 1.2627461484560363, + 0.8899167223419955, + 0.5149138488284759, + 0.13951066804923412, + -0.2296033268271061, + -0.591829481554159, + -0.9573890043522815, + -1.3166312642264035, + -1.6669610420107002, + -2.0145518803280438, + -2.358203833896228, + -2.692206333792402, + -3.0249828635782507, + -3.3557618429030107, + -3.6816599275330524, + -4.016322961691832, + -4.351571897100986, + -4.675807072225649, + -5.041576474438306, + -5.378514314993975, + -5.7039036488851185, + -6.02861948480421, + -6.358260529889325, + -6.676209376700972, + -6.989398990788357, + -7.312298479580842, + -7.6236194742443555, + -7.927205615455769, + -8.240102947187161, + -8.543009513448073, + -8.838444679863796, + -9.137091857448395, + -9.415722084809714, + -9.691691680682883, + -9.965773486513827, + -10.218589818676252, + -10.465514082027534, + -10.712818963107472, + -10.944972752958886, + -11.173853063918022, + -11.402659063638243, + -11.626426552006645, + -11.851278530386587, + -12.066220910704354, + -12.265764676120943, + -12.45828065849491, + -12.63974964329277, + -12.812596511472101, + -12.964719668410408, + -13.095294771471865, + -13.214339362907191, + -13.309465808223615, + -13.381200570507621, + -13.440495933906309, + -13.48485224290256, + -13.509996579861, + -13.515912248322786, + -13.500791456951184, + -13.464092162041537, + -13.406465305272217, + -13.330448626995928, + -13.236713126610788, + -13.121820887101268, + -12.988946983863665, + -12.839521300856248, + -12.670847189035445, + -12.486159298049978, + -12.26964340203116, + -12.05784575956907, + -11.830414994001524, + -11.593130857039451, + -11.343976837364954, + -11.081427559928919, + -10.811469593127093, + -10.535280039116042, + -10.249323704083963, + -9.959281481145865, + -9.663436591566693, + -9.359519135571645, + -9.055676396199996, + -8.746249492785685, + -8.426506664897529, + -8.107769917340214, + -7.789079683603949, + -7.43187617424925, + -7.106811805114043, + -6.781308953675875, + -6.457427865651798, + -6.135067137444237, + -5.8076078210946935, + -5.485660342494167, + -5.163982711028811, + -4.842804830095412, + -4.525497963425851, + -4.202286730925984, + -3.8872365048945516, + -3.5710007459511868, + -3.2493033790092642, + -2.9307718569842347, + -2.622909204046957, + -2.311799986789748, + -1.9929130432471385, + -1.6879130536560099, + -1.3801645624367718, + -1.0786901109785534, + -0.7705709269465955, + -0.45871066379595865, + -0.16591942495330286, + 0.13388850852863304, + 0.4386527176271459, + 0.7271016700638674, + 1.0147017642829126, + 1.312925412256923, + 1.599547572556182, + 1.875647084564698, + 2.1607866979288173, + 2.4405236677390967, + 2.7088855627183834, + 2.9821984624413624, + 3.2807639018105226, + 3.544126139165194, + 3.8052634940311676, + 4.066878661153095, + 4.327566222075714, + 4.586850509581693, + 4.84374354429191, + 5.102617470320565, + 5.361612688753339, + 5.620601378978854, + 5.882371534952736, + 6.144447683011872, + 6.408028410118787, + 6.670309283992486, + 6.93518484682412, + 7.199380948441766, + 7.4592094822253205, + 7.720781631205502, + 7.984802436534399, + 8.241033501825141, + 8.495310167576601, + 8.756498462701014, + 9.01279369066786, + 9.267185207063543, + 9.524648071103888, + 9.778804858863614, + 10.032278542536712, + 10.286735654355022, + 10.545834201612884, + 10.808438749298523, + 11.065849071428358, + 11.329283903918698, + 11.599905800962043, + 11.869236803334779, + 12.14395574068719, + 12.422198556594, + 12.694262219069953, + 12.973886411152089, + 13.261834923721766, + 13.544937046851691, + 13.835374000449056, + 14.137318148082358, + 14.44031304259292, + 14.750956372342285, + 15.072998599781041, + 15.396776005795898, + 15.725591150462137, + 16.05812728995256, + 16.401111259621587, + 16.743713804636872, + 17.08569379124639, + 17.43713552016897, + 17.79009196415209, + 18.137325966390065, + 18.485598410218454, + 18.841061012833208, + 19.1947311733276, + 19.55024998889843, + 19.91739273560585, + 20.279800851750586, + 20.641698825072954, + 21.01626753275855, + 21.381437269980324, + 21.74945836364647, + 22.123307300275794, + 22.49810250771896, + 22.873446513383893, + 23.25454720162248, + 23.633985364458233, + 24.017236684911364, + 24.400465324202926, + 24.780432533521612, + 25.165300920798973, + 25.553796097726693, + 25.94090905050499, + 26.329928742885684, + 26.72625019593362, + 27.127724848900797, + 27.524905111658466, + 27.919932337766923, + 28.32272714539061, + 28.721867424026556, + 29.10499095204518, + 29.501284213662537, + 29.902546573077874, + 30.289747900845505, + 30.687852056436082, + 31.096502013698338, + 31.498374388560404, + 31.89864995764112, + 32.31440908050786, + 32.72648830702518, + 33.12853595823151, + 33.547462960297494, + 33.96920776536035, + 34.37413899475233, + 34.7848389750732, + 35.2014649572255, + 35.597268719613716, + 35.99926741469605, + 36.408458444436256, + 36.80721240488395, + 37.20257949248309, + 37.60052453329765, + 37.991657355594654, + 38.373106260558764, + 38.7586474969034, + 39.15054874965966, + 39.531146311052645, + 39.91638877380719, + 40.3052011809927, + 40.67213221278191, + 41.031639581896655, + 41.38904008884563, + 41.740934311828376, + 42.068906969612975, + 42.403283573499834, + 42.739995148320155, + 43.05545313539726, + 43.374885587472235, + 43.69105050585382, + 44.034718590261754, + 44.399440405877925, + 44.75573882919998, + 45.11269320822648, + 45.47207171954012, + 45.82321291832529, + 46.167324051461485, + 46.529838813112896, + 46.867935361514974, + 47.20358920137738, + 47.53154596324945, + 47.82824565864461, + 48.13035638881362, + 48.439578661092845, + 48.72878415650247, + 49.01799174590698, + 49.31509378649518, + 49.59065565637017, + 49.872446879664224, + 50.161030673020164, + 50.43093707360798, + 50.71653099600174, + 51.00801499391844, + 51.28412378986799, + 51.570232325542904, + 51.84684824699016, + 52.10135537498573, + 52.36382541889213, + 52.62285233340489, + 52.857304296666236, + 53.08168246480826, + 53.297658560875924, + 53.494553520301, + 53.682882360170154, + 53.86564705686268, + 54.03316019127849, + 54.18906611239944, + 54.335096088576485, + 54.47040493086842, + 54.5981560552488, + 54.71558719964669, + 54.820270750345635, + 54.91759047027468, + 55.01055491161814, + 55.09588636158094, + 55.17623508168371, + 55.252569539690406, + 55.32559478133029, + 55.39501599037662, + 55.45728538600888, + 55.51160645854966, + 55.56203731730469, + 55.60777989868791, + 55.6497247389787, + 55.68871194470887, + 55.72431214489305, + 55.75557230577191, + 55.78536217914103, + 55.81369211386821, + 55.840490438198856, + 55.86707253324583, + 55.89317166298818, + 55.917497181025844, + 55.938754360869986, + 55.9578805013551, + 55.975057160104434, + 55.99200341947563, + 56.008960749704706, + 56.02611811151575, + 56.04551855081822, + 56.065612828790556, + 56.08624290434219, + 56.10849143838573, + 56.13327154137771, + 56.15864056253118, + 56.18625727930865, + 56.21526082904195, + 56.24609847812245, + 56.27941913145412, + 56.31335090786335, + 56.34825342646937, + 56.38488166382764, + 56.422272186809735, + 56.45978262271737, + 56.498774051881874, + 56.53963479954145, + 56.58270614033862, + 56.62631234549384, + 56.666835504765636, + 56.70561396556938, + 56.74447719423239, + 56.77953562869674, + 56.81235956700406, + 56.84522458717532, + 56.874152619023114, + 56.89958071593323, + 56.92362663322244, + 56.94608380077201, + 56.96512763148799, + 56.9810790312063, + 56.99099649348849, + 56.99733998415812, + 57.001302773784445, + 57.002257291044984, + 57.00164993548657, + 56.99998009121031, + 56.99684186251042, + 56.99268569402752, + 56.98721195516007, + 56.97963365895441, + 56.968764749230175, + 56.95480109752451, + 56.941476203504855, + 56.926593043316956, + 56.90965162175531, + 56.89141894751151, + 56.872775902199436, + 56.852442614849934, + 56.83026612892718, + 56.807155095724006, + 56.78434553057613, + 56.762774392814606, + 56.74061184045273, + 56.71773567127197, + 56.694092432452265, + 56.668751995777875, + 56.64301787073612, + 56.61360022029209, + 56.58706620967639, + 56.56200859435146, + 56.535993205281834, + 56.50908694382358, + 56.483003094332055, + 56.45838257856404, + 56.4346862193037, + 56.40936271856511, + 56.385699750130506, + 56.36241765049165, + 56.33407824649129, + 56.300186924489005, + 56.2626047742628, + 56.217622540906355, + 56.164301967674, + 56.104470415148654, + 56.03568400588743, + 55.958923235646004, + 55.87017771658777, + 55.771115929307356, + 55.66050217532969, + 55.53044770724891, + 55.38055949319694, + 55.216001877033484, + 55.03403979101949, + 54.839375040529994, + 54.62895565047312, + 54.40213511838124, + 54.162324164496454, + 53.90124285846883, + 53.622444319674706, + 53.3366974726652, + 53.07248271198428, + 52.79705010867054, + 52.507318094547344, + 52.21294697273232, + 51.92120120248295, + 51.61207252562718, + 51.30699332943816, + 51.00734363108432, + 50.702721721217024, + 50.38718403716465, + 50.04851660808337, + 49.707037104368034, + 49.360224670300354, + 49.00487502463951, + 48.641829306869624, + 48.278330910604694, + 47.90812569109004, + 47.53010797359777, + 47.14905486851263, + 46.77431686372914, + 46.39850932456343, + 46.01506796786698, + 45.649455406700426, + 45.28012244268648, + 44.90598094101536, + 44.54835840428026, + 44.19305491361802, + 43.831669333156846, + 43.481563082465144, + 43.130917728424755, + 42.77102309335774, + 42.42588471985768, + 42.088970847074165, + 41.73601757904162, + 41.4070432000424, + 41.09028077060689, + 40.75586405661557, + 40.43920184656599, + 40.13908606542127, + 39.820912095716515, + 39.51821026570658, + 39.22565784053581, + 38.92544930996288, + 38.62890237091544, + 38.33675220193973, + 38.04031603291111, + 37.74089227426836, + 37.4523878475412, + 37.15338460713522, + 36.84949927002007, + 36.547048751106004, + 36.240560246554416, + 35.929161909053114, + 35.62311824272138, + 35.3183424998264, + 35.01037187522542, + 34.707709613049104, + 34.39915913979863, + 34.099861708615606, + 33.79279965725131, + 33.487875124784374, + 33.183087723674696, + 32.87830187627792, + 32.577227629946606, + 32.27096875349995, + 31.965519217591762, + 31.66172759978884, + 31.354365384492315, + 31.046656141832095, + 30.738625668025836, + 30.43607848762624, + 30.12677037888246, + 29.81739633486835, + 29.51947034584702, + 29.218203390804486, + 28.92149718800499, + 28.63320082420781, + 28.342611341872676, + 28.056307698892773, + 27.778988845446865, + 27.496641777074625, + 27.203736782492673, + 26.928179703117003, + 26.654071999193174, + 26.360346835877365, + 26.08156308849356, + 25.8090037438668, + 25.525486766014126, + 25.24645351763025, + 24.978613261245844, + 24.707167086692618, + 24.430153252330985, + 24.161261099425584, + 23.890192597742644, + 23.619054792305313, + 23.34488060380485, + 23.07430620809438, + 22.801931440354025, + 22.525441500138093, + 22.244284613603494, + 21.965360344997897, + 21.68341061143713, + 21.389656174831394, + 21.10467362856162, + 20.82047946996094, + 20.53505359737702, + 20.245510637256043, + 19.967293857664238, + 19.691222198091676, + 19.411483917414408, + 19.138347021124353, + 18.864962985798453, + 18.589269426263186, + 18.31100174176081, + 18.03492111190702, + 17.75558296647682, + 17.473562671069693, + 17.200438934518257, + 16.917401201824916, + 16.631651987269017, + 16.359695686680062, + 16.083964508251945, + 15.808445329769434, + 15.528998344664615, + 15.246312974770017, + 14.963048683336664, + 14.678183598668438, + 14.38567804772808, + 14.09108602102483, + 13.79067820563298, + 13.484981238648714, + 13.17233610697443, + 12.854409475124706, + 12.543579069186688, + 12.224576288312015, + 11.903988117926017, + 11.590515042156978, + 11.27156361328683, + 10.937149255696873, + 10.621284336546001, + 10.307138076044264, + 9.96187736183818, + 9.633799869322353, + 9.316861496514987, + 8.975615959095764, + 8.640931975238832, + 8.314022543478073, + 7.976308910818991, + 7.636775708274165, + 7.304373279250715, + 6.966748681866484, + 6.626228722662883, + 6.290696473460649, + 5.94855215362453, + 5.606647634962997, + 5.262264275062881, + 4.915850589696338, + 4.56503725971969, + 4.215819886913209, + 3.862648417740447, + 3.5067342928165557, + 3.1521366230353665, + 2.7905079156473334, + 2.4331973674042784, + 2.0733013157448377, + 1.7096896004210587, + 1.3468153360950268, + 0.9843736049861767, + 0.6206651559982981, + 0.25386579255841035, + -0.10787248571359065, + -0.4647305094568017, + -0.8277431577087507, + -1.188716416606794, + -1.5396355120916694, + -1.8932530120750826, + -2.2583644158023266, + -2.603560017956953, + -2.94857786189462, + -3.299685367007091, + -3.641631300058217, + -3.9777075859163875, + -4.311540341567952, + -4.647905601911665, + -4.98643944564314, + -5.3161867597026315, + -5.645378308979822, + -5.982064220250516, + -6.309198909992838, + -6.625696462397852, + -6.959890518684558, + -7.279114416760989, + -7.5801872903702785, + -7.898283006223394, + -8.215782352106562, + -8.511581200654915, + -8.81823986077847, + -9.117396045045018, + -9.40529871691725, + -9.703334169787272, + -9.968453923865091, + -10.227751449352153, + -10.49488408352675, + -10.737110431797747, + -10.964925381875702, + -11.192439612456948, + -11.401710433912035, + -11.597219541926718, + -11.78649369066499, + -11.960974289084511, + -12.121558477089204, + -12.274004597117614, + -12.414278156546354, + -12.539394400219807, + -12.651796775165819, + -12.750172513848746, + -12.833263999671926, + -12.898343621041262, + -12.944115314510055, + -12.970450817396848, + -12.975166246931376, + -12.957854522222375, + -12.915919799690897, + -12.851487504768736, + -12.766147034397553, + -12.657835511816371, + -12.529562243907494, + -12.382168859257977, + -12.212984734604289, + -12.022222884524053, + -11.813070345141318, + -11.589851849627294, + -11.344780693265411, + -11.082835235302445, + -10.807150355459857, + -10.515798799134334, + -10.21669837731114, + -9.912289205662937, + -9.594714083095585, + -9.268121412855555, + -8.938893856842977, + -8.599022533715896, + -8.218035145122501, + -7.872654199631793, + -7.521511439317353, + -7.169695461721039, + -6.817039824455227, + -6.462762387535386, + -6.113915135750591, + -5.7617602594028465, + -5.409145548072722, + -5.059375207302049, + -4.7073067158858874, + -4.355453720158067, + -4.004345884288577, + -3.6555353066442637, + -3.306697587703429, + -2.9549071260976794, + -2.6056834721656603, + -2.2547126947573575, + -1.016144631818952, + -0.6593447068545467, + -0.29691349244891246, + 0.06682109086171656, + 0.42267325086137597, + 0.7813629011494736, + 1.1464116872567325, + 1.4985278040133412, + 1.847828384791398, + 2.1944482616636787, + 2.5560238488109652, + 2.9089475188257614, + 3.248541863940694, + 3.6071166754576898, + 3.9611254341968856, + 4.29951460278969, + 4.649203489040254, + 5.004768934062478, + 5.341215066110188, + 5.683026295931434, + 6.035152746299424, + 6.371613634847714, + 6.710384205710767, + 7.055907689133003, + 7.391088314122611, + 7.723706761010639, + 8.059606274998435, + 8.399822638319982, + 8.737262714589445, + 9.072764668335603, + 9.411394409922703, + 9.750168634756196, + 10.086398424812142, + 10.427871163356038, + 10.770141606423742, + 11.112137081393188, + 11.45508885312039, + 11.801456017264574, + 12.143606023859176, + 12.481942940541515, + 12.823880464472007, + 13.164568009481984, + 13.495294709750159, + 13.830083006709483, + 14.170955919684296, + 14.501566572749946, + 14.835912197727998, + 15.172442622621617, + 15.506267221802657, + 15.839129408792655, + 16.18113497915037, + 16.526883586559574, + 16.865436657362082, + 17.214431431623144, + 17.569915001443942, + 17.92107011923, + 18.27697382081262, + 18.629669892403687, + 18.974664218883955, + 19.329598141794772, + 19.683660795842304, + 20.037833166246752, + 20.406925935986468, + 20.77969883510911, + 21.155172943833268, + 21.543468568745645, + 21.933708084255827, + 22.322769562578095, + 22.71685622794749, + 23.117219972608545, + 23.506586144966622, + 23.901943228873048, + 24.302859177000435, + 24.692795543066143, + 25.078906741171313, + 25.47115779143322, + 25.862400063794517, + 26.239704017299378, + 26.6150304365897, + 26.98916615447716, + 27.3561448797532, + 27.731475046043933, + 28.132988239803222, + 28.496582464071857, + 28.864531397545658, + 29.22946662361722, + 29.593362792573764, + 29.9689814226995, + 30.347515479261563, + 30.72503102136061, + 31.106642370879552, + 31.47985463613509, + 31.851931624853773, + 32.225114075915926, + 32.59535383595824, + 32.9683166877988, + 33.34025448514065, + 33.70690669880313, + 34.06789038744542, + 34.42489888646252, + 34.78197595343813, + 35.14068119064813, + 35.49968765818269, + 35.847348483160104, + 36.19502013226061, + 36.55285549019777, + 36.903679690722576, + 37.254313549553984, + 37.62096065220641, + 37.99019885205885, + 38.354835747346755, + 38.717330858397546, + 39.08805854400857, + 39.45769299447226, + 39.820194113275996, + 40.186930864553055, + 40.55830313266503, + 40.92637271855744, + 41.29350248721418, + 41.66182453114698, + 42.02773198370218, + 42.38898935582809, + 42.743691438432414, + 43.09952598950704, + 43.45621614353036, + 43.807111789810214, + 44.15206120455052, + 44.49881874566006, + 44.84529438441963, + 45.18294435790405, + 45.51704133575203, + 45.85655652158104, + 46.19523093613297, + 46.53007774290174, + 46.86857589089276, + 47.211413736876786, + 47.54622747104714, + 47.87276187551954, + 48.19569546135149, + 48.519195885036176, + 48.84260235486342, + 49.1473908981684, + 49.46374395892525, + 49.78029019133622, + 50.08493866689776, + 50.39204986447101, + 50.69319910828734, + 50.99132840440384, + 51.29192071105291, + 51.582045384248445, + 51.872471859917276, + 52.1592504111497, + 52.4350525913333, + 52.70901959667804, + 52.98711179932178, + 53.23758650158044, + 53.49646772508539, + 53.75713529197604, + 54.002655723677016, + 54.255169822508606, + 54.49764875251168, + 54.72549938618048, + 54.95806390038172, + 55.18029935360197, + 55.38916754716942, + 55.60544845519947, + 55.80996449878175, + 56.00416256686348, + 56.20602419424737, + 56.39689791882204, + 56.5819638418341, + 56.76605931488675, + 56.93121186961011, + 57.0847437656932, + 57.24087262915049, + 57.3841441269592, + 57.50971834427297, + 57.62984755985808, + 57.7394818044663, + 57.8357333791372, + 57.92317404854355, + 58.00007169204911, + 58.06464848285505, + 58.118889449338944, + 58.16351942840969, + 58.20018761272942, + 58.22886715626672, + 58.248042460390316, + 58.256639159487, + 58.2568197075274, + 58.248665075037955, + 58.22969429536686, + 58.20419783083681, + 58.17560086311876, + 58.141548691773025, + 58.101857499033954, + 58.060145303296245, + 58.011058868062456, + 57.95489809423012, + 57.897603938181994, + 57.84009500065257, + 57.774109457229166, + 57.70487994792536, + 57.63580509237289, + 57.56282063930549, + 57.486398785431106, + 57.41099580810595, + 57.334142946106496, + 57.25537022169586, + 57.17719709774812, + 57.09592902731557, + 57.01470632604266, + 56.93447193980057, + 56.85307117702178, + 56.77029213847556, + 56.68748898081699, + 56.60171108044309, + 56.5144062955533, + 56.42697707059443, + 56.33888147756388, + 56.249912172280084, + 56.163371018533866, + 56.074755366893996, + 55.985709385729166, + 55.897674213490085, + 55.806567331121016, + 55.716551287058394, + 55.62852978140373, + 55.54110829949496, + 55.452063913251514, + 55.36928513113563, + 55.28299417322558, + 55.194485989480135, + 55.10741852876635, + 55.014959570444105, + 54.92078588489622, + 54.828211820035186, + 54.731937231042934, + 54.63481426538961, + 54.54185814289958, + 54.45039042089325, + 54.353863355020806, + 54.25830390614105, + 54.16355367013178, + 54.067183952066834, + 53.96961556322214, + 53.875489068239254, + 53.782588779146074, + 53.68728669789345, + 53.59160240253313, + 53.493813961135, + 53.39312249025475, + 53.293917428978496, + 53.19549328311058, + 53.09784616416041, + 53.00343346813311, + 52.91138524518661, + 52.816895899896316, + 52.72559033045191, + 52.63372847956242, + 52.537673534742126, + 52.438352767813484, + 52.335850437803785, + 52.23429022460171, + 52.13032291459659, + 52.02138747127137, + 51.9091621323457, + 51.7955864664183, + 51.68045543786064, + 51.56484038437353, + 51.449693409955174, + 51.333268513282285, + 51.22080427580808, + 51.11119085894538, + 50.998876538331565, + 50.884358210639235, + 50.76843972732959, + 50.6547493701092, + 50.53670168027883, + 50.414539489854974, + 50.29250382161416, + 50.16923226197554, + 50.04648686772441, + 49.915343279841046, + 49.78405666415551, + 49.6547537874927, + 49.5227238004472, + 49.382419832792245, + 49.24782791651712, + 49.1139395589107, + 48.96570417039539, + 48.813339413030064, + 48.66321947995453, + 48.50128959409817, + 48.32829467363929, + 48.163317734267125, + 47.99783935450026, + 47.811215670249794, + 47.615792104090346, + 47.42010955719554, + 47.202104508530084, + 46.97541122544629, + 46.74832788648891, + 46.503515383730296, + 46.257124492157836, + 46.00443966411958, + 45.737693166825295, + 45.466144122088366, + 45.18918840755828, + 44.896555531244026, + 44.60083749977606, + 44.30263169740128, + 43.98121558449072, + 43.65122579502918, + 43.320550280330075, + 42.97924154608048, + 42.62774551219158, + 42.27931734017526, + 41.930926612424564, + 41.57160453423903, + 41.22628263456777, + 40.88772771176841, + 40.53334759994677, + 40.18087262972471, + 39.84929522337897, + 39.50183422096595, + 39.15547316248579, + 38.82199146021086, + 38.48419826495861, + 38.13588746646588, + 37.7985795891807, + 37.465327585095864, + 37.12438785272797, + 36.78748070236091, + 36.460936828741694, + 36.13849174292853, + 35.818019446615295, + 35.50032179179734, + 35.19408740014488, + 34.89625721624557, + 34.602307171649095, + 34.309653977381, + 34.02623414673576, + 33.74330974570317, + 33.46000908308997, + 33.1857097589885, + 32.9177196606458, + 32.64263546308539, + 32.380992591960194, + 32.130901719529504, + 31.87157752205381, + 31.61917304560049, + 31.37988264498719, + 31.13101326647757, + 30.884323106330893, + 30.646533440124994, + 30.40408282964225, + 30.146959891245604, + 29.88448504438357, + 29.61865810262047, + 29.348917852009006, + 29.087264615127534, + 28.819257770215366, + 28.545539879660744, + 28.275144151039928, + 28.004524754651715, + 27.729003807976547, + 27.47098481153848, + 27.223162800229783, + 26.972923554608013, + 26.72677387454312, + 26.47887433409944, + 26.236261017013035, + 25.987254879866487, + 25.73616714567915, + 25.486351945808043, + 25.23541638191824, + 24.976612733565506, + 24.708836813349716, + 24.444242088522454, + 24.183680460309283, + 23.92023230755656, + 23.662138150480853, + 23.40775737023184, + 23.160553351897548, + 22.908975463679933, + 22.661340123032478, + 22.43080775202382, + 22.20553687882793, + 21.9860609892867, + 21.770918182486945, + 21.555406605446567, + 21.34986405403206, + 21.15032088740068, + 20.94772370812601, + 20.746033767161908, + 20.557948720122173, + 20.37911246069998, + 20.2050970463388, + 20.045346731317927, + 19.887660113538683, + 19.723106650941904, + 19.567161955808007, + 19.41781667897727, + 19.25912313221167, + 19.1018936338632, + 18.94802132826251, + 18.780077784699476, + 18.604879785384224, + 18.426844352999904, + 18.25017374463643, + 18.07334494052737, + 17.893627294245118, + 17.711399994261882, + 17.534140096189052, + 17.358126432405346, + 17.171053903579285, + 16.994746910297717, + 16.825380401154792, + 16.654548016098808, + 16.481239113968705, + 16.31238100766003, + 16.14682618402819, + 15.976957195972991, + 15.807003608531945, + 15.63030631280838, + 15.448823938741326, + 15.256503734705, + 15.055776462028861, + 14.853561737107857, + 14.642350626253576, + 14.42957160162266, + 14.216913929764194, + 13.99637284496533, + 13.772255968871258, + 13.543923645364524, + 13.310583581208467, + 13.081051851545233, + 12.842513876182316, + 12.600887179171432, + 12.365494317937173, + 12.125053940886609, + 11.87754675994134, + 11.634779045426287, + 11.391636950288863, + 11.138752588746124, + 10.885737495057397, + 10.637110817193527, + 10.37631275176222, + 10.120747349680473, + 9.866323904194086, + 9.603697820146095, + 9.332286823133868, + 9.0748035923133, + 8.814631046542207, + 8.530801654482412, + 8.26847597313656, + 7.998613394407122, + 7.709034026499522, + 7.426737459710137, + 7.145135392698271, + 6.855922882173727, + 6.565047225511663, + 6.2805755454440995, + 5.990557694676198, + 5.699136396613642, + 5.410124824571167, + 5.120077302615389, + 4.831230677099671, + 4.54207279813495, + 4.252944707874897, + 3.9586098010546507, + 3.669764536832375, + 3.3765471139175487, + 3.0878020454357307, + 2.800668191323897, + 2.509544658820502, + 2.2238096768409816, + 1.9397069578386525, + 1.6500897063979356, + 1.362347080419284, + 1.0772277250530258, + 0.7910930729576051, + 0.5020353633970458, + 0.21958796629526706, + -0.060293937664332276, + -0.34665879499137725, + -0.6310382034723865, + -0.9060391670727266, + -1.1798149642421087, + -1.4612438091295152, + -1.7260298304563348, + -1.9870151144306107, + -2.255890685863474, + -2.51332495304702, + -2.7681952879705367, + -3.025491755782631, + -3.2823477372675747, + -3.5414708569113142, + -3.803992522585109, + -4.0609974068591885, + -4.323129468016861, + -4.584471712017325, + -4.836342448098703, + -5.099679855212179, + -5.352847808689377, + -5.5982512165993565, + -5.848306335182828, + -6.09036860514888, + -6.322384989945734, + -6.550318190646657, + -6.774286712598426, + -6.988667685569313, + -7.199921601710623, + -7.399068101227516, + -7.588067265110479, + -7.774274646162148, + -7.948121765275557, + -8.111447390893122, + -8.269613069632488, + -8.41651431549843, + -8.55200273365739, + -8.67634862753494, + -8.78987639016042, + -8.89117457887087, + -8.979672196526547, + -9.053647673504077, + -9.111662863150716, + -9.153118241515317, + -9.177439947421492, + -9.182679654991453, + -9.164435525480405, + -9.122535578493585, + -9.059180953482048, + -8.966721078634922, + -8.84719695506742, + -8.709832818046813, + -8.546924630265831, + -8.363554638520565, + -8.164954223425692, + -7.945885542441818, + -7.707600011315168, + -7.45303802312471, + -7.187178875430662, + -6.904081494774582, + -6.607476668832274, + -6.302587949724487, + -5.985350965623969, + -5.666028423818949, + -5.344198943377727, + -5.015818853909928, + -4.682784448086348, + -4.351447614988249, + -4.01687874605739, + -3.6809000214827328, + -3.345357551805807, + -3.008512821048182, + -2.673979506163399, + -2.3397883323658, + -2.0053681283661695, + -1.6771229294828973, + -1.3459446271774362, + -1.0144560215997926, + -0.6882772597742572, + -0.3597937308891938, + -0.028713806931663866, + 0.3009334585075025, + 0.6288209474265939, + 0.9906581931130227, + 1.3229981073005046, + 1.6528271932735743, + 1.9834804546204001, + 2.3158101796974684, + 2.650389499645336, + 2.989698323975892, + 3.3303782701733358, + 3.67362537437298, + 4.0256435901686025, + 4.377563864505549, + 4.726978463147397, + 5.088270473534252, + 5.446698852249907, + 5.805426737360769, + 6.162648068491221, + 6.537312796135578, + 6.906323029752279, + 7.264904769651772, + 7.648205452805329, + 8.028705949725971, + 8.39481433418138, + 8.775486502453115, + 9.164022319070252, + 9.534991230269316, + 9.91797625104327, + 10.307106815210924, + 10.681830130858234, + 11.064319217170734, + 11.449135985864679, + 11.822286885609556, + 12.197967429029495, + 12.583588751817393, + 12.963715083103914, + 13.339447140418724, + 13.72308593987491, + 14.10818544495083, + 14.487205736668509, + 14.872303321247559, + 15.264265386621576, + 15.654693611545001, + 16.045843922128682, + 16.44264593510048, + 16.832226639154566, + 17.21709171809061, + 17.607646634318066, + 17.98703884753735, + 18.360256176383263, + 18.745020681817333, + 19.122283620366723, + 19.494047547673123, + 19.871883338024883, + 20.25025525227716, + 20.620143493119027, + 20.996648415891052, + 21.379095723299685, + 21.75120988024822, + 22.128902431355506, + 22.549028405390022, + 22.92257552152903, + 23.298492799534674, + 23.668039618765476, + 24.034418180630414, + 24.402587775607156, + 24.768509258560105, + 25.14092822366267, + 25.520675120181387, + 25.89587035681767, + 26.281559208811142, + 26.67579382364871, + 27.06094841140931, + 27.443116739652332, + 27.836726486238437, + 28.220730891261532, + 28.598404621714625, + 28.986670185687952, + 29.368667031179605, + 29.735330368782186, + 30.10698685884798, + 30.488333490875757, + 30.85604320241579, + 31.231458714020444, + 31.610428430291396, + 31.981387603217183, + 32.35147615571863, + 32.725201401803595, + 33.090163939738815, + 33.45714896101673, + 33.82373504984475, + 34.190023025847744, + 34.55467782749827, + 34.91993996208546, + 35.28209442854368, + 35.64771721796965, + 36.00808404331896, + 36.363754253246114, + 36.72175203849156, + 37.0766317342795, + 37.43179336496569, + 37.787541168055846, + 38.14628469754537, + 38.505612032640514, + 38.86385894889629, + 39.22160109609035, + 39.58281340265719, + 39.942272359667086, + 40.2909610335045, + 40.6467467456102, + 41.00943179588437, + 41.39339467250685, + 41.745327077367385, + 42.10756385294624, + 42.46416835450666, + 42.813080626938905, + 43.17076516555194, + 43.530657740696626, + 43.88048509542785, + 44.23209581492437, + 44.58887016261397, + 44.93822925178907, + 45.28542915062545, + 45.63212764383536, + 45.976375664207836, + 46.31569444536887, + 46.64991857063094, + 46.98564606356336, + 47.321883982566234, + 47.64909307566419, + 47.9751049527662, + 48.34048032252985, + 48.66693411421494, + 48.985844207941184, + 49.3108016268647, + 49.63670035314136, + 49.9593325086482, + 50.28244189043483, + 50.60929008070905, + 50.928695093063304, + 51.23992569710519, + 51.543961489579914, + 51.85075025401761, + 52.14936616276105, + 52.43408692711314, + 52.72808444983445, + 53.01386257315126, + 53.29189700453342, + 53.566049763412636, + 53.833545106028154, + 54.09520349323003, + 54.37086918180053, + 54.63662494331925, + 54.89861891143578, + 55.15205340272464, + 55.39346628788784, + 55.6361666685264, + 55.85404262031117, + 56.073175974680794, + 56.290664268951645, + 56.493493350033795, + 56.682564783040604, + 56.859825735682755, + 57.02611248973415, + 57.19278327516731, + 57.34786474456324, + 57.49352738841198, + 57.64208441539389, + 57.77824828335502, + 57.90325866739047, + 58.026066272551375, + 58.13497327538347, + 58.23738653231144, + 58.33204417169462, + 58.410107921082485, + 58.47934173556328, + 58.545108023930155, + 58.59728381719211, + 58.63235198478038, + 58.65698705479223, + 58.67059514290284, + 58.67287685816191, + 58.66331579414038, + 58.641028586388636, + 58.60497545332039, + 58.554691873595644, + 58.49210613343218, + 58.41795591290818, + 58.33025605033609, + 58.233244842556886, + 58.1289313021224, + 58.00953886144346, + 57.8847753613733, + 57.755545790777425, + 57.62198379887005, + 57.489626431310825, + 57.3545590289746, + 57.21034560762268, + 57.06810764394721, + 56.924392466209, + 56.77141156498824, + 56.618519142870355, + 56.46650087897269, + 56.312699591565114, + 56.14783236248102, + 55.98127169651004, + 55.81325362599921, + 55.640681113484476, + 55.463359867676985, + 55.28486447754226, + 55.10360758017922, + 54.92062582233616, + 54.737989991586964, + 54.551390604301346, + 54.364011487690796, + 54.178580706612046, + 53.990632158596966, + 53.80028055044182, + 53.609742480587116, + 53.41514836203741, + 53.21727608030595, + 53.018675490599364, + 52.818713805094134, + 52.616883089988555, + 52.397905667915005, + 52.196155179863446, + 51.99639774843956, + 51.799775949009806, + 51.600953721753065, + 51.40861947716391, + 51.22333370824064, + 51.0374712372325, + 50.855005057686355, + 50.688353478211674, + 50.51723710675954, + 50.3455432861825, + 50.18420966713949, + 50.014774032471976, + 49.84001643121023, + 49.67033723345798, + 49.49521791401003, + 49.31761842796205, + 49.139475273930294, + 48.95933033664392, + 48.78201883995827, + 48.60116010014866, + 48.41164010110454, + 48.22460340804343, + 48.03657447342987, + 47.8409772761511, + 47.64541445104406, + 47.452407790689605, + 47.252335229036255, + 47.0488862075855, + 46.84674289594181, + 46.63773838425997, + 46.42499982516288, + 46.2182392115676, + 46.01085050903486, + 45.8043570241303, + 45.605832838573946, + 45.40521264084731, + 45.20693185152201, + 45.010951940781084, + 44.810024484071626, + 44.60403119177929, + 44.394837331665336, + 44.18681003464203, + 43.97336916175396, + 43.752453457310786, + 43.52824975368074, + 43.30260856699138, + 43.07399057832258, + 42.84597649759885, + 42.618286310099975, + 42.39456679747721, + 42.17734075859258, + 41.95813335150637, + 41.736125474207135, + 41.51449057201843, + 41.298491646435735, + 41.07445834605348, + 40.845753658880696, + 40.620731123992435, + 40.397990705663894, + 40.167896103367454, + 39.93193243618115, + 39.705918339212104, + 39.48686327720169, + 39.25550186563384, + 39.03039582169425, + 38.82213733268875, + 38.59952219886444, + 38.36562859500524, + 38.140918113165704, + 37.914551919383136, + 37.67704500904111, + 37.4327648269679, + 37.19576843222316, + 36.96346024087171, + 36.71256033806325, + 36.45569824698664, + 36.204202526053386, + 35.93594137111388, + 35.65439732910691, + 35.375069343554244, + 35.080647498042644, + 34.78159124444144, + 34.48432259043408, + 34.17601416112367, + 33.85730585675768, + 33.54022467148753, + 33.21398289048241, + 32.88057173567504, + 32.5593991025957, + 32.224338959321855, + 31.87265507606582, + 31.52941986245883, + 31.185321588093913, + 30.83495790527638, + 30.483176710360837, + 30.13984230595454, + 29.796797585259508, + 29.452398249545908, + 29.1322259691733, + 28.81259330422633, + 28.482039901889774, + 28.17419431590544, + 27.874902248263705, + 27.563809951539003, + 27.269759329242813, + 26.983040244336255, + 26.696945727645215, + 26.414159339864348, + 26.14317399628155, + 25.877638291023967, + 25.61564585304183, + 25.364128917046393, + 25.119938752473665, + 24.88640618896987, + 24.65859446559463, + 24.433826356383783, + 24.21643080004734, + 24.008157091077344, + 23.80333956225134, + 23.600609285363234, + 23.4076440355656, + 23.216191374205522, + 23.023618396041325, + 22.838021091596005, + 22.66020368462961, + 22.485041918917382, + 22.316591084404195, + 22.15788052741282, + 21.997984346471842, + 21.83896013348688, + 21.690936198905295, + 21.542541913930926, + 21.39239283017581, + 21.250398569419726, + 21.107269455421736, + 20.960765028847213, + 20.818883520396817, + 20.674993319240766, + 20.529411838200115, + 20.386071380537, + 20.242313367399, + 20.093573492457427, + 19.945424843322208, + 19.7989882397102, + 19.647953509156423, + 19.501039537502717, + 19.3556920737729, + 19.209085238573966, + 19.06330342794033, + 18.918478256689006, + 18.77486174515046, + 18.633719742302276, + 18.49000570181859, + 18.348067580210355, + 18.20713156423599, + 18.0656706274686, + 17.92719991485461, + 17.78930854430543, + 17.653967240576634, + 17.51903243840091, + 17.385085715720912, + 17.25147021804598, + 17.121157525230412, + 16.98185303784235, + 16.855799462632948, + 16.737402931218128, + 16.622222900466735, + 16.508102186416515, + 16.3973683401855, + 16.287392703540053, + 16.17888974795789, + 16.077843114009983, + 15.978509781379111, + 15.878763835543987, + 15.779724745055054, + 15.683413642691823, + 15.58394893642623, + 15.480133015069253, + 15.38560077921869, + 15.294942582353142, + 15.202954767045279, + 15.11395564612569, + 15.031383348761619, + 14.948242149173982, + 14.862989452871833, + 14.784488079339466, + 14.707975202758927, + 14.634557299443852, + 14.561178330444479, + 14.486456195534181, + 14.41355166338427, + 14.340906341707845, + 14.26773474513965, + 14.196080415019612, + 14.126438836301809, + 14.052929287433628, + 13.976312358939373, + 13.905125482021152, + 13.833979933989347, + 13.763800127267915, + 13.693954097686055, + 13.626452561139033, + 13.561447246186475, + 13.496182939018363, + 13.431471462656013, + 13.364576785567673, + 13.29585001214357, + 13.226417469600339, + 13.154359280208228, + 13.080463713908975, + 13.004086915134017, + 12.924146264629002, + 12.845026846044929, + 12.76354742233718, + 12.675264175570048, + 12.584875501159399, + 12.490826933505096, + 12.389457866110359, + 12.2833232450772, + 12.169568542283086, + 12.051591662224784, + 11.927632691096996, + 11.797434316577835, + 11.661087415284696, + 11.51508876505498, + 11.363401749670194, + 11.208025391217001, + 11.042703546607404, + 10.870557113075433, + 10.698461611548485, + 10.515109654234719, + 10.328454685155128, + 10.145049098202099, + 9.94897754958753, + 9.75200451071638, + 9.565967845310452, + 9.367609930019624, + 9.163689649461205, + 8.970504288197038, + 8.770406357156276, + 8.56133768651176, + 8.358837965309284, + 8.155067030621748, + 7.940836112770166, + 7.731509062739313, + 7.5234482583928095, + 7.28526067276694, + 7.070014317418713, + 6.854367070369595, + 6.633388634553658, + 6.410954627601904, + 6.192049275553677, + 5.9705046702960685, + 5.755387213196163, + 5.540641501117966, + 5.325883354987782, + 5.113387960963603, + 4.904037823469608, + 4.698568365125043, + 4.494646583619932, + 4.29218571797638, + 4.093804735683565, + 3.896581582931915, + 3.6993393982423237, + 3.505321696459772, + 3.3167939247334557, + 3.1278995747289886, + 2.939826740939026, + 2.752114055376342, + 2.564092687476761, + 2.375925355461953, + 2.188564650280692, + 2.0038153122997704, + 1.8179548653111994, + 1.636489682623588, + 1.4562968534847012, + 1.2772114130502996, + 1.0984468883964866, + 0.9185990675512066, + 0.7422600774377751, + 0.5654532985069779, + 0.3878533244882312, + 0.21078542518007173, + 0.037122848075738596, + -0.13821766985363051, + -0.30730480925290515, + -0.4669344715889308, + -0.629604770435598, + -0.7979579967315752, + -0.9616886513649983, + -1.1202269848165958, + -1.2842019743708855, + -1.441649735100221, + -1.5919414639715663, + -1.7476787980126764, + -1.897477187769446, + -2.0350045674053407, + -2.1697924221821117, + -2.289948912450747, + -2.397736672250482, + -2.499356564980556, + -2.5899008827531285, + -2.669267673896533, + -2.738850729866976, + -2.7951505785145234, + -2.8377208418394777, + -2.8663366494140776, + -2.8794436653839237, + -2.8776957629360793, + -2.8595911987638174, + -2.824526413361812, + -2.7709179574840324, + -2.696244378742531, + -2.601035143764783, + -2.485421930246041, + -2.3457330933755687, + -2.1773171084694902, + -1.9903669536036461, + -1.7854975400534367, + -1.5570653153689051, + -1.3173961752674428, + -1.0613700065472569, + -0.7895680456187398, + -0.511874985937101, + -0.21563107184882196, + 0.08619616904984623, + 0.3861972580418534, + 0.6989633706869209, + 1.0207778708357498, + 1.3340136554300601, + 1.647363864596315, + 1.9636364324608744, + 2.2709774468720036, + 2.5761679738693184, + 2.8833864721198497, + 3.183990907197781, + 3.4818681885855867, + 3.778698258048975, + 4.06841110373894, + 4.355047830106308, + 4.6371999480398, + 4.916395758076938, + 5.193492379308082, + 5.465895497959123, + 5.7385962611517, + 6.015746147238133, + 6.290191929925999, + 6.562553096291006, + 6.838310051198807, + 7.116597158078895, + 7.394019270287811, + 7.672057141573245, + 7.958146147804446, + 8.244931821960849, + 8.534882842226468, + 8.83530631478094, + 9.136302496739152, + 9.44406113805684, + 9.754740063000591, + 10.068058177803316, + 10.39105223878012, + 10.718506105259266, + 11.044796019125517, + 11.385180477162388, + 11.722801891058703, + 12.05320039379507, + 12.38368058333018, + 12.730029679732034, + 13.076882270802804, + 13.411874226214321, + 13.768707794190131, + 14.129101589668405, + 14.474625946615612, + 14.831333816580438, + 15.204381977351597, + 15.559623746703922, + 15.920784396862322, + 16.294087893959922, + 16.653143891585895, + 17.014040541042117, + 17.384905041853532, + 17.745210599431626, + 18.10701657019424, + 18.475855999380688, + 18.84630246801874, + 19.21472420232902, + 19.584540346121482, + 19.958100851664916, + 20.329597553521033, + 20.703147161033325, + 21.077787570745635, + 21.455960380519414, + 21.83415061963746, + 22.212369177737774, + 22.590516713945995, + 22.96436719868864, + 23.334278174377356, + 23.708226006935764, + 24.069648944614524, + 24.428433814823237, + 24.79761049909782, + 25.156074499134487, + 25.513139828635605, + 25.874825823022793, + 26.23221926054202, + 26.58051456533564, + 26.934570028422193, + 27.294888642306194, + 27.64325586475552, + 27.99604897895633, + 28.35418418730505, + 28.704773551893815, + 29.05658952341212, + 29.405256966231253, + 29.74381520410639, + 30.08952216504667, + 30.430189107576307, + 30.7686305982312, + 31.117670972715597, + 31.464284899047584, + 31.812090753528327, + 32.16944790293168, + 32.52699567878868, + 32.874598944993224, + 33.22732837432121, + 33.58027532993124, + 33.920839240893265, + 34.264828922228986, + 34.61128728634481, + 34.94589082877861, + 35.275329567294946, + 35.61041409457445, + 35.94043869854516, + 36.263390583040376, + 36.596066657461364, + 36.92665925182317, + 37.250184402734334, + 37.57994817482243, + 37.90020345663488, + 38.219552007931355, + 38.53980901236464, + 38.857577217796305, + 39.17250149844429, + 39.489643777499076, + 39.80358727079865, + 40.11781339224544, + 40.42924151967666, + 40.73622379955207, + 41.04445989472741, + 41.35088874478574, + 41.65497520405229, + 41.9614265250755, + 42.271072168318476, + 42.58123792493518, + 42.88786571829572, + 43.19305142909594, + 43.50057737772373, + 43.806329961741476, + 44.10132497765635, + 44.40195420490786, + 44.70752236099932, + 45.00281189532224, + 45.29845662417915, + 45.601799273884694, + 45.90751130700917, + 46.22640173857268, + 46.55017347414858, + 46.87469062819132, + 47.1914469307637, + 47.509470256328534, + 47.829164737400525, + 48.14280668634397, + 48.45386128703238, + 48.76420039518074, + 49.06519472456141, + 49.35004865653113, + 49.63000821728161, + 49.90821819677075, + 50.18827143675649, + 50.459815092181316, + 50.72820355268208, + 50.999958718424246, + 51.26788606915844, + 51.529091092358115, + 51.788276407407864, + 52.03588759590051, + 52.28029948126108, + 52.52381975742576, + 52.76955019493967, + 53.00974585183275, + 53.24282837028358, + 53.46962553471766, + 53.693679547011214, + 53.93955750395511, + 54.146748278555286, + 54.358127773173806, + 54.56898477118201, + 54.76912973935323, + 54.96387077493352, + 55.15659915367171, + 55.34248867620885, + 55.52535343603381, + 55.69920598625639, + 55.86621491056163, + 56.03220550731532, + 56.191473521787486, + 56.36291856370291, + 56.50561650020915, + 56.64437977042498, + 56.79340185676669, + 56.91837500975861, + 57.03138426467584, + 57.13356465682801, + 57.22602088932318, + 57.306044779724736, + 57.373374627639585, + 57.43217605875413, + 57.47720983081423, + 57.50457653292974, + 57.518346584204416, + 57.517745136272, + 57.500487446771686, + 57.47007387378284, + 57.43002968444119, + 57.377647365975996, + 57.31172282407779, + 57.23228604653392, + 57.134661511158505, + 57.02283434346222, + 56.902839022987706, + 56.76898220682917, + 56.61913788109337, + 56.45991171551233, + 56.287242736497, + 56.09977345872899, + 55.90374298983799, + 55.694997872309806, + 55.48467590340144, + 55.26874395373312, + 55.04751029904672, + 54.82045999010986, + 54.5954923019847, + 54.37309560019452, + 54.14158247539891, + 53.912583983921216, + 53.68682979856381, + 53.454702245081336, + 53.22027405095019, + 52.987656573905795, + 52.75257882631101, + 52.51185481929927, + 52.27302426442743, + 52.03078080113344, + 51.7850461427806, + 51.535293447741935, + 51.284703451296494, + 51.02929721836514, + 50.77101184539267, + 50.514173365922076, + 50.25228348169515, + 49.99072382687665, + 49.73213031797938, + 49.47005648043545, + 49.20333961606832, + 48.93857753061649, + 48.667908248004714, + 48.391078766366796, + 48.1154159957497, + 47.838437967857956, + 47.559067587884954, + 47.281372268163594, + 47.00132095405864, + 46.71760973445366, + 46.43593591471696, + 46.148292753451024, + 45.85632035163507, + 45.56862844645088, + 45.282904155000296, + 44.989302572254914, + 44.704910769193255, + 44.42901498775145, + 44.13873673718737, + 43.858723890277005, + 43.58039164446446, + 43.28891447462725, + 43.00576875020978, + 42.72864412225899, + 42.44265494073887, + 42.15898871057275, + 41.88689907876974, + 41.61368484837829, + 41.327364085667234, + 41.046209576389124, + 40.76926760918821, + 40.48166119739983, + 40.194410107886064, + 39.91605647677451, + 39.62920357923275, + 39.33792984507867, + 39.05339181290073, + 38.76237088309712, + 38.4649716455232, + 38.178118865473664, + 37.89437612941539, + 37.61095868416416, + 37.336097056222286, + 37.059832140687206, + 36.792794415777585, + 36.521075602631896, + 36.24654837775251, + 35.97019030513656, + 35.686331141051305, + 35.40642427889326, + 35.122147083347684, + 34.828857187409064, + 34.531376365016975, + 34.23472377670125, + 33.93274465898551, + 33.62964009170522, + 33.331536649326054, + 33.03132993227059, + 32.74293205246278, + 32.458982818919466, + 32.14237998376419, + 31.84724423609909, + 31.564821111582603, + 31.28608185163985, + 30.99343429225877, + 30.70429426182989, + 30.41737243083531, + 30.133758209340453, + 29.8382305747696, + 29.54635221663946, + 29.262143347438062, + 28.98076134509705, + 28.68571467674391, + 28.391921053556594, + 28.11188659467534, + 27.818004255932617, + 27.507904324632964, + 27.206354039645042, + 26.911777427116274, + 26.606186530568813, + 26.295056480866123, + 26.001851147523087, + 25.71810823123377, + 25.414931948480888, + 25.109368387626994, + 24.812703481004373, + 24.500925429686777, + 24.17977716141395, + 23.863600441803996, + 23.535817489830475, + 23.206757416779915, + 22.87973901683669, + 22.545880706805285, + 22.20427044091888, + 21.87027721572043, + 21.53078791872301, + 21.186893632697284, + 20.860359773882664, + 20.523793427818788, + 20.176538424821942, + 19.842862198609936, + 19.515026461287324, + 19.18573807860114, + 18.862686199628882, + 18.55648016665923, + 18.254130940050203, + 17.959637128272686, + 17.693546357961637, + 17.43255899973859, + 17.169570683985533, + 16.93550594306842, + 16.706753175460392, + 16.47809497246344, + 16.268830451164877, + 16.06851982986017, + 15.86680107248597, + 15.675349135262836, + 15.496831360608812, + 15.323160165364191, + 15.154540067823977, + 14.994344490690464, + 14.841959243213388, + 14.699499778565324, + 14.562038114444736, + 14.429925052762783, + 14.309649224771386, + 14.19974837828178, + 14.09281525672261, + 13.993474326854908, + 13.899836614039902, + 13.807523505040926, + 13.720160367754033, + 13.6394658713343, + 13.561564199439234, + 13.486552628367923, + 13.419424742245496, + 13.357006884840908, + 13.29439758194053, + 13.237246403268642, + 13.185012380973864, + 13.13124646089739, + 13.078802037518454, + 13.029589159916524, + 12.981466238682376, + 12.934984205905668, + 12.889845745152797, + 12.84617754646977, + 12.802311799011676, + 12.760668913530496, + 12.71760184302839, + 12.67377151391265, + 12.629442438187981, + 12.585999024896909, + 12.541943734308978, + 12.49921556714577, + 12.457245846960795, + 12.41509718658898, + 12.375730652571994, + 12.338253608650444, + 12.30393641953865, + 12.268642748119944, + 12.233768028973527, + 12.199364296666758, + 12.16415614209694, + 12.130178938237007, + 12.097122292398462, + 12.065817800076445, + 12.035992452837231, + 12.006532963544583, + 11.978500825586012, + 11.953501872204232, + 11.932815965296683, + 11.91329320756139, + 11.896007849020101, + 11.88341876043335, + 11.87442466711471, + 11.867866548338968, + 11.864990772143154, + 11.867153803251925, + 11.874609506538231, + 11.884294961902922, + 11.898923454501027, + 11.914961715370145, + 11.930796634704771, + 11.947213581796671, + 11.963619880648508, + 11.982247804514596, + 12.005729692428412, + 12.030458410889816, + 12.055371413336282, + 12.082351238999578, + 12.108712329648034, + 12.133241154011937, + 12.160475194187498, + 12.190017801922899, + 12.219956348312024, + 12.247621640343734, + 12.274406341192748, + 12.301076438098079, + 12.328609375867408, + 12.356533492138102, + 12.384076943385171, + 12.412500567823237, + 12.440592031673063, + 12.46926969789536, + 12.498346279275344, + 12.528319221798814, + 12.559454978675912, + 12.591555833550991, + 12.62432600353895, + 12.65542895869155, + 12.684652641170796, + 12.711778591617128, + 12.737357850368166, + 12.759273938751397, + 12.778740743505077, + 12.794658543587905, + 12.80794660003961, + 12.818119636231492, + 12.822140132166782, + 12.820026059043235, + 12.813528730161853, + 12.800612387586742, + 12.781655138724323, + 12.757536204330618, + 12.72991474814405, + 12.698511711481249, + 12.661985663036733, + 12.62089824419992, + 12.576494600555773, + 12.52967153342739, + 12.474534690002027, + 12.413906582724858, + 12.349826979581051, + 12.280737716352515, + 12.211218291269581, + 12.139716963289713, + 12.061824432406015, + 11.986364997791302, + 11.910639904622586, + 11.824844548804544, + 11.743863769929234, + 11.665871110660671, + 11.577252055411606, + 11.485051602653554, + 11.393171123223864, + 11.296277000318709, + 11.195578308255824, + 11.09789480115782, + 11.000593540045958, + 10.89974334016699, + 10.79478199233719, + 10.688647086583925, + 10.579899533922429, + 10.46876836558437, + 10.35834152951342, + 10.24604010401854, + 10.135789428545994, + 10.024426354590814, + 9.915408777931122, + 9.809892677074464, + 9.690502556628143, + 9.568845010186527, + 9.44948845425078, + 9.329345825764314, + 9.210788423624953, + 9.094740096593306, + 8.981250760713174, + 8.869008724662915, + 8.759087914090877, + 8.654570927896945, + 8.558440799660923, + 8.466489237235667, + 8.37694196219669, + 8.288965865742293, + 8.199190543994659, + 8.109330310369584, + 8.022090972547874, + 7.934504286438223, + 7.846448633167835, + 7.760029696434877, + 7.6723880755626, + 7.584815270506617, + 7.496686799929899, + 7.407182621643937, + 7.317985356212052, + 7.2353434867070066, + 7.152570059125531, + 7.0710588167918935, + 6.99677753000603, + 6.923162654023745, + 6.854308092054447, + 6.790927212107014, + 6.730942123001968, + 6.6746098504638915, + 6.624191221291647, + 6.578235463220679, + 6.53568360116851, + 6.499806109005132, + 6.469925867811654, + 6.444626735024947, + 6.425174858766019, + 6.41130754770066, + 6.404394650407598, + 6.404731373174716, + 6.411926150723632, + 6.426463929379376, + 6.449763435402024, + 6.481803466196001, + 6.5234848931937, + 6.57586273086052, + 6.639274138436655, + 6.714297420238251, + 6.8009625620786265, + 6.90357961841715, + 7.020815263863826, + 7.149711280344686, + 7.296393538330737, + 7.462987255751147, + 7.641623185464991, + 7.8287948857142124, + 8.044999776456184, + 8.28775859286178, + 8.535562218000656, + 8.792808696598971, + 9.06682767516232, + 9.339638558131611, + 9.619226296623978, + 9.90699890156163, + 10.193880604205342, + 10.485797678629408, + 10.796644596607308, + 11.070419359678132, + 11.350216718684798, + 11.629109942162875, + 11.901352374105752, + 12.169770891789925, + 12.430130313416093, + 12.682173623610057, + 12.928658888705487, + 13.167277353948695, + 13.401859977525756, + 13.627224026174238, + 13.84808027205692, + 14.062692975073334, + 14.268134588907262, + 14.471169548669833, + 14.669167292320772, + 14.8608675302553, + 15.051004870162453, + 15.235143071635735, + 15.415890054492111, + 15.598363106013123, + 15.778062308897118, + 15.956238195706161, + 16.137684244592446, + 16.31997576246259, + 16.503687983755558, + 16.69005559798489, + 16.87882971366824, + 17.07319447522499, + 17.270317689560514, + 17.468839201329406, + 17.671602490253267, + 17.87897598609055, + 18.090712455672396, + 18.30765249090772, + 18.528780803642082, + 18.756977050385643, + 18.994609254251344, + 19.232421288610336, + 19.477242452508207, + 19.733908815230023, + 19.989288532694463, + 20.249931476722182, + 20.51197771340003, + 20.78705618039728, + 21.061403124296426, + 21.33083236390065, + 21.61857787570625, + 21.906607252471186, + 22.185178090997447, + 22.473137670441695, + 22.774031558632206, + 23.067130972314928, + 23.361836180778283, + 23.66836859448006, + 23.971027775377983, + 24.269749084419086, + 24.578033814122037, + 24.8858323012305, + 25.188334065545572, + 25.498649613846748, + 25.80548880478919, + 26.118879041891603, + 26.433331971708736, + 26.743520835196794, + 27.056669054485372, + 27.372039579355043, + 27.687009174724732, + 28.000868542639235, + 28.32254383953865, + 28.64040950241382, + 28.957066871469387, + 29.277448768422754, + 29.59241592452326, + 29.902026466826495, + 30.21071923414979, + 30.51748793933198, + 30.81424518134586, + 31.115312893397437, + 31.41691701548777, + 31.70935462994214, + 32.01002736632239, + 32.305487686362774, + 32.59175093012523, + 32.88108925124949, + 33.17164525781489, + 33.46162107819969, + 33.74158875561453, + 34.02100002905836, + 34.305183666129366, + 34.5799553017979, + 34.850607264477475, + 35.112672686025306, + 35.361655041668115, + 35.61005739853109, + 35.84955917601088, + 36.08065467694008, + 36.30674445473008, + 36.52828429164542, + 36.740786993766555, + 36.950978128104765, + 37.1515263566296, + 37.3379031196239, + 37.51386446547182, + 37.677077230058806, + 37.82778807464054, + 37.966008424912935, + 38.11130017116466, + 38.23093466869777, + 38.33561346131356, + 38.43143108582396, + 38.519650293463094, + 38.59730815158196, + 38.667173203124555, + 38.72823633779689, + 38.780231826800176, + 38.82131391856022, + 38.8537240151622, + 38.877803819647404, + 38.894234864962385, + 38.90159752065538, + 38.89953729044153, + 38.890052082037606, + 38.87367813816234, + 38.84854955248623, + 38.81797434746558, + 38.779441676028604, + 38.73501562451974, + 38.6864053617166, + 38.6335014144021, + 38.57785177822729, + 38.517439602618225, + 38.45287013695489, + 38.38402128169546, + 38.30882886427461, + 38.230177988295075, + 38.15059225832807, + 38.065486871257875, + 37.976527684340674, + 37.884758965332885, + 37.7878007505029, + 37.685561069492735, + 37.5804973011744, + 37.477257537827064, + 37.3713607379538, + 37.26225480359238, + 37.155321347240104, + 37.04618385764532, + 36.93476024600219, + 36.82306572527969, + 36.71047495261248, + 36.60347725647842, + 36.493653492177515, + 36.38721544580902, + 36.28899847501084, + 36.187005267077254, + 36.09139940740021, + 35.99904055330144, + 35.90677109545825, + 35.82346517571844, + 35.749401535921855, + 35.672391822966624, + 35.60268346879452, + 35.541761543344734, + 35.48030599214533, + 35.42566726058668, + 35.37888302380268, + 35.333398957189836, + 35.2946347743286, + 35.26039733908834, + 35.23183590435802, + 35.20940945821903, + 35.18965660954598, + 35.17240261894478, + 35.15775757130984, + 35.14392850831232, + 35.13013122461834, + 35.11606018872258, + 35.102360036807724, + 35.098107667433965, + 35.09449582923006, + 35.09129154278542, + 35.088055727967266, + 35.08522575229344, + 35.082758732141116, + 35.08035372730898, + 35.07813168641757, + 35.07620098611242, + 35.07460852969232, + 35.05984971422305, + 35.04339496355989, + 35.02667244107595, + 35.00962336343616, + 34.99226311457334, + 34.974576565465476, + 34.95656525119766, + 34.93827142952938, + 34.91943288048625, + 34.90014012752183, + 34.895416468441276, + 34.89234186534965, + 34.88915666286287, + 34.88598630017445, + 34.88281658910924, + 34.87956137744027, + 34.87633219304776, + 34.87307011284546, + 34.86976703210665, + 34.86644475581382, + 34.8551747366878, + 34.8429768893144, + 34.83070422844722, + 34.818430484206424, + 34.806125256584295, + 34.79378574988798, + 34.781432463025915, + 34.76903933762169, + 34.75661634860349, + 34.74412907053127, + 34.7397093680804, + 34.73609114357576, + 34.732428863718184, + 34.72880953363549, + 34.72522656296134, + 34.72155208566735, + 34.71785899180338, + 34.71419676103996, + 34.71044181848479, + 34.706710040852414, + 34.68587287380501, + 34.66277496472863, + 34.63964893091603, + 34.61657909776959, + 34.59361775950861, + 34.57065433245965, + 34.54759662177167, + 34.52461395494192, + 34.50171177409114, + 34.47853041139153, + 34.47362277545028, + 34.47080664475168, + 34.46805739335795, + 34.46543050703443, + 34.462802817358906, + 34.46018330417802, + 34.45752989679673, + 34.45458549870025, + 34.451876702902915, + 34.44921957873822, + 34.4485014385168, + 34.44782136311084, + 34.447247605163966, + 34.446667736507294, + 34.445973827983906, + 34.44530600473072, + 34.44469594169167, + 34.444056801391554, + 34.443373638260226 + ], + "yaxis": "y" + }, + { + "line": { + "color": "black" + }, + "mode": "lines", + "name": "Optimized Path", + "type": "scatter", + "x": [ + -34.20561757044228, + -34.20512760429347, + -34.20454790552907, + -34.2039475820338, + -34.203528029543456, + -34.20318769697766, + -34.20250008828952, + -34.201887393251134, + -34.20110695414667, + -34.20043328331251, + -34.199797365257, + -34.19902567216335, + -34.19822373944125, + -34.19756620269559, + -34.19691395620989, + -34.19612628784581, + -34.19539587647322, + -34.19464752519713, + -34.19413826717369, + -34.19362218978343, + -34.19308286816422, + -34.19247713345691, + -34.1919654756452, + -34.19138345574506, + -34.190871769903445, + -34.19032247122443, + -34.18980320715251, + -34.18935691811098, + -34.18894357394385, + -34.188490371118526, + -34.188142308575856, + -34.18779060926308, + -34.187408824528056, + -34.18704889979322, + -34.18660587485973, + -34.186197158312446, + -34.185842641909616, + -34.18554050023449, + -34.185178222994665, + -34.18478562614525, + -34.1845163518966, + -34.184152676221, + -34.183672892900894, + -34.18341526313705, + -34.18317743785774, + -34.182904178641174, + -34.18255394965871, + -34.18229836253587, + -34.18202343423894, + -34.18168564101408, + -34.18137437935082, + -34.180999760656505, + -34.18063044088135, + -34.1803417108544, + -34.18004184497972, + -34.17974380811583, + -34.17939100594898, + -34.179096825713465, + -34.17889403629774, + -34.17857668929551, + -34.17836158297033, + -34.178069181253385, + -34.17775251387628, + -34.17751570665378, + -34.17725998686529, + -34.176965245194936, + -34.17669134606577, + -34.17606814416233, + -34.17522295581092, + -34.174452355660485, + -34.17371311972212, + -34.17281768998747, + -34.171850618743974, + -34.17098917190925, + -34.170173012591064, + -34.169262807754016, + -34.168241223649744, + -34.16753996547593, + -34.166801221654865, + -34.165990313703595, + -34.165372902431336, + -34.16463275076087, + -34.16372519837798, + -34.163001524746676, + -34.16231107211428, + -34.16138802048847, + -34.16053081643791, + -34.15958643540004, + -34.15848955858913, + -34.157424462718645, + -34.1563743189374, + -34.1553950611015, + -34.15438764173777, + -34.15330519898663, + -34.15229595639603, + -34.15128403563302, + -34.15032583585512, + -34.14940720504957, + -34.148747773708, + -34.148157429515166, + -34.14737296142082, + -34.146622897467466, + -34.14609913542775, + -34.145519128021874, + -34.14502975057139, + -34.144284896489644, + -34.143434800923956, + -34.14280878290143, + -34.142058943459496, + -34.14131342461109, + -34.140581272596584, + -34.139696783478215, + -34.138875008191974, + -34.13819982788251, + -34.13745784699546, + -34.13665333234713, + -34.135783958014784, + -34.1349121329733, + -34.13429143553747, + -34.13368132261655, + -34.132894153643726, + -34.13206479282877, + -34.131356852160444, + -34.13073211020393, + -34.129958414662426, + -34.12910768001923, + -34.12829256670085, + -34.12767517785592, + -34.12722646375426, + -34.12646961049529, + -34.125659878715005, + -34.125128620572006, + -34.12447133849393, + -34.12358465970485, + -34.123023731530715, + -34.12210246976016, + -34.12151730651414, + -34.12098252068224, + -34.12066488981601, + -34.11994193737324, + -34.119172869338506, + -34.11881621364209, + -34.1182378633531, + -34.11754844375961, + -34.11683706421001, + -34.11598998946467, + -34.11525392540833, + -34.11469304205291, + -34.11388298715692, + -34.11270671221946, + -34.112151292684246, + -34.111601557295415, + -34.11083929244948, + -34.11001892168905, + -34.109320386475915, + -34.10880792155222, + -34.10840442199014, + -34.10808228712271, + -34.10735719121386, + -34.10673042576127, + -34.106331790496746, + -34.10589372950673, + -34.105172678418185, + -34.10426190981686, + -34.103003041120786, + -34.10241863646337, + -34.10185535156437, + -34.100838685205716, + -34.09928819133874, + -34.09708354240105, + -34.09556069941669, + -34.09431089634316, + -34.09250476578938, + -34.09060968110186, + -34.08888225864368, + -34.08717589837203, + -34.085444038845665, + -34.083816814136235, + -34.08219763196009, + -34.08048540458973, + -34.07889818574541, + -34.07733461922295, + -34.07566360130542, + -34.073918629785176, + -34.07229456398648, + -34.07055171459505, + -34.06880304173993, + -34.06740468816458, + -34.06625705097835, + -34.06494957727392, + -34.06342972415235, + -34.06188819030862, + -34.06043797807096, + -34.059363132909475, + -34.058109234914646, + -34.05662927587014, + -34.055258540792856, + -34.054034104321765, + -34.05312530342876, + -34.05198121342687, + -34.0504555867898, + -34.04948585276847, + -34.048398485563695, + -34.04709464880089, + -34.0454102457629, + -34.04266646319351, + -34.0409465339217, + -34.03835988273773, + -34.03597418314847, + -34.0336651065715, + -34.026657465890594, + -34.0128748956983, + -33.98879699105395, + -33.95120492104014, + -33.89847043071538, + -33.83217480926878, + -33.759082516147195, + -33.688152090901596, + -33.62902239804277, + -33.581904201912735, + -33.54761355832541, + -33.521976425812205, + -33.503625704206605, + -33.49091867870461, + -33.479746893959316, + -33.46613840600857, + -33.44623741792179, + -33.41348354991016, + -33.366492860284716, + -33.304430002101135, + -33.2265010859668, + -33.13328627029537, + -33.026047374446584, + -32.904400659034586, + -32.76791621366324, + -32.61504638432957, + -32.444588303201385, + -32.257641503338114, + -32.057264055099246, + -31.845896423892555, + -31.62169938902757, + -31.382115349269377, + -31.134352270515613, + -30.880264731544443, + -30.621592093416492, + -30.35452716825152, + -30.084251738630325, + -29.814435917332784, + -29.535859682475248, + -29.26008893727225, + -28.98908448934071, + -28.711604365075154, + -28.437710308015056, + -28.167123579287267, + -27.903511142314834, + -27.640916520907638, + -27.384319979531227, + -27.14404416686677, + -26.909325595507926, + -26.681111574104893, + -26.465553354460898, + -26.262944822222714, + -26.071024748783216, + -25.896680086140506, + -25.739502325773667, + -25.597339361397758, + -25.469877735215118, + -25.359166951779105, + -25.269094561371322, + -25.19209099554038, + -25.13037068292393, + -25.09191261411201, + -25.069700809315894, + -25.06395870061066, + -25.074761203703314, + -25.100204339113603, + -25.137218874930355, + -25.18718783476567, + -25.24978584704496, + -25.317153382883465, + -25.39510282737947, + -25.484067165473096, + -25.57582872449151, + -25.675141800072094, + -25.785155098916132, + -25.899992780062643, + -26.02146982739026, + -26.151192080146767, + -26.287612712018074, + -26.42813875081477, + -26.57531957852832, + -26.73030498687557, + -26.886367542777563, + -27.046764994992802, + -27.21833001407868, + -27.392179771408387, + -27.570118001596843, + -27.754507213233985, + -27.950860643741503, + -28.13744686676629, + -28.32731941259005, + -28.525896778413372, + -28.71960461455676, + -28.91003404390529, + -29.10566392179609, + -29.30564275628184, + -29.495330460098923, + -29.68888344896392, + -29.887600083069856, + -30.079538241210784, + -30.26661584695017, + -30.45954199955235, + -30.648351976094574, + -30.830012935363236, + -31.017014787628053, + -31.201843391943203, + -31.38726115318541, + -31.569889064281064, + -31.75503809481409, + -31.941639224946446, + -32.12293501781387, + -32.30373019515281, + -32.479155690728824, + -32.66034617134181, + -32.82886258580736, + -32.99644742433231, + -33.170881164548135, + -33.337583190309445, + -33.499261533426264, + -33.66113989274895, + -33.8264744454099, + -33.98787157382627, + -34.14278176975569, + -34.29897856697425, + -34.453265970126935, + -34.605058507221436, + -34.75402248432084, + -34.90301103772693, + -35.04775593067414, + -35.18872387727439, + -35.33140545605798, + -35.463404703490355, + -35.59117549177854, + -35.720451508688384, + -35.8435311671989, + -35.95921239213348, + -36.07599763476948, + -36.186211537122986, + -36.28911837561348, + -36.38976082163263, + -36.48056851922742, + -36.565927578444594, + -36.64488302557363, + -36.71523314991207, + -36.78012984628027, + -36.841769117004866, + -36.89603652639348, + -36.946037299585576, + -36.99486233621137, + -37.03741023356843, + -37.07801470893926, + -37.11690550027645, + -37.15317238300912, + -37.188491887268846, + -37.22497997271774, + -37.26155949805779, + -37.298584975356945, + -37.33759753421884, + -37.376077634267816, + -37.41258936031957, + -37.44838660622586, + -37.48300805057889, + -37.51739476319382, + -37.55267565865365, + -37.58875856088244, + -37.62609696041984, + -37.665195715488586, + -37.70594469185669, + -37.74892679149871, + -37.79219388880461, + -37.8378527933611, + -37.884237089227575, + -37.93068842754541, + -37.978499241950765, + -38.030999184382026, + -38.086470630036565, + -38.14112251571634, + -38.20331311821484, + -38.26065790686239, + -38.31602276906785, + -38.37248345049218, + -38.430691674291126, + -38.48720945720995, + -38.544139784274144, + -38.60167691584601, + -38.66074969657934, + -38.72056922037399, + -38.782622426839275, + -38.84408807873072, + -38.907387780298954, + -38.9740301194087, + -39.03879585844459, + -39.10734523055302, + -39.1828198754861, + -39.26188093301199, + -39.34274627729819, + -39.432958033968546, + -39.525947432600134, + -39.6212713935699, + -39.73086413311233, + -39.84499137207389, + -39.962527898239294, + -40.09329713891962, + -40.230802602702255, + -40.372889353100234, + -40.527385513557775, + -40.68354228401489, + -40.84828850045461, + -41.0254641616563, + -41.20078019583397, + -41.387720825838066, + -41.59004337321235, + -41.79219816931896, + -42.00869827938041, + -42.24539198990937, + -42.484668380759224, + -42.73662447826301, + -43.00114416394548, + -43.27609452432519, + -43.56481912633542, + -43.872609957200716, + -44.1693705404054, + -44.46503290335496, + -44.78204638662235, + -45.0903708313035, + -45.389688917183896, + -45.70721401650844, + -46.01449876014241, + -46.301933990162915, + -46.5928799282053, + -46.878278503481994, + -47.15099380296704, + -47.415478539240446, + -47.6679250249944, + -47.90793035440927, + -48.141185365189216, + -48.36129979155681, + -48.56970213554213, + -48.76957357090377, + -48.95917637108032, + -49.138204288159045, + -49.31027172223736, + -49.47066745504553, + -49.622680692705416, + -49.767410520606916, + -49.90190489333228, + -50.02881817334456, + -50.1506213795373, + -50.267191345817075, + -50.38086896087241, + -50.49376203664987, + -50.608163853918185, + -50.72401842175004, + -50.84244240574792, + -50.963751019578346, + -51.08983043878479, + -51.22075674893193, + -51.35900562531298, + -51.50906280459484, + -51.66635719129263, + -51.83105697024285, + -52.00717503961635, + -52.188688529726036, + -52.37242421765366, + -52.56709421064206, + -52.773474958964805, + -52.97892257285614, + -53.195123381676176, + -53.42681577712202, + -53.649910780207875, + -53.88451912230249, + -54.13223293236011, + -54.37460480163445, + -54.629416172263774, + -54.894364243322975, + -55.14641611317685, + -55.40506948288841, + -55.6716570181352, + -55.922705028940356, + -56.17810759978741, + -56.45321031865366, + -56.7201638563687, + -56.97808654414694, + -57.25424099397908, + -57.530213492589006, + -57.79258684599805, + -58.06926282313392, + -58.349819335344705, + -58.616750299832695, + -58.88732139066519, + -59.159086273397115, + -59.41794493152703, + -59.67696311829514, + -59.93524212644045, + -60.18963265574833, + -60.445610170856284, + -60.701419088223226, + -60.95504493480911, + -61.21153464433444, + -61.465873569219475, + -61.72036104617876, + -61.972811903378805, + -62.225017583114415, + -62.47134097875486, + -62.71335073223099, + -62.95098370756537, + -63.180162311978606, + -63.40013121217142, + -63.614687223332176, + -63.82479531230667, + -64.03329465455552, + -64.24406272880509, + -64.45625782342314, + -64.66556219238166, + -64.87026423892154, + -65.06956097464109, + -65.26413631925908, + -65.46059588017901, + -65.65490575539503, + -65.84367197770793, + -66.02220358487762, + -66.19413132258474, + -66.36399270954566, + -66.53266854105782, + -66.70051426694702, + -66.86400963304442, + -67.0258983849939, + -67.18579003191651, + -67.33930976604466, + -67.49264233865657, + -67.6493452168336, + -67.80094813227709, + -67.94931241038378, + -68.09844525743789, + -68.2487474904265, + -68.39589637121036, + -68.54040290713341, + -68.6826353460433, + -68.8183367994397, + -68.9489152643788, + -69.08132083452956, + -69.21092947082028, + -69.33548314964287, + -69.46049604747336, + -69.58185184846917, + -69.69362773715109, + -69.8067214135986, + -69.91712302018885, + -70.02196333199016, + -70.1288564870053, + -70.23515589674767, + -70.33463397310949, + -70.43577245998249, + -70.53622732540317, + -70.63223798341733, + -70.73156769828218, + -70.82895939543982, + -70.92245067205916, + -71.01812746600336, + -71.11129764816239, + -71.20210707045638, + -71.29436376759374, + -71.38657745020753, + -71.48054413206515, + -71.57735010220847, + -71.67422081859812, + -71.76958137297436, + -71.86815681626645, + -71.96324078243423, + -72.05808794141366, + -72.15075367355747, + -72.23538300654613, + -72.3172211523773, + -72.39269759781176, + -72.4555167203586, + -72.5104650780865, + -72.55810370146347, + -72.59489616614175, + -72.62159065848107, + -72.63975840705338, + -72.6497529077105, + -72.65224454910688, + -72.64372445092144, + -72.62802140267841, + -72.60428635492597, + -72.57200414560242, + -72.53598392872436, + -72.49531034686584, + -72.4486386120134, + -72.39588093509896, + -72.33560353735982, + -72.27111568484752, + -72.20093793747819, + -72.12291088238662, + -72.03903957638944, + -71.94796436942242, + -71.84852238273824, + -71.74858084124595, + -71.6332122852996, + -71.50002467744615, + -71.3639000574612, + -71.21504056848309, + -71.04432374782473, + -70.87186353529634, + -70.70006983579766, + -70.50740459203469, + -70.30066096169622, + -70.08982898006605, + -69.85721683152681, + -69.60581928650862, + -69.35221098806976, + -69.0872216975325, + -68.80662929845899, + -68.51546197996846, + -68.21009619484687, + -67.89401674493533, + -67.56731518926061, + -67.2252024176128, + -66.87492859708027, + -66.52184388554022, + -66.15251578092575, + -65.76952733798213, + -65.38416451188696, + -64.99594837258051, + -64.59321183200468, + -64.18884442630625, + -63.811600619865764, + -63.42288931395214, + -63.01624508767463, + -62.64152953678123, + -62.2640666791697, + -61.853317592866794, + -61.46500081063432, + -61.08532152543534, + -60.67614560631991, + -60.278129799393, + -59.884513000214504, + -59.47114448678991, + -59.06483706492197, + -58.666134233806375, + -58.260466515774944, + -57.85924175400575, + -57.460730879351644, + -57.05784778303783, + -56.65216634152449, + -56.24967960194449, + -55.84581873091747, + -55.44815547419902, + -55.052092128106615, + -54.66085908411506, + -54.26291846472017, + -53.871946508503974, + -53.47772906935791, + -53.08057496209116, + -52.69119362573196, + -52.31307326450289, + -51.923414829847125, + -51.55950949536136, + -51.207830192801644, + -50.84093883846838, + -50.49204521980163, + -50.14344131050435, + -49.77948774904636, + -49.43017201488649, + -49.08340048155227, + -48.69173333570923, + -48.34133732481832, + -47.995854895310224, + -47.63904047154031, + -47.2728492181963, + -46.91690442804988, + -46.56092988530211, + -46.195362154793386, + -45.83653714396913, + -45.48547058399427, + -45.124833690094285, + -44.76351168082494, + -44.41093447816134, + -44.049341516020974, + -43.68533322212456, + -43.33408925432588, + -42.98191301291801, + -42.63227271458896, + -42.297458368977836, + -41.957143229546375, + -41.62223188374709, + -41.291430313327695, + -40.954228962864995, + -40.61244750504851, + -40.26365841179854, + -39.91746402724253, + -39.565673344191794, + -39.20039404198487, + -38.82819536532496, + -38.451998976616736, + -38.073731729118414, + -37.692383651950195, + -37.30834384334934, + -36.92657384677088, + -36.55511111050676, + -36.18682623258284, + -35.81271986813442, + -35.44236500443909, + -35.07719525981692, + -34.70534660570074, + -34.329309988475934, + -33.95439710123461, + -33.57987473620433, + -33.207241277978454, + -32.81504103111591, + -32.431353744027135, + -32.059889510799664, + -31.66570261798346, + -31.271381983330798, + -30.910961686079972, + -30.527924061534268, + -30.130132589322397, + -29.76505216077786, + -29.400547957043873, + -29.016938705416603, + -28.656525429300615, + -28.329218485812287, + -27.97424408178218, + -27.616340026906627, + -27.288527481947636, + -26.94552486918197, + -26.598130779161686, + -26.271703671420283, + -25.940302877460553, + -25.61588364589193, + -25.300940871294408, + -24.989829850443677, + -24.68433470046486, + -24.395699014681064, + -24.107083793074718, + -23.831048492865037, + -23.5716359513729, + -23.302969298821715, + -23.03913392308083, + -22.794603442449816, + -22.5552067675838, + -22.320274036579058, + -22.09706591076508, + -21.889360945408974, + -21.687582386626527, + -21.503739452482794, + -21.33699740777679, + -21.17906702782219, + -21.032342953580972, + -20.904274164261622, + -20.7852065655937, + -20.675111681466376, + -20.58038576204182, + -20.494987813321163, + -20.424543775185434, + -20.369521301243612, + -20.32778348630391, + -20.301372124137583, + -20.290567430834937, + -20.29368962038936, + -20.308198730708714, + -20.33540061225545, + -20.37386703665702, + -20.421659905577652, + -20.47593434402756, + -20.53758723670193, + -20.60642808792559, + -20.680183954183804, + -20.75776454402994, + -20.83978984455303, + -20.928601994800303, + -21.024117224113652, + -21.12296310318474, + -21.220500724220777, + -21.32168127111698, + -21.42744980385682, + -21.528942427912764, + -21.634378590709453, + -21.74217623346717, + -21.850195175055266, + -21.955570731659417, + -22.06388804448218, + -22.170560273902325, + -22.27407383348731, + -22.382967638474106, + -22.4925149597515, + -22.599065162893176, + -22.708665111122727, + -22.8205675553048, + -22.931634332948207, + -23.04140948060133, + -23.154014483046176, + -23.26637901700943, + -23.376624767611364, + -23.4902370038099, + -23.603200317860484, + -23.71334714780898, + -23.82266886687317, + -23.93029049379185, + -24.038336944674572, + -24.149188868153907, + -24.256472663897387, + -24.363898751880633, + -24.474573907058865, + -24.582892558222987, + -24.690156388425507, + -24.796890856674764, + -24.90411437220659, + -25.01201872208549, + -25.122113714063985, + -25.232789670764756, + -25.34418579036815, + -25.459784354752852, + -25.57620761824168, + -25.694946343991376, + -25.817599642611988, + -25.9413085051037, + -26.066936002154012, + -26.19706329518293, + -26.32595914993584, + -26.459489960937468, + -26.601541244681247, + -26.74275048851859, + -26.888385569412215, + -27.04218815800793, + -27.202602317061192, + -27.35577720375166, + -27.516671766379552, + -27.682944697420943, + -27.845102592808274, + -28.00796474243966, + -28.17274308615302, + -28.34023289729439, + -28.500565227029785, + -28.66232227715479, + -28.82531492102295, + -28.98318192323284, + -29.143036716681856, + -29.306655581984884, + -29.4718442800354, + -29.63385378808072, + -29.79608649738163, + -29.961653524281843, + -30.126446349891978, + -30.2957713753911, + -30.46280090623393, + -30.632082760341724, + -30.803925200921448, + -30.968043344124233, + -31.13383621297871, + -31.301162516675138, + -31.468852141513388, + -31.631743910557933, + -31.796441075882125, + -31.965584640409897, + -32.14833293033363, + -32.31169447231609, + -32.478993527224304, + -32.64902287211386, + -32.815287145159246, + -32.975320701313485, + -33.13505501637585, + -33.29120205433395, + -33.441914696308004, + -33.59105718495849, + -33.735973601338095, + -33.87465035676541, + -34.00427994875884, + -34.131091904112985, + -34.252362061489286, + -34.3630693642207, + -34.47336982364717, + -34.58286223788178, + -34.685704274603715, + -34.786078286924045, + -34.88827383593227, + -34.98373788858449, + -35.07424027594026, + -35.166704351451514, + -35.25208013037038, + -35.3308165106297, + -35.4101595569824, + -35.48416554115981, + -35.55142340097925, + -35.6202453861711, + -35.68968285234464, + -35.75289694299259, + -35.824094886915425, + -35.89136759882674, + -35.94968688652356, + -36.008249596315906, + -36.065589915635414, + -36.118317987507425, + -36.16969494296698, + -36.222088346329805, + -36.273165347559356, + -36.323530074248744, + -36.374673453579675, + -36.4236215397993, + -36.470225773011755, + -36.515395573226314, + -36.5577760656214, + -36.59852145020301, + -36.63780472140653, + -36.676010107139824, + -36.714076889677585, + -36.751293158262406, + -36.788997442630574, + -36.82675897923843, + -36.866198737719344, + -36.905451275148295, + -36.94429329164378, + -36.98460902868335, + -37.025025379994595, + -37.065409761868935, + -37.10865523908023, + -37.155461102019125, + -37.20353647817547, + -37.25157198262911, + -37.30062393083243, + -37.35073523680281, + -37.40123512065318, + -37.453051846566204, + -37.50717640957091, + -37.562629870881366, + -37.61676335648442, + -37.672537690070804, + -37.72776860651589, + -37.78408638175532, + -37.84052927721857, + -37.897093478155405, + -37.95330166201434, + -38.01125301151972, + -38.071293117480295, + -38.12995578170714, + -38.1899408145891, + -38.25028469790277, + -38.31046471589048, + -38.378134869548575, + -38.440349644564876, + -38.502398485575746, + -38.568505903985056, + -38.64070355117893, + -38.718004924913664, + -38.798034410615564, + -38.886119712661454, + -38.98175935053867, + -39.0792656495281, + -39.18640041717412, + -39.302336197043665, + -39.41611697571312, + -39.53847524404857, + -39.67173282772624, + -39.80518618284488, + -39.94576151338095, + -40.09793918827699, + -40.2534738635743, + -40.41798295828943, + -40.5925092383742, + -40.7750465306845, + -40.967669750246635, + -41.174281781029805, + -41.39035522092231, + -41.622582145892046, + -41.86528641863914, + -42.11695153836835, + -42.37669364414768, + -42.64749591458337, + -42.93708228422639, + -43.22370060867796, + -43.50647753263288, + -43.81115578117619, + -44.11800141268965, + -44.41584984317279, + -44.72360411818214, + -45.03380834625305, + -45.33381904642938, + -45.63846832439477, + -45.93757090775836, + -46.22087270613417, + -46.5035711566294, + -46.77893332517433, + -47.0343150457652, + -47.27939174702824, + -47.51675722133514, + -47.734860012290014, + -47.94634545524114, + -48.150103336025424, + -48.335769837534514, + -48.51310542120231, + -48.682150875261904, + -48.83516736394039, + -48.979383748674465, + -49.11591484749563, + -49.241701242482264, + -49.35943228833208, + -49.471916464854864, + -49.579275885315106, + -49.68140555403737, + -49.78068342554034, + -49.87876999000025, + -49.97746400314953, + -50.07987937357662, + -50.18702396270841, + -50.30061060505931, + -50.4190670660807, + -50.54167523643701, + -50.668310228884216, + -50.797953441456606, + -50.93191387947032, + -51.06994160759672, + -51.21266111259615, + -51.362440538875454, + -51.51674988472523, + -51.67432768509761, + -51.84114265664589, + -52.009844684999905, + -52.18063095458253, + -52.354294153950086, + -52.537658325279395, + -52.723674366177775, + -52.90765586066133, + -53.10627122377588, + -53.30947140228061, + -53.50495036559547, + -53.70962865698191, + -53.92714645252598, + -54.13864078241311, + -54.356556979290815, + -54.58711562939852, + -54.811027595367385, + -55.0332942622891, + -55.26607397218623, + -55.499364896850125, + -55.72975936842476, + -55.9657624271867, + -56.20831832678944, + -56.45031950148498, + -56.692888409526255, + -56.93865140555208, + -57.189295935363894, + -57.43666875487494, + -57.68549157026442, + -57.942014773998274, + -58.197070005529056, + -58.447576896293654, + -58.70128078389291, + -58.958418390378796, + -59.20524170909641, + -59.44723399903469, + -59.69388276513721, + -59.931027810033974, + -60.165977657778846, + -60.4028858163006, + -60.635923995332774, + -60.86840049443835, + -61.099011161298996, + -61.325072857826285, + -61.552572902852525, + -61.78186442401753, + -62.00610369182656, + -62.22918669114481, + -62.45120033636901, + -62.66727576523948, + -62.879589792410876, + -63.08974891346408, + -63.29184799188126, + -63.486150043694316, + -63.68212296761833, + -63.86879288188045, + -64.05406816514606, + -64.24127952634656, + -64.42679519785167, + -64.60940060804988, + -64.79549943956603, + -64.97872401622303, + -65.15444151049354, + -65.32801925922261, + -65.5010308641436, + -65.6690807977606, + -65.83598480396726, + -66.00257711323798, + -66.16103668846448, + -66.31358773017325, + -66.4655443820104, + -66.61597280568952, + -66.7633316363911, + -66.9144278711085, + -67.06458938311995, + -67.20988754556, + -67.35477514527832, + -67.49798257352218, + -67.6346399139633, + -67.77105389797094, + -67.90665128465112, + -68.03823275845356, + -68.16493582203498, + -68.2896012594511, + -68.41387172692838, + -68.53705570690228, + -68.65882461662041, + -68.7799636896839, + -68.90099820793556, + -69.02059525215228, + -69.13835116649797, + -69.25683954163979, + -69.37662718872424, + -69.49376580699942, + -69.61047033623086, + -69.72717242719273, + -69.84145886864682, + -69.94982029032533, + -70.05864851901192, + -70.16732703621027, + -70.27151727827419, + -70.37548834154985, + -70.48073257001012, + -70.5829090979195, + -70.68274677358421, + -70.78443357946844, + -70.88324425648482, + -70.97875286639791, + -71.0771372511972, + -71.17400172032515, + -71.26666261625638, + -71.36021160708452, + -71.45432636041001, + -71.54492733949573, + -71.63466489105116, + -71.72399609523117, + -71.81149568228606, + -71.89823959411831, + -71.98727468863211, + -72.0758127803173, + -72.16293437796791, + -72.24940121128824, + -72.33655908358352, + -72.42154608291942, + -72.50624690961207, + -72.59123584654553, + -72.67362123085358, + -72.75186449679083, + -72.82996198472189, + -72.90490868215244, + -72.97216599709894, + -73.03504118983045, + -73.09233370380218, + -73.14451355979722, + -73.1919683590342, + -73.23528530488475, + -73.27076059019343, + -73.299488019885, + -73.32362145007964, + -73.33851140409004, + -73.34531509384277, + -73.34695945224483, + -73.3424087915722, + -73.32927881981134, + -73.31226240646915, + -73.2913679854743, + -73.26556044980245, + -73.23357381696566, + -73.19316870617422, + -73.14410981350582, + -73.09015924720568, + -73.02809580184176, + -72.95659557025354, + -72.8758583497977, + -72.78872408487702, + -72.68912027937967, + -72.58337446465849, + -72.46927066682753, + -72.33150129817837, + -72.18001428613026, + -72.0243428194608, + -71.84454500362263, + -71.65815842349501, + -71.49037568036576, + -71.30876935098065, + -71.11536600067517, + -70.918510031055, + -70.70831981370121, + -70.48326402899058, + -70.25481640942388, + -70.0209624884734, + -69.77772697405878, + -69.52418182853609, + -69.24642944281652, + -68.96152470675838, + -68.66849124212922, + -68.36533051358055, + -68.05095836453975, + -67.72653230141428, + -67.40800899464818, + -67.07722682486768, + -66.73974947011678, + -66.39400293804786, + -66.04112442409881, + -65.68870114746116, + -65.3252483383514, + -64.9690263792324, + -64.61522214180339, + -64.25733066435907, + -63.896024046542664, + -63.54395670129856, + -63.1810097778616, + -62.81461679950509, + -62.462797250069386, + -62.105486920101235, + -61.739157656934054, + -61.371912575150866, + -61.002145638833085, + -60.62331255397244, + -60.24365392961673, + -59.86259983590844, + -59.47781512744066, + -59.096471828561725, + -58.70280251911583, + -58.303276871678776, + -57.90745462998524, + -57.504595142428485, + -57.0966764523211, + -56.69158748334247, + -56.285752056943494, + -55.87673676370104, + -55.47318605198147, + -55.06618157922572, + -54.665725044789625, + -54.26595706250994, + -53.857825526175226, + -53.454269450239025, + -53.06013790782204, + -52.65472789689884, + -52.25882172385109, + -51.87490334890676, + -51.47517555816263, + -51.090607751439016, + -50.713532095332575, + -50.322817204092026, + -49.94353977548596, + -49.56960416043476, + -49.181510866065764, + -48.80359830476866, + -48.4448484297422, + -48.062382789169405, + -47.67769802278691, + -47.31172074956801, + -46.92809033117677, + -46.538474389050236, + -46.16966764647056, + -45.793121883677884, + -45.40924538838363, + -45.03933168433307, + -44.66302865712396, + -44.27767986426334, + -43.91017910195085, + -43.548231782474964, + -43.18426635421187, + -42.83115000476785, + -42.48264528557074, + -42.14120091959226, + -41.79415281047823, + -41.448216382821734, + -41.095658436095306, + -40.74045215053444, + -40.38941567630401, + -40.030357553279735, + -39.66004802795179, + -39.28816934699813, + -38.92008888138836, + -38.53951639982919, + -38.16579844170024, + -37.80201826545343, + -37.4316824132214, + -37.07636853113231, + -36.731254333408614, + -36.36886406753462, + -35.994593852746696, + -35.644686155523374, + -35.29275641245632, + -34.9221115546295, + -34.55673588553961, + -34.20032882942233, + -33.83728767472021, + -33.45697811608634, + -33.08519563632155, + -32.728002369484535, + -32.36119685971681, + -31.977475412711723, + -31.616290722678038, + -31.251161151136085, + -30.855887380410685, + -30.47225987380637, + -30.112296712085538, + -29.735067792671984, + -29.355465807928212, + -29.01767533126146, + -28.680667256120955, + -28.31921822196352, + -27.97768005804322, + -27.64634110188014, + -27.29371948580858, + -26.955000168482044, + -26.624163410977957, + -26.288802749226107, + -25.96300211141147, + -25.644157811184783, + -25.327056545952257, + -25.027643932369575, + -24.730564143525797, + -24.441578575588572, + -24.169146097405985, + -23.895351187594173, + -23.63028700949434, + -23.38296078570461, + -23.14604931948845, + -22.916478434330745, + -22.70735651481451, + -22.514005728692524, + -22.329998272855793, + -22.171505652456872, + -22.029889435845746, + -21.894412725974114, + -21.78228510233631, + -21.68518470781308, + -21.59812155651093, + -21.526664627147596, + -21.46860293568498, + -21.420539513005977, + -21.384150362160078, + -21.360917704232072, + -21.34954348239964, + -21.347730488762924, + -21.355580505067692, + -21.372648608046457, + -21.3978895192888, + -21.43044603174177, + -21.471452813977116, + -21.520787475343546, + -21.579112284658947, + -21.64354971943037, + -21.713874490410145, + -21.79184470150812, + -21.876986914490168, + -21.96544535695405, + -22.05611358331269, + -22.156054009105308, + -22.256593663555137, + -22.357601166068722, + -22.466490675010423, + -22.577486612307805, + -22.685844058486587, + -22.800832239871397, + -22.913894083257276, + -23.02742504509644, + -23.14686173528819, + -23.265635507621756, + -23.383383408534776, + -23.506092238075524, + -23.628263199794006, + -23.746394027939324, + -23.868957372851582, + -23.988830886203996, + -24.10567964078512, + -24.22435960299237, + -24.34058552757865, + -24.452572459304545, + -24.56388831150348, + -24.674461733590807, + -24.785902768653536, + -24.895137988378217, + -25.006350719277297, + -25.11759056525727, + -25.22791188299324, + -25.337221370274982, + -25.448966595733047, + -25.562735125114518, + -25.677846585016777, + -25.79463943932319, + -25.915713709840393, + -26.05309114117935, + -26.181002826989857, + -26.31516199984558, + -26.454617501708643, + -26.596105223950445, + -26.74490022057487, + -26.89710439552725, + -27.052115549729542, + -27.21716863699173, + -27.385546391576813, + -27.5540481686624, + -27.733667049908824, + -27.915404422007466, + -28.08703068348064, + -28.268331385924668, + -28.44997703764731, + -28.623567168102102, + -28.802148517620413, + -28.98714174059946, + -29.158786128981784, + -29.33031276672451, + -29.505906541512033, + -29.674513162984464, + -29.842594653558052, + -30.018725428694076, + -30.193115327473397, + -30.36093531459758, + -30.533288718119326, + -30.7074120461382, + -30.88242342936583, + -31.056804731709143, + -31.238054817841395, + -31.41832962220704, + -31.59600747980589, + -31.77725005068032, + -31.959089786116657, + -32.13843940973086, + -32.31692212486721, + -32.49912140190639, + -32.68094620894967, + -32.85854325658454, + -33.03843065730013, + -33.220607826591774, + -33.39433998624003, + -33.56453442653805, + -33.73328469536549, + -33.89625837329445, + -34.05685182777162, + -34.21273828291849, + -34.36079847525791, + -34.50036662722723, + -34.63451845931453, + -34.76022089678012, + -34.87757621300925, + -34.995826049520176, + -35.109700034739355, + -35.217170967816976, + -35.32522092774323, + -35.42601635100748, + -35.52081672573161, + -35.61305180879768, + -35.6960979698165, + -35.77396957510407, + -35.850287610540086, + -35.92099082034511, + -35.99055615817691, + -36.06215681655589, + -36.12625174757882, + -36.19003801965097, + -36.257201658343085, + -36.31772119051593, + -36.37925753930431, + -36.44161303355463, + -36.50001273721537, + -36.55558580929922, + -36.61388019442608, + -36.66907481331578, + -36.7201508134886, + -36.771543375522924, + -36.820361795533444, + -36.8653732662636, + -36.90904771130603, + -36.950963689888844, + -36.99143231778586, + -37.032876369583775, + -37.07395239415177, + -37.116882095021914, + -37.16277527765196, + -37.21059543611934, + -37.259212505421836, + -37.30777624741638, + -37.3580817430735, + -37.408806823713284, + -37.45939363954084, + -37.51165032368335, + -37.56745677446037, + -37.62612219928459, + -37.68473941635717, + -37.74329437562592, + -37.80139604481766, + -37.85826472824297, + -37.91558332731925, + -37.975349226051364, + -38.03435687639339, + -38.09420449912109, + -38.15508525727983, + -38.21804998030959, + -38.28161549201361, + -38.348479589781206, + -38.41707661278754, + -38.48649857567124, + -38.56022360068908, + -38.636629483553854, + -38.7135357334543, + -38.805735547576035, + -38.89794135909566, + -38.992763532192456, + -39.09235706618665, + -39.198407158233756, + -39.30397097995307, + -39.41269334100938, + -39.52769184278593, + -39.640097203588674, + -39.75180558087459, + -39.870650344317774, + -39.98884954358368, + -40.1066709983397, + -40.22838674105961, + -40.3462994792553, + -40.4691352147877, + -40.5979271308363, + -40.724106268875964, + -40.85594362991394, + -40.995353075372975, + -41.134157015113836, + -41.28127444889768, + -41.44006024885091, + -41.608035097763796, + -41.78888625628457, + -41.9748382738213, + -42.16411434677769, + -42.36535549935075, + -42.57579816572816, + -42.80049713766172, + -43.02337075710654, + -43.24689201724717, + -43.497279433114976, + -43.74603636513933, + -43.98200479679747, + -44.23040045138251, + -44.485857650140844, + -44.739184064761446, + -44.997872630275744, + -45.26070066858167, + -45.523645603503546, + -45.78847717037881, + -46.04773110733275, + -46.2992685722003, + -46.55259145446595, + -46.80007144209028, + -47.03845237717201, + -47.27045894331738, + -47.4926324932838, + -47.72366491521886, + -47.923117693638396, + -48.11535493101869, + -48.29659317863487, + -48.47009199345922, + -48.637838119736, + -48.79572843895207, + -48.944495597548574, + -49.08694433152678, + -49.22090298307765, + -49.34651754585118, + -49.46533616941493, + -49.5765442194328, + -49.68364513813707, + -49.78879809149675, + -49.889262692400614, + -49.9874158272796, + -50.09634376092556, + -50.19576710057528, + -50.297358091270446, + -50.40030751286942, + -50.50512372765578, + -50.61493278372968, + -50.725778079211544, + -50.83807633716309, + -50.952604360629145, + -51.069484093994326, + -51.1914745656385, + -51.31343961475373, + -51.43767964447409, + -51.568411580925336, + -51.703359570426095, + -51.838878158797286, + -51.980465520918976, + -52.12988377836994, + -52.2787234498552, + -52.433643418508495, + -52.59124637272818, + -52.75576543549834, + -52.92723801656904, + -53.09841357511194, + -53.28096049895093, + -53.47299187937339, + -53.65979836561209, + -53.85197386929605, + -54.05830275954625, + -54.26462258086851, + -54.47298960068094, + -54.69639809207101, + -54.92165184926563, + -55.140997397553726, + -55.3682536213105, + -55.62434382218987, + -55.855937101434016, + -56.088887631397164, + -56.32682179904883, + -56.56866772283272, + -56.81154467589484, + -57.052939783540054, + -57.2970527772479, + -57.54214075775572, + -57.78669197780942, + -58.032497304470176, + -58.27967952359254, + -58.52774357224673, + -58.77324601619516, + -59.019509838824206, + -59.26156790685768, + -59.496353226895316, + -59.728490885098786, + -59.96132338045377, + -60.18548071028015, + -60.40567806437624, + -60.631134611711715, + -60.85136762315885, + -61.069033495158784, + -61.289347958701384, + -61.50736395700268, + -61.72347449000393, + -61.939433601832036, + -62.158663735438424, + -62.37831023797241, + -62.589998805896094, + -62.801589910631016, + -63.01407203613896, + -63.21925101967681, + -63.420167343260886, + -63.61693401032472, + -63.801862417023145, + -63.988055628833884, + -64.17375911329682, + -64.35002008589018, + -64.5236144681962, + -64.69821147686149, + -64.8683362185876, + -65.03690332883215, + -65.20572564603471, + -65.37083184703691, + -65.5336935025303, + -65.69478772717814, + -65.85550151993193, + -66.01141360499129, + -66.16347518903787, + -66.31600828851577, + -66.46685912434538, + -66.61327058465216, + -66.75775482380826, + -66.90273195606284, + -67.0451210619066, + -67.18581604536278, + -67.32652949042996, + -67.46236741218684, + -67.59471377435128, + -67.72909579005884, + -67.85708759166262, + -67.98331332316326, + -68.10856359109131, + -68.23196028232547, + -68.35270906625568, + -68.47234904104525, + -68.58894775687868, + -68.70519331366043, + -68.81933775352118, + -68.9287282967578, + -69.0350238041871, + -69.13931426185329, + -69.24108634981746, + -69.34074525673996, + -69.43985139453707, + -69.53891835664706, + -69.63756927493108, + -69.73643952069175, + -69.835510543083, + -69.93325376388403, + -70.02713854660192, + -70.12218653390872, + -70.21863083959651, + -70.31050182161633, + -70.40344900670789, + -70.49801069897822, + -70.59049777649363, + -70.68120128931315, + -70.77460918967162, + -70.86659526620204, + -70.95608610167788, + -71.04888932948845, + -71.14220723778301, + -71.2333036714523, + -71.32667892572601, + -71.42176601217464, + -71.51345143520112, + -71.6052065561612, + -71.69851796318068, + -71.79124783698138, + -71.88443953462979, + -71.98045729420745, + -72.07651352764492, + -72.17089185978968, + -72.26771600686197, + -72.36762094583482, + -72.4662781235121, + -72.56529152217168, + -72.66201877693607, + -72.75159279818001, + -72.83639716468278, + -72.91553209081161, + -72.98838838000754, + -73.05353020727999, + -73.11455549438739, + -73.1701273981084, + -73.21761953976316, + -73.26305864936852, + -73.30208247936146, + -73.33645770433473, + -73.36328313632707, + -73.38163615064862, + -73.39005826457684, + -73.3866503716562, + -73.37400770830855, + -73.35194307038122, + -73.31649179531554, + -73.27070148876368, + -73.21394170131056, + -73.15035019123178, + -73.08311978347196, + -73.00253306695204, + -72.90854317889664, + -72.8117280172042, + -72.70427412025454, + -72.5828492945219, + -72.4596292587395, + -72.32496285568756, + -72.18089137001792, + -72.03529966191883, + -71.86587160094157, + -71.68519964704127, + -71.5060972856814, + -71.30747012180845, + -71.10345346077327, + -70.90409173025043, + -70.68989897080223, + -70.46301300837499, + -70.23453850822543, + -69.99370391280686, + -69.74306451517064, + -69.4959556154675, + -69.2394447764751, + -68.96774231204915, + -68.69006828212707, + -68.40043206298986, + -68.09948161268093, + -67.79282386824059, + -67.47152927350916, + -67.14480627156297, + -66.81698670152699, + -66.48051217030299, + -66.13570153059416, + -65.78647079032615, + -65.4305139246895, + -65.07917736454287, + -64.72365256364178, + -64.35613278813504, + -64.00350270732935, + -63.655136203008, + -63.28886564557143, + -62.9273300654285, + -62.579748916534875, + -62.21017372899824, + -61.836477619202384, + -61.47350337887478, + -61.1008249535478, + -60.71415475534699, + -60.332003420196386, + -59.943172039128854, + -59.5485529376962, + -59.15426482353507, + -58.755637214234206, + -58.35944865007205, + -57.96476758828307, + -57.56247830460719, + -57.161140157436456, + -56.757150457204766, + -56.34768032479303, + -55.94168592092459, + -55.53823042428493, + -55.12830973725134, + -54.72426812679187, + -54.31949894213728, + -53.90381736075342, + -53.49621002591705, + -53.0846398593366, + -52.66291357533989, + -52.25341797433776, + -51.850147258909864, + -51.43450981864474, + -51.0365245660489, + -50.639311770561314, + -50.23593871875689, + -49.84051448336762, + -49.439048458325956, + -49.035373660510835, + -48.638461917228796, + -48.23818514395617, + -47.83466478803581, + -47.45112056857801, + -47.05763278466847, + -46.65462077974918, + -46.265031651687735, + -45.8771526776741, + -45.47841986714464, + -45.092728007361636, + -44.70829649211626, + -44.31425058319479, + -43.92707972096912, + -43.53537566959353, + -43.140793675114004, + -42.75961674373031, + -42.384060074633446, + -42.01561279186344, + -41.65556265907764, + -41.2995770107581, + -40.946812727407384, + -40.59555163971216, + -40.23539967134619, + -39.83077264214173, + -39.46922443327784, + -39.10261505271557, + -38.72285868011823, + -38.34155409149054, + -37.95830984399811, + -37.57513454571789, + -37.191304760479625, + -36.81228982990092, + -36.453848817041255, + -36.10962661123027, + -35.76992828774044, + -35.43235562368165, + -35.09771367660345, + -34.761070274268704, + -34.430830560281635, + -34.064936749467876, + -33.72802115042855, + -33.3884745768605, + -33.04053844542425, + -32.67824290852522, + -32.30606908525183, + -31.949736176341432, + -31.593263273275998, + -31.21765403116339, + -30.84924780909487, + -30.49996112795178, + -30.131494928893538, + -29.75869173195225, + -29.426153827602022, + -29.09757429589814, + -28.76331572748573, + -28.4405905877889, + -28.125292329920228, + -27.8155872775575, + -27.493448737626125, + -27.174845519305034, + -26.863668142690212, + -26.539548198055, + -26.208131612719583, + -25.882742137279763, + -25.560682506944286, + -25.248144214210402, + -24.94114367309649, + -24.64343167338548, + -24.362160350965954, + -24.08613851774954, + -23.817602907175132, + -23.56744787616472, + -23.356015671971146, + -23.151980651712975, + -22.95480771635995, + -22.769441901460297, + -22.597136903305817, + -22.426157284335947, + -22.27166366447541, + -22.1324945742302, + -22.00130698839695, + -21.876265645220474, + -21.75434285139997, + -21.645254344648617, + -21.547557005019296, + -21.45856069978314, + -21.37939293682077, + -21.311189013530417, + -21.25309551201301, + -21.20557348792329, + -21.171527159773515, + -21.150957991194968, + -21.14130200926466, + -21.14025867458907, + -21.147961798964047, + -21.164197151549327, + -21.18824462908672, + -21.21966739881452, + -21.261952053246265, + -21.311996859093508, + -21.366131815035523, + -21.426038309354904, + -21.495373934270177, + -21.567955697698117, + -21.644642539758348, + -21.732794006910982, + -21.820461877566785, + -21.910900047123498, + -22.011139657176635, + -22.110251970269548, + -22.207773884133747, + -22.31299887627784, + -22.414125583728794, + -22.515190634189363, + -22.62249533479528, + -22.730541938980085, + -22.838987962371448, + -22.952646705541515, + -23.06838414896128, + -23.180429927557974, + -23.296060714071494, + -23.413192561394116, + -23.529043078436736, + -23.646830262371253, + -23.76618527124554, + -23.883010770436165, + -23.998695889332346, + -24.114510168247467, + -24.229932321702456, + -24.349513825273373, + -24.46569754239584, + -24.583037437367008, + -24.69839248535096, + -24.8125479296067, + -24.924394357554746, + -25.034280336750573, + -25.146661463453228, + -25.258615913407247, + -25.370027944819448, + -25.48201818696872, + -25.594674485710865, + -25.70855185414031, + -25.825369750386947, + -25.948013831457107, + -26.074575968770056, + -26.20187795843058, + -26.3372241379381, + -26.475654507637902, + -26.613111328826246, + -26.758472964173844, + -26.909911565185983, + -27.062880474483674, + -27.223308590270733, + -27.39709571678683, + -27.56437525379657, + -27.731090354296406, + -27.909967760479717, + -28.082592547246488, + -28.256855683377623, + -28.441568873274427, + -28.62323793446386, + -28.800517794148625, + -28.97921707859944, + -29.15763802650757, + -29.32991328126194, + -29.50635196611896, + -29.683277368690934, + -29.86152289239508, + -30.034442351516546, + -30.207041266426565, + -30.38047756978916, + -30.556496988681747, + -30.731094175719168, + -30.908611320169694, + -31.09119761384564, + -31.267628697179813, + -31.44237864562472, + -31.61648346992752, + -31.79372627018451, + -31.965404650868926, + -32.1377182409115, + -32.31234807631853, + -32.48281031826397, + -32.651604616090424, + -32.821689646498704, + -32.99251020534204, + -33.15963768414815, + -33.32681250036105, + -33.4920865431513, + -33.65085490929323, + -33.81257237209739, + -33.96919173036498, + -34.11165882221215, + -34.251662605275875, + -34.383907141372084, + -34.51014533806945, + -34.63050273278304, + -34.746729444854346, + -34.859697273761114, + -34.969802736821386, + -35.07417576552302, + -35.17476816452238, + -35.27138688436677, + -35.364899049192125, + -35.453327789637434, + -35.5328169499633, + -35.609244510032724, + -35.6826138209185, + -35.74977862580279, + -35.81500672838077, + -35.88192158112244, + -35.942921690403494, + -36.002179587006516, + -36.06609667012786, + -36.12637253909442, + -36.18345419230827, + -36.24493760294374, + -36.30529625873671, + -36.364839077668876, + -36.428505599417306, + -36.49522661031054, + -36.56363478847932, + -36.63710760798189, + -36.71123301780791, + -36.78222335371588, + -36.85195795002662, + -36.91853852386554, + -36.98234954054238, + -37.04389356771069, + -37.10499677065232, + -37.16534516451735, + -37.224170107050696, + -37.28280200350135, + -37.339885199625684, + -37.39648174857182, + -37.45148984848398, + -37.50646642243688, + -37.56071198436012, + -37.61458021804285, + -37.66885063614813, + -37.72513253379038, + -37.78412111826494, + -37.844278895107536, + -37.90277794206758, + -37.96177968865448, + -38.02038787557107, + -38.075196790831605, + -38.12855014990877, + -38.18358897831821, + -38.23237750887591, + -38.281048678981826, + -38.32973351622501, + -38.37585017490633, + -38.419831201724996, + -38.461883479514555, + -38.50248969525944, + -38.54228972829945, + -38.57974311447889, + -38.61906683149036, + -38.662987591884615, + -38.708152160755645, + -38.7538632966728, + -38.80723895795233, + -38.86394351500577, + -38.92379686133418, + -38.99444680855197, + -39.06873158039537, + -39.14372931978027, + -39.22923763504379, + -39.318160259924284, + -39.40985085571478, + -39.51275130065492, + -39.61122438541254, + -39.714470911702534, + -39.8284911944118, + -39.94158870101025, + -40.06100659443418, + -40.19435475796122, + -40.33186039164071, + -40.47682463618865, + -40.633597056362724, + -40.79695911625718, + -40.968220849515, + -41.15403227418905, + -41.35153141315813, + -41.55781594961092, + -41.77531954575916, + -42.00420403549024, + -42.247393582151105, + -42.50156310109564, + -42.76156242322968, + -43.03445494217945, + -43.31517011160254, + -43.59347004207036, + -43.88930962336479, + -44.18794412627615, + -44.48608944446388, + -44.78889267724565, + -45.089537159473515, + -45.38698177120378, + -45.682403627769865, + -45.97529097931601, + -46.261430098627095, + -46.53526208599471, + -46.80630225030792, + -47.06785442598212, + -47.3152266334425, + -47.55148647420521, + -47.7727859855664, + -47.979927906250204, + -48.17807357325699, + -48.36401955571604, + -48.535696073243024, + -48.698161843699104, + -48.866119315437736, + -49.007279536280805, + -49.142422169914305, + -49.27158570672841, + -49.39432867880314, + -49.51154581961109, + -49.622143228463365, + -49.72858427761303, + -49.83137919900098, + -49.930705866692385, + -50.02878875156228, + -50.125757551113885, + -50.22244616789082, + -50.3191528476129, + -50.41726936908804, + -50.51881736102967, + -50.62161135459325, + -50.725926855578386, + -51.104104140815814, + -51.22722230732899, + -51.35859689132128, + -51.497454856501264, + -51.64049622582717, + -51.7908697346413, + -51.94977633626489, + -52.110707221040876, + -52.27606294113724, + -52.446041568212955, + -52.62682281192127, + -52.81087641960585, + -52.99751965688172, + -53.20069328308993, + -53.40593530267518, + -53.60576161773223, + -53.81662011621015, + -54.0363859903432, + -54.24895745990442, + -54.470291911878576, + -54.702035372537516, + -54.926283360310514, + -55.153412288459734, + -55.38859946280714, + -55.62136929201882, + -55.85464556458957, + -56.09361780526448, + -56.33891086598978, + -56.585375250091275, + -56.832455481140336, + -57.08339681330611, + -57.335510781256005, + -57.58576096869138, + -57.83955120557427, + -58.09600277330934, + -58.352361145455035, + -58.60888287383229, + -58.867941412667015, + -59.12192676004352, + -59.37101674191034, + -59.62012198677071, + -59.86747564315497, + -60.10659450424401, + -60.34725169686158, + -60.59143425121999, + -60.826934719278476, + -61.064590497045124, + -61.30420734228774, + -61.53964230085126, + -61.771863926087114, + -62.00771278686136, + -62.24277486200863, + -62.46852697600483, + -62.69539498731651, + -62.921773392318904, + -63.13995199077138, + -63.353377089943685, + -63.558165939789085, + -63.75233187361694, + -63.94798892266304, + -64.13748826811339, + -64.3209118127535, + -64.50594654125743, + -64.68832685466805, + -64.86769665506284, + -65.04781813965363, + -65.22564273730137, + -65.39978413217911, + -65.57328278158236, + -65.74517774677835, + -65.90903561375244, + -66.07151149511637, + -66.23364536307122, + -66.39001437685894, + -66.54268316367983, + -66.69482035322696, + -66.84299493688042, + -66.98274034898887, + -67.11686109685202, + -67.2473232768979, + -67.37275471986435, + -67.49853608468358, + -67.63057259800027, + -67.74723486022438, + -67.8627077497535, + -67.9754571031743, + -68.08563069929107, + -68.19746510360383, + -68.30848435778216, + -68.41775607238436, + -68.52744413690742, + -68.633129533093, + -68.73462688784191, + -68.83376460339574, + -68.92985064092387, + -69.02481244365634, + -69.1173943163264, + -69.20688750904361, + -69.29468845144093, + -69.38250890651003, + -69.47103973688623, + -69.55929183473162, + -69.64702136147605, + -69.73280545630337, + -69.81785841424487, + -69.90491359660227, + -69.99002561248199, + -70.07270331667695, + -70.15718528968421, + -70.24114478170252, + -70.32285413442807, + -70.40286431587688, + -70.48500864897936, + -70.56735820100766, + -70.64829401426988, + -70.73064782133481, + -70.81531743197613, + -70.90159992571424, + -70.99074831706196, + -71.08203625302541, + -71.1737823807634, + -71.26560347411566, + -71.35571460623784, + -71.44458409917311, + -71.53410019676936, + -71.62295534525737, + -71.7111769274895, + -71.80043232083361, + -71.89071528860671, + -71.97862287266754, + -72.06534242553148, + -72.15351705548409, + -72.24117369948681, + -72.32650167517815, + -72.41122097304289, + -72.49328193817811, + -72.57072266807357, + -72.64345901658709, + -72.71068551852751, + -72.77265378086943, + -72.83047258330451, + -72.88209913081309, + -72.92911119174103, + -72.97024557292157, + -73.0053868767717, + -73.0383985314366, + -73.06545461102495, + -73.0852370553975, + -73.09928378783825, + -73.1087244585547, + -73.11147575647097, + -73.10607968738555, + -73.0951326101401, + -73.07672976892772, + -73.04882031546873, + -73.0153053370118, + -72.9738471882484, + -72.92611455391813, + -72.87199505469133, + -72.80457282100957, + -72.73097061433972, + -72.65216854718145, + -72.56090098688745, + -72.46202221143442, + -72.35736852543373, + -72.23959141650906, + -72.11878320863434, + -71.9872752962235, + -71.83335570725413, + -71.67600007722505, + -71.5082009586617, + -71.3226854473823, + -71.13967185499301, + -70.95531392522747, + -70.75511956253877, + -70.54824546667773, + -70.33577210613676, + -70.10360904416274, + -69.8636953328458, + -69.62389018932022, + -69.37241409173863, + -69.11186569568176, + -68.84310024975234, + -68.56326051952144, + -68.2788475443871, + -67.98568182237305, + -67.68116684124008, + -67.37032745691873, + -67.05976567889473, + -66.73941471965175, + -66.41002122166618, + -66.07466277720971, + -65.73825608816385, + -65.40428778136757, + -65.06069040998966, + -64.71283201352946, + -64.38068598184057, + -64.04711991252417, + -63.69919072118485, + -63.36045179508659, + -63.03081307576595, + -62.68012909007039, + -62.32914207032507, + -61.989412403740566, + -61.637577939691624, + -61.274648871301345, + -60.918499374464, + -60.554813837407, + -60.18255952722983, + -59.814131800365786, + -59.44028335958801, + -59.066652406202465, + -58.699669500159914, + -58.32747429279155, + -57.95035782823271, + -57.57893243124308, + -57.2015442561234, + -56.82194501661254, + -56.444909701417465, + -56.07030598180746, + -55.69193783730353, + -55.320991664748064, + -54.94326555580486, + -54.565853351401366, + -54.19275388213334, + -53.80979434614635, + -53.42879887286961, + -53.056674984054744, + -52.68218507457872, + -52.30282238250406, + -51.945454525362926, + -51.57771802373846, + -51.20765486741763, + -50.8522112158168, + -50.48447880841819, + -50.1120619303601, + -49.752072825817976, + -49.38694215549192, + -49.015260622606014, + -48.652537033453896, + -48.301659566727885, + -47.93622987317094, + -47.5723193998465, + -47.21515073392902, + -46.85766357491683, + -46.49537288254257, + -46.14264890857052, + -45.79243412342383, + -45.43645386527342, + -45.085052382305506, + -44.73595334042792, + -44.379767622031174, + -44.028763042692674, + -43.685164444857925, + -43.343848401608, + -43.012091961379625, + -42.69060782612624, + -42.36425244115255, + -42.04825224996773, + -41.73480724870234, + -41.41441243507075, + -41.0921312480419, + -40.76485267464405, + -40.44072650062485, + -40.11282446283272, + -39.7736541006895, + -39.42821715886703, + -39.07752717892047, + -38.72405253756792, + -38.37030778842886, + -38.01542125747221, + -37.65771833034179, + -37.30912094736801, + -36.97015089642019, + -36.62917551896926, + -36.286347071222515, + -35.94195532420182, + -35.60710138784223, + -35.26868239734169, + -34.92113480034112, + -34.57375815483517, + -34.222897939554244, + -33.877839771189244, + -33.5152299650239, + -33.15177753168167, + -32.79719870871715, + -32.43859434101738, + -32.06062449476858, + -31.6976841775139, + -31.344135662429256, + -30.96425179459354, + -30.586699789811345, + -30.23517487586146, + -29.87593242086572, + -29.508515417656383, + -29.173218552870345, + -28.85248231542016, + -28.502487471058757, + -28.15436597505832, + -27.82600105176375, + -27.480492381027922, + -27.14040098056358, + -26.818235037510153, + -26.48786770164433, + -26.168594017144397, + -25.855947760439268, + -25.543205646099622, + -25.24361924081397, + -24.958346399129535, + -24.675161495617857, + -24.405523781770352, + -24.147787478236896, + -23.882518986274178, + -23.625294806610068, + -23.38517342263037, + -23.152766348575657, + -22.926984042363703, + -22.71657230599161, + -22.52244116998466, + -22.338667653741318, + -22.178302880267452, + -22.03615085465187, + -21.904981151443053, + -21.78990010064519, + -21.6963480793184, + -21.613747592994223, + -21.54364303104233, + -21.489888101017385, + -21.449162135376433, + -21.420155343571256, + -21.404812291255986, + -21.40213329016019, + -21.410364979733004, + -21.426419901066044, + -21.450392900374975, + -21.48255379374399, + -21.52181980838533, + -21.566752356307656, + -21.617906400593903, + -21.675744574721357, + -21.74009389863133, + -21.808948837752926, + -21.881695033221146, + -21.95996610249677, + -22.043234161006392, + -22.12873334291695, + -22.216131199334185, + -22.312097411132406, + -22.40773944947401, + -22.503296470655233, + -22.604860789459906, + -22.70734042294508, + -22.806527681647584, + -22.910816627161694, + -23.014358524896686, + -23.11652643527728, + -23.224677322919145, + -23.341089481025154, + -23.460994431856744, + -23.586267115755597, + -23.71340177789751, + -23.83760832125027, + -23.96347255600051, + -24.091878684772656, + -24.217255789373564, + -24.343818347883307, + -24.472411613524987, + -24.59255368192226, + -24.707446420951598, + -24.822001529025115, + -24.936338059234696, + -25.05346619487281, + -25.168532093608093, + -25.284772150448276, + -25.399863934689044, + -25.512926965641253, + -25.623795242374193, + -25.73869243665912, + -25.8589866064603, + -25.980525096739612, + -26.10325281833032, + -26.230922253086067, + -26.36083833319771, + -26.494724704125975, + -26.632181265085112, + -26.775610582136455, + -26.920690184971154, + -27.06160750835324, + -27.205520303705732, + -27.348691431134522, + -27.492973293355632, + -27.646363384845003, + -27.80307212819232, + -27.960243606801313, + -28.12738507107007, + -28.300127591950236, + -28.462697404409184, + -28.616130898816355, + -28.764101486603447, + -28.903455225751628, + -29.047105846118832, + -29.197672432922435, + -29.340093284795767, + -29.480170953913447, + -29.626435268751734, + -29.768619712304925, + -29.907694450155788, + -30.063491616359183, + -30.2264148861466, + -30.391165525726823, + -30.551426562065945, + -30.71109749627567, + -30.872512599777036, + -31.03737624842146, + -31.198026544621342, + -31.35786466378723, + -31.52571873691776, + -31.684402155851675, + -31.838102843849853, + -31.99288658025006, + -32.1496604126573, + -32.30598904381027, + -32.45968877410026, + -32.61603854432724, + -32.76791095037131, + -32.919650626058015, + -33.06765874423673, + -33.2178597785099, + -33.365596639245545, + -33.50724207131844, + -33.6484933976596, + -33.782886269933776, + -33.912713808330366, + -34.04134101986095, + -34.161454401007475, + -34.27607778327195, + -34.38921456369967, + -34.49702669521139, + -34.6041454533932, + -34.71258653644202, + -34.81814139191315, + -34.92442156617737, + -35.03216765565739, + -35.13733824058586, + -35.24200591057709, + -35.34633163784157, + -35.44501160020167, + -35.53957133994688, + -35.63592727341846, + -35.724942728733325, + -35.81039933839135, + -35.89608018183842, + -35.983055487875625, + -36.060055258248404, + -36.13729389360015, + -36.2190335217945, + -36.29380199754092, + -36.370085172867455, + -36.448152006644364, + -36.520831158203706, + -36.59100718893863, + -36.66216444260028, + -36.73423179336943, + -36.80433656535305, + -36.87618225739581, + -36.94537952166152, + -37.010679968574514, + -37.072969154176, + -37.13285029859125, + -37.191295790064, + -37.25092507617021, + -37.31183414492856, + -37.3713380132829, + -37.433365792362764, + -37.4971670191308, + -37.5628269128984, + -37.63097813777338, + -37.699012704893015, + -37.769435757172225, + -37.84189825486961, + -37.914756035992724, + -37.988742200839646, + -38.06551436234993, + -38.14708283579221, + -38.22911926432711, + -38.30904482859451, + -38.3902750587055, + -38.47160773935936, + -38.550120030785145, + -38.627287314663164, + -38.70955147292591, + -38.78572465026189, + -38.86154282958575, + -38.9382615457867, + -39.00948838112435, + -39.081504051841044, + -39.15511425591152, + -39.22727900136679, + -39.29846265937135, + -39.36872293272774, + -39.438970452184016, + -39.51232499659036, + -39.588437810121455, + -39.66396416195027, + -39.743988370059036, + -39.823112536793204, + -39.90268698328979, + -39.9867816678149, + -40.072107999887486, + -40.159006006417734, + -40.250078036371875, + -40.34362239027905, + -40.43851925498407, + -40.537980841227835, + -40.63686774097731, + -40.73795543783005, + -40.844981139273216, + -40.951997655991065, + -41.062690713572, + -41.18180314080349, + -41.307329208067905, + -41.44024518833797, + -41.58153772520447, + -41.733041062909344, + -41.89537060354485, + -42.07029808011077, + -42.25720454661528, + -42.45745057649343, + -42.671435256628, + -42.892956458648165, + -43.13191280487126, + -43.389287638409286, + -43.65070052288813, + -43.91365502178964, + -44.19959321805714, + -44.49737192850483, + -44.79033843281663, + -45.09598334134922, + -45.405067274308934, + -45.70920220166909, + -46.01425072261265, + -46.317304105233, + -46.613317919410036, + -46.89837567953706, + -47.179077156090514, + -47.45091126839585, + -47.70893069272744, + -47.95662111698227, + -48.18789324522698, + -48.405751102902144, + -48.61268120552227, + -48.80753421101286, + -48.987618755372026, + -49.1562446018585, + -49.31277179685632, + -49.457034962429695, + -49.591081371629585, + -49.71484328687455, + -49.8304950212542, + -49.93881467203453, + -50.03962474813927, + -50.13723889288927, + -50.23107991068973, + -50.320494546372174, + -50.408648561633775, + -50.497625457993195, + -50.58806231571165, + -50.68198472484677, + -50.79033761795886, + -50.89499511994884, + -51.00324592740218, + -51.115030614156616, + -51.23129294714832, + -51.35322385256986, + -51.481471340784694, + -51.61424372173705, + -51.75393805702607, + -51.90377061741117, + -52.06050420202254, + -52.222156271705295, + -52.394580496612235, + -52.57149118435109, + -52.75292957732888, + -52.9377989091786, + -53.134282737481975, + -53.33335510585575, + -53.53409937865804, + -53.753196876631485, + -53.97381604718522, + -54.18828048480063, + -54.41403487900981, + -54.64806054950085, + -54.875146016140285, + -55.113852348529534, + -55.35932450445642, + -55.59736520126808, + -55.84171882926131, + -56.0913281623881, + -56.33675122268888, + -56.586828509734204, + -56.84645158231835, + -57.105353229431735, + -57.36315396310824, + -57.62805759933618, + -57.89511300182526, + -58.15814254705349, + -58.42489083303824, + -58.69760737542457, + -58.96942418517086, + -59.24165393872915, + -59.51799607437879, + -59.78745639577197, + -60.051496890101284, + -60.318086325924355, + -60.57647712497823, + -60.829664493707966, + -61.089348444484514, + -61.342362295883774, + -61.590171930938006, + -61.840577862365556, + -62.08899124020301, + -62.32866134735973, + -62.56948967078802, + -62.810940186372875, + -63.04181238803805, + -63.270961800570134, + -63.52118008974367, + -63.73858861593142, + -63.9522525364015, + -64.15714907441796, + -64.35680510475528, + -64.55344204506143, + -64.7450186534997, + -64.93492156360699, + -65.12505449436121, + -65.30984675137664, + -65.49602432660923, + -65.68185049036664, + -65.85909398972477, + -66.03222030475257, + -66.2064532389386, + -66.37401886460268, + -66.53539869670644, + -66.6985382415549, + -66.857341670653, + -67.00712940751521, + -67.15573684701633, + -67.30613178967323, + -67.45020065289773, + -67.59357998259453, + -67.73453120723646, + -67.86918594435251, + -68.0011948422586, + -68.13257348039454, + -68.25935694699257, + -68.38566652761453, + -68.51056179429035, + -68.63436200715414, + -68.75565096024698, + -68.87546292780858, + -68.99282874008783, + -69.11023820445519, + -69.22466758983161, + -69.33468198051443, + -69.44310951160371, + -69.54881493634024, + -69.65342167514686, + -69.75714370448921, + -69.8605528093441, + -69.96358955871048, + -70.06705091748779, + -70.17159199691042, + -70.27653473081132, + -70.38163126501072, + -70.48469938809419, + -70.58894280010354, + -70.6952027796743, + -70.80683967692613, + -70.90696307173944, + -71.00849527404763, + -71.10734642399387, + -71.20210867594348, + -71.29832012644825, + -71.39494324686648, + -71.48811737299084, + -71.58071228282576, + -71.67378359830272, + -71.76504382257333, + -71.85638880146503, + -71.94775855297245, + -72.03750961353443, + -72.12567968732866, + -72.21206477269702, + -72.29753395289379, + -72.38342029434568, + -72.46731971505908, + -72.5515910213241, + -72.64663355544188, + -72.732839311115, + -72.81624316602283, + -72.901715811989, + -72.98705115780574, + -73.07009560253982, + -73.15129387580456, + -73.22998566881122, + -73.30417297342126, + -73.37406424879377, + -73.43827279790231, + -73.49806968063889, + -73.5521308174943, + -73.60012315712991, + -73.64249681469272, + -73.67776486988559, + -73.70786129595258, + -73.73245491818513, + -73.75037626017347, + -73.76096310499868, + -73.76761645811072, + -73.76765015357171, + -73.75765566842436, + -73.74072933909764, + -73.71620342746488, + -73.68093604015272, + -73.63982579510566, + -73.59035007510316, + -73.53466103521208, + -73.47265353218445, + -73.40309255384136, + -73.32944400762746, + -73.25130573791414, + -73.16230480886657, + -73.06752573671588, + -72.9672829983631, + -72.85611241352224, + -72.74419859281247, + -72.61921903993031, + -72.47404739316538, + -72.32686216697094, + -72.16467187993177, + -71.9885379108041, + -71.81780401831426, + -71.64248681967499, + -71.45144925311202, + -71.25363328925569, + -71.05082778228895, + -70.82933891285678, + -70.60145680780992, + -70.36555620250806, + -70.11914779332301, + -69.86427258962065, + -69.60176588158231, + -69.32821624436541, + -69.04867461769744, + -68.7622866254037, + -68.46035136398608, + -68.15417838541254, + -67.84934334267064, + -67.51660686204437, + -67.18006026928688, + -66.84683050956784, + -66.5139525084509, + -66.18958612057345, + -65.86508625350565, + -65.52600748979158, + -65.19780033000949, + -64.87306228785998, + -64.53885253412979, + -64.21174275802292, + -63.889297093666265, + -63.56603406039059, + -63.22680774639339, + -62.88925307727907, + -62.55158389158242, + -62.204757205436614, + -61.850141228831596, + -61.49493611992698, + -61.133561501780655, + -60.7682341474149, + -60.403196154833125, + -60.03311148041931, + -59.66151870048452, + -59.294543079513154, + -58.92252380011841, + -58.54585870532376, + -58.17075925244724, + -57.78989628918336, + -57.40416890949777, + -57.01767620400345, + -56.63055227967966, + -56.2398902039165, + -55.815056094274745, + -55.42416406330756, + -55.037800670356056, + -54.65814333611411, + -54.27572995893224, + -53.90526799348135, + -53.54884526792905, + -53.1904069727871, + -52.83869899765796, + -52.51539821997287, + -52.18397723536897, + -51.85326286316791, + -51.54369886767894, + -51.22154895006788, + -50.8900600594513, + -50.567919830073016, + -50.238946547903275, + -49.90651232739457, + -49.57197917342724, + -49.23157240598229, + -48.89862461994845, + -48.561948865908484, + -48.2088730452881, + -47.86152172391734, + -47.515635822188536, + -47.158799882982365, + -46.80377744315119, + -46.45426898482567, + -46.09410455978452, + -45.729982580655594, + -45.373113659034374, + -45.00680731941585, + -44.63455124099906, + -44.273173006355385, + -43.91276741964215, + -43.5533060258781, + -43.207836711125424, + -42.859755450366194, + -42.515026160370205, + -42.174556283897594, + -41.827228888305825, + -41.474203211374444, + -41.1166003228051, + -40.76126631629593, + -40.39787635296161, + -40.02305115063716, + -39.64332177524524, + -39.26138377887114, + -38.87490905469687, + -38.48941234249474, + -38.10312517420079, + -37.72321208719548, + -37.35458157673017, + -36.98509227572977, + -36.61337380348764, + -36.24343138388839, + -35.88565943938279, + -35.51894090174665, + -35.14486172996532, + -34.77690100262629, + -34.413139594164754, + -34.04020123593851, + -33.65875654838488, + -33.294072335597114, + -32.9430046897531, + -32.57604697232716, + -32.21957629982182, + -31.89288716544579, + -31.548315725412877, + -31.191063175333376, + -30.855126303307152, + -30.526094463741856, + -30.190168716530895, + -29.853459583523566, + -29.537033855191776, + -29.234367169527925, + -28.912386761556956, + -28.589913428867064, + -28.28365768842951, + -27.96768317526559, + -27.646121184402677, + -27.33720040958477, + -27.021651497423683, + -26.709951528558385, + -26.408690283330845, + -26.10660710189547, + -25.806030843244482, + -25.52021273064992, + -25.238077132963465, + -24.960202361192145, + -24.702441811898723, + -24.44206910812618, + -24.178438374884472, + -23.932752796138534, + -23.697957088673878, + -23.468088363313232, + -23.24676333327689, + -23.041116256445584, + -22.847627037706772, + -22.66558015740162, + -22.506780926503883, + -22.36131253966572, + -22.223154946736862, + -22.106767204562416, + -22.0055917946128, + -21.913345280482684, + -21.83688567789569, + -21.774353449959808, + -21.725099594685577, + -21.688985323927486, + -21.66779355513553, + -21.66030608881035, + -21.664788800881023, + -21.67989884857852, + -21.70499464686902, + -21.741247610544526, + -21.78754799980009, + -21.842325973360637, + -21.905107015268626, + -21.974332876644127, + -22.05136276264909, + -22.133163676920763, + -22.218371266576543, + -22.310521558986576, + -22.40860015534457, + -22.508613126915478, + -22.609289371038862, + -22.71382496821083, + -22.820691050549115, + -22.924692204138633, + -23.03230104429842, + -23.14383462442385, + -23.250388408083037, + -23.36118182242375, + -23.473403513505087, + -23.581556433942954, + -23.694475229182572, + -23.811210912908113, + -23.92505655536757, + -24.042729277753185, + -24.162580327007138, + -24.27982814133648, + -24.39577483064936, + -24.515711527890677, + -24.632166887095853, + -24.74770785086778, + -24.8657160960641, + -24.98031543136073, + -25.09232632962804, + -25.204551367529355, + -25.31538009348689, + -25.428093000116814, + -25.541802724850776, + -25.653470278878302, + -25.768725268624824, + -25.883854715918872, + -25.99887929067349, + -26.11332680776609, + -26.230185343128916, + -26.348394244416827, + -26.467038324614, + -26.587056173289348, + -26.707141726174534, + -26.82839831459594, + -26.95172480503895, + -27.088632898654566, + -27.213282215996067, + -27.330318260786278, + -27.448982591299654, + -27.56962666398281, + -27.688239511316485, + -27.810714016146456, + -27.938183897315056, + -28.0650872093922, + -28.194880683342525, + -28.333138671150422, + -28.475966850131677, + -28.61760821654979, + -28.766071865948344, + -28.92146894633009, + -29.070657143446724, + -29.22422802710299, + -29.385903743844, + -29.542416803210983, + -29.695852358968107, + -29.851503536036773, + -30.006195950637736, + -30.14856336818705, + -30.29493053515212, + -30.440294285828557, + -30.587000217327315, + -30.733322646456728, + -30.874674696407837, + -31.01731820512761, + -31.16316280922664, + -31.310119044395524, + -31.45344521173325, + -31.60767394929439, + -31.766191557101273, + -31.9190058298071, + -32.074065503801485, + -32.228796949286945, + -32.383772776022994, + -32.5410936792175, + -32.694536222334115, + -32.851903567622585, + -33.00731397936124, + -33.16479337679203, + -33.32195672400879, + -33.47817753691862, + -33.63713624301213, + -33.792569634726775, + -33.94731391188095, + -34.10329075153213, + -34.25523369853277, + -34.4079274320869, + -34.563498765133495, + -34.710589537913776, + -34.85589298973087, + -34.99914611466545, + -35.134036033510604, + -35.26538876619463, + -35.38957006750351, + -35.51121304820496, + -35.62984354445944, + -35.74184630850491, + -35.85021819893029, + -35.952990467030794, + -36.04783564474804, + -36.139501935712616, + -36.224341487478966, + -36.29999616730834, + -36.372695122010256, + -36.441052538782095, + -36.50292336374147, + -36.56620817451979, + -36.63060500154476, + -36.69127603050018, + -36.75586038320107, + -36.82216151579864, + -36.881812676850565, + -36.943891287636845, + -37.00580343667554, + -37.064972200238124, + -37.12419393029799, + -37.1856362431639, + -37.24440312907708, + -37.30370876832406, + -37.36946333548556, + -37.424478513873204, + -37.476130524066555, + -37.52683398474871, + -37.575959487269806, + -37.625142517126186, + -37.67848777970751, + -37.73327083379501, + -37.79135549615383, + -37.853619553999316, + -37.91933421108968, + -37.98769305223514, + -38.05902781617655, + -38.13467257549317, + -38.212624414565816, + -38.291838341694465, + -38.372991048118166, + -38.4570755685649, + -38.54310598807688, + -38.629521157064566, + -38.71859799931532, + -38.80453428000226, + -38.88889156320609, + -38.973395340598174, + -39.055845926745334, + -39.13535263929575, + -39.216446102612764, + -39.30030859574843, + -39.380351751541, + -39.45943892893928, + -39.53727213526203, + -39.61341596272377, + -39.68764591577625, + -39.75839456183066, + -39.82889039671367, + -39.89887000731089, + -39.96780342280601, + -40.03261238511189, + -40.0975086193935, + -40.15847314672556, + -40.21613056346378, + -40.27571688804471, + -40.33631782904814, + -40.393772456831634, + -40.45105878171714, + -40.51398034732638, + -40.57636941356571, + -40.63809129414276, + -40.706375294108355, + -40.77964353975551, + -40.85774952271849, + -40.94325778825428, + -41.030378145817686, + -41.123030717826204, + -41.22530365075202, + -41.33341408708455, + -41.447538674650104, + -41.57029218848021, + -41.69767799045506, + -41.831609278564535, + -41.977255124425824, + -42.13276642953561, + -42.303686612216886, + -42.489307909538404, + -42.68536348100295, + -42.89533021608527, + -43.12239409554427, + -43.36163292358729, + -43.61071729634861, + -43.87507741773644, + -44.15899577150894, + -44.44551025073052, + -44.73572194980638, + -45.037476230017006, + -45.33434133482656, + -45.63375539861817, + -45.934273611890994, + -46.2246161097934, + -46.51860376423774, + -46.80304120799316, + -47.07243959361878, + -47.34073115611892, + -47.604272940148654, + -47.848343341458154, + -48.080532690116016, + -48.30452853349216, + -48.51264112400717, + -48.70902912561279, + -48.896694172169674, + -49.07109008140121, + -49.23493477866019, + -49.389386429441714, + -49.531356440876905, + -49.66401278069163, + -49.78790789402918, + -49.90500911811212, + -50.01555925926447, + -50.11974526865521, + -50.22069451438372, + -50.31976315461191, + -50.41499710680453, + -50.50820149524243, + -50.60233865674474, + -50.69773349991716, + -50.79430275689069, + -50.8932559150181, + -50.9982434665074, + -51.107256735857966, + -51.220208095445265, + -51.34011509805129, + -51.464285678518024, + -51.59522568841392, + -51.7312715779073, + -51.87296321622957, + -52.02557375764567, + -52.18664529993934, + -52.353214305233365, + -52.5320650111789, + -52.71479653015089, + -52.89777777504159, + -53.08470440195738, + -53.28374009135521, + -53.48716125101572, + -53.68998017573295, + -53.91000322667469, + -54.13533458543162, + -54.35342060705394, + -54.58099670350793, + -54.821927119247604, + -55.05372578752008, + -55.29206620718725, + -55.540477380525786, + -55.780943383535224, + -56.0232542784252, + -56.27384792825905, + -56.519203875280624, + -56.76662136797318, + -57.020413642514974, + -57.27712521065072, + -57.533859760139535, + -57.79181824091577, + -58.052748467975825, + -58.31220874205509, + -58.5723088868142, + -58.833604416417074, + -59.09772737102568, + -59.361570399724314, + -59.625061289337665, + -59.887723101503454, + -60.14630337617529, + -60.400522243944295, + -60.65710277365724, + -60.90423173572673, + -61.1488480029457, + -61.39992955238983, + -61.642869706520315, + -61.884112713830014, + -62.12798305831393, + -62.367499252827734, + -62.5989911168697, + -62.83226971129024, + -63.068067969165035, + -63.29352201894287, + -63.51869377171798, + -63.744574060217595, + -63.9632054081868, + -64.17946918008111, + -64.39087128100185, + -64.59307288142473, + -64.79774072629073, + -64.99614119848623, + -65.19018627749644, + -65.38663935244789, + -65.5791784738423, + -65.77004746504917, + -65.96283931597681, + -66.15308611727723, + -66.33529531489182, + -66.51771575184496, + -66.69709734865911, + -66.86730509002842, + -67.03571981630326, + -67.20266167852309, + -67.36236189113457, + -67.5171315661556, + -67.67207276242547, + -67.82266881094722, + -67.96788663045962, + -68.11370491917054, + -68.25574671714102, + -68.3920826262183, + -68.52880159768614, + -68.65945337777421, + -68.78769555534664, + -68.9138116590175, + -69.03735264394497, + -69.15802800532765, + -69.27768878207934, + -69.39457963372257, + -69.51133214403787, + -69.62687921144068, + -69.7393260983239, + -69.85024232875082, + -69.9596104934127, + -70.06789635784469, + -70.17622383472096, + -70.28477731920614, + -70.39338978148825, + -70.50211593579483, + -70.61170336267585, + -70.72176317533427, + -70.8316308284024, + -70.93848200194604, + -71.04682356266727, + -71.15713819051456, + -71.26310597183229, + -71.36791507471087, + -71.47429848460003, + -71.58049798198662, + -71.68947274577285, + -71.79898023393233, + -71.9086231587463, + -72.01462225740896, + -72.12003512988949, + -72.22491050130363, + -72.32694776170058, + -72.42697346969334, + -72.5256454083299, + -72.61945798242765, + -72.7071885146368, + -72.79224341616671, + -72.8749685885782, + -72.95711888288096, + -73.03644209778228, + -73.11470831988068, + -73.19403338250781, + -73.27356732183902, + -73.35080617233405, + -73.4277729671337, + -73.501169825925, + -73.57255014380672, + -73.64150808359304, + -73.70859952090991, + -73.77128668775255, + -73.82999345515604, + -73.88400820460873, + -73.93194521593419, + -73.97965887212314, + -74.01613727503462, + -74.04693529831493, + -74.0711026333788, + -74.0891947739312, + -74.10325171556272, + -74.11077181359764, + -74.11224291845295, + -74.10828877711101, + -74.0995104973766, + -74.08196665257952, + -74.05749153338483, + -74.02688759415784, + -73.98220592122641, + -73.93424848937234, + -73.88049603108865, + -73.81435573295539, + -73.74277211899157, + -73.65782746601664, + -73.56386568216291, + -73.46030199570448, + -73.34927496015943, + -73.22821280892013, + -73.09456365374437, + -72.95534846178123, + -72.79194288760058, + -72.61153947551863, + -72.42478106331122, + -72.21697852077787, + -72.00260673344646, + -71.79210803903807, + -71.56718201144498, + -71.33436197572068, + -71.09789845810721, + -70.84104591911839, + -70.57407981936726, + -70.30955852147622, + -70.03324249063157, + -69.74250551351156, + -69.45126632532073, + -69.15049988756635, + -68.83555389653114, + -68.51632900035767, + -68.18579209814202, + -67.8591784862852, + -67.52711456750755, + -67.18935273017047, + -66.8467766567328, + -66.50913836766722, + -66.17689903230985, + -65.8340396162566, + -65.49895269304913, + -65.17246795909914, + -64.84161569730651, + -64.51065992391854, + -64.1835038915548, + -63.853982286047746, + -63.518785170244925, + -63.187701230962915, + -62.852965890122164, + -62.51342907730107, + -62.16892689916969, + -61.82381178700715, + -61.47193908943564, + -61.116189280358064, + -60.76282956869246, + -60.404002941780696, + -60.04598434886867, + -59.69282519615926, + -59.3355286987274, + -58.97310781191996, + -58.61453102387709, + -58.250098536509334, + -57.87932129976984, + -57.5116168124708, + -57.14338302489704, + -56.77321915078401, + -56.406310194796994, + -56.03706174316875, + -55.66348173484058, + -55.29385376614534, + -54.918175066708905, + -54.53869383123781, + -54.165367036136196, + -53.79573585058121, + -53.416813290274135, + -53.049804785035974, + -52.6926426026352, + -52.317505681165656, + -51.95627625284769, + -51.59828188664619, + -51.22393505513749, + -50.859494122315446, + -50.50313720286346, + -50.134912510661984, + -49.76719458920423, + -49.41273356824788, + -49.05769279857246, + -48.68567417822952, + -48.320252811100765, + -47.961158080307854, + -47.589422946578104, + -47.219485378610656, + -46.86196010809194, + -46.494724550229684, + -46.122710718837624, + -45.76135235637507, + -45.393067032803195, + -45.01750524526487, + -44.65563382811126, + -44.29875536440921, + -43.94205462077312, + -43.59641488842708, + -43.24954644027592, + -42.914529220701965, + -42.574872968087384, + -42.23274150579978, + -41.889634041074956, + -41.53797942480727, + -41.1911990771342, + -40.83934144669573, + -40.47686020806958, + -40.10907247027804, + -39.74284072565406, + -39.370736601841465, + -38.99759851659228, + -38.62990285959735, + -38.25927149692369, + -37.90318501940935, + -37.55408283226934, + -37.166623151450565, + -36.8072200946209, + -36.46453107940023, + -36.128300651418876, + -35.7763325115361, + -35.428569609206676, + -35.08406897859184, + -34.74486171144833, + -34.39238648350678, + -34.043556708428305, + -33.704591975519946, + -33.369973164503264, + -33.02009351016525, + -32.67145044945371, + -32.34029104081088, + -31.994903242438408, + -31.632808495022406, + -31.28420150444608, + -30.94808069482364, + -30.603704159974015, + -30.257207380248254, + -29.935797232362642, + -29.629354078135176, + -29.304974384635095, + -28.982420528642937, + -28.674891263915935, + -28.357181273736156, + -28.034906293558503, + -27.722810937030946, + -27.404920432311187, + -27.091178198832235, + -26.784810356529796, + -26.478407622341198, + -26.172518449022466, + -25.882606313413188, + -25.596617669386553, + -25.31453978147959, + -25.05390906041133, + -24.79162688852437, + -24.52846305266152, + -24.284195927541965, + -24.052768889441175, + -23.827648996882292, + -23.613913911141825, + -23.41927575372894, + -23.236386968614017, + -23.067603123255417, + -22.923615727124492, + -22.792925001168992, + -22.670437417729644, + -22.57089391261818, + -22.484266716557016, + -22.4067478490948, + -22.344300745758325, + -22.29419816744857, + -22.25345585392556, + -22.223168234744026, + -22.20442084963895, + -22.196149841969746, + -22.19559734872195, + -22.20184814816654, + -22.21540543056247, + -22.236235750390676, + -22.263721066747788, + -22.29830980446049, + -22.339697232955015, + -22.38933498422438, + -22.446094186534943, + -22.506256163603172, + -22.570743553814037, + -22.641006816368133, + -22.71519314874621, + -22.791179347569532, + -22.87099126784645, + -22.959337521455176, + -23.045615996691463, + -23.133909052688374, + -23.228763257555926, + -23.32352023053608, + -23.41722304572924, + -23.51645027077434, + -23.61365317364001, + -23.71032232278593, + -23.813225598005634, + -23.916403884699655, + -24.0184935966503, + -24.12572634325993, + -24.23460642583712, + -24.34153043183256, + -24.449640124412333, + -24.560573724624394, + -24.66885722620413, + -24.778775825390326, + -24.890884635331997, + -25.001748186045617, + -25.11207307827067, + -25.223034111710778, + -25.33482529744038, + -25.45046818840307, + -25.56512873329032, + -25.681520692822403, + -25.798817957352274, + -25.91524350757026, + -26.03002243635211, + -26.143763577234296, + -26.261303446326345, + -26.378715497757252, + -26.49573694808921, + -26.615050922919693, + -26.73533115676734, + -26.857122051466344, + -26.980457917951913, + -27.107964023508945, + -27.23607163317926, + -27.36648567972102, + -27.501538580892056, + -27.635394845876924, + -27.7731271784617, + -27.91813098687874, + -28.063598752924364, + -28.210489899091275, + -28.3690240199239, + -28.525881151008605, + -28.67540648404655, + -28.83542775015255, + -28.995631100008875, + -29.149310986007713, + -29.312150932910924, + -29.480085566937127, + -29.63891981710694, + -29.79867940438424, + -29.966136471328255, + -30.12500452839244, + -30.285518039199967, + -30.450265333170695, + -30.61569229003806, + -30.77587338589635, + -30.93508740824461, + -31.09540284954392, + -31.258388061342448, + -31.41888294932133, + -31.57511818464571, + -31.737554664825634, + -31.896783844435237, + -32.053913423833016, + -32.2114636332057, + -32.37285461287056, + -32.531051429290095, + -32.68885754441402, + -32.849919198020686, + -33.00869883027609, + -33.169217120024626, + -33.32953013097244, + -33.49035867659496, + -33.646755494579786, + -33.802256803579, + -33.955449110026514, + -34.10296899335835, + -34.250813973129034, + -34.39329342626929, + -34.52784724879321, + -34.64676426306048, + -34.752619918620674, + -34.85377242376047, + -34.950183775080376, + -35.0431327394526, + -35.13238961508849, + -35.21874391813624, + -35.30281467880575, + -35.381490817891525, + -35.4582819949889, + -35.53996193367997, + -35.616590107385285, + -35.68956565653621, + -35.76184809414489, + -35.829051701971274, + -35.893337102969625, + -35.959892861350184, + -36.022430691597776, + -36.080563598518474, + -36.141196549900215, + -36.19420986742409, + -36.238498716166326, + -36.283105563442625, + -36.32311202516677, + -36.35841697035875, + -36.393616704528924, + -36.42838685123053, + -36.461653021008956, + -36.495958607085576, + -36.52883412950095, + -36.55988560497902, + -36.589851425797285, + -36.61854055322231, + -36.64555510450045, + -36.67180243832743, + -36.698966839607515, + -36.726416047033425, + -36.75468946679683, + -36.784307222512474, + -36.81465248395067, + -36.85061933889827, + -36.88839578271501, + -36.92881176290857, + -36.970508841199, + -37.0124036301459, + -37.05516878506645, + -37.10048210395789, + -37.14931223859016, + -37.201847743513774, + -37.25415119973633, + -37.304060846615926, + -37.35504341018441, + -37.40645438665597, + -37.45525506765074, + -37.50498196766519, + -37.55530352161304, + -37.60141837390055, + -37.64822888551679, + -37.694669500420986, + -37.73974673067676, + -37.788065496143844, + -37.83668534628448, + -37.8833431924286, + -37.92992269066535, + -37.97776682788842, + -38.025260366043135, + -38.07608450505955, + -38.130903931610774, + -38.18601668684481, + -38.24546539137898, + -38.30471364862205, + -38.36127910163396, + -38.42337867460787, + -38.49053103356383, + -38.559046235963514, + -38.63070092178023, + -38.70786239381107, + -38.78697439848398, + -38.87259986043353, + -38.9602754610177, + -39.04790578092653, + -39.14281320903069, + -39.24095898243617, + -39.34093970189105, + -39.44555304012069, + -39.55552261316482, + -39.67188470694354, + -39.79273439752751, + -39.921398871028515, + -40.05825434488069, + -40.203954986859465, + -40.35927436739419, + -40.52298427492694, + -40.70148877232968, + -40.89172554297195, + -41.088991989474486, + -41.301719994357086, + -41.53137312305492, + -41.76659644905784, + -42.0033102063515, + -42.266706122545244, + -42.55190916660074, + -42.83431239110593, + -43.11980664808165, + -43.41643315967788, + -43.704789850167394, + -43.99378305087913, + -44.284294004099976, + -44.56733231697766, + -44.84901880223397, + -45.14262932561309, + -45.39503423546914, + -45.64718664193296, + -45.89280238506646, + -46.126440530149985, + -46.35065560107665, + -46.56234101265238, + -46.761896887716475, + -46.95158941523801, + -47.12938539508751, + -47.29836031322895, + -47.45544865766907, + -47.60394811544859, + -47.74295632423858, + -47.87106068008201, + -47.993593223548224, + -48.10976556269096, + -48.21892041048798, + -48.32369685749149, + -48.422170680874856, + -48.51669582792246, + -48.610401463933925, + -48.70169559739552, + -48.79147168802411, + -48.882838260999215, + -48.975189263300585, + -49.06928345423546, + -49.166417832837865, + -49.266457713987485, + -49.3714375898157, + -49.480223195598334, + -49.59149892689455, + -49.70678305324979, + -49.826808801777645, + -49.95194004448032, + -50.082452297263266, + -50.21807923079181, + -50.361558018743985, + -50.514409024277334, + -50.67061672461271, + -50.834204484430636, + -51.00830436447421, + -51.184348015706426, + -51.366044215941244, + -51.550840106418335, + -51.7459946678317, + -51.942738181755246, + -52.13879522193111, + -52.34981877110988, + -52.56250856672601, + -52.76912675684228, + -52.983814961013, + -53.20988218085747, + -53.431262921729946, + -53.65561601212929, + -53.890473672877825, + -54.12368164840494, + -54.35454687599877, + -54.59398972802996, + -54.83470042125781, + -55.072299763695455, + -55.31706067977363, + -55.56017187087555, + -55.80896819330829, + -56.05888353134362, + -56.305095144594596, + -56.553294781269116, + -56.803129973270366, + -57.05278402075685, + -57.302251695235306, + -57.558426812495306, + -57.81186606034034, + -58.06452826636794, + -58.320173441964805, + -58.571170087697595, + -58.81734892790467, + -59.06261893753183, + -59.30592263046282, + -59.540753466804894, + -59.77839893293952, + -60.01597097146128, + -60.246152471621585, + -60.482093510196215, + -60.71311524881444, + -60.935457803639665, + -61.159174954753766, + -61.38275356524102, + -61.604117530256154, + -61.815999437562795, + -62.02546661288117, + -62.23627981905073, + -62.437549724307544, + -62.632319914357566, + -62.81756671724356, + -62.990131744697436, + -63.15967130606996, + -63.3191309661283, + -63.46876535000585, + -63.61110191209921, + -63.746722989349834, + -63.87263456611171, + -63.992556969555906, + -64.10112727749845, + -64.19547178489243, + -64.27681153071063, + -64.34420266388581, + -64.39943343354585, + -64.44347929525618, + -64.48128483890173, + -64.50311173822463, + -64.5120139442953, + -64.5096371015061, + -64.49850153409362, + -64.47950075523246, + -64.45163045449058, + -64.41416220760645, + -64.36897675213383, + -64.31384599841805, + -64.2493267477937, + -64.17706346934067, + -64.09761794367536, + -64.00927862738813, + -63.91159264663967, + -63.80749746454112, + -63.696547442040384, + -63.57789532984996, + -63.45432440947033, + -63.32320996893662, + -63.18565827365563, + -63.04502521405786, + -62.89976067033772, + -62.752920552544374, + -62.600480222341616, + -62.44721397224273, + -62.290612511229114, + -62.12647951509279, + -61.96072754865706, + -61.79657756608333, + -61.62487085156758, + -61.45062504191556, + -61.275425740967925, + -61.09571027256372, + -60.91222915922305, + -60.72632851819106, + -60.54625517509737, + -60.36409377513301, + -60.17779025002081, + -59.9958028602795, + -59.812472784514306, + -59.62777059657209, + -59.44413951121483, + -59.260975869043435, + -59.088850214626156, + -58.914916575313356, + -58.7475783916765, + -58.59426034776173, + -58.436836148636466, + -58.29010923648031, + -58.15007357386761, + -58.01089684352622, + -57.88490424849898, + -57.77295261524937, + -57.65768987481995, + -57.553667457432866, + -57.46312017780374, + -57.372386975243636, + -57.2919274731208, + -57.22319484214453, + -57.15656172906295, + -57.09982847861494, + -57.049924400068825, + -57.00840937187823, + -56.975832459024005, + -56.94719294332324, + -56.922234480091596, + -56.901077370392734, + -56.88110958657552, + -56.86118869640121, + -56.84088613130771, + -56.821132914215454, + -56.815002106926656, + -56.80979611381951, + -56.80517883350121, + -56.80051808684475, + -56.79644297281487, + -56.79289144647149, + -56.78943010656069, + -56.786233593180526, + -56.78345673966681, + -56.7811665630323, + -56.75996454540282, + -56.7363381058681, + -56.71233840244565, + -56.68787842570376, + -56.662983636726814, + -56.63763657016417, + -56.61183675452828, + -56.58564663370481, + -56.558692202886405, + -56.531097615057625, + -56.52434464810236, + -56.5199519386102, + -56.515403388683794, + -56.51087858954138, + -56.5063573209964, + -56.5017161581568, + -56.497114993181945, + -56.49246965306654, + -56.48776828222017, + -56.48304234668775, + -56.46702078317542, + -56.44969022770539, + -56.43226281970084, + -56.41484371752729, + -56.39738923996846, + -56.379895753924686, + -56.362391804866704, + -56.34484174931023, + -56.327259820587955, + -56.309596904818946, + -56.3033488562526, + -56.298236827300386, + -56.293065661739035, + -56.287957444135024, + -56.28290294654708, + -56.27772258408275, + -56.27251843788752, + -56.2673617287949, + -56.26207736656889, + -56.2568281989473, + -56.2275274174694, + -56.19506507780273, + -56.162582375227316, + -56.13019612303026, + -56.09797893912742, + -56.06577374827643, + -56.03345300393017, + -56.00125422789405, + -55.96918269502179, + -55.93673707253973, + -55.92987352379566, + -55.9259372303979, + -55.92209594057085, + -55.918427741871454, + -55.91475993280608, + -55.91110545407247, + -55.90740545539027, + -55.90330183965871, + -55.89952828966962, + -55.89582850535093, + -55.894829120635116, + -55.893883172380534, + -55.89308540843156, + -55.892279575204036, + -55.891315691557, + -55.89038851536575, + -55.88954197162121, + -55.88865548285507, + -55.887708389988845 + ], + "y": [ + 45.299718434481434, + 45.30013974702479, + 45.30063571154232, + 45.30114686375785, + 45.30150261131389, + 45.3017899970426, + 45.30236707808463, + 45.30287884751629, + 45.3035273124906, + 45.30408450232165, + 45.30460802412102, + 45.30524000954758, + 45.305893681440025, + 45.30642718230222, + 45.306953849677924, + 45.30758655349011, + 45.30817058079298, + 45.308765977677744, + 45.30916949728607, + 45.309576423754294, + 45.30999953180667, + 45.310472382304106, + 45.310869975986996, + 45.31131992004422, + 45.3117136569928, + 45.31213422949182, + 45.31252989359154, + 45.31286838849167, + 45.31318042227869, + 45.313520830069514, + 45.31378112954761, + 45.314042891621064, + 45.3143255803598, + 45.31459079192223, + 45.314915446046335, + 45.315213503667415, + 45.31547083747926, + 45.31568919264709, + 45.315949555167926, + 45.316230264771434, + 45.31642204305476, + 45.31667953636436, + 45.31701735727197, + 45.31719809178335, + 45.31736415483957, + 45.317553916882986, + 45.31779573502166, + 45.31797146615517, + 45.31815950894265, + 45.31838925028085, + 45.31859991944094, + 45.318852018727746, + 45.319099285855756, + 45.31929173583678, + 45.319490588135054, + 45.31968722633857, + 45.3199187057454, + 45.3201108558734, + 45.32024283799233, + 45.320447928901416, + 45.32058641481309, + 45.3207734550583, + 45.320974930400254, + 45.32112493246592, + 45.321286050816404, + 45.32147070970754, + 45.32164142123714, + 45.32202703316613, + 45.32254705800193, + 45.32301875091753, + 45.32346885341235, + 45.32401104849823, + 45.324593452118236, + 45.32510954271194, + 45.32559590644499, + 45.326135359662985, + 45.32673746967972, + 45.327148770307815, + 45.32757959164762, + 45.32804989611945, + 45.32840617801765, + 45.328830825116064, + 45.32934855748933, + 45.32975924646779, + 45.33014891795632, + 45.330666778999976, + 45.33114515148283, + 45.33166922226085, + 45.33227448848537, + 45.33285895295016, + 45.333431930156806, + 45.33396327881899, + 45.334506865189574, + 45.33508755040129, + 45.33562600519236, + 45.33616278148277, + 45.33666823981242, + 45.33715002225605, + 45.33749402104377, + 45.3378002849158, + 45.338204896435045, + 45.33858942999313, + 45.33885646317251, + 45.33915047530712, + 45.339397152283055, + 45.33977023237858, + 45.34019352087018, + 45.34050336250638, + 45.34087238457947, + 45.34123706047124, + 45.34159301383292, + 45.3420204810963, + 45.34241525119844, + 45.342737730564025, + 45.343089890197156, + 45.34346947381766, + 45.343877097795875, + 45.344283396952605, + 45.34457099063465, + 45.34485192241254, + 45.34521201475351, + 45.34558913175783, + 45.34590903170268, + 45.34618959737896, + 45.34653486909946, + 45.34691220323054, + 45.347271394714035, + 45.34754169409517, + 45.34773696126847, + 45.34806415342266, + 45.34841192672122, + 45.34863862528806, + 45.348917300136186, + 45.34929052345286, + 45.34952539985571, + 45.349908144116874, + 45.350149840272444, + 45.35036920642808, + 45.35049867688795, + 45.35079137871575, + 45.35110058592429, + 45.35124302567623, + 45.35147245537082, + 45.35174403836285, + 45.35202228803002, + 45.35235141245206, + 45.35263531962548, + 45.352850133960885, + 45.35315828262761, + 45.35360275870033, + 45.35381100387733, + 45.354015574240876, + 45.35429750230924, + 45.354598633230985, + 45.35485305326219, + 45.35503844423474, + 45.35518332085755, + 45.355298077054144, + 45.355554716864894, + 45.35577485070798, + 45.35591374938485, + 45.35606529705287, + 45.35631288796946, + 45.35662317568206, + 45.35704873448834, + 45.35724478362889, + 45.3574322394342, + 45.35776813085408, + 45.35827647169903, + 45.358993093937855, + 45.359484524864584, + 45.35988466028037, + 45.360457989654854, + 45.36105480217147, + 45.36159448796326, + 45.36212316190755, + 45.36265534864159, + 45.36315123310733, + 45.36364058951429, + 45.36415365574575, + 45.36462535441737, + 45.36508600318736, + 45.365574105334055, + 45.36607946422612, + 45.36654579849777, + 45.36704170154077, + 45.367534887791635, + 45.36792576494745, + 45.36824359412654, + 45.36860242175758, + 45.36901586722353, + 45.369431327282356, + 45.36981859469267, + 45.37010287348836, + 45.370431506244174, + 45.37081576962552, + 45.37116814001007, + 45.37147989284605, + 45.371708942071166, + 45.371994700159625, + 45.37237211183017, + 45.37260933731308, + 45.37287272161522, + 45.373185633182736, + 45.37358584990655, + 45.374231086817765, + 45.37463113642426, + 45.3752267849971, + 45.37577063238242, + 45.37629185712969, + 45.37785964432921, + 45.380910216409134, + 45.38617583063742, + 45.39429231259471, + 45.40556256610919, + 45.419621192537164, + 45.434869706598384, + 45.449319283626465, + 45.461055341864586, + 45.4702245686378, + 45.476840328805594, + 45.481741220634696, + 45.4851970429676, + 45.487556127879074, + 45.48961027497986, + 45.49209305494798, + 45.495681503693234, + 45.5015125032667, + 45.50976071472965, + 45.52044139833738, + 45.533528007324854, + 45.548705950369374, + 45.56547029537028, + 45.58344988667698, + 45.60219700821508, + 45.62155458682291, + 45.64131175768604, + 45.66107190257342, + 45.68058405608774, + 45.699084214421234, + 45.71513592310621, + 45.72692820998699, + 45.73296659798701, + 45.73228577610344, + 45.72478547695079, + 45.709062265710436, + 45.68362931552094, + 45.648436638923904, + 45.6005590076713, + 45.54143022575991, + 45.47090161889065, + 45.38532656442469, + 45.287275538844284, + 45.17602499405964, + 45.05258492662113, + 44.915518150037336, + 44.76668684699259, + 44.61138974751405, + 44.44210175245866, + 44.26121033544627, + 44.07218039214349, + 43.871952149589525, + 43.6559605939235, + 43.43215626095299, + 43.20088398599591, + 42.95980262188665, + 42.7066848852861, + 42.44721022482909, + 42.19139453924118, + 41.92009323109292, + 41.637968510937874, + 41.38158954687498, + 41.10566257344352, + 40.81940390385516, + 40.536771920455365, + 40.250119352401605, + 39.96497931607584, + 39.671763886065285, + 39.36561448117603, + 39.07776853498432, + 38.78177220721696, + 38.469709243214545, + 38.1741102843626, + 37.87541437027626, + 37.562343323161734, + 37.25458553859626, + 36.95009843762025, + 36.6420838233015, + 36.32836054955793, + 36.017065111071396, + 35.706307861354105, + 35.39298610169376, + 35.08713300691843, + 34.78053963067478, + 34.46585239272821, + 34.16073274696967, + 33.85785656816834, + 33.54907006348222, + 33.227535361675486, + 32.92284224858699, + 32.612054841562994, + 32.28347767411683, + 31.962557944624518, + 31.64741134177734, + 31.323628803847757, + 30.991931591852087, + 30.678251753168134, + 30.357053326498573, + 30.021636992706057, + 29.69641475409675, + 29.38114451722201, + 29.0529807876609, + 28.728670196043417, + 28.414933994334607, + 28.090089622494144, + 27.768404888564156, + 27.44341361720266, + 27.124451282605364, + 26.80030761476627, + 26.472147653847113, + 26.15321433224592, + 25.83227239584316, + 25.515193337579735, + 25.18402986331489, + 24.872502961866697, + 24.55917164764911, + 24.229671287982033, + 23.907246162616186, + 23.586484310217152, + 23.26357655551848, + 22.931446184257094, + 22.599980187960238, + 22.27444689632395, + 21.94300759057357, + 21.611178204578085, + 21.280281711262774, + 20.949274543673777, + 20.612428582052907, + 20.279241690577816, + 19.944961979066782, + 19.595267171610544, + 19.259262663045853, + 18.924220664589885, + 18.57185009209973, + 18.220623855561502, + 17.87645459159285, + 17.514145952525595, + 17.15378437989861, + 16.795532783890447, + 16.42789815116257, + 16.06968735391795, + 15.706132269368716, + 15.334544702668433, + 14.970436603584684, + 14.603678506298932, + 14.221207066737518, + 13.849615250578609, + 13.475084425184, + 13.084228921148902, + 12.706312703669063, + 12.32769580443048, + 11.938432352067267, + 11.556455460116831, + 11.17793251207936, + 10.784890990753082, + 10.391839837392332, + 10.010067844493385, + 9.620242422889108, + 9.23219747383752, + 8.850523047061543, + 8.470468283710078, + 8.08419987199292, + 7.697968232820205, + 7.311387319346879, + 6.92510609587932, + 6.533090560048482, + 6.145142317640205, + 5.757666940316765, + 5.363570563632581, + 4.9756568144842745, + 4.585886155497769, + 4.1905936097729555, + 3.801351940174415, + 3.41798755083955, + 3.028529933190099, + 2.6441059141994376, + 2.27294101898256, + 1.856458096383074, + 1.4757070871246285, + 1.1073339766813302, + 0.7402110061908301, + 0.37133908131931304, + 0.009268102579207183, + -0.3457574475286201, + -0.7019142405637846, + -1.0528789878397145, + -1.3998820125069955, + -1.748833447218612, + -2.0891258901127263, + -2.4350264130741515, + -2.785304479979115, + -3.127946758194442, + -3.473779161421556, + -3.8291551568676474, + -4.175866904769248, + -4.512490675048943, + -4.865137311174306, + -5.203824063105863, + -5.525428504572238, + -5.864225366552495, + -6.1934773822465194, + -6.50552746940229, + -6.827145053616824, + -7.140766272701244, + -7.4390147475393675, + -7.738128503613352, + -8.016994525444474, + -8.286986912703423, + -8.554893537359042, + -8.799055506627557, + -9.036050212755432, + -9.269804210267157, + -9.481770440048242, + -9.68514090025804, + -9.8825226452152, + -10.05848048544291, + -10.223649914517283, + -10.376832739330755, + -10.51179117091306, + -10.625221040234637, + -10.718551990605059, + -10.78307430643003, + -10.824965206016069, + -10.849411350416643, + -10.85139176078873, + -10.82953169832549, + -10.779750369459013, + -10.705911849149164, + -10.61298179251615, + -10.49391067136101, + -10.350766286003042, + -10.186750919467716, + -9.999394790259581, + -9.79340996295848, + -9.571596565786326, + -9.328850536567419, + -9.07259253143243, + -8.802643265996876, + -8.517846586137384, + -8.221934394019296, + -7.916477216537806, + -7.596357269582938, + -7.271702008812883, + -6.936659116357311, + -6.589647711483182, + -6.239218289766555, + -5.8808913029715, + -5.513012902334701, + -5.143407059275042, + -4.7702321530630165, + -4.39279341333818, + -4.011544482728926, + -3.632042918431274, + -3.2515495911424566, + -2.8706436719586867, + -2.4889554275436208, + -2.1076317650996987, + -1.722980415101513, + -1.3319706820070059, + -0.9476356750613282, + -0.5692006826162967, + -0.18486554621349793, + 0.19177756857133768, + 0.5591343653191786, + 0.9330755093307356, + 1.3130695247353235, + 1.668335501336059, + 2.026710924675365, + 2.395607639437436, + 2.7395694832199577, + 3.091391319017581, + 3.4504230238737565, + 3.785974770069895, + 4.127158137604507, + 4.473588339007547, + 4.798607039033906, + 5.128483228468712, + 5.461247205304259, + 5.7655720498109835, + 6.067001276667719, + 6.386035219520769, + 6.690737910994235, + 6.983572461445581, + 7.294810123032193, + 7.600664154524186, + 7.887940111141231, + 8.189534055963769, + 8.494710828262713, + 8.787944134083013, + 9.089908475778346, + 9.396032782226843, + 9.695039455568445, + 10.001482738587534, + 10.309826726403713, + 10.616670528201501, + 10.927144917211407, + 11.237467369938699, + 11.546610029571692, + 11.862483991377665, + 12.178504454089424, + 12.499498488895368, + 12.826413684488807, + 13.16268807738713, + 13.501623699204668, + 13.844831221993385, + 14.192886668940524, + 14.543329633718544, + 14.893128370914617, + 15.24878032105807, + 15.609834546852696, + 15.979671300259401, + 16.35936206302697, + 16.748549500796656, + 17.142047565456913, + 17.540025105362574, + 17.941856171873095, + 18.345344946496976, + 18.75984374133597, + 19.181929054644538, + 19.605205658104733, + 20.02302033658512, + 20.442662642128155, + 20.86771243508503, + 21.292999017297102, + 21.722163313318603, + 22.151078902835863, + 22.587714870984676, + 23.029974944912194, + 23.45741883619464, + 23.887343065941536, + 24.331733065699446, + 24.767102537829327, + 25.204996765771696, + 25.651895296889773, + 26.10077990944607, + 26.54195298933848, + 26.982260825027105, + 27.425128176576813, + 27.862844339234286, + 28.299885433274653, + 28.753022624041996, + 29.20088045582045, + 29.63810338480583, + 30.091352763500165, + 30.54192730345249, + 30.97446726905821, + 31.428574818885732, + 31.87858895660617, + 32.31684114625722, + 32.77663596869445, + 33.23856387174748, + 33.68254988557835, + 34.14938978863933, + 34.613864356845774, + 35.061688999591375, + 35.53232232805609, + 35.99736162284397, + 36.442166119780346, + 36.90088174463004, + 37.34261803819572, + 37.78440266390773, + 38.23778605939985, + 38.682875278383925, + 39.1220452773332, + 39.560964175837675, + 39.9879118137015, + 40.41426254539005, + 40.85459174029404, + 41.27966374565932, + 41.714394888999884, + 42.15154032030003, + 42.56496434196218, + 42.98446922691957, + 43.407134447006655, + 43.799038515324206, + 44.208977672828986, + 44.62151561116713, + 45.00893355671741, + 45.399683171035534, + 45.78761048775274, + 46.16170088818614, + 46.517655009136895, + 46.87465502207902, + 47.22198568565066, + 47.556843273577904, + 47.88657827671448, + 48.197671938606085, + 48.504250466129676, + 48.80945175274481, + 49.10156254666932, + 49.387723910464985, + 49.663963228244945, + 49.93547473105268, + 50.20682153355503, + 50.46915343670965, + 50.73415436196795, + 51.00762638157096, + 51.265193279432815, + 51.52898761067486, + 51.80565998422979, + 52.06979113005717, + 52.3374184984377, + 52.62198242960895, + 52.88887632021847, + 53.13652760244822, + 53.400097811866836, + 53.66251131653647, + 53.90445457836404, + 54.148481490728166, + 54.39349952947101, + 54.623062075947814, + 54.845516176624216, + 55.06405268457755, + 55.27260353632475, + 55.474568221008, + 55.67091792567738, + 55.86447039743989, + 56.05864867993102, + 56.24866552618537, + 56.43021379205581, + 56.610413816557354, + 56.78715684713698, + 56.955495457294504, + 57.11927878250059, + 57.28203357398337, + 57.43671511441069, + 57.574630312304805, + 57.705510415894544, + 57.835600156804055, + 57.948661288221594, + 58.056433788488995, + 58.166337838612584, + 58.26478493445352, + 58.35488297879964, + 58.44709736338487, + 58.536642329987835, + 58.62357865105658, + 58.715468251870966, + 58.8065326495339, + 58.8956919640694, + 58.98632877450392, + 59.07763340690364, + 59.16911483062227, + 59.2610262875103, + 59.353715803910546, + 59.44656242845687, + 59.54056291020131, + 59.633396953774316, + 59.727674662425315, + 59.82263572496919, + 59.92002879337948, + 60.01673053702014, + 60.1149554497501, + 60.21437594137841, + 60.31188757167649, + 60.40667423941273, + 60.503569609384655, + 60.59391001250553, + 60.68069824189817, + 60.76856181061859, + 60.85035285607706, + 60.92865332396755, + 61.00901663235724, + 61.08530036970657, + 61.1579708568082, + 61.23947846913224, + 61.314573324793386, + 61.38789174904695, + 61.461227712517555, + 61.53642352392255, + 61.60882835505364, + 61.678254184127354, + 61.74775833431579, + 61.81540779649075, + 61.88182080219317, + 61.94877899678814, + 62.01451179528355, + 62.07539832696194, + 62.13664749663531, + 62.19835750943565, + 62.25684351688425, + 62.31367673992014, + 62.369448462907485, + 62.42124931964589, + 62.47118969451585, + 62.51911025909183, + 62.5643019681068, + 62.60789583103667, + 62.64846958027227, + 62.687924221901426, + 62.725836468702795, + 62.762387471385054, + 62.79841944632367, + 62.83351905150026, + 62.868695798379285, + 62.902924958497266, + 62.93644674954601, + 62.97033210948266, + 63.00306015736388, + 63.03619020297542, + 63.06864193774922, + 63.100670138939414, + 63.13264698016124, + 63.16349918765155, + 63.193273338716864, + 63.22394150467434, + 63.256073790139574, + 63.289994807170864, + 63.32362329309499, + 63.35901355230254, + 63.39411268457746, + 63.428387436834186, + 63.46241222028587, + 63.4967296617323, + 63.52682094882466, + 63.5547675894417, + 63.57924482731159, + 63.59364229800525, + 63.597104207933505, + 63.589973932013265, + 63.573005082347024, + 63.54629652988308, + 63.510034210478096, + 63.462809643827065, + 63.40683170762029, + 63.3342011625207, + 63.24758795434877, + 63.15255794382895, + 63.04257681538751, + 62.92362129571702, + 62.79555055824176, + 62.652914340423955, + 62.49554621804873, + 62.32887212151441, + 62.146187451440724, + 61.95595683547793, + 61.7632949171735, + 61.55181887631534, + 61.32843895611934, + 61.101943844958896, + 60.862216410026456, + 60.61150680878929, + 60.35640260905442, + 60.09807585763194, + 59.82600904989316, + 59.55434354351422, + 59.28470199198781, + 59.00059902902347, + 58.707861829629316, + 58.42276912132257, + 58.12529707466105, + 57.81671397272391, + 57.51082495910958, + 57.18869645214282, + 56.86423947156095, + 56.535151086582914, + 56.192845116687735, + 55.84928555032313, + 55.50075464328807, + 55.149409976312725, + 54.79769945184625, + 54.44698362153218, + 54.096706162612975, + 53.743709295913376, + 53.39614795661498, + 53.04993354424443, + 52.70558761596855, + 52.36842284572481, + 52.03414162007931, + 51.702623876531554, + 51.370835228899004, + 51.03407171436232, + 50.69746261807563, + 50.373322353732895, + 50.04299787072454, + 49.705770127821246, + 49.38735525533109, + 49.060510811853995, + 48.72654359469327, + 48.39837977209214, + 48.08072854856022, + 47.75452253146979, + 47.42944116755567, + 47.1155725241505, + 46.79244682804856, + 46.467626569995666, + 46.151702190248166, + 45.8292167429687, + 45.502990015424785, + 45.17938716036984, + 44.85720971375609, + 44.525492671489545, + 44.192492880390596, + 43.86487148618212, + 43.527394975486594, + 43.190341149071514, + 42.85898798333011, + 42.52778486699666, + 42.19862233449117, + 41.87133250581469, + 41.53675172662458, + 41.21201284379724, + 40.884079589178135, + 40.547753097573086, + 40.21730789093999, + 39.88486738699658, + 39.55194229664582, + 39.22205392495302, + 38.89214369967228, + 38.559399991732164, + 38.2296817338311, + 37.90250431708949, + 37.568319985971456, + 37.241578581982324, + 36.917479880631426, + 36.58797100728486, + 36.26245884112828, + 35.94543369055382, + 35.62657591952224, + 35.31727339509226, + 35.00585671904028, + 34.68671640288381, + 34.38207220279461, + 34.07675083097773, + 33.762715685796266, + 33.444015436249614, + 33.14219928493705, + 32.82654199851878, + 32.49818148759017, + 32.17965533632465, + 31.86184362378993, + 31.541619123950866, + 31.214264888095485, + 30.902050300599047, + 30.588530913072027, + 30.264963162783282, + 29.949730656161847, + 29.635073113076377, + 29.319626887633856, + 29.003824174077053, + 28.693928414828797, + 28.384420771836822, + 28.070868989852066, + 27.76129562865431, + 27.447121910555577, + 27.13920364454229, + 26.829861640631954, + 26.51451931543211, + 26.213818487789933, + 25.910309771230075, + 25.602923559619786, + 25.295772151217005, + 25.00131852769632, + 24.705508344289374, + 24.400694098862083, + 24.069037142059887, + 23.770650168471438, + 23.463429690467894, + 23.146745727324166, + 22.8309992416603, + 22.518337589381826, + 22.20067248985571, + 21.882702293861733, + 21.56824074072042, + 21.24663983868902, + 20.92269709573191, + 20.60022027443589, + 20.28195184331143, + 19.955211297103826, + 19.626730938105542, + 19.31171750581098, + 18.98858179091357, + 18.656965688388144, + 18.334384526936276, + 18.008454892066144, + 17.66708395473627, + 17.337427911309227, + 17.013719013550592, + 16.670790836970745, + 16.337592369280337, + 16.015397605573686, + 15.67462497366007, + 15.339540589266472, + 15.018530345703198, + 14.676651760850092, + 14.331775623839576, + 14.009754581590677, + 13.637650212408312, + 13.281136798153804, + 12.951800864609703, + 12.615131051089216, + 12.258860228240723, + 11.9187579393447, + 11.57789390158883, + 11.223050074155491, + 10.873341690901782, + 10.523687391868252, + 10.166554889456599, + 9.811022414357117, + 9.456020377858247, + 9.100903652998541, + 8.750158985983907, + 8.395229134951304, + 8.037985110034583, + 7.682742899483137, + 7.324366851919589, + 6.964263587073127, + 6.603888882368382, + 6.252824518194672, + 5.891020870699171, + 5.531405672386699, + 5.177081777470986, + 4.813802372561208, + 4.451963739189691, + 4.090995219729578, + 3.727774677820828, + 3.36168838532809, + 3.0008321018421924, + 2.641543516871443, + 2.279111765583993, + 1.9168337173546421, + 1.5582123203951013, + 1.1996223339978025, + 0.8385918355327884, + 0.4808254145686994, + 0.12979181543773116, + -0.22413403291554124, + -0.5691012455811524, + -0.9066823542473489, + -1.241229619184098, + -1.5732899174351296, + -1.8995770661416154, + -2.219694902437592, + -2.5451530279516223, + -2.8676134221602236, + -3.1942237481503195, + -3.5170686339268715, + -3.8363874605060797, + -4.197714871251118, + -4.526329228339178, + -4.841803876738634, + -5.158672505485492, + -5.482287674054555, + -5.804824767867621, + -6.115071052011439, + -6.427658671448018, + -6.741351839801882, + -7.040627960359345, + -7.342648513446687, + -7.640580726166761, + -7.909928498674154, + -8.180489757848637, + -8.453984438454636, + -8.705336956341986, + -8.947818543021045, + -9.189655263630117, + -9.41685446197051, + -9.636423663430703, + -9.848628239347748, + -10.050138741681844, + -10.243170565631027, + -10.431450973305097, + -10.609436771122674, + -10.7821667520709, + -10.945187722832038, + -11.097407254984088, + -11.238559238641908, + -11.3666326213761, + -11.478365323903308, + -11.564914080634889, + -11.629557490103016, + -11.674596107296022, + -11.696876356448303, + -11.697352245294429, + -11.676752317474575, + -11.63449483230157, + -11.571438008900385, + -11.483399684290735, + -11.37233264607733, + -11.242877523136368, + -11.088205242283749, + -10.91056875650235, + -10.718160389732232, + -10.505390403873873, + -10.273047338603224, + -10.035556106735442, + -9.777673079790448, + -9.502533688776865, + -9.2272971204055, + -8.936788449605405, + -8.63271952734524, + -8.330509922735615, + -8.017566487984993, + -7.6950731376609625, + -7.370192516103867, + -7.040907752697563, + -6.705000514000552, + -6.365876617460091, + -6.026181323894576, + -5.6814681384112315, + -5.3345401137271455, + -4.987284086519732, + -4.639743838543606, + -4.294469330527796, + -3.947484022729094, + -3.605390912128818, + -3.2651466286676394, + -2.9240691824482448, + -2.586496380041736, + -2.250161547337725, + -1.9136633110936039, + -1.581305949194603, + -1.2489914413368912, + -0.9222156255151451, + -0.6035045789681034, + -0.2765286946560145, + 0.04137218537884545, + 0.35477961485070936, + 0.6634608219180338, + 0.9839620741974724, + 1.2989556210052042, + 1.5940082184992426, + 1.9042955664513466, + 2.213861720834922, + 2.506437533023011, + 2.805491823780999, + 3.1142433768799918, + 3.4059430044454757, + 3.695619840593113, + 3.995339418006365, + 4.281903490289008, + 4.564851886172743, + 4.855746893704478, + 5.138465675552538, + 5.413489986877798, + 5.689286808248597, + 5.967330587568085, + 6.238536138005329, + 6.507042690114719, + 6.775407574006047, + 7.045585969704588, + 7.309449764010907, + 7.5723985085288215, + 7.842220575059579, + 8.109555396134546, + 8.374119988514705, + 8.64442282897711, + 8.921310848286897, + 9.192569313460302, + 9.465006450503253, + 9.74493409671807, + 10.015831188524905, + 10.288190471128273, + 10.564148014719482, + 10.836869669755542, + 11.112199181272134, + 11.388103570023366, + 11.660245268410408, + 11.937327420051052, + 12.22035238673423, + 12.500843520726555, + 12.78598478054187, + 13.07675490219391, + 13.367905308542989, + 13.66281125320392, + 13.964202485517921, + 14.265349677648844, + 14.564895065825162, + 14.873363527118272, + 15.17767439391314, + 15.488244814187693, + 15.81096980609484, + 16.13688661774782, + 16.466180743034002, + 16.81161151063625, + 17.158775097569574, + 17.50404835518807, + 17.85839062136845, + 18.22047169463572, + 18.572945852675076, + 18.931854457309303, + 19.298604546159268, + 19.657525031722894, + 20.013298239763355, + 20.37683390267937, + 20.741021277886734, + 21.097254409597824, + 21.4650874339504, + 21.83556483746958, + 22.200648195698733, + 22.574209425164877, + 22.95101750668138, + 23.31549922460493, + 23.686787346742054, + 24.065527328103176, + 24.442428388728448, + 24.817619440541705, + 25.201725529021076, + 25.587511252661145, + 25.971495371479403, + 26.351701392202713, + 26.734579025955508, + 27.11994913277827, + 27.503247114367703, + 27.884579569813056, + 28.274581807396096, + 28.670825075468827, + 29.05828344423737, + 29.444369655159377, + 29.840481155694537, + 30.233112698734114, + 30.612579488717785, + 31.005186875526537, + 31.40026183882251, + 31.784034993281782, + 32.1767600092729, + 32.57839635990616, + 32.973788085172124, + 33.36707385723474, + 33.7747350773587, + 34.174867195432704, + 34.56565927007528, + 34.97269897372242, + 35.38099174232684, + 35.773274418694164, + 36.17188052679075, + 36.576210912661864, + 36.96590210487735, + 37.36045124150102, + 37.763519221555654, + 38.15592466177955, + 38.54705143584231, + 38.93957607209103, + 39.3252501621869, + 39.700663506512065, + 40.0767022581467, + 40.45821761035811, + 40.83428228061062, + 41.21088079845879, + 41.59903782760523, + 41.975886954303824, + 42.34046905396035, + 42.715320312597285, + 43.091465560146496, + 43.44936522764123, + 43.8092069440132, + 44.17622953167472, + 44.526079067298404, + 44.86735441023502, + 45.21638709862258, + 45.5461049856716, + 45.87635458468328, + 46.2000237449179, + 46.502226615595546, + 46.80576047816677, + 47.095318697331194, + 47.37578712277759, + 47.67164256501043, + 47.94343864522116, + 48.20589043275671, + 48.48325940919611, + 48.756924946637035, + 49.028377199005995, + 49.30363230442888, + 49.570889558757266, + 49.84634301215178, + 50.12768744689074, + 50.40895489953932, + 50.68343352813979, + 50.973440414634375, + 51.25861087042464, + 51.53085556400556, + 51.81766805132871, + 52.1050147640509, + 52.374967442266225, + 52.66039473441991, + 52.93390555095745, + 53.163167180092074, + 53.39940834873647, + 53.63822416578305, + 53.86074179851649, + 54.07701365947243, + 54.29386895756701, + 54.49971335955047, + 54.69685665335548, + 54.88883473806454, + 55.07533841403359, + 55.2639708544337, + 55.44340921058112, + 55.6153452312377, + 55.78231773439923, + 55.944807794529694, + 56.10256210045506, + 56.251104206942145, + 56.40120995073123, + 56.55155818927396, + 56.699635714050984, + 56.84899230943216, + 56.996418069619715, + 57.14424297262831, + 57.284734479281234, + 57.4194130306999, + 57.548906820982815, + 57.67551577901924, + 57.797573164866, + 57.92076478080977, + 58.041334590806294, + 58.154182211743525, + 58.26686528487959, + 58.38001533876473, + 58.491997052698785, + 58.602908337428495, + 58.71531936015631, + 58.827309263636785, + 58.93697907124501, + 59.04640275622206, + 59.1535203554293, + 59.26366343136951, + 59.373620509730934, + 59.48072217849345, + 59.58638357077552, + 59.690346099203815, + 59.79134802306432, + 59.890581611258135, + 59.98941652947211, + 60.087114248711984, + 60.18527892985866, + 60.281659385175374, + 60.376610175961304, + 60.47176002002214, + 60.56558070662002, + 60.65612145810298, + 60.749356352593466, + 60.841439717548006, + 60.93324770443983, + 61.027408169805604, + 61.117695948170216, + 61.2045982862352, + 61.29410255104259, + 61.381195932078256, + 61.46481315224713, + 61.550881215562875, + 61.63579468844195, + 61.714126687994906, + 61.795932589882604, + 61.87795318689741, + 61.954480203287204, + 62.03250571918005, + 62.109842296365365, + 62.181616376468, + 62.25242505552403, + 62.322987891037634, + 62.3880198885742, + 62.45218275526259, + 62.51655948768926, + 62.57709176450033, + 62.635301424366226, + 62.69445847580147, + 62.751419852966315, + 62.80751083418683, + 62.86266293527033, + 62.91770705234575, + 62.97150070976861, + 63.02489322387806, + 63.07811426752116, + 63.1314365399524, + 63.18582217685417, + 63.240760811207124, + 63.29610738279832, + 63.349196002358134, + 63.402238665549575, + 63.45430719454715, + 63.50527843059613, + 63.557342666072415, + 63.60613622365498, + 63.64945623342096, + 63.69104080081217, + 63.72936882520374, + 63.761744699570755, + 63.79052776083536, + 63.81878188577173, + 63.84581992116187, + 63.86872330072505, + 63.88951849870405, + 63.9102267618383, + 63.930799640352205, + 63.9479467658193, + 63.96411161136835, + 63.9809442578884, + 63.996950116555325, + 64.00983083328845, + 64.02031513663198, + 64.02394371680037, + 64.01834009142722, + 64.00298935037688, + 63.978349825407875, + 63.94582408675004, + 63.905179930672396, + 63.85325136599898, + 63.79161879404028, + 63.716599209905894, + 63.62170596504502, + 63.514439546560816, + 63.394067655483155, + 63.25752856365438, + 63.11203323564524, + 62.952839397423055, + 62.77460926932836, + 62.584505746832164, + 62.37551002067494, + 62.15314717829945, + 61.92615249192401, + 61.6810368107225, + 61.4212869485904, + 61.1545317132926, + 60.874904437163096, + 60.58021150000361, + 60.28828276463054, + 59.98743453016053, + 59.669637717004456, + 59.364048008832896, + 59.05164330443183, + 58.71497916071203, + 58.39252988437138, + 58.059631911515474, + 57.7107673804263, + 57.37080032709071, + 57.026701339767335, + 56.66154841804023, + 56.2978799863472, + 55.939373319824746, + 55.56802153118479, + 55.19274824341826, + 54.82516836484518, + 54.46036420260913, + 54.09312668068759, + 53.720602759993774, + 53.347141082355314, + 52.977217399313176, + 52.60544469504744, + 52.231245758458655, + 51.86262875506664, + 51.48958602472073, + 51.10815682545779, + 50.734183351549625, + 50.367506478884444, + 49.98626029194108, + 49.6205372239061, + 49.27001394314357, + 48.903551084548106, + 48.545840628233854, + 48.20572630638323, + 47.85017563444385, + 47.50203638598253, + 47.16189595676222, + 46.8105192683672, + 46.4616724198868, + 46.11675334786447, + 45.76150551370608, + 45.40480869765571, + 45.0564256342748, + 44.69301438476904, + 44.328669530061376, + 43.970718524939905, + 43.600648893620146, + 43.234265683391236, + 42.87335991012285, + 42.50779225583399, + 42.14136351297361, + 41.773998289621716, + 41.413963899819706, + 41.04360806681638, + 40.67227553532139, + 40.30534187909715, + 39.938583850157, + 39.57232258726005, + 39.20461295054296, + 38.84186948892558, + 38.4815026544245, + 38.11863754521617, + 37.71766328846792, + 37.364449059155376, + 37.00607120374936, + 36.64493000384855, + 36.293010597450625, + 35.939525769616345, + 35.5904616235215, + 35.24546513219415, + 34.894027191727304, + 34.549105368730565, + 34.21214441652453, + 33.860048232656354, + 33.506993469430085, + 33.173262668129574, + 32.81705216205169, + 32.455906030819726, + 32.1119529633496, + 31.76042768706502, + 31.392221451121877, + 31.04788433749136, + 30.70089819819073, + 30.336189436506217, + 29.985364833468218, + 29.64365077860534, + 29.289581901103503, + 28.94066344790009, + 28.60358170096688, + 28.25857592849617, + 27.910567763065607, + 27.567151212378207, + 27.22930915995325, + 26.883128163039142, + 26.53755015476938, + 26.202097147862276, + 25.861695991717816, + 25.520314020498144, + 25.188096392192843, + 24.860353423164398, + 24.526045586486205, + 24.190550145528015, + 23.858761824728827, + 23.520103726112797, + 23.171835358180676, + 22.83017504711984, + 22.485837478395712, + 22.136195057745407, + 21.790947699710443, + 21.439661254885042, + 21.083696979380083, + 20.729152384853908, + 20.373968406818832, + 20.0119016424376, + 19.65164263492593, + 19.299154643473575, + 18.933127191151954, + 18.567172565391644, + 18.203942620002955, + 17.82041076974728, + 17.44219721807595, + 17.066433865393208, + 16.67981266439099, + 16.299925036839067, + 15.921158900128974, + 15.535325581248024, + 15.159703687894108, + 14.778789360563444, + 14.38486600912855, + 14.018149681546012, + 13.64354128263099, + 13.24390955367839, + 12.871769614452925, + 12.498122272196419, + 12.102375483405968, + 11.717987764513454, + 11.341031861739433, + 10.94354944890784, + 10.562486265862209, + 10.211661168617892, + 9.850749834560679, + 9.493321670701118, + 9.147193298779058, + 8.792766806243337, + 8.435000983779947, + 8.08425470503224, + 7.725638548135348, + 7.367650831168109, + 7.001657342914041, + 6.626779304949715, + 6.2492442416911524, + 5.872324041868941, + 5.501708559410655, + 5.128360917396018, + 4.755126297768746, + 4.3848997099928075, + 4.017877371069346, + 3.646376893614569, + 3.2757738324049233, + 2.906398981568199, + 2.534818768370754, + 2.1627778091897523, + 1.7969270286896442, + 1.4380057167064924, + 1.0759154855397155, + 0.7200750159389558, + 0.37321479041646605, + 0.02914811308890497, + -0.31084487447118736, + -0.6411563408619088, + -0.9700405069957634, + -1.2968516204502167, + -1.6187702029437863, + -1.94924394322357, + -2.280196630770843, + -2.600157316472305, + -2.960841026799311, + -3.292736306607323, + -3.6130130420295874, + -3.9324589721138103, + -4.2566077648040315, + -4.569230536732782, + -4.877077986532633, + -5.194499418537056, + -5.500649079211376, + -5.7992824020769485, + -6.107106154386381, + -6.405171577397624, + -6.695996081850355, + -6.990106228515937, + -7.2645641923146504, + -7.536418918896798, + -7.806437790192162, + -8.055528415089872, + -8.298830415702062, + -8.542599043226232, + -8.771534970970293, + -8.99732734817232, + -9.223156039062935, + -9.444156429620103, + -9.666449060639593, + -9.879196217107502, + -10.076953233068856, + -10.268047652564398, + -10.448530993608301, + -10.620862636321968, + -10.773007855871452, + -10.90413711598579, + -11.024395682413983, + -11.12131767093289, + -11.195311711290422, + -11.257564571362938, + -11.30554867383601, + -11.334862831547248, + -11.345610505732335, + -11.335971282122784, + -11.305315244874388, + -11.254326853020563, + -11.185334945115759, + -11.098908981935024, + -10.991857438779702, + -10.867094453315586, + -10.725895449337363, + -10.565612729848949, + -10.389309516606826, + -10.181857961698018, + -9.978157231422392, + -9.75877894732609, + -9.529303184775374, + -9.287813591964635, + -9.032844174721795, + -8.770159377744065, + -8.500939516158535, + -8.221755519556217, + -7.938159960585356, + -7.648412131392705, + -7.350297755837052, + -7.05191260506969, + -6.747764242693863, + -6.4332160388749555, + -6.119451080795939, + -5.805630004632701, + -5.453848208092183, + -5.133743843150374, + -4.813329377269034, + -4.494614359040718, + -4.177520454427168, + -3.8555846546148986, + -3.5392039734301997, + -3.223142220419046, + -2.9076650903579653, + -2.5961477603127685, + -2.2789353876814418, + -1.9698300895897383, + -1.6595802990074289, + -1.3441143596696223, + -1.0319385955766565, + -0.7303708648775338, + -0.4257343819453934, + -0.11355873769257524, + 0.1848800796468899, + 0.48594135202888367, + 0.7807654884331111, + 1.0821147100280377, + 1.3871041777993764, + 1.673214114492387, + 1.966100598569601, + 2.2638067337789956, + 2.5456166530868902, + 2.8266206016463196, + 3.118014791034848, + 3.3980619553093994, + 3.6677763652226436, + 3.946345628878007, + 4.219737474503075, + 4.482193017474221, + 4.749661617988702, + 5.041937120542202, + 5.299879178200307, + 5.555825128889483, + 5.812391850943208, + 6.068196503660831, + 6.32281550630052, + 6.575297631144122, + 6.829924972350936, + 7.084858196225822, + 7.339981650440308, + 7.598041464755717, + 7.856545112144505, + 8.116685456238024, + 8.375691789472686, + 8.637395828400763, + 8.898571832320323, + 9.155551053943862, + 9.41437108513193, + 9.675681488936188, + 9.929339015685203, + 10.181109481421531, + 10.439739513296772, + 10.693531272221275, + 10.945431649953704, + 11.200342214580663, + 11.451931446830132, + 11.702806565882462, + 11.954600655223974, + 12.210912814967877, + 12.470629714020555, + 12.72515289627694, + 12.985583709935213, + 13.253058338559866, + 13.519215734229753, + 13.790686281091544, + 14.065600262647369, + 14.334390661359674, + 14.610560765833304, + 14.894901100692035, + 15.17442051311233, + 15.461168351372704, + 15.75923402742882, + 16.058283484698343, + 16.364850777698678, + 16.682641728470735, + 17.002094767420743, + 17.326480451301308, + 17.654470714292504, + 17.99275921647582, + 18.33065303775773, + 18.66789065502258, + 19.014426084696105, + 19.36238286110806, + 19.704622712487296, + 20.04782905101017, + 20.39807170399852, + 20.74648153364409, + 21.09667575382273, + 21.458376186852544, + 21.8154178775815, + 22.171981850202762, + 22.54102625495687, + 22.900840225382197, + 23.263486469752056, + 23.631912560010452, + 24.001278602969418, + 24.37123281051683, + 24.7469215559245, + 25.12101708519, + 25.49887012928312, + 25.876734331534657, + 26.251514829847398, + 26.631308113226876, + 27.01478272088062, + 27.39695444809838, + 27.78110199218448, + 28.17254613216134, + 28.569106724102877, + 28.961339627436082, + 29.35135558414037, + 29.749100074450322, + 30.14321972192303, + 30.52148331775037, + 30.912838854047582, + 31.309051754079654, + 31.691424831442735, + 32.08462793478433, + 32.48826967906086, + 32.88522327773766, + 33.280666398757916, + 33.69143051461729, + 34.09857635249731, + 34.495809284122906, + 34.90972755492537, + 35.32641800863097, + 35.726380578907765, + 36.131956109604666, + 36.54334045182919, + 36.93405689100981, + 37.33096345447413, + 37.73495854488367, + 38.12850926519715, + 38.51861270734441, + 38.91108642013776, + 39.29670465846797, + 39.672704604662584, + 40.05261378546899, + 40.43865700868703, + 40.81342358090363, + 41.1927947000017, + 41.57587892278698, + 41.93749766957197, + 42.29198412341117, + 42.64473959848332, + 42.99240438704664, + 43.31661455331717, + 43.64753312021521, + 43.9811848093274, + 44.29410966325423, + 44.61116345109599, + 44.925425524671525, + 45.26764747288758, + 45.63159911322485, + 45.987783056310484, + 46.34545024379717, + 46.70655364556542, + 47.060195150761096, + 47.4076211125713, + 47.77472973248199, + 48.11828680602984, + 48.46043676644089, + 48.795559069212345, + 49.09971632883479, + 49.41064145883806, + 49.730083158507405, + 50.02982309514541, + 50.330727559914244, + 50.64107993575205, + 50.93014156712458, + 51.22678746960409, + 51.531412154092614, + 51.81763255621389, + 52.12230758122566, + 52.434341496681384, + 52.73102397372358, + 53.04013513222913, + 53.34059037417727, + 53.618605490128516, + 53.90659760280088, + 54.192890790903306, + 54.45498188317695, + 54.70871464379646, + 54.95550652188816, + 55.183049012966066, + 55.40346651223312, + 55.62050662003525, + 55.82331803509388, + 56.016324483685715, + 56.20121427424938, + 56.37644610438219, + 56.546352990824865, + 56.70698258528733, + 56.855316132679235, + 56.997761037135625, + 57.13730842154169, + 57.27012624841349, + 57.39918845375359, + 57.523924552491216, + 57.646218279906286, + 57.76682881762626, + 57.87845154979485, + 57.98171683278338, + 58.0837930203256, + 58.180703875228225, + 58.27202527955494, + 58.3636526320031, + 58.45261810388046, + 58.53582866390415, + 58.61906585290884, + 58.70293991074844, + 58.78471591221687, + 58.86730692886669, + 58.95029758161424, + 59.031485447131544, + 59.11021138571174, + 59.18642734809558, + 59.260428315398634, + 59.33524061103537, + 59.40986068200712, + 59.48497563361193, + 59.563038262200706, + 59.64118904352176, + 59.719389227563056, + 59.79999744605393, + 59.88217153361043, + 59.964871410899896, + 60.05119441990244, + 60.137591677123176, + 60.22619471515172, + 60.318508430333836, + 60.40952165630987, + 60.50043222917768, + 60.5945583922765, + 60.68679686442921, + 60.778815804493554, + 60.872926974700064, + 60.96760948296921, + 61.06510027982875, + 61.163188489969684, + 61.25702503300955, + 61.349315056846976, + 61.44188562803304, + 61.527751759479266, + 61.61244873209348, + 61.69821207881477, + 61.77804468509739, + 61.85392699597834, + 61.9296259251221, + 62.00185851993849, + 62.07031203850655, + 62.13670537887578, + 62.1959730071792, + 62.252054615502345, + 62.30594724122542, + 62.354968908932186, + 62.40157162573766, + 62.446080474692295, + 62.48793407151723, + 62.528135959076735, + 62.56649463856644, + 62.602434624261974, + 62.63605204349345, + 62.67193698824227, + 62.7030455772307, + 62.73310789095448, + 62.76261250005511, + 62.79090938588217, + 62.818936450635455, + 62.845163302784016, + 62.8695290224375, + 62.892292289603034, + 62.912795979382366, + 62.93276787448488, + 62.951547733171196, + 62.96930952381978, + 62.985908338554886, + 63.00100839521937, + 63.01491422169226, + 63.029392089035795, + 63.043274882227536, + 63.05896518683577, + 63.07471420229797, + 63.091320673777, + 63.109982962561546, + 63.128254780772394, + 63.14753697128567, + 63.16757708753383, + 63.18851365896184, + 63.20761823645554, + 63.224094590590525, + 63.235655279438106, + 63.23870598354821, + 63.233969492609766, + 63.22170615467716, + 63.20163108773384, + 63.171795011999365, + 63.133420056463805, + 63.084749435676436, + 63.025458453939386, + 62.95380604453136, + 62.86446133042564, + 62.75632565721195, + 62.63288671535663, + 62.4917398965239, + 62.336809315963485, + 62.16553558828467, + 61.97675291774159, + 61.77291507890253, + 61.54716385384834, + 61.30276804090229, + 61.04906636793197, + 60.81192018532945, + 60.56260959142985, + 60.29807756051385, + 60.02735269771747, + 59.75756439150738, + 59.47018141777021, + 59.18461171782139, + 58.90238529591176, + 58.614051219608356, + 58.3138527602646, + 57.98987137159376, + 57.66113841023117, + 57.32528506035067, + 56.97945762935523, + 56.624291519878994, + 56.26690719973818, + 55.901062792314356, + 55.52552192809759, + 55.144598532642135, + 54.76773163315791, + 54.38781787880138, + 53.99855289255219, + 53.625743133069726, + 53.2475060155093, + 52.862831946016485, + 52.49345287559652, + 52.124271896562554, + 51.74727760748255, + 51.38079460569861, + 51.01246481029312, + 50.6327046425791, + 50.26711932774592, + 49.90888746479829, + 49.53182921533975, + 49.179061853261985, + 48.837956607367765, + 48.47663391855183, + 48.13339849572884, + 47.807130651350334, + 47.46060498414247, + 47.13047961357537, + 46.81050199965301, + 46.48116377776248, + 46.15517677256216, + 45.83336861948094, + 45.50583457082173, + 45.17456112370085, + 44.85502704005448, + 44.52374282985643, + 44.186904996750734, + 43.851592128623814, + 43.511495011844005, + 43.16579926367237, + 42.8259385661728, + 42.487421675428635, + 42.14539076670972, + 41.808687079462835, + 41.46479020081303, + 41.130959931063494, + 40.788691585847054, + 40.44887466649771, + 40.10927829772693, + 39.77002482148344, + 39.43485072208063, + 39.093569581347964, + 38.75302585523253, + 38.41412028805515, + 38.07120754858951, + 37.72757880701141, + 37.38312390395235, + 37.04339759063215, + 36.69508614787157, + 36.345535567599875, + 36.00737759443102, + 35.663580378106325, + 35.32349665479488, + 34.99210119425043, + 34.656152584047234, + 34.32288104240155, + 33.99827326290476, + 33.66638131292083, + 33.31999482143221, + 32.99295440893254, + 32.66735726284639, + 32.31820279224586, + 31.985899408158176, + 31.659437313613736, + 31.31880198601785, + 30.983438920063314, + 30.660649658063626, + 30.33365059744347, + 30.000866297226633, + 29.677988482754955, + 29.351699464293194, + 29.025146253227067, + 28.695054930418227, + 28.370034291751537, + 28.04320686008069, + 27.711887811765415, + 27.375061413167217, + 27.040921969547455, + 26.702907940340957, + 26.35139220415963, + 26.010598618440127, + 25.671114492553663, + 25.33059340504493, + 24.985079994070087, + 24.652816454680803, + 24.322710260057878, + 23.988332825446566, + 23.661986743018332, + 23.33595772102648, + 23.007365920352882, + 22.67609709624427, + 22.34821549841634, + 22.017152230876107, + 21.684010531005494, + 21.361914949505756, + 21.02906773489013, + 20.694940535120928, + 20.378817997334668, + 20.059647697944126, + 19.742853954303467, + 19.42372570966386, + 19.102934200679478, + 18.782781053885877, + 18.461994721161368, + 18.134255251297347, + 17.805967472141052, + 17.47281580815261, + 17.135381320577427, + 16.791744922108798, + 16.444079608910577, + 16.105995807866144, + 15.760409508327378, + 15.41407709316523, + 15.076647029920318, + 14.734190441943847, + 14.375625391305734, + 14.03758728061147, + 13.70184017889557, + 13.333255814926211, + 12.983241297030743, + 12.645480373088091, + 12.28193083004375, + 11.925467495779497, + 11.577256488612214, + 11.217164940611902, + 10.854636258351285, + 10.499137907620133, + 10.137277040644857, + 9.772402009631524, + 9.41340352889663, + 9.047990871382273, + 8.68358350029497, + 8.317308092290189, + 7.949508399718211, + 7.577362602041926, + 7.207065092168341, + 6.833096390969102, + 6.456403504196448, + 6.081422938363752, + 5.6993800241452375, + 5.322112442291334, + 4.9422177586188925, + 4.558682149708401, + 4.1759764551250615, + 3.793614633532611, + 3.4095077825844093, + 3.021632790120178, + 2.6386464893866926, + 2.260961565749568, + 1.8768156788892656, + 1.494776247195664, + 1.1237720527434525, + 0.750241881576778, + 0.3644939115835353, + 0.0003985413238350999, + -0.36358758444680306, + -0.7339211116538464, + -1.0944189240434319, + -1.4485512442573514, + -1.8000793387959915, + -2.154012506924186, + -2.5101263575659245, + -2.856845843226264, + -3.203570454917672, + -3.5591999394454676, + -3.9054885234646655, + -4.241166831409329, + -4.597008179585605, + -4.938465526157004, + -5.262236639455328, + -5.606329825662732, + -5.950955584231887, + -6.273702279706305, + -6.610493222183457, + -6.94071855056408, + -7.260365747155487, + -7.593618122696932, + -7.892163121286971, + -8.18627500426156, + -8.491631030293615, + -8.771412568717908, + -9.038346341614425, + -9.309063432433401, + -9.562449417428644, + -9.804035582156809, + -10.04283045296987, + -10.268579233684013, + -10.482590142379573, + -10.692718389030276, + -10.894029361453741, + -11.082637687465967, + -11.261804939941495, + -11.430246541106198, + -11.587534568944571, + -11.729897448269384, + -11.854485351357262, + -11.963264935204627, + -12.05246316171118, + -12.118558364809497, + -12.164869482562567, + -12.189130725413053, + -12.191962098734965, + -12.172762375102891, + -12.132524787942378, + -12.071756574667436, + -11.987976332305832, + -11.881197911663184, + -11.753366259590033, + -11.60717323003133, + -11.437445332374683, + -11.247192511763327, + -11.038114118134464, + -10.809118261493788, + -10.567216774687227, + -10.315191112009325, + -10.046424754158279, + -9.764175592237091, + -9.474437967949074, + -9.17042074704547, + -8.824884232635538, + -8.507898210986419, + -8.182792298142976, + -7.854943463752893, + -7.524013289983076, + -7.189469816086135, + -6.858392215792005, + -6.522374038079284, + -6.184604798517509, + -5.8486399555739315, + -5.50980696830572, + -5.170810860163108, + -4.832505029669365, + -4.4966380160899915, + -4.161232258298383, + -3.8238912928848556, + -3.4897011370596083, + -3.154191311839693, + -1.9737318427051402, + -1.6385391859771126, + -1.3002215533887205, + -0.9630799955640327, + -0.6356851791594373, + -0.307764297562342, + 0.024012512080520465, + 0.3414866463822026, + 0.6545461276978739, + 0.9632812372732267, + 1.2842463641676103, + 1.5950713413832374, + 1.891069559661427, + 2.2016936967191065, + 2.506943151730935, + 2.79764489119945, + 3.0967509811087672, + 3.3992660380833524, + 3.684146787958361, + 3.971970866198464, + 4.26742962751653, + 4.5489891462046295, + 4.8322019951504664, + 5.1200867715042, + 5.398035224886245, + 5.67328487536808, + 5.950327825487951, + 6.230058613141949, + 6.506658642707398, + 6.7811784829935435, + 7.0579095864872645, + 7.33456036649446, + 7.609245833004409, + 7.888440785146189, + 8.16775389894576, + 8.446902979043847, + 8.727087537616262, + 9.010143277063444, + 9.290403626206134, + 9.568224255375616, + 9.849845092091241, + 10.1307202506979, + 10.403706081597347, + 10.680476080620002, + 10.9625292292068, + 11.23648399879197, + 11.513661240099827, + 11.792487271740285, + 12.069717001604555, + 12.346867083314574, + 12.632405499810076, + 12.922026735659495, + 13.2069000058912, + 13.502272801566226, + 13.80449773840674, + 14.10463318696719, + 14.411123877948137, + 14.716847300164286, + 15.01772420836033, + 15.328457788309667, + 15.640121931645558, + 15.953731111737216, + 16.2824006428232, + 16.615693116438134, + 16.95270320722105, + 17.302864723360862, + 17.65573322551638, + 18.008482388213544, + 18.36665727974754, + 18.73189700118935, + 19.088133894567918, + 19.451082926110107, + 19.81995209976455, + 20.179114721815864, + 20.535434180325428, + 20.8983707253235, + 21.261541890376268, + 21.61281452399978, + 21.963886782965623, + 22.314933020785375, + 22.660123067030305, + 23.014022588880138, + 23.393473736406502, + 23.738104036360916, + 24.087768581149984, + 24.435201541277188, + 24.7824500190354, + 25.141564869019163, + 25.504081536225755, + 25.86615912699942, + 26.232462113011955, + 26.591296082660524, + 26.95045571710823, + 27.311673803146704, + 27.670899872623043, + 28.033469254476483, + 28.395852571991693, + 28.753774740279187, + 29.106318672094904, + 29.45465755315703, + 29.802844724543828, + 30.152908814015888, + 30.503525446701126, + 30.84279161926177, + 31.182376399200262, + 31.532104117487183, + 31.875105262532564, + 32.21885387849948, + 32.57907926851076, + 32.94231376733323, + 33.30151913415881, + 33.659118712600886, + 34.02475940265809, + 34.38919311999698, + 34.74656831143345, + 35.10797829610265, + 35.47350575426272, + 35.834912568002814, + 36.19424489417513, + 36.5540653260781, + 36.911152798106926, + 37.26325471497696, + 37.60901900683631, + 37.956517716861924, + 38.30472036872867, + 38.64699233524936, + 38.98316056813063, + 39.32090458742762, + 39.65797964012224, + 39.986538965712995, + 40.311786431913724, + 40.64233160779546, + 40.972222121131104, + 41.298964887565184, + 41.62993903784697, + 41.96672059886023, + 42.29677412252249, + 42.61986524652843, + 42.94138147128926, + 43.26574115153405, + 43.59179284992204, + 43.900353090044746, + 44.22344286570073, + 44.54930420767907, + 44.864903689150474, + 45.18420711455336, + 45.49969274010402, + 45.81512917397828, + 46.13584710069355, + 46.44733423181216, + 46.76220208799387, + 47.076807981698416, + 47.382076065757346, + 47.688806309722004, + 48.00442256531817, + 48.292607069219116, + 48.593730951703755, + 48.899864756455, + 49.1925564533268, + 49.4991376773186, + 49.79782814085616, + 50.08316079673435, + 50.379642796385134, + 50.66860915344607, + 50.94589924954362, + 51.23773510837194, + 51.518432553090456, + 51.793116339138074, + 52.08706940377377, + 52.37097901113291, + 52.65383574061299, + 52.94443050456713, + 53.21341918663115, + 53.47068292800913, + 53.73884723518855, + 53.996471347978506, + 54.23767144868568, + 54.48282433504803, + 54.720611058513306, + 54.94401215399161, + 55.16382514437546, + 55.3768715664172, + 55.580756052840634, + 55.77909951804382, + 55.969507456717686, + 56.155881026108496, + 56.33948246819552, + 56.5161142029926, + 56.68125300566708, + 56.842342615480625, + 56.999093377325856, + 57.14716472899634, + 57.288858847494616, + 57.426220120422165, + 57.56270789814683, + 57.69536873625203, + 57.818045539406576, + 57.93343194193157, + 58.048467410144085, + 58.157744944336095, + 58.26230734617762, + 58.36832211829607, + 58.470997291306155, + 58.5681774612219, + 58.667291050790496, + 58.76832674550958, + 58.86706566241966, + 58.968086576631144, + 59.071374491239226, + 59.17335319888448, + 59.274612249440175, + 59.37575831482317, + 59.47451892877917, + 59.57455920261261, + 59.675472399878764, + 59.77330548291015, + 59.87071791706412, + 59.96739275776205, + 60.06244165708001, + 60.15531053455021, + 60.24892509758613, + 60.34125835131264, + 60.43449433922638, + 60.52684563408207, + 60.61788529151114, + 60.710231249883186, + 60.802531957020676, + 60.89229565968945, + 60.98364618799147, + 61.075344749079385, + 61.16267403481749, + 61.25099316157184, + 61.33769375279625, + 61.418371415806654, + 61.49886545283948, + 61.57946770113693, + 61.65534421255556, + 61.72932788793069, + 61.80529134523092, + 61.88113926562536, + 61.952468600354884, + 62.025018703511805, + 62.09757486678338, + 62.16739706332694, + 62.23525307390041, + 62.30380653146329, + 62.37119854336666, + 62.43841707233342, + 62.505455562680034, + 62.56953399713478, + 62.629853184173896, + 62.69007172836357, + 62.74913967076412, + 62.805214306062396, + 62.860767487516306, + 62.91504266123033, + 62.966751746810516, + 63.017817537026566, + 63.067214910558434, + 63.1145316734767, + 63.160261658140854, + 63.20302685052921, + 63.24439547293186, + 63.285078147137455, + 63.32464416443559, + 63.36378760992091, + 63.402003962270605, + 63.4409601578963, + 63.47927263730376, + 63.516952602389274, + 63.55546472979714, + 63.59366697584465, + 63.63179518795001, + 63.668400506018685, + 63.702777610892625, + 63.73541358316437, + 63.76707001065267, + 63.796620918936085, + 63.82288155468991, + 63.84869527026163, + 63.87444941905167, + 63.90034133648056, + 63.92404792968703, + 63.94650694364895, + 63.96913409079851, + 63.98982060470319, + 64.0093302322701, + 64.0286271966915, + 64.0473146786593, + 64.06248738416762, + 64.07402740341747, + 64.08002180612183, + 64.07659962763822, + 64.06384040676674, + 64.04279999167841, + 64.01591457120747, + 63.981901711643054, + 63.93830113197171, + 63.88432825143542, + 63.82110130817472, + 63.74144488631624, + 63.64991395774259, + 63.54982046129109, + 63.43423524800037, + 63.31195682136455, + 63.179859981281865, + 63.03251568845554, + 62.873890024259914, + 62.70273104787438, + 62.51344950987808, + 62.31450843931211, + 62.10732110698419, + 61.87820412792564, + 61.63588581346066, + 61.3847033016833, + 61.11810205098032, + 60.83706638036837, + 60.55203503960896, + 60.2591233378391, + 59.948951560720836, + 59.64281947898163, + 59.33516076505868, + 59.004243035341744, + 58.667274938813655, + 58.34273001607041, + 57.994636080939785, + 57.64120466906325, + 57.29364517337805, + 56.93426079697316, + 56.556660529239416, + 56.18403017854882, + 55.80900449570857, + 55.41917603594155, + 55.02937074627333, + 54.64668410989559, + 54.263856088877475, + 53.87902730349544, + 53.493855497489264, + 53.11790955051931, + 52.74745688527212, + 52.377430646436544, + 52.00596605767546, + 51.642450941617355, + 51.276010578250194, + 50.90592467610153, + 50.54444678464213, + 50.18869726716759, + 49.81958842033298, + 49.46563725991618, + 49.12457225145264, + 48.769088141286524, + 48.42062152718872, + 48.08871152984518, + 47.7424664506105, + 47.39875944077264, + 47.06572009332854, + 46.723479088438125, + 46.359131743290476, + 45.986169541620534, + 45.60580434355666, + 45.21941283139749, + 44.84368944054191, + 44.459233632677716, + 44.06626309643785, + 43.678532573836115, + 43.28945541800294, + 42.89309493447638, + 42.52171615307756, + 42.16496809230723, + 41.80526766013752, + 41.45012656547276, + 41.09094409781602, + 40.73883385461795, + 40.37823207683645, + 40.01556331005153, + 39.65527860386862, + 39.2946882258996, + 38.9221253452897, + 38.53544198257951, + 38.15137565783821, + 37.77096038937727, + 37.38378573234496, + 37.00115849769297, + 36.62009551481536, + 36.24490909142492, + 35.86053987428015, + 35.479430322576235, + 35.12068256213927, + 34.76594592787762, + 34.41818353302561, + 34.074535796423135, + 33.724472684194104, + 33.38380537361463, + 33.0496550609126, + 32.70537985536714, + 32.358402812894454, + 32.03367477796552, + 31.725437651837435, + 31.42617294459622, + 31.149074929892038, + 30.871568882677945, + 30.581436281530905, + 30.306547390480556, + 30.04087091043798, + 29.76012651411064, + 29.483645071357614, + 29.21307170943519, + 28.915186308402184, + 28.604167477899512, + 28.288628513693478, + 27.977575436308996, + 27.666749410052798, + 27.351455150869977, + 27.031084307673783, + 26.71936963476472, + 26.4097667489724, + 26.082145734507638, + 25.773228112565835, + 25.475845342097497, + 25.17623792187484, + 24.87266148744582, + 24.57485526049901, + 24.28284714423407, + 23.984346432486845, + 23.688828093892848, + 23.385733891422916, + 23.079637227283133, + 22.75973774823947, + 22.431820054580353, + 22.106285926365747, + 21.77078716473946, + 21.438052313008484, + 21.108643319797075, + 20.77109786837603, + 20.434946040825935, + 20.097575044871853, + 19.755615424501208, + 19.421709829416844, + 19.07805445042185, + 18.730357425605046, + 18.392039300055664, + 18.04775191546549, + 17.694706556844277, + 17.349081231626972, + 17.003669784259788, + 16.647475010543413, + 16.294823821546398, + 15.95004523550347, + 15.590401465404417, + 15.241476400933735, + 14.896275917120366, + 14.541738143053328, + 14.176568671082565, + 13.833629669157414, + 13.4877111984884, + 13.11209533932878, + 12.765639870716381, + 12.409852160708132, + 12.030519169784274, + 11.662935647236951, + 11.29781739679997, + 10.923576480105778, + 10.547104620491362, + 10.179325940711486, + 9.80434720851576, + 9.429431366182074, + 9.059660224708054, + 8.69054853623304, + 8.324308983430388, + 7.958635966271055, + 7.592422218232839, + 7.219580964664512, + 6.85391204688046, + 6.481846032388735, + 6.113956451600927, + 5.746893148429063, + 5.3738508094908966, + 5.007064243172127, + 4.640787405981305, + 4.266990967158904, + 3.8950800310339235, + 3.5254868278999685, + 3.1530785584810084, + 2.7745049887310405, + 2.4031625463945376, + 2.0358503048240895, + 1.6602091810320045, + 1.2866470989772245, + 0.9253257759194027, + 0.5660115461467957, + 0.1947891702247525, + -0.15397659762822646, + -0.4983643907005726, + -0.8525912938512082, + -1.190695290075616, + -1.5265366704449703, + -1.86635950314589, + -2.205113876403413, + -2.546212473323805, + -2.8910134919435793, + -3.229743424973572, + -3.5765738944320233, + -3.924473354456995, + -4.261422577449902, + -4.614755685900284, + -4.956168369049133, + -5.289259111332057, + -5.630929687233937, + -5.964512369533704, + -6.287819979380584, + -6.609399078478686, + -6.928382847656105, + -7.2375223397370885, + -7.546363982114743, + -7.841229940460219, + -8.126118350021194, + -8.41201674665735, + -8.683967032550587, + -8.946428999248381, + -9.208739878809554, + -9.462449244669466, + -9.70802138855128, + -9.946431884395997, + -10.179279382753352, + -10.405321405135073, + -10.62507300362832, + -10.836118675686093, + -11.037670172389538, + -11.22931187704759, + -11.406259548666682, + -11.572792775313768, + -11.724318105319606, + -11.850917331391768, + -11.953485160141375, + -12.037361516674807, + -12.097391138291137, + -12.133227296558076, + -12.147547885513015, + -12.14006660237752, + -12.111208670075818, + -12.058593481029705, + -11.981601836514225, + -11.880140002609227, + -11.757401062127498, + -11.610686807803447, + -11.4412308739108, + -11.251774504910673, + -11.039699254475883, + -10.81315614756676, + -10.573723007639135, + -10.318117403544377, + -10.04776067425619, + -9.768494126980976, + -9.476561592617353, + -9.173701308180583, + -8.86204466143557, + -8.540913147582616, + -8.214752736638937, + -7.882719101297022, + -7.5446705883891445, + -7.208515508164834, + -6.8660881419934165, + -6.520255981065731, + -6.17761044765736, + -5.830993800361853, + -5.481652060542046, + -5.135176310518312, + -4.7935572385906084, + -4.420157076347853, + -4.081138504039376, + -3.7480614424401693, + -3.416683568894925, + -3.0866646700464693, + -2.7582059205503073, + -2.428680949195049, + -2.1009562566269633, + -1.7753578176490288, + -1.4465325729677032, + -1.1231669232756571, + -0.8067701258043809, + -0.48370082569399264, + -0.16769986167306367, + 0.1451894369885438, + 0.4535405492032794, + 0.774943946132012, + 1.0872690449768723, + 1.3852465568904504, + 1.700348673591054, + 2.010794353926612, + 2.307851899755635, + 2.6146603307090945, + 2.9251205363825696, + 3.218847870114183, + 3.5189409669088203, + 3.8216973438900106, + 4.112045409085448, + 4.407418879691832, + 4.701849051475603, + 4.984908571612931, + 5.267735812588464, + 5.555947167319271, + 5.837924725715278, + 6.115309628035547, + 6.3973571694964235, + 6.6796926940459445, + 6.957475656784271, + 7.240111295023662, + 7.526943558446389, + 7.812566779546011, + 8.098813056052256, + 8.389093241211894, + 8.675448464599093, + 8.959908552629726, + 9.249561132054787, + 9.531362916679806, + 9.80930281397461, + 10.09680498468821, + 10.379857955303388, + 10.65987416102991, + 10.94550052063651, + 11.233213006933104, + 11.516749345803488, + 11.807598814861917, + 12.105316539300597, + 12.397904728931232, + 12.698608826519814, + 13.036461936633428, + 13.340525748616427, + 13.650228885451888, + 13.958421377134563, + 14.266513153286832, + 14.579031386588914, + 14.892473484213435, + 15.21520906247777, + 15.546890816370478, + 15.87688046768632, + 16.218917749749462, + 16.571873797087093, + 16.919927397179663, + 17.267370962628103, + 17.62829709758554, + 17.982281450383365, + 18.333048093511373, + 18.695792703167193, + 19.054039015790117, + 19.399965811812052, + 19.753101088424188, + 20.11710475903152, + 20.468904903706072, + 20.83096264184473, + 21.199402163121455, + 21.56266363500743, + 21.92694427097784, + 22.296374902080235, + 22.65840419189045, + 23.02344377997737, + 23.389167695567007, + 23.75545997424605, + 24.121720005111438, + 24.489980522115406, + 24.856307937139775, + 25.227080510221093, + 25.59362096993688, + 25.95773426957631, + 26.326110032938168, + 26.692752133667813, + 27.060702097660787, + 27.43017958349347, + 27.803788210660944, + 28.178526286266035, + 28.55166991805745, + 28.92343631307273, + 29.299377923421208, + 29.67307358882372, + 30.03479181254738, + 30.404678196397786, + 30.78183326366769, + 31.181878292729593, + 31.550363409317743, + 31.93092223212536, + 32.30652392097987, + 32.67565231571263, + 33.05489198021725, + 33.43671800031759, + 33.808555633598, + 34.18322179631348, + 34.56419436743094, + 34.93726239722992, + 35.307625422191144, + 35.677443536753614, + 36.04553293088179, + 36.408704500576086, + 36.76691273206612, + 37.12789688860783, + 37.48933793544555, + 37.84095834791005, + 38.190896365890865, + 38.582773265874806, + 38.93203951531471, + 39.274042532265845, + 39.62231096192946, + 39.9720781761825, + 40.31968433298482, + 40.66959107610259, + 41.026548389147635, + 41.3778024857211, + 41.72225025845963, + 42.06229157401763, + 42.40974953285443, + 42.751621699956935, + 43.080787822582, + 43.42690167768115, + 43.76855703310241, + 44.10479228063313, + 44.440915959201, + 44.77431337359457, + 45.10662851386231, + 45.46094619120686, + 45.808342695585985, + 46.15975171217776, + 46.506315606348885, + 46.844078813241644, + 47.19322510494851, + 47.515266626471785, + 47.84670460256572, + 48.18191510737193, + 48.50381769766905, + 48.81466401158964, + 49.11401632061397, + 49.403317735523665, + 49.70326838030182, + 49.99350772715099, + 50.27664946918454, + 50.574009520554895, + 50.856127445613495, + 51.13563734988419, + 51.43100948252961, + 51.71024698691648, + 51.995041528716584, + 52.2828001245033, + 52.543999734477055, + 52.79818063393478, + 53.062833429930436, + 53.31603947627008, + 53.5513319686284, + 53.790476856280144, + 54.02128608025901, + 54.24484994796885, + 54.46278214766334, + 54.671946921444174, + 54.87010320200749, + 55.05981263720886, + 55.23892510914591, + 55.409239038933634, + 55.57628863237356, + 55.73512105855887, + 55.88312969636046, + 56.037601843785545, + 56.18883410184367, + 56.33116699255883, + 56.46760413259681, + 56.59790203899644, + 56.72495218899766, + 56.85380808523675, + 56.975184052245204, + 57.09142895916407, + 57.20426547039739, + 57.310540910036146, + 57.41370663231651, + 57.51538703476197, + 57.61742164489792, + 57.71561049045584, + 57.81201532446704, + 57.91116592490751, + 58.011422147909336, + 58.11068680342482, + 58.21220435793892, + 58.31522108255103, + 58.418442245193724, + 58.52105016626588, + 58.62400693566569, + 58.7250857106172, + 58.82750827951949, + 58.93101737692925, + 59.032590191622816, + 59.1339849327446, + 59.235384220430845, + 59.33631552578168, + 59.43574142362113, + 59.535779689522975, + 59.64500019523664, + 59.744836338341294, + 59.842736860445015, + 59.93816991984187, + 60.032897376559305, + 60.12473050145164, + 60.2124355964005, + 60.30097411514164, + 60.3873991649243, + 60.46803999003559, + 60.550004255285856, + 60.6301685483377, + 60.7040459447709, + 60.7784767488248, + 60.85417969709186, + 60.9276451685494, + 60.99980458984615, + 61.071522607718556, + 61.14417113005666, + 61.219322102440415, + 61.29096448216104, + 61.360927914315965, + 61.4341652842808, + 61.505068575542055, + 61.57289079132632, + 61.64030095303006, + 61.70571420281428, + 61.76912038039181, + 61.83250286637176, + 61.89463014528182, + 61.95143213143881, + 62.007336552737364, + 62.06335851195561, + 62.11710249448164, + 62.168773601698476, + 62.220483847542305, + 62.26979688580645, + 62.318384438452625, + 62.36678070723835, + 62.41410722291134, + 62.460758185586684, + 62.50550431651555, + 62.54984886165757, + 62.5934387022575, + 62.63681602675735, + 62.68027596955813, + 62.7235165704154, + 62.76658786753604, + 62.809537712329906, + 62.85219241103102, + 62.89579581765202, + 62.93877130776275, + 62.980085827608356, + 63.01933518024041, + 63.056670212543544, + 63.092758501150115, + 63.12530266204414, + 63.15499639291959, + 63.18495235437026, + 63.21425369132545, + 63.24276248105419, + 63.26959046188912, + 63.29614862701168, + 63.32094853470265, + 63.342821015002045, + 63.36247286048999, + 63.381113352907896, + 63.39559935579364, + 63.4069544812618, + 63.41464804030659, + 63.41553550559999, + 63.40804107192399, + 63.39187460734041, + 63.36740745068784, + 63.334509840312606, + 63.29559094073917, + 63.249253431392745, + 63.195464350706004, + 63.134319662336736, + 63.05950820059209, + 62.97197680453213, + 62.87605146515514, + 62.76589256673009, + 62.64607750835021, + 62.519256160605494, + 62.37833259911176, + 62.22200641190058, + 62.05437435134139, + 61.87094591087604, + 61.67387044530865, + 61.47487611204491, + 61.259381666821334, + 61.02421136780594, + 60.78382551403607, + 60.53201503761655, + 60.266923094640035, + 59.99175650230652, + 59.71330163664198, + 59.42358865267714, + 59.12095716488916, + 58.829465736798284, + 58.525738793353874, + 58.19957422235465, + 57.883692342574726, + 57.56468454713975, + 57.220189492809055, + 56.883718281401364, + 56.54346139561328, + 56.19058480752353, + 55.82890053225424, + 55.46851848470298, + 55.10164367346424, + 54.72723891690356, + 54.35637953066699, + 53.98522439163164, + 53.61728799423, + 53.24664548859881, + 52.871031989161175, + 52.497065621641994, + 52.12881950173182, + 51.75679706051156, + 51.38211768770357, + 51.01719823254678, + 50.64654502135135, + 50.26738345506349, + 49.895512985789246, + 49.53345190249438, + 49.17047924444769, + 48.81407677580592, + 48.47413449100175, + 48.12799927402099, + 47.77831493568805, + 47.44929499195971, + 47.114600336976636, + 46.775184081547565, + 46.45143781016481, + 46.12032014097613, + 45.77953445033482, + 45.44804795964565, + 45.108872168663865, + 44.76423894352988, + 44.42513789819475, + 44.0862473496595, + 43.73504441833441, + 43.38793249611571, + 43.04378390555962, + 42.68951428160363, + 42.34454641705418, + 42.00420293947376, + 41.661184645138384, + 41.32038723498097, + 40.97837013283119, + 40.63649447577548, + 40.30005306001455, + 39.955183111636096, + 39.612556261236584, + 39.270990312134, + 38.92871827550783, + 38.58766717483126, + 38.24539001260121, + 37.90590095785497, + 37.56488989454538, + 37.22471904645714, + 36.883129955754804, + 36.54360508713182, + 36.174200328018145, + 35.83846948748642, + 35.52263117867542, + 35.20928432755148, + 34.89472508837139, + 34.58717727219647, + 34.27577478710454, + 33.96028078619159, + 33.656393101388375, + 33.35125219401434, + 33.03503564062306, + 32.71402241803113, + 32.39811779029053, + 32.06878705847447, + 31.724016816164948, + 31.400510017562983, + 31.077360952642394, + 30.74206556774704, + 30.41713643667577, + 30.105490155339325, + 29.78995024060322, + 29.471923274046212, + 29.17887591341842, + 28.88386513040068, + 28.59463801367735, + 28.30362591585875, + 28.010759354391112, + 27.72652510242391, + 27.440972500198153, + 27.150589205568867, + 26.861112483725588, + 26.579060996421017, + 26.277706763108057, + 25.966240397912934, + 25.670134418173415, + 25.371371672587152, + 25.074535109157953, + 24.777970317510672, + 24.482322071433558, + 24.19536270629075, + 23.903390143250498, + 23.614795122863292, + 23.320471315145653, + 23.023878300246846, + 22.72756634988025, + 22.424149403454845, + 22.122413473384118, + 21.817985269867396, + 21.50691703044525, + 21.202369412985476, + 20.89370456908331, + 20.571532633005138, + 20.25669443070181, + 19.938851502163917, + 19.612679927434932, + 19.289613832044996, + 18.959568853554533, + 18.632076621377326, + 18.2990021641359, + 17.960528193336145, + 17.621018854283523, + 17.271625409828836, + 16.920712917607652, + 16.574009682210736, + 16.21647818063653, + 15.85707275970383, + 15.508918724821502, + 15.147679745181923, + 14.787002438138943, + 14.43920787628254, + 14.071234177125318, + 13.70121492837306, + 13.352430513109278, + 12.981205153702996, + 12.600208273152308, + 12.243284342932425, + 11.87373390693562, + 11.491377337532775, + 11.12234811865268, + 10.751762284048406, + 10.363468548624388, + 9.985834010670732, + 9.609833523832139, + 9.182118154976337, + 8.800749782509422, + 8.422753380660426, + 8.038101562884759, + 7.6532280665617565, + 7.273715753938879, + 6.885858079780781, + 6.5060941357564435, + 6.123356359182788, + 5.736088139167882, + 5.348443740434719, + 4.962594126544416, + 4.579245000671015, + 4.193447609052545, + 3.8072503171656864, + 3.425665742939745, + 3.0435922483278706, + 2.658170011828071, + 2.275281716611861, + 1.8999890526239773, + 1.5210622922455812, + 1.14663090463916, + 0.7742754514835176, + 0.40107664980557045, + 0.029681644600288548, + -0.3375242291933822, + -0.7028733736258722, + -1.0732581212481862, + -1.4331811266702945, + -1.7904946565320976, + -2.1451324583006004, + -2.497803521150139, + -2.8503835368231774, + -3.194247338562687, + -3.5389898385324794, + -3.8848295469978393, + -4.2292078205621, + -4.5643403234788416, + -4.902665704726873, + -5.2276636048163585, + -5.535170021196102, + -5.850088807595772, + -6.175451794889589, + -6.490853013774716, + -6.7988372140586835, + -7.122367251740657, + -7.436068606666205, + -7.738802645661212, + -8.058399769177601, + -8.375578011371097, + -8.680409821592939, + -8.990697894762434, + -9.281158435043855, + -9.55993118367805, + -9.841602130141302, + -10.113998451079441, + -10.37716774491123, + -10.6364891967188, + -10.881568979445975, + -11.114003490277911, + -11.33980081487278, + -11.554208799752875, + -11.765195615113322, + -11.9695233647449, + -12.160861718609366, + -12.341040433527219, + -12.510037517159404, + -12.662400773404304, + -12.795279434582298, + -12.909618821637794, + -13.003301468671635, + -13.070831645924557, + -13.114504403662622, + -13.135191530377767, + -13.131422865659708, + -13.10440465335795, + -13.053012216564387, + -12.978458620578525, + -12.87795730558982, + -12.755289034242294, + -12.615325071788435, + -12.45223498061398, + -12.267184377297351, + -12.069759167457331, + -11.855477485909732, + -11.624536527858567, + -11.386480230515378, + -11.135352927495594, + -10.868062423603151, + -10.593086987169931, + -10.307467506183428, + -10.009868595637103, + -9.706427327421112, + -9.39458778062222, + -9.077600195467477, + -8.755615634299993, + -8.427476673356207, + -8.098039874970743, + -7.76305834477517, + -7.417184262657636, + -7.070243305740809, + -6.723813539134538, + -6.372553053415411, + -6.018511449792451, + -5.667633752166593, + -5.319108153797582, + -4.965128321716547, + -4.615845657752876, + -4.266784506746329, + -3.909442032206474, + -3.5574691551888336, + -3.2035921575796356, + -2.8522142286154786, + -2.504641409065519, + -2.1561305486307263, + -1.8123236764333392, + -1.4788333507227696, + -1.1386033911629663, + -0.8091393293994319, + -0.49301161598759924, + -0.18270464766558236, + 0.13770503153790448, + 0.4524245561292514, + 0.7470438234917015, + 1.0549312652219875, + 1.36121201935598, + 1.6517144085978883, + 1.9479459678253364, + 2.253380787979585, + 2.5406985707543126, + 2.8288417292864243, + 3.1235974378665317, + 3.404785308807161, + 3.686393098423363, + 3.9734070895377904, + 4.24947446088114, + 4.525114679277028, + 4.803821304103324, + 5.081124078841802, + 5.354843251199424, + 5.629153282026435, + 5.905654709798293, + 6.1805847588072975, + 6.458039682918237, + 6.735638786511495, + 7.015293552817844, + 7.295300354743993, + 7.575781706023804, + 7.857224626470109, + 8.136920484415251, + 8.415860337758605, + 8.698377916937957, + 8.972581163060369, + 9.245734698546478, + 9.527635078046034, + 9.802522133696957, + 10.077364894200452, + 10.356453842522031, + 10.63423918323383, + 10.90760730553423, + 11.18831155135763, + 11.476218192746636, + 11.758071208659235, + 12.047860819825235, + 12.345803509434328, + 12.640961374320227, + 12.941536761503569, + 13.243543379062109, + 13.541128701489344, + 13.847610044548075, + 14.154283866681745, + 14.463323969946268, + 14.787272714874067, + 15.11267581300668, + 15.44262188124273, + 15.786438787498332, + 16.134340167310306, + 16.476612757450123, + 16.827621450604358, + 17.183491532595667, + 17.531150826263314, + 17.887468419248233, + 18.250366537784384, + 18.603258103224125, + 18.95443092986873, + 19.315382663174475, + 19.673979602903874, + 20.02819178460713, + 20.398673367513535, + 20.771161872270007, + 21.1397403314832, + 21.518887519664364, + 21.890392100554525, + 22.26401380716324, + 22.642512051992497, + 23.020604647065987, + 23.398080979758404, + 23.781131794701917, + 24.16279834599238, + 24.54538941963393, + 24.925034022976934, + 25.301558341561474, + 25.682691242010932, + 26.06308178519438, + 26.441107240221204, + 26.823407454652976, + 27.211171095128275, + 27.5999302754471, + 27.982455200227168, + 28.361343680583293, + 28.74381713711348, + 29.123582215110392, + 29.488886270875092, + 29.862096056049598, + 30.241283770536587, + 30.60876348191735, + 30.97868120493982, + 31.36004238146997, + 31.745994525277986, + 32.15135014040447, + 32.564712558980936, + 32.9793444069204, + 33.38570310892224, + 33.79531811428434, + 34.20884110835389, + 34.61594856754298, + 35.02158154670799, + 35.42810542797403, + 35.82533851398963, + 36.20299150015205, + 36.576049237986034, + 36.949603448124485, + 37.32747549150403, + 37.694552580094026, + 38.05777027885687, + 38.42564998251778, + 38.78661261190079, + 39.13919620363345, + 39.48881580763127, + 39.823269953387324, + 40.1552476544533, + 40.48951364580601, + 40.8308380346881, + 41.169123505931374, + 41.50091361817909, + 41.82877954165472, + 42.161211761307214, + 42.53384607403117, + 42.85390103882031, + 43.190585475213666, + 43.53687048371664, + 43.8734460201353, + 44.206873986830985, + 44.54718352235755, + 44.88486527932402, + 45.22597486607037, + 45.55864806328055, + 45.89295706657062, + 46.23685371584923, + 46.578635342002485, + 46.96570251114636, + 47.30549813131491, + 47.647944107113084, + 48.0299351396432, + 48.37663105407652, + 48.723091223027645, + 49.06461095247348, + 49.40423309311393, + 49.73345353823621, + 50.05590173565162, + 50.38364087341626, + 50.69538798388635, + 51.01397427168325, + 51.33558879433273, + 51.641343886013566, + 51.951002026893995, + 52.24745270667296, + 52.52009976595814, + 52.79409336395465, + 53.056168776154074, + 53.29916197386721, + 53.542119577137356, + 53.77548751838303, + 53.98972566766802, + 54.19780608146605, + 54.40000101563082, + 54.58542908373879, + 54.76149985847198, + 54.933541685609974, + 55.09680317271314, + 55.25516648543737, + 55.404337880606256, + 55.55260192293612, + 55.70100143229448, + 55.84689530842236, + 55.98901658440931, + 56.1274801447216, + 56.266954479522866, + 56.398290155081085, + 56.52141291498931, + 56.639818795214296, + 56.75417643877159, + 56.86588439053571, + 56.97724895851334, + 57.08765418632386, + 57.194903490001494, + 57.302095010086965, + 57.4111502464549, + 57.52125196218386, + 57.63103824796659, + 57.74345404533255, + 57.85723979687369, + 57.96989623182933, + 58.082251173422755, + 58.193998337290665, + 58.30316282875393, + 58.41279646773634, + 58.52226490575659, + 58.62883440371537, + 58.733900490591566, + 58.83782226094718, + 58.93856533122835, + 59.03756024483546, + 59.135116845068765, + 59.23017499310952, + 59.32459931545914, + 59.41932113439755, + 59.510972975658966, + 59.601211201574046, + 59.689308873746064, + 59.77493653151537, + 59.85776452024836, + 59.941096147987736, + 60.02163587470475, + 60.10170195176904, + 60.18460267445845, + 60.263232971017366, + 60.33926511666251, + 60.41769819132252, + 60.495179538168934, + 60.570220558885225, + 60.64833769707762, + 60.73019306636724, + 60.81172843274648, + 60.89178449406931, + 60.97538424734452, + 61.05748686121893, + 61.136606124892936, + 61.216399925047156, + 61.293448043374816, + 61.36617121951862, + 61.43871449842724, + 61.510564895585645, + 61.57681795945674, + 61.64200146238275, + 61.70695730478563, + 61.76872440249366, + 61.82767457302494, + 61.88676427249198, + 61.943332805132165, + 61.99901608227632, + 62.05215932312734, + 62.103813847898344, + 62.15394203445875, + 62.201862856079764, + 62.24951191947457, + 62.29634182247722, + 62.34310520623603, + 62.39020576470519, + 62.438015061127025, + 62.48455579702712, + 62.530495442270784, + 62.57580279453953, + 62.62146665975984, + 62.667897127129066, + 62.71240911459497, + 62.753441841747254, + 62.79587534233998, + 62.83213741251281, + 62.864540001077366, + 62.892898865774384, + 62.9207419286591, + 62.94819145548893, + 62.97430483549647, + 62.99771545227248, + 63.02032406898697, + 63.043862817966506, + 63.065520088153946, + 63.08522345786388, + 63.10413648566231, + 63.12341713274369, + 63.13976962941787, + 63.15316861263422, + 63.16319691866358, + 63.16681037120316, + 63.16258576546753, + 63.15065501859352, + 63.13130205748566, + 63.10407062765513, + 63.069659479745, + 63.02757885766015, + 62.977488055501304, + 62.918935496376534, + 62.847733698542605, + 62.76560608451621, + 62.67557487074328, + 62.57220187688181, + 62.45885335213861, + 62.33653285337155, + 62.20024636437273, + 62.04708262626295, + 61.880802128259035, + 61.69602429674882, + 61.49496048924611, + 61.29084773812193, + 61.06874810301068, + 60.82581287630145, + 60.57639517485764, + 60.31534715831782, + 60.03931630033132, + 59.754994038584314, + 59.47036274404793, + 59.1715753454941, + 58.8625908398959, + 58.56693161420471, + 58.25656568451404, + 57.925795746722315, + 57.61280676055169, + 57.28595121383907, + 56.94111979189009, + 56.608454883131486, + 56.270588487932976, + 55.91067887127243, + 55.551892713296326, + 55.19792082565269, + 54.833086432303105, + 54.463140350791555, + 54.097272129762004, + 53.73312554031859, + 53.375446048491646, + 53.01450056636561, + 52.65013323361343, + 52.29745304089723, + 51.9502983136156, + 51.59424668940708, + 51.247238090189526, + 50.90315280372953, + 50.54905785577626, + 50.19696928216013, + 49.855216879994146, + 49.51076195171792, + 49.154018596198995, + 48.81857258633425, + 48.48865318120291, + 48.143320891553486, + 47.80972640693565, + 47.48871297119639, + 47.1512167145284, + 46.81997949432103, + 46.49637951304719, + 46.16083474483752, + 45.8274410700448, + 45.49846805089586, + 45.16070593469609, + 44.817721726843224, + 44.48321331151424, + 44.14153088138874, + 43.79062762329432, + 43.443213757129946, + 43.09318198656066, + 42.73562721602073, + 42.382947454964935, + 42.03219536972676, + 41.67843307535282, + 41.328529023447196, + 40.97344681645272, + 40.627303121565774, + 40.27364871945597, + 39.91782059955079, + 39.5640208647328, + 39.21084060759426, + 38.86200755971636, + 38.5055333369679, + 38.15261714586123, + 37.80319478493362, + 37.44814959969886, + 37.09327679201676, + 36.74140749230282, + 36.395768617004535, + 36.04201882293896, + 35.69140672805515, + 35.34625782172316, + 34.998131812084736, + 34.658060101582414, + 34.317091093958076, + 33.970542088840354, + 33.6356431092576, + 33.30204028703879, + 32.95188023809419, + 32.60846743182351, + 32.28153403172458, + 31.929165487454924, + 31.575270490308046, + 31.242567646197134, + 30.899120391448676, + 30.545351229558054, + 30.21400816570368, + 29.88511266633807, + 29.534345705160842, + 29.19952034673891, + 28.867191193189598, + 28.529758972681886, + 28.191057625758333, + 27.858915026211122, + 27.526308181645305, + 27.190103794311515, + 26.849015263509017, + 26.51499068605483, + 26.190509471998876, + 25.85229131803252, + 25.521173501037953, + 25.196906729390108, + 24.872561950203373, + 24.540782558185178, + 24.22042256237104, + 23.90379147736523, + 23.580770986210098, + 23.259193605999087, + 22.928224860142095, + 22.592313515169423, + 22.25120512719226, + 21.911808214257647, + 21.56848348644662, + 21.221891796361295, + 20.883161507515446, + 20.535772971541892, + 20.18594869984632, + 19.840256311549158, + 19.522894062647886, + 19.221767428364362, + 18.916869370600157, + 18.610694419625357, + 18.304527120903813, + 17.998193376915065, + 17.68614497829255, + 17.368374003372246, + 17.055898032511053, + 16.742428610601262, + 16.395708258790776, + 16.047696883677325, + 15.700350034610413, + 15.342330962379123, + 14.996353855710264, + 14.65303434823042, + 14.288252134843123, + 13.940287211306334, + 13.602940410547475, + 13.234047716816413, + 12.896610716579785, + 12.588389358956583, + 12.252416432126967, + 11.918681419217677, + 11.597451551881075, + 11.263986521165688, + 10.922164135037553, + 10.59205226676616, + 10.260804067987845, + 9.924129373158884, + 9.581488140247956, + 9.238636738886148, + 8.892296718298766, + 8.543953044630854, + 8.19932896820383, + 7.847807479737154, + 7.500880523391266, + 7.149134410768912, + 6.800151472885508, + 6.458298987676256, + 6.067467643415407, + 5.6663057329743864, + 5.264503893602143, + 4.8572832148179215, + 4.453235721366303, + 4.053094547937241, + 3.652960086725024, + 3.2470833617517623, + 2.8377152466977327, + 2.442170781170606, + 2.0733639653890075, + 1.7121062176798152, + 1.3553154484853542, + 1.008120248677175, + 0.6531759357421323, + 0.2957001583769022, + -0.045588823825584934, + -0.39040236296740793, + -0.7365156575763289, + -1.0759587364390546, + -1.42765018385535, + -1.7810083058053876, + -2.132145207433067, + -2.487960236796579, + -2.8473526621413052, + -3.1894780564959735, + -3.541628825093142, + -3.9018145842456127, + -4.244464990438296, + -4.597772037326932, + -4.938988118005556, + -5.259683603972067, + -5.586728562499185, + -5.918260677472239, + -6.238395573807465, + -6.555802078373068, + -6.879731327802897, + -7.191564412808025, + -7.505322713276001, + -7.813143843720128, + -8.10568855883533, + -8.403458055589457, + -8.691535697206799, + -8.96512686888636, + -9.232974116072883, + -9.495618210597758, + -9.751710520551049, + -9.995911282781275, + -10.234816636036385, + -10.466279546186946, + -10.691092941439853, + -10.909667557359215, + -11.118302880163718, + -11.322286401467391, + -11.516752150838526, + -11.696961868980662, + -11.868592194147638, + -12.029254118218732, + -12.169693663933018, + -12.288543113346856, + -12.396469529359633, + -12.48652212662586, + -12.552545055998337, + -12.59818074208725, + -12.624269391935025, + -12.629106635940238, + -12.614101957322276, + -12.577234483587432, + -12.520041035001883, + -12.442057338132571, + -12.339029238408774, + -12.228663788046836, + -12.097357603808792, + -11.948131239600722, + -11.782771255608534, + -11.599891594303266, + -11.40369688475966, + -11.196285598363788, + -10.97561484954418, + -10.742889917127997, + -10.495056045696266, + -10.239725653017821, + -9.971596647763095, + -9.69362709385564, + -9.411177411156174, + -9.118580270417132, + -8.822237366562877, + -8.524324944016028, + -8.217322449982737, + -7.910114178832905, + -7.601505598627543, + -7.284268983769043, + -6.9686018967643735, + -6.653185389937518, + -6.331826886778154, + -6.010864554039517, + -5.690842623903828, + -5.371808261193764, + -5.054195012682517, + -4.733805838736679, + -4.416618655951184, + -4.10299996747427, + -3.788231790806858, + -3.473462289396849, + -3.160723804066829, + -2.8480700036458626, + -2.538085486383813, + -2.2298726158062685, + -1.9203394273430623, + -1.6213310265684997, + -1.3227658015797874, + -1.0184324606870485, + -0.7249762027226001, + -0.4322715980699082, + -0.14508058340152255, + 0.15235075104773366, + 0.4419773073619327, + 0.7171089936424838, + 1.0054662364139046, + 1.2892299372113842, + 1.5605599943474036, + 1.8373176021811874, + 2.1208128844037812, + 2.3930942708221936, + 2.661157093171031, + 2.9351009213663573, + 3.2013135802439643, + 3.46178745605126, + 3.726781028256172, + 3.9861202558622395, + 4.237716202058085, + 4.492567951177932, + 4.741130887136513, + 4.993463675497179, + 5.245831451551488, + 5.495833298364509, + 5.74944512382775, + 6.00536853669388, + 6.260677354889801, + 6.513063815117789, + 6.770365841426887, + 7.023898623723458, + 7.276124508341358, + 7.531558524567593, + 7.784017237435444, + 8.034259964974401, + 8.284689138222124, + 8.535342159440725, + 8.779928423684392, + 9.030426110527335, + 9.283448483197963, + 9.529826705558682, + 9.786024332313293, + 10.041049836365245, + 10.293593384284025, + 10.55281780802128, + 10.81738048985599, + 11.088002760129802, + 11.35617748549179, + 11.631303476708556, + 11.919522587916266, + 12.207777129396131, + 12.504517114288772, + 12.804301013902991, + 13.101980739751278, + 13.409195325961342, + 13.720499712703655, + 14.036892550655365, + 14.362011516524657, + 14.695609050562826, + 15.031900523752672, + 15.38259496943098, + 15.73981525956396, + 16.09709122612972, + 16.46417458246968, + 16.835838019024283, + 17.206555908693492, + 17.57279411182098, + 17.991427406425363, + 18.372803663965243, + 18.746692056133323, + 19.130651942000195, + 19.52018427367376, + 19.900199475698994, + 20.28545860993254, + 20.674789782189027, + 21.059827285836285, + 21.441772860971263, + 21.827496927549927, + 22.211904051257765, + 22.59551358289561, + 22.979273351188308, + 23.363501395093923, + 23.744613641519187, + 24.126580476455306, + 24.504983215049606, + 24.88230034185392, + 25.258633532933196, + 25.63812818572565, + 26.01412035014803, + 26.39250284579615, + 26.767103944085427, + 27.146009381300964, + 27.51170048987215, + 27.87410896255844, + 28.241952288576122, + 28.602691943464166, + 28.95355977046983, + 29.313446394771386, + 29.668189436415958, + 30.015513608150005, + 30.360145692133205, + 30.698401782550082, + 31.035309387674015, + 31.355796543763514, + 31.674132913036836, + 31.99673504156595, + 32.31082093979031, + 32.62140843180969, + 32.92821709329264, + 33.229568166137355, + 33.525258079597634, + 33.79812562467964, + 34.06653626079953, + 34.321557028165536, + 34.55231789168267, + 34.78432485260065, + 34.998310715271934, + 35.197683409277694, + 35.3938340601963, + 35.5725446714508, + 35.731257533845074, + 35.89134601101259, + 36.03495718213001, + 36.15892083376345, + 36.28134096300529, + 36.389296709138954, + 36.48105293487644, + 36.56944746692986, + 36.64455672695461, + 36.71000569805783, + 36.76410075508549, + 36.80649007590402, + 36.84359396210188, + 36.875750921106814, + 36.902926290955435, + 36.92854379253948, + 36.95410207191664, + 36.98011036055201, + 37.00537275589032, + 37.01320860167798, + 37.01985694270312, + 37.025749134491626, + 37.03169101143714, + 37.03688238596416, + 37.041405491709455, + 37.045811110102896, + 37.04987485131563, + 37.0534028622793, + 37.056311229292355, + 37.08321001137313, + 37.11314971410027, + 37.143528791302856, + 37.17446579043236, + 37.20591960279453, + 37.237896668859186, + 37.27040584185612, + 37.303362114184154, + 37.33723189714945, + 37.371875566971745, + 37.38034051641658, + 37.38583697011502, + 37.391522477780526, + 37.39717013777862, + 37.40280510310003, + 37.40858299711785, + 37.41430185704812, + 37.4200672221251, + 37.42589436129573, + 37.4317431418861, + 37.45154482485271, + 37.472932469680785, + 37.494409422589015, + 37.51584461079809, + 37.537293522947095, + 37.55875868362723, + 37.58020758034309, + 37.6016794688646, + 37.623156909146495, + 37.64470476223522, + 37.65231583624131, + 37.65853359551304, + 37.66481328947362, + 37.67100918601555, + 37.677132190172806, + 37.683396930808506, + 37.689682498981604, + 37.69590200806786, + 37.70226605813416, + 37.70857938006345, + 37.74377347336275, + 37.782708193364776, + 37.82160512511236, + 37.86032954299645, + 37.89879756115578, + 37.937202991114304, + 37.975692103694485, + 38.013981789777695, + 38.05207367964482, + 38.09055529940335, + 38.09868021371338, + 38.10333396589485, + 38.10787050330368, + 38.112195856538385, + 38.11651440069659, + 38.12081101898356, + 38.12515539439644, + 38.12996653572406, + 38.13438467616609, + 38.138710648102204, + 38.13987763102785, + 38.140980726973915, + 38.14190973106088, + 38.14284673668466, + 38.143966100564406, + 38.1450411963866, + 38.14602135520899, + 38.14704642208374, + 38.14814007552123 + ] + }, + { + "marker": { + "color": "red", + "size": 8, + "symbol": "star" + }, + "mode": "markers", + "name": "Landmarks", + "type": "scatter", + "x": [ + -48.11741249184751, + -80.9281129508125, + -47.60339748000676, + -17.70157972379622 + ], + "y": [ + 31.924679924108325, + 53.95372590607549, + -19.972945092661757, + 66.35356579052397 + ] + } + ], + "layout": { + "legend": { + "tracegroupgap": 0, + "x": 0.01, + "xanchor": "left", + "y": 0.99, + "yanchor": "top" + }, + "margin": { + "b": 20, + "l": 20, + "r": 20, + "t": 40 + }, + "template": { + "data": { + "bar": [ + { + "error_x": { + "color": "#2a3f5f" + }, + "error_y": { + "color": "#2a3f5f" + }, + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "bar" + } + ], + "barpolar": [ + { + "marker": { + "line": { + "color": "#E5ECF6", + "width": 0.5 + }, + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "barpolar" + } + ], + "carpet": [ + { + "aaxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "baxis": { + "endlinecolor": "#2a3f5f", + "gridcolor": "white", + "linecolor": "white", + "minorgridcolor": "white", + "startlinecolor": "#2a3f5f" + }, + "type": "carpet" + } + ], + "choropleth": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "choropleth" + } + ], + "contour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "contour" + } + ], + "contourcarpet": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "contourcarpet" + } + ], + "heatmap": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "heatmap" + } + ], + "heatmapgl": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "heatmapgl" + } + ], + "histogram": [ + { + "marker": { + "pattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + } + }, + "type": "histogram" + } + ], + "histogram2d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2d" + } + ], + "histogram2dcontour": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "histogram2dcontour" + } + ], + "mesh3d": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "type": "mesh3d" + } + ], + "parcoords": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "parcoords" + } + ], + "pie": [ + { + "automargin": true, + "type": "pie" + } + ], + "scatter": [ + { + "fillpattern": { + "fillmode": "overlay", + "size": 10, + "solidity": 0.2 + }, + "type": "scatter" + } + ], + "scatter3d": [ + { + "line": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatter3d" + } + ], + "scattercarpet": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattercarpet" + } + ], + "scattergeo": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergeo" + } + ], + "scattergl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattergl" + } + ], + "scattermapbox": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scattermapbox" + } + ], + "scatterpolar": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolar" + } + ], + "scatterpolargl": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterpolargl" + } + ], + "scatterternary": [ + { + "marker": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "type": "scatterternary" + } + ], + "surface": [ + { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + }, + "colorscale": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "type": "surface" + } + ], + "table": [ + { + "cells": { + "fill": { + "color": "#EBF0F8" + }, + "line": { + "color": "white" + } + }, + "header": { + "fill": { + "color": "#C8D4E3" + }, + "line": { + "color": "white" + } + }, + "type": "table" + } + ] + }, + "layout": { + "annotationdefaults": { + "arrowcolor": "#2a3f5f", + "arrowhead": 0, + "arrowwidth": 1 + }, + "autotypenumbers": "strict", + "coloraxis": { + "colorbar": { + "outlinewidth": 0, + "ticks": "" + } + }, + "colorscale": { + "diverging": [ + [ + 0, + "#8e0152" + ], + [ + 0.1, + "#c51b7d" + ], + [ + 0.2, + "#de77ae" + ], + [ + 0.3, + "#f1b6da" + ], + [ + 0.4, + "#fde0ef" + ], + [ + 0.5, + "#f7f7f7" + ], + [ + 0.6, + "#e6f5d0" + ], + [ + 0.7, + "#b8e186" + ], + [ + 0.8, + "#7fbc41" + ], + [ + 0.9, + "#4d9221" + ], + [ + 1, + "#276419" + ] + ], + "sequential": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ], + "sequentialminus": [ + [ + 0, + "#0d0887" + ], + [ + 0.1111111111111111, + "#46039f" + ], + [ + 0.2222222222222222, + "#7201a8" + ], + [ + 0.3333333333333333, + "#9c179e" + ], + [ + 0.4444444444444444, + "#bd3786" + ], + [ + 0.5555555555555556, + "#d8576b" + ], + [ + 0.6666666666666666, + "#ed7953" + ], + [ + 0.7777777777777778, + "#fb9f3a" + ], + [ + 0.8888888888888888, + "#fdca26" + ], + [ + 1, + "#f0f921" + ] + ] + }, + "colorway": [ + "#636efa", + "#EF553B", + "#00cc96", + "#ab63fa", + "#FFA15A", + "#19d3f3", + "#FF6692", + "#B6E880", + "#FF97FF", + "#FECB52" + ], + "font": { + "color": "#2a3f5f" + }, + "geo": { + "bgcolor": "white", + "lakecolor": "white", + "landcolor": "#E5ECF6", + "showlakes": true, + "showland": true, + "subunitcolor": "white" + }, + "hoverlabel": { + "align": "left" + }, + "hovermode": "closest", + "mapbox": { + "style": "light" + }, + "paper_bgcolor": "white", + "plot_bgcolor": "#E5ECF6", + "polar": { + "angularaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "radialaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "scene": { + "xaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "yaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + }, + "zaxis": { + "backgroundcolor": "#E5ECF6", + "gridcolor": "white", + "gridwidth": 2, + "linecolor": "white", + "showbackground": true, + "ticks": "", + "zerolinecolor": "white" + } + }, + "shapedefaults": { + "line": { + "color": "#2a3f5f" + } + }, + "ternary": { + "aaxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "baxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + }, + "bgcolor": "#E5ECF6", + "caxis": { + "gridcolor": "white", + "linecolor": "white", + "ticks": "" + } + }, + "title": { + "x": 0.05 + }, + "xaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + }, + "yaxis": { + "automargin": true, + "gridcolor": "white", + "linecolor": "white", + "ticks": "", + "title": { + "standoff": 15 + }, + "zerolinecolor": "white", + "zerolinewidth": 2 + } + } + }, + "title": { + "text": "Plaza2 Batch SLAM Result" + }, + "xaxis": { + "anchor": "y", + "domain": [ + 0, + 1 + ], + "title": { + "text": "X (m)" + } + }, + "yaxis": { + "anchor": "x", + "domain": [ + 0, + 1 + ], + "scaleanchor": "x", + "scaleratio": 1, + "title": { + "text": "Y (m)" + } + } + } + } + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "# Plot using Plotly (similar to iSAM example)\n", + "fig = px.line(x=positions_initial[:,0], y=positions_initial[:,1], title='Plaza2 Batch SLAM Result')\n", + "fig.data[0].name = 'Initial (Odometry)'\n", + "fig.data[0].showlegend = True\n", + "fig.data[0].line.color = 'orange'\n", + "fig.data[0].line.dash = 'dash'\n", + "\n", + "fig.add_scatter(x=positions_result[:,0], y=positions_result[:,1], mode='lines', \n", + " line=dict(color='black'), name='Optimized Path')\n", + "\n", + "fig.add_scatter(x=landmarks_result[:,0], y=landmarks_result[:,1], mode='markers', \n", + " marker=dict(color='red', symbol='star', size=8), name='Landmarks')\n", + "\n", + "# Configure layout\n", + "fig.update_layout(margin=dict(l=20, r=20, t=40, b=20), \n", + " legend=dict(yanchor=\"top\", y=0.99, xanchor=\"left\", x=0.01),\n", + " xaxis_title=\"X (m)\", yaxis_title=\"Y (m)\")\n", + "fig.update_yaxes(scaleanchor=\"x\", scaleratio=1) # Ensure aspect ratio is 1:1\n", + "fig.show()" + ] + } + ], + "metadata": { + "kernelspec": { + "display_name": "py312", + "language": "python", + "name": "python3" + }, + "language_info": { + "codemirror_mode": { + "name": "ipython", + "version": 3 + }, + "file_extension": ".py", + "mimetype": "text/x-python", + "name": "python", + "nbconvert_exporter": "python", + "pygments_lexer": "ipython3", + "version": "3.12.6" + }, + "orig_nbformat": 4 + }, + "nbformat": 4, + "nbformat_minor": 2 +}