diff --git a/gtsam/navigation/AHRSFactor.h b/gtsam/navigation/AHRSFactor.h index 496fcde3d..deea724be 100644 --- a/gtsam/navigation/AHRSFactor.h +++ b/gtsam/navigation/AHRSFactor.h @@ -29,7 +29,7 @@ namespace gtsam { /** - * PreintegratedAHRSMeasurements accumulates (integrates) the Gyroscope + * PreintegratedAHRSMeasurements accumulates (integrates) the gyroscope * measurements (rotation rates) and the corresponding covariance matrix. * Can be built incrementally so as to avoid costly integration at time of factor construction. */ @@ -49,7 +49,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation /** * Default constructor, initialize with no measurements - * @param bias Current estimate of acceleration and rotation rate biases + * @param bias Current estimate of rotation rate biases */ PreintegratedAhrsMeasurements(const std::shared_ptr& p, const Vector3& biasHat) : @@ -60,7 +60,7 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation /** * Non-Default constructor, initialize with measurements * @param p: Parameters for AHRS pre-integration - * @param bias_hat: Current estimate of acceleration and rotation rate biases + * @param bias_hat: Current estimate of rotation rate biases * @param deltaTij: Delta time in pre-integration * @param deltaRij: Delta rotation in pre-integration * @param delRdelBiasOmega: Jacobian of rotation wrt. to gyro bias @@ -87,11 +87,11 @@ class GTSAM_EXPORT PreintegratedAhrsMeasurements : public PreintegratedRotation /// equals bool equals(const PreintegratedAhrsMeasurements&, double tol = 1e-9) const; - /// Reset inetgrated quantities to zero + /// Reset integrated quantities to zero void resetIntegration(); /** - * Add a single Gyroscope measurement to the preintegration. + * Add a single gyroscope measurement to the preintegration. * Measurements are taken to be in the sensor * frame and conversion to the body frame is handled by `body_P_sensor` in * `PreintegratedRotationParams` (if provided). diff --git a/gtsam/navigation/PreintegratedRotation.cpp b/gtsam/navigation/PreintegratedRotation.cpp index 6c8e510e5..00e41fa98 100644 --- a/gtsam/navigation/PreintegratedRotation.cpp +++ b/gtsam/navigation/PreintegratedRotation.cpp @@ -27,7 +27,7 @@ namespace gtsam { void PreintegratedRotationParams::print(const string& s) const { cout << (s.empty() ? s : s + "\n") << endl; - cout << "gyroscopeCovariance:\n[\n" << gyroscopeCovariance << "\n]" << endl; + cout << "gyroscopeCovariance:\n" << gyroscopeCovariance << endl; if (omegaCoriolis) cout << "omegaCoriolis = (" << omegaCoriolis->transpose() << ")" << endl; if (body_P_sensor) body_P_sensor->print("body_P_sensor"); diff --git a/gtsam/navigation/PreintegratedRotation.h b/gtsam/navigation/PreintegratedRotation.h index a887ef321..9473ec51d 100644 --- a/gtsam/navigation/PreintegratedRotation.h +++ b/gtsam/navigation/PreintegratedRotation.h @@ -126,12 +126,12 @@ class GTSAM_EXPORT PreintegratedRotation { Rot3 deltaRij_; ///< Preintegrated relative orientation (in frame i) Matrix3 delRdelBiasOmega_; ///< Jacobian of preintegrated rotation w.r.t. angular rate bias - /// Default constructor for serialization - PreintegratedRotation() {} - - public: + public: /// @name Constructors /// @{ + + /// Default constructor for serialization + PreintegratedRotation() {} /// Default constructor, resets integration to zero explicit PreintegratedRotation(const std::shared_ptr& p) : p_(p) { @@ -149,9 +149,6 @@ class GTSAM_EXPORT PreintegratedRotation { /// @name Basic utilities /// @{ - /// Re-initialize PreintegratedMeasurements - void resetIntegration(); - /// check parameters equality: checks whether shared pointer points to same Params object. bool matchesParamsWith(const PreintegratedRotation& other) const { return p_ == other.p_; @@ -175,6 +172,9 @@ class GTSAM_EXPORT PreintegratedRotation { /// @name Main functionality /// @{ + /// Re-initialize PreintegratedMeasurements + void resetIntegration(); + /** * @brief Calculate an incremental rotation given the gyro measurement and a * time interval, and update both deltaTij_ and deltaRij_. diff --git a/gtsam/navigation/doc/AHRSFactor.ipynb b/gtsam/navigation/doc/AHRSFactor.ipynb new file mode 100644 index 000000000..452ca13c2 --- /dev/null +++ b/gtsam/navigation/doc/AHRSFactor.ipynb @@ -0,0 +1,215 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# AHRSFactor\n", + "\n", + "\"Open\n", + "\n", + "## Overview\n", + "\n", + "The `AHRSFactor` class implements a factor to implement an *Attitude and Heading Reference System* (AHRS) within GTSAM. It is a binary factor, taking preintegrated measurements from a gyroscope between two discrete time steps, typically denoted as $t_i$ and $t_j$. These preintegrated measurements encapsulate the rotational motion observed by an inertial measurement unit (IMU) between these two timestamps.\n", + "\n", + "The `AHRSFactor` thus constrains two attitude states (represented as elements of $SO(3)$) based solely on gyroscope measurements. Accelerometer or magnetometer aiding, needed to build a complete AHRS system, must be handled separately." + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam plotly" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Mathematical Formulation\n", + "\n", + "The `AHRSFactor` relies on the use of `PreintegratedRotation`, which applies successive exponential maps to each individual gyroscope measurement $\\omega$ over the interval $[t_i, t_j]$. In this approach, every measurement contributes a small rotation given by $\\exp(\\omega_k \\Delta t)$, and the overall preintegrated rotation is obtained by composing these incremental rotations:\n", + "$$\n", + "\\Delta R_{ij}^{meas} = \\prod_{k} \\exp(\\omega_k \\Delta t)\n", + "$$\n", + "\n", + "Given two estimated rotations $R_i$ at time $t_i$ and $R_j$ at time $t_j$, the factor enforces:\n", + "$$\n", + "R_j \\approx R_i \\cdot \\Delta R_{ij}^{meas}\n", + "$$\n", + "\n", + "The error term optimized by the factor graph is the rotational discrepancy captured by the logarithmic map:\n", + "$$\n", + "e = \\text{Log}\\left((\\Delta R_{ij}^{meas})^T \\cdot R_i^T R_j\\right)\n", + "$$\n", + "\n", + "Note: the reality is a bit more complicated, because the code also takes into account the effects of bias, and if desired, coriolis forces." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Key Functionality\n", + "\n", + "### Constructor\n", + "\n", + "The constructor initializes the factor using a preintegrated AHRS measurement object, relating orientation states at discrete time instances $t_i$ and $t_j$.\n", + "\n", + "### Core Methods\n", + "\n", + "- `evaluateError`: calculates the error between two estimated orientations at times $t_i$ and $t_j$, relative to the preintegrated gyroscopic measurements. The error is computed as:\n", + "\n", + " $$\n", + " \\text{error} = \\text{Log}\\left((\\Delta R_{ij}^{meas})^T \\cdot R_i^T R_j\\right)\n", + " $$\n", + "\n", + " Here:\n", + "\n", + " - $R_i, R_j$ are the estimated rotation matrices at times $t_i$ and $t_j$.\n", + " - $\\Delta R_{ij}^{meas}$ is the rotation matrix obtained by integrating gyroscope measurements from $t_i$ to $t_j$.\n", + " - $\\text{Log}(\\cdot)$ is the logarithmic map from $SO(3)$ to $\\mathbb{R}^3$.\n", + "\n", + " The resulting 3-dimensional error vector represents the rotational discrepancy.\n", + "\n", + "- `print`: outputs a readable representation of the internal state of the factor, including the associated time steps and preintegrated measurements, aiding debugging and verification.\n", + "\n", + "- `equals` determines if another `AHRSFactor` instance is identical, useful in testing scenarios or when verifying the correctness of factor graph constructions." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Usage\n", + "\n", + "First, create a PreintegratedAhrsMeasurements (PAM) object by supplying the necessary IMU parameters. " + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [], + "source": [ + "import numpy as np\n", + "from gtsam import PreintegrationParams, PreintegratedAhrsMeasurements\n", + "\n", + "params = PreintegrationParams.MakeSharedU(9.81)\n", + "params.setGyroscopeCovariance(np.deg2rad(1)*np.eye(3))\n", + "params.setAccelerometerCovariance(0.01*np.eye(3))\n", + "\n", + "biasHat = np.zeros(3) # Assuming no bias for simplicity\n", + "pam = PreintegratedAhrsMeasurements(params, biasHat) " + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\n", + "Next, integrate each gyroscope measurement along with its corresponding time interval to accumulate the preintegrated rotation." + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import Point3\n", + "np.random.seed(42) # For reproducibility\n", + "for _ in range(15): # Add 15 random measurements, biased to move around z-axis\n", + " omega = Point3(0,0,-0.5) + 0.1*np.random.randn(3) # Random angular velocity vector\n", + " pam.integrateMeasurement(omega, deltaT=0.1)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "Finally, construct the AHRSFactor using the accumulated PAM and the keys representing the rotation states at the two time instants." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [], + "source": [ + "from gtsam import AHRSFactor\n", + "bias_key = 0 # Key for the bias\n", + "i, j = 1, 2 # Indices of the two attitude unknowns\n", + "ahrs_factor = AHRSFactor(i, j, bias_key, pam)" + ] + }, + { + "cell_type": "code", + "execution_count": 5, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "AHRSFactor(1,2,0, preintegrated measurements: deltaTij [1.5]\n", + " deltaRij.ypr = ( -0.82321 -0.0142842 0.0228577)\n", + "biasHat [0 0 0]\n", + " PreintMeasCov [ 0.0261799 1.73472e-18 1.35525e-20\n", + "1.73472e-18 0.0261799 9.23266e-20\n", + "1.35525e-20 1.17738e-19 0.0261799 ]\n", + " noise model: diagonal sigmas [0.161802159; 0.161802159; 0.161802159];\n", + "\n" + ] + } + ], + "source": [ + "print(ahrs_factor)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [AHRSFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/AHRSFactor.h)\n", + "- [AHRSFactor.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/AHRSFactor.cpp)" + ] + } + ], + "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" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/PreintegratedRotation.ipynb b/gtsam/navigation/doc/PreintegratedRotation.ipynb new file mode 100644 index 000000000..40392cfdd --- /dev/null +++ b/gtsam/navigation/doc/PreintegratedRotation.ipynb @@ -0,0 +1,9073 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# PreintegratedRotation" + ] + }, + { + "cell_type": "markdown", + "metadata": { + "vscode": { + "languageId": "plaintext" + } + }, + "source": [ + "\"Open" + ] + }, + { + "cell_type": "code", + "execution_count": 1, + "metadata": { + "tags": [ + "remove-cell" + ] + }, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "Note: you may need to restart the kernel to use updated packages.\n" + ] + } + ], + "source": [ + "%pip install --quiet gtsam plotly" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "\n", + "## Overview\n", + "`PreintegratedRotation` is a class within GTSAM used primarily for pre-integrating rotation rate measurements in factor graph-based estimation problems. It facilitates efficient handling of rotation rate measurements, typically from gyroscopes in inertial measurement units (IMU). By preintegrating rotations between two time instances, it enables effective and accurate state estimation without repeatedly recalculating rotations from individual measurements.\n", + "\n", + "This is the base class for `PreintegratedAhrsMeasurements` defined in [AHRSFactor.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/AHRSFactor.h) and used in the `AHRSFactor`. The `IMUFactor` has its own integration classes, derived from [PreintegrationBase](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegrationBase.h).\n", + "\n", + "## Mathematical Background\n", + "The class employs exponential maps and logarithms in the Lie group $SO(3)$. The rotation integration leverages incremental updates via rotation matrices and their tangent spaces, utilizing efficient methods from Lie group theory:\n", + "\n", + "- **Exponential map**: Converts a rotation vector $\\omega$ into a rotation matrix using:\n", + " $$\n", + " R = \\exp([\\omega]_\\times)\n", + " $$\n", + "- **Logarithmic map**: Converts rotation matrices back into rotation vectors:\n", + " $$\n", + " \\omega = \\log(R)\n", + " $$\n", + "\n", + "Here, $[\\omega]_\\times$ denotes the skew-symmetric matrix associated with vector $\\omega$." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "The preintegration process updates rotations incrementally according to:\n", + "$$\n", + "R_{k+1} = R_k \\exp\\left(\\left[\\omega_{\\text{bias-corrected}}\\Delta t\\right]_\\times\\right)\n", + "$$\n", + "\n", + "Bias correction is performed as:\n", + "$$\n", + "\\omega_{\\text{bias-corrected}} = \\omega_{\\text{measured}} - b_\\omega\n", + "$$" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## PreintegratedRotation Parameters\n", + "\n", + "The `PreintegratedRotationParams` class configures the gyroscope preintegration:\n", + "\n", + "| Parameter | Description |\n", + "|-----------|-------------|\n", + "| `gyroscopeCovariance` | 3×3 continuous-time noise covariance matrix of gyroscope measurements (units: rad²/s²/Hz) |\n", + "| `omegaCoriolis` | Optional Coriolis acceleration compensation vector (for earth rotation effects) |\n", + "| `body_P_sensor` | Optional pose transformation between the IMU sensor frame and body frame |\n", + "\n", + "The covariance matrix represents the uncertainty in angular velocity measurements, which propagates into orientation uncertainty during integration. When the IMU is not located at the center of the body frame, the optional body-to-sensor transformation allows for proper handling of lever-arm effects.\n", + "\n", + "In C++ you typically create a `shared_ptr` to a single object and pass it to all `PreintegratedRotation` objects. In python this is automatic, as all objects are encapsulated in shared pointers:" + ] + }, + { + "cell_type": "code", + "execution_count": 2, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + "\n", + "gyroscopeCovariance:\n", + "1 0 0\n", + "0 1 0\n", + "0 0 1\n", + "\n" + ] + } + ], + "source": [ + "from gtsam import PreintegratedRotationParams\n", + "params = PreintegratedRotationParams()\n", + "print(params)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "You can (and should) configure using your gyroscope's noise covariance matrix and the optional Coriolis acceleration compensation vector:\n", + "\n", + "### Setters\n", + "- `setGyroscopeCovariance`: Sets the 3×3 continuous-time noise covariance matrix for gyroscope measurements.\n", + "- `setOmegaCoriolis`: Sets an optional Coriolis acceleration compensation vector.\n", + "- `setBodyPSensor`: Sets an optional pose transformation between the body frame and the sensor frame.\n", + "\n", + "### Getters\n", + "- `getGyroscopeCovariance`: Returns the gyroscope covariance matrix.\n", + "- `getOmegaCoriolis`: Returns the optional Coriolis acceleration vector.\n", + "- `getBodyPSensor`: Returns the optional body-to-sensor pose transformation." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Core Methods\n", + "\n", + "Typically you use these methods between timesteps $t_i$ and $t_j$:\n", + "- `PreintegratedRotation`: Constructs the object, needs a shared pointer to parameters.\n", + "- `resetIntegration`: Clears the integrated rotation, typically used after updating state estimates or correcting biases.\n", + "- `integrateGyroMeasurement`: Integrates incremental rotation measurements, given angular velocities and integration intervals.\n", + "\n", + "You can then query:\n", + "- `deltaTij`: Accumulated time interval.\n", + "- `deltaRij`: The integrated rotation between the two timestamps as element of $SO(3)$.\n", + "- `biascorrectedDeltaRij`: A *bias corrected* version of the integrated rotation, given an increment on the estimated bias." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Internals\n", + "- `delRdelBiasOmega`: Returns Jacobian of integrated rotation with respect to gyroscope bias. This is useful for updating bias estimates during optimization." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Example" + ] + }, + { + "cell_type": "code", + "execution_count": 3, + "metadata": {}, + "outputs": [ + { + "name": "stdout", + "output_type": "stream", + "text": [ + " deltaTij [1.5]\n", + " deltaRij.ypr = ( -0.82321 -0.0142842 0.0228577)\n", + "\n" + ] + } + ], + "source": [ + "from gtsam import PreintegratedRotation, Point3\n", + "import numpy as np\n", + "\n", + "# Create a PreintegratedRotation object using the params\n", + "preintegrated_rotation = PreintegratedRotation(params)\n", + "\n", + "# Add random omega measurements\n", + "biasHat = np.zeros(3) # Assuming no bias for simplicity\n", + "np.random.seed(42) # For reproducibility\n", + "rotations = [] # List to record integrated rotations\n", + "for _ in range(15): # Add 15 random measurements, biased to move around z-axis\n", + " omega = Point3(0,0,-0.5) + 0.1*np.random.randn(3) # Random angular velocity vector\n", + " preintegrated_rotation.integrateGyroMeasurement(omega, biasHat, deltaT=0.1)\n", + " rotations.append(preintegrated_rotation.deltaRij())\n", + "\n", + "print(preintegrated_rotation)" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "We can show the evolution of the integrated rotation by showing how it transforms the point (1,0,0) on the sphere." + ] + }, + { + "cell_type": "code", + "execution_count": 4, + "metadata": {}, + "outputs": [ + { + "data": { + "application/vnd.plotly.v1+json": { + "config": { + "plotlyServerURL": "https://plot.ly" + }, + "data": [ + { + "colorscale": [ + [ + 0, + "#440154" + ], + [ + 0.1111111111111111, + "#482878" + ], + [ + 0.2222222222222222, + "#3e4989" + ], + [ + 0.3333333333333333, + "#31688e" + ], + [ + 0.4444444444444444, + "#26828e" + ], + [ + 0.5555555555555556, + "#1f9e89" + ], + [ + 0.6666666666666666, + "#35b779" + ], + [ + 0.7777777777777778, + "#6ece58" + ], + [ + 0.8888888888888888, + "#b5de2b" + ], + [ + 1, + "#fde725" + ] + ], + "opacity": 0.3, + "showscale": false, + "type": "surface", + "x": [ + [ + 0, + 0.06407021998071291, + 0.127877161684506, + 0.1911586287013723, + 0.25365458390950735, + 0.31510821802362066, + 0.3752670048793741, + 0.4338837391175581, + 0.49071755200393785, + 0.5455349012105486, + 0.5981105304912159, + 0.6482283953077884, + 0.6956825506034864, + 0.7402779970753155, + 0.7818314824680298, + 0.8201722545969559, + 0.8551427630053461, + 0.886599306373, + 0.9144126230158124, + 0.9384684220497603, + 0.9586678530366606, + 0.9749279121818236, + 0.9871817834144502, + 0.9953791129491982, + 0.9994862162006879, + 0.9994862162006879, + 0.9953791129491982, + 0.9871817834144502, + 0.9749279121818236, + 0.9586678530366607, + 0.9384684220497604, + 0.9144126230158126, + 0.8865993063730001, + 0.8551427630053462, + 0.820172254596956, + 0.7818314824680299, + 0.7402779970753157, + 0.6956825506034865, + 0.6482283953077888, + 0.5981105304912161, + 0.545534901210549, + 0.49071755200393813, + 0.43388373911755823, + 0.3752670048793745, + 0.3151082180236209, + 0.2536545839095078, + 0.19115862870137254, + 0.1278771616845065, + 0.06407021998071323, + 1.2246467991473532e-16 + ], + [ + 0, + 0.06354420436032968, + 0.12682729195475367, + 0.1895892190021668, + 0.25157208328194003, + 0.3125211839094652, + 0.3721860679567226, + 0.4303215596170847, + 0.48668876768529507, + 0.5410560672126732, + 0.5932000513037121, + 0.6429064491429322, + 0.689971006479623, + 0.7342003249523721, + 0.7754126568044163, + 0.8134386517241579, + 0.8481220527419211, + 0.8793203383233581, + 0.9069053080210033, + 0.9307636092774119, + 0.9507972032151313, + 0.9669237674994794, + 0.9790770346186743, + 0.9872070641912558, + 0.9912804481818243, + 0.9912804481818243, + 0.9872070641912558, + 0.9790770346186743, + 0.9669237674994794, + 0.9507972032151314, + 0.930763609277412, + 0.9069053080210036, + 0.8793203383233582, + 0.8481220527419212, + 0.813438651724158, + 0.7754126568044164, + 0.7342003249523723, + 0.6899710064796231, + 0.6429064491429325, + 0.5932000513037123, + 0.5410560672126736, + 0.48668876768529534, + 0.4303215596170848, + 0.372186067956723, + 0.3125211839094654, + 0.2515720832819405, + 0.18958921900216705, + 0.12682729195475417, + 0.06354420436033, + 1.2145924658549477e-16 + ], + [ + 0, + 0.06197479466112418, + 0.12369492159743405, + 0.1849067595684226, + 0.24535877600196893, + 0.30480256059563077, + 0.36299384608786095, + 0.4196935120045804, + 0.47466856725649686, + 0.5276931075494681, + 0.5785492436737019, + 0.6270279968572571, + 0.672930157504642, + 0.7160671037917743, + 0.7562615767535142, + 0.7933484086787744, + 0.8271752018200734, + 0.8576029546285695, + 0.8845066329412399, + 0.907775683773077, + 0.927314489603017, + 0.9430427612868441, + 0.9548958679825054, + 0.9628251027321053, + 0.9667978826092422, + 0.9667978826092422, + 0.9628251027321053, + 0.9548958679825054, + 0.9430427612868441, + 0.9273144896030171, + 0.9077756837730772, + 0.8845066329412401, + 0.8576029546285696, + 0.8271752018200735, + 0.7933484086787745, + 0.7562615767535144, + 0.7160671037917745, + 0.6729301575046421, + 0.6270279968572574, + 0.5785492436737021, + 0.5276931075494685, + 0.47466856725649714, + 0.4196935120045805, + 0.36299384608786134, + 0.304802560595631, + 0.24535877600196934, + 0.18490675956842284, + 0.12369492159743453, + 0.061974794661124495, + 1.1845945578524248e-16 + ], + [ + 0, + 0.059387760546968704, + 0.11853148404721524, + 0.17718813625458818, + 0.23511668440335493, + 0.2920790876635377, + 0.34784127530174314, + 0.4021741085280142, + 0.45485432207626786, + 0.505665441649164, + 0.5543986734574267, + 0.6008537621983103, + 0.6448398139475933, + 0.6861760805836592, + 0.7246927025202993, + 0.760231406696186, + 0.7926461569528329, + 0.8218037541284933, + 0.8475843834020871, + 0.8698821066380016, + 0.888605297708614, + 0.903677019005703, + 0.9150353375935849, + 0.9226335797048304, + 0.9264405225327864, + 0.9264405225327864, + 0.9226335797048304, + 0.9150353375935849, + 0.903677019005703, + 0.8886052977086141, + 0.8698821066380017, + 0.8475843834020872, + 0.8218037541284934, + 0.792646156952833, + 0.7602314066961862, + 0.7246927025202994, + 0.6861760805836594, + 0.6448398139475934, + 0.6008537621983107, + 0.5543986734574269, + 0.5056654416491644, + 0.45485432207626814, + 0.40217410852801433, + 0.3478412753017435, + 0.2920790876635379, + 0.23511668440335534, + 0.1771881362545884, + 0.1185314840472157, + 0.059387760546969, + 1.1351456399598494e-16 + ], + [ + 0, + 0.055825581046495265, + 0.11142176280592091, + 0.16656008864208385, + 0.2210139833469895, + 0.27455968418697163, + 0.3269771603917619, + 0.3780510173081215, + 0.4275713815026731, + 0.47533476317685647, + 0.5211448923501592, + 0.5648135253755664, + 0.606161218473084, + 0.6450180651027222, + 0.6812243941469122, + 0.7146314260333781, + 0.7451018841023128, + 0.7725105587056182, + 0.7967448217202071, + 0.8177050893611193, + 0.835305231392655, + 0.8494729250559881, + 0.8601499522588952, + 0.8672924388063843, + 0.8708710346891732, + 0.8708710346891732, + 0.8672924388063843, + 0.8601499522588952, + 0.8494729250559881, + 0.8353052313926551, + 0.8177050893611194, + 0.7967448217202072, + 0.7725105587056184, + 0.7451018841023129, + 0.7146314260333783, + 0.6812243941469123, + 0.6450180651027223, + 0.6061612184730841, + 0.5648135253755667, + 0.5211448923501594, + 0.47533476317685686, + 0.4275713815026733, + 0.3780510173081216, + 0.3269771603917622, + 0.2745596841869718, + 0.22101398334698988, + 0.16656008864208408, + 0.11142176280592135, + 0.05582558104649554, + 1.0670576620419285e-16 + ], + [ + 0, + 0.05134674704861986, + 0.10248249929977425, + 0.15319712897887872, + 0.20328223879432783, + 0.2525320182866676, + 0.30074408954791937, + 0.34772033883581394, + 0.39326773066565324, + 0.4371991010345237, + 0.4793339265183303, + 0.5194990660812683, + 0.5575294725494782, + 0.5932688708252852, + 0.6265704000550977, + 0.6572972171121543, + 0.6853230589142861, + 0.7105327612660042, + 0.7328227320928807, + 0.7521013771236047, + 0.7682894762704882, + 0.7813205091618005, + 0.7911409284882434, + 0.7977103800403309, + 0.8010018685324929, + 0.8010018685324929, + 0.7977103800403309, + 0.7911409284882434, + 0.7813205091618005, + 0.7682894762704883, + 0.7521013771236047, + 0.732822732092881, + 0.7105327612660042, + 0.6853230589142862, + 0.6572972171121544, + 0.6265704000550978, + 0.5932688708252855, + 0.5575294725494782, + 0.5194990660812686, + 0.47933392651833046, + 0.4371991010345241, + 0.39326773066565346, + 0.347720338835814, + 0.3007440895479197, + 0.25253201828666777, + 0.2032822387943282, + 0.1531971289788789, + 0.10248249929977465, + 0.05134674704862012, + 9.814486268136805e-17 + ], + [ + 0, + 0.04602480088376357, + 0.09186047598840694, + 0.13731867669320363, + 0.18221260550070414, + 0.226357783627721, + 0.2695728090682192, + 0.3116801020130699, + 0.35250663456357667, + 0.3918846417402257, + 0.4296523108649721, + 0.46565444648424276, + 0.499743108100344, + 0.5317782180907005, + 0.5616281373168522, + 0.5891702060579113, + 0.6142912480456656, + 0.6368880355301407, + 0.6568677134645673, + 0.6741481810666854, + 0.6886584291884691, + 0.7003388321079476, + 0.709141392544086, + 0.7150299388879092, + 0.7179802738394011, + 0.7179802738394011, + 0.7150299388879092, + 0.709141392544086, + 0.7003388321079476, + 0.6886584291884692, + 0.6741481810666855, + 0.6568677134645675, + 0.6368880355301408, + 0.6142912480456656, + 0.5891702060579114, + 0.5616281373168522, + 0.5317782180907006, + 0.4997431081003441, + 0.465654446484243, + 0.42965231086497224, + 0.39188464174022597, + 0.35250663456357684, + 0.31168010201307, + 0.26957280906821945, + 0.22635778362772116, + 0.18221260550070445, + 0.1373186766932038, + 0.09186047598840728, + 0.046024800883763796, + 8.797242322667637e-17 + ], + [ + 0, + 0.03994712876082017, + 0.07973010620092988, + 0.11918545553260583, + 0.15815104626229826, + 0.19646676041960587, + 0.23397515051636136, + 0.2705220865321328, + 0.305957389267538, + 0.34013544746278873, + 0.3729158161455902, + 0.40416379374965783, + 0.43375097563234616, + 0.4615557817168686, + 0.48746395609091187, + 0.5113690365086868, + 0.5331727918671332, + 0.5527856258585924, + 0.5701269451412537, + 0.5851254905144835, + 0.5977196297381651, + 0.607857610792794, + 0.6154977745396268, + 0.6206087259070177, + 0.6231694628995023, + 0.6231694628995023, + 0.6206087259070177, + 0.6154977745396268, + 0.607857610792794, + 0.5977196297381651, + 0.5851254905144835, + 0.5701269451412538, + 0.5527856258585925, + 0.5331727918671333, + 0.5113690365086869, + 0.4874639560909119, + 0.4615557817168688, + 0.4337509756323462, + 0.40416379374965805, + 0.3729158161455904, + 0.340135447462789, + 0.3059573892675382, + 0.27052208653213283, + 0.2339751505163616, + 0.196466760419606, + 0.15815104626229853, + 0.119185455532606, + 0.0797301062009302, + 0.03994712876082036, + 7.635547901473156e-17 + ], + [ + 0, + 0.033213525888022094, + 0.06629057027389135, + 0.09909521248722244, + 0.13149265121658713, + 0.16334975843701763, + 0.19453562646161712, + 0.22492210586932482, + 0.254384332098375, + 0.2828012385415649, + 0.31005605403491204, + 0.3360367826954148, + 0.3606366641361582, + 0.3837546121676442, + 0.4052956301826273, + 0.4251712015175499, + 0.4432996531865001, + 0.4596064914930296, + 0.474024708140731, + 0.48649505558470113, + 0.4969662904924116, + 0.5053953843135537, + 0.5117477000935814, + 0.5159971348043871, + 0.5181262266072434, + 0.5181262266072434, + 0.5159971348043871, + 0.5117477000935814, + 0.5053953843135537, + 0.49696629049241164, + 0.4864950555847012, + 0.4740247081407311, + 0.4596064914930297, + 0.44329965318650016, + 0.42517120151754995, + 0.4052956301826274, + 0.38375461216764434, + 0.36063666413615825, + 0.336036782695415, + 0.31005605403491215, + 0.28280123854156514, + 0.2543843320983752, + 0.22492210586932487, + 0.19453562646161732, + 0.16334975843701774, + 0.13149265121658735, + 0.09909521248722258, + 0.06629057027389161, + 0.03321352588802226, + 6.348477994832602e-17 + ], + [ + 0, + 0.025934557838380178, + 0.051762545015657246, + 0.07737782879243389, + 0.1026751504732102, + 0.12755055793694137, + 0.15190183279860078, + 0.17562891044644982, + 0.1986342912289912, + 0.22082344110195082, + 0.24210518008894294, + 0.26239205695955137, + 0.28160070858519326, + 0.29965220249609603, + 0.3164723612317465, + 0.3319920671519871, + 0.3461475464562251, + 0.3588806312436586, + 0.3701389985376579, + 0.3798763852920998, + 0.3880527784961474, + 0.39463457959629433, + 0.39959474256002825, + 0.4029128850137795, + 0.4045753719984663, + 0.4045753719984663, + 0.4029128850137795, + 0.39959474256002825, + 0.39463457959629433, + 0.3880527784961474, + 0.3798763852920998, + 0.37013899853765797, + 0.3588806312436586, + 0.3461475464562251, + 0.33199206715198715, + 0.31647236123174655, + 0.2996522024960961, + 0.2816007085851933, + 0.26239205695955153, + 0.24210518008894302, + 0.22082344110195098, + 0.19863429122899132, + 0.17562891044644985, + 0.15190183279860095, + 0.12755055793694148, + 0.10267515047321037, + 0.07737782879243399, + 0.05176254501565745, + 0.025934557838380307, + 4.957166255030046e-17 + ], + [ + 0, + 0.018229745066031613, + 0.03638458019931885, + 0.05438990328809911, + 0.07217172659767089, + 0.08965698080186606, + 0.10677381524058427, + 0.1234518931695674, + 0.1396226807891687, + 0.15521972886443622, + 0.17017894577927234, + 0.18443886090263206, + 0.19794087718453124, + 0.21062951194389418, + 0.22245262485879105, + 0.23336163222220474, + 0.24331170658290424, + 0.25226196095105724, + 0.26017561681164136, + 0.2670201552552517, + 0.2727674506052745, + 0.2773938859923256, + 0.2808804504010323, + 0.28321281679037347, + 0.2843814009665643, + 0.2843814009665643, + 0.28321281679037347, + 0.2808804504010323, + 0.2773938859923256, + 0.2727674506052746, + 0.26702015525525175, + 0.2601756168116414, + 0.25226196095105724, + 0.24331170658290427, + 0.23336163222220477, + 0.22245262485879108, + 0.21062951194389423, + 0.19794087718453127, + 0.18443886090263215, + 0.1701789457792724, + 0.15521972886443633, + 0.13962268078916878, + 0.12345189316956742, + 0.10677381524058438, + 0.08965698080186613, + 0.07217172659767103, + 0.05438990328809919, + 0.03638458019931899, + 0.018229745066031703, + 3.484457982368154e-17 + ], + [ + 0, + 0.010225600383687304, + 0.020409181582013634, + 0.03050889707546375, + 0.04048324496669288, + 0.05029123852072506, + 0.059892574588238746, + 0.06924779921985241, + 0.07831846979086533, + 0.08706731297024851, + 0.09545837788475688, + 0.10345718384877894, + 0.11103086205287002, + 0.11814829062874063, + 0.1247802225356889, + 0.13089940574296421, + 0.1364806952142072, + 0.14150115623379772, + 0.1459401586505207, + 0.14977946165128286, + 0.15300328871652613, + 0.1555983924493307, + 0.15755410901181044, + 0.15886240194511025, + 0.15951789519293927, + 0.15951789519293927, + 0.15886240194511025, + 0.15755410901181044, + 0.1555983924493307, + 0.15300328871652616, + 0.1497794616512829, + 0.14594015865052073, + 0.14150115623379772, + 0.13648069521420722, + 0.13089940574296424, + 0.12478022253568892, + 0.11814829062874067, + 0.11103086205287004, + 0.103457183848779, + 0.0954583778847569, + 0.08706731297024858, + 0.07831846979086539, + 0.06924779921985243, + 0.05989257458823881, + 0.0502912385207251, + 0.04048324496669295, + 0.030508897075463788, + 0.020409181582013713, + 0.010225600383687354, + 1.9545350059688153e-17 + ], + [ + 0, + 0.002053551625744841, + 0.004098664767374055, + 0.006126935616313293, + 0.008130029572581531, + 0.010099715493450158, + 0.012027899516974019, + 0.013906658321406279, + 0.015728271683827025, + 0.017485254204195225, + 0.019170386064463127, + 0.020776742696357237, + 0.02229772323591468, + 0.023727077647849114, + 0.02505893240828634, + 0.02628781464033378, + 0.02740867460330552, + 0.02841690644319002, + 0.029308367119092134, + 0.03007939342787687, + 0.0307268170570568, + 0.0312479776040677, + 0.0316407335084333, + 0.0319034708518967, + 0.03203510999035662, + 0.03203510999035662, + 0.0319034708518967, + 0.0316407335084333, + 0.0312479776040677, + 0.030726817057056804, + 0.030079393427876872, + 0.02930836711909214, + 0.028416906443190025, + 0.027408674603305525, + 0.026287814640333782, + 0.025058932408286348, + 0.02372707764784912, + 0.022297723235914682, + 0.020776742696357247, + 0.019170386064463134, + 0.01748525420419524, + 0.01572827168382703, + 0.013906658321406282, + 0.012027899516974031, + 0.010099715493450165, + 0.008130029572581545, + 0.006126935616313302, + 0.004098664767374071, + 0.0020535516257448516, + 3.92518618807508e-18 + ], + [ + 0, + -0.006152216393118851, + -0.0122791520094321, + -0.018355629956268747, + -0.024356680682344804, + -0.030257644583005488, + -0.036034273331830194, + -0.04166282952220702, + -0.047120184209428186, + -0.052383911952485, + -0.05743238296501517, + -0.062244851996734595, + -0.06680154358012054, + -0.07108373329204962, + -0.07507382469646869, + -0.07875542165192508, + -0.08211339568682872, + -0.08513394816558706, + -0.08780466699015839, + -0.09011457760402515, + -0.09205418808900069, + -0.09361552816955712, + -0.09479218196439701, + -0.09557931435068594, + -0.09597369083260925, + -0.09597369083260925, + -0.09557931435068594, + -0.09479218196439701, + -0.09361552816955712, + -0.0920541880890007, + -0.09011457760402516, + -0.0878046669901584, + -0.08513394816558707, + -0.08211339568682874, + -0.07875542165192509, + -0.0750738246964687, + -0.07108373329204964, + -0.06680154358012055, + -0.06224485199673463, + -0.05743238296501519, + -0.05238391195248504, + -0.04712018420942821, + -0.04166282952220703, + -0.03603427333183023, + -0.030257644583005512, + -0.024356680682344846, + -0.01835562995626877, + -0.012279152009432148, + -0.006152216393118882, + -1.1759429132228557e-17 + ], + [ + 0, + -0.014256965188894749, + -0.02845534544971889, + -0.04253679659243768, + -0.05644345491384388, + -0.07011817497192599, + -0.08350476440874709, + -0.09654821485689687, + -0.1091949279806725, + -0.12139293572313695, + -0.13309211385401198, + -0.144244387940892, + -0.1548039308973987, + -0.16472735129650895, + -0.17397387167523579, + -0.18250549609797065, + -0.19028716628993278, + -0.19728690569914042, + -0.20347595089492174, + -0.20882886976302126, + -0.2133236660116124, + -0.216941869558779, + -0.21966861243004346, + -0.22149268985406328, + -0.2224066063054398, + -0.2224066063054398, + -0.22149268985406328, + -0.21966861243004346, + -0.216941869558779, + -0.21332366601161243, + -0.20882886976302129, + -0.2034759508949218, + -0.19728690569914045, + -0.1902871662899328, + -0.18250549609797068, + -0.1739738716752358, + -0.16472735129650898, + -0.15480393089739872, + -0.1442443879408921, + -0.13309211385401204, + -0.12139293572313704, + -0.10919492798067257, + -0.0965482148568969, + -0.08350476440874718, + -0.07011817497192604, + -0.05644345491384398, + -0.04253679659243773, + -0.028455345449719, + -0.01425696518889482, + -2.7250954951287993e-17 + ], + [ + 0, + -0.022127615010424057, + -0.04416430290441175, + -0.06601951020455195, + -0.08760342917612111, + -0.10882736686632898, + -0.1296041095626861, + -0.14984828117285584, + -0.1694766940533308, + -0.18840869084530373, + -0.20656647591305585, + -0.22387543502291118, + -0.24026444194912708, + -0.25566615074681287, + -0.2700172724908626, + -0.28325883534372415, + -0.2953364268833286, + -0.3062004176954046, + -0.31580616531138656, + -0.32411419765389404, + -0.3310903752359643, + -0.3367060314475272, + -0.340938090352655, + -0.34376916151353265, + -0.3451876114514973, + -0.3451876114514973, + -0.34376916151353265, + -0.340938090352655, + -0.3367060314475272, + -0.33109037523596435, + -0.3241141976538941, + -0.31580616531138667, + -0.3062004176954047, + -0.2953364268833286, + -0.28325883534372415, + -0.27001727249086266, + -0.2556661507468129, + -0.2402644419491271, + -0.2238754350229113, + -0.20656647591305594, + -0.18840869084530387, + -0.16947669405333088, + -0.14984828117285587, + -0.12960410956268623, + -0.10882736686632904, + -0.08760342917612127, + -0.06601951020455205, + -0.04416430290441192, + -0.022127615010424168, + -4.2295020843440566e-17 + ], + [ + 0, + -0.02963493000523314, + -0.059148083726402234, + -0.08841818528431536, + -0.11732495755325396, + -0.14574961640548179, + -0.17357535882070482, + -0.20068784285473587, + -0.22697565749506948, + -0.25233078047263, + -0.27664902214844583, + -0.2998304536512246, + -0.32177981750651985, + -0.3424069190701263, + -0.36162699715721996, + -0.3793610723442469, + -0.3955362715123164, + -0.41008612729847777, + -0.42295085122437115, + -0.4340775793799106, + -0.44342058965242914, + -0.4509414896086477, + -0.45660937425741815, + -0.4604009530449612, + -0.46230064556074785, + -0.46230064556074785, + -0.4604009530449612, + -0.45660937425741815, + -0.4509414896086477, + -0.4434205896524292, + -0.4340775793799106, + -0.42295085122437126, + -0.4100861272984778, + -0.39553627151231646, + -0.37936107234424693, + -0.36162699715722, + -0.34240691907012644, + -0.3217798175065199, + -0.2998304536512248, + -0.27664902214844594, + -0.25233078047263025, + -0.22697565749506962, + -0.20068784285473593, + -0.173575358820705, + -0.1457496164054819, + -0.11732495755325417, + -0.08841818528431548, + -0.05914808372640246, + -0.029634930005233286, + -5.664460366265281e-17 + ], + [ + 0, + -0.03665564026865816, + -0.07316065464884222, + -0.10936503620616299, + -0.14512001337098593, + -0.18027866127272224, + -0.21469650548563737, + -0.24823211570525602, + -0.2807476869158199, + -0.3121096056606567, + -0.3421889990885334, + -0.3708622645198453, + -0.39801157735653875, + -0.42352537524865863, + -0.4472988165279737, + -0.46923421102488, + -0.4892414214982625, + -0.5072382340287528, + -0.5231506958533589, + -0.5369134192532314, + -0.5484698502458251, + -0.5577725009773447, + -0.5647831448605221, + -0.5694729736558629, + -0.5718227158508821, + -0.5718227158508821, + -0.5694729736558629, + -0.5647831448605221, + -0.5577725009773447, + -0.5484698502458251, + -0.5369134192532314, + -0.5231506958533592, + -0.5072382340287529, + -0.48924142149826255, + -0.4692342110248801, + -0.44729881652797376, + -0.42352537524865874, + -0.3980115773565388, + -0.3708622645198455, + -0.34218899908853356, + -0.312109605660657, + -0.2807476869158201, + -0.2482321157052561, + -0.2146965054856376, + -0.18027866127272238, + -0.14512001337098618, + -0.10936503620616314, + -0.07316065464884251, + -0.03665564026865834, + -7.00640836557489e-17 + ], + [ + 0, + -0.04307446593227168, + -0.0859719296445837, + -0.12851611625706505, + -0.17053220258122562, + -0.2118475355059372, + -0.252292341466101, + -0.29170042407864316, + -0.3299098470791013, + -0.3667635997524712, + -0.4021102421239128, + -0.43580452725809077, + -0.4677079981099873, + -0.4976895564745989, + -0.5256260016975813, + -0.5514025369331647, + -0.5749132408690162, + -0.5960615029796337, + -0.6147604205197164, + -0.6309331556261868, + -0.6445132510614519, + -0.6554449033004467, + -0.663683191839289, + -0.6691942637832655, + -0.6719554729556372, + -0.6719554729556372, + -0.6691942637832655, + -0.663683191839289, + -0.6554449033004467, + -0.644513251061452, + -0.6309331556261869, + -0.6147604205197165, + -0.5960615029796337, + -0.5749132408690163, + -0.5514025369331647, + -0.5256260016975814, + -0.49768955647459906, + -0.46770799810998737, + -0.43580452725809105, + -0.4021102421239129, + -0.3667635997524715, + -0.32990984707910154, + -0.2917004240786432, + -0.2522923414661013, + -0.21184753550593735, + -0.17053220258122592, + -0.12851611625706522, + -0.08597192964458404, + -0.0430744659322719, + -8.233311333224372e-17 + ], + [ + 0, + -0.04878601005613519, + -0.0973715479323834, + -0.14555696523204592, + -0.1931442577396988, + -0.23993787906298591, + -0.28574554417468956, + -0.33037901955315246, + -0.3736548966741939, + -0.4153953456760771, + -0.4554288461005551, + -0.4935908917072249, + -0.5297246664649554, + -0.5636816889425967, + -0.59532242245103, + -0.6245168484293526, + -0.6511450007190351, + -0.6750974585305987, + -0.6962757960771091, + -0.7145929870268489, + -0.7299737621131803, + -0.7423549184321078, + -0.7516855791565671, + -0.757927402600221, + -0.7610547397716725, + -0.7610547397716725, + -0.757927402600221, + -0.7516855791565671, + -0.7423549184321078, + -0.7299737621131804, + -0.7145929870268489, + -0.6962757960771092, + -0.6750974585305987, + -0.6511450007190352, + -0.6245168484293526, + -0.59532242245103, + -0.5636816889425968, + -0.5297246664649555, + -0.4935908917072252, + -0.4554288461005553, + -0.41539534567607744, + -0.3736548966741941, + -0.3303790195531525, + -0.28574554417468984, + -0.23993787906298608, + -0.19314425773969912, + -0.1455569652320461, + -0.09737154793238377, + -0.048786010056135434, + -9.32502355640449e-17 + ], + [ + 0, + -0.05369648924363901, + -0.1071723280951151, + -0.16020777286205606, + -0.2125848895258473, + -0.2640884492792611, + -0.31450681294779165, + -0.36363280066042, + -0.4112645431961434, + -0.457206311507906, + -0.5012693210152365, + -0.5432725073605832, + -0.5830432704415978, + -0.6204181836619785, + -0.6552436654864092, + -0.6873766105400307, + -0.7166849776591226, + -0.7430483324765678, + -0.7663583423124991, + -0.7865192213365194, + -0.8034481241722242, + -0.8170754863266232, + -0.8273453100455638, + -0.8342153944205147, + -0.8376575088011508, + -0.8376575088011508, + -0.8342153944205147, + -0.8273453100455638, + -0.8170754863266232, + -0.8034481241722243, + -0.7865192213365195, + -0.7663583423124992, + -0.7430483324765679, + -0.7166849776591228, + -0.6873766105400309, + -0.6552436654864093, + -0.6204181836619788, + -0.5830432704415979, + -0.5432725073605834, + -0.5012693210152366, + -0.4572063115079064, + -0.41126454319614364, + -0.36363280066042003, + -0.314506812947792, + -0.2640884492792613, + -0.2125848895258477, + -0.16020777286205629, + -0.10717232809511551, + -0.053696489243639275, + -1.0263619150592636e-16 + ], + [ + 0, + -0.05772527356228186, + -0.11521334159346397, + -0.17222797329085426, + -0.22853488330320798, + -0.2839026944594901, + -0.3381038885473012, + -0.39091574123401485, + -0.44212123728883435, + -0.491509962344926, + -0.538878967537186, + -0.5840336034626599, + -0.6267883200366905, + -0.6669674289580173, + -0.7044058256496908, + -0.7389496677091939, + -0.7704570070798733, + -0.7987983733459518, + -0.823857305754238, + -0.8455308317763421, + -0.8637298902448827, + -0.8783796973249266, + -0.8894200538168082, + -0.8968055925275532, + -0.9005059646944062, + -0.9005059646944062, + -0.8968055925275532, + -0.8894200538168082, + -0.8783796973249266, + -0.8637298902448828, + -0.8455308317763423, + -0.8238573057542382, + -0.7987983733459518, + -0.7704570070798734, + -0.738949667709194, + -0.7044058256496909, + -0.6669674289580175, + -0.6267883200366906, + -0.5840336034626602, + -0.5388789675371862, + -0.4915099623449264, + -0.44212123728883457, + -0.39091574123401496, + -0.33810388854730156, + -0.28390269445949035, + -0.2285348833032084, + -0.17222797329085449, + -0.11521334159346441, + -0.057725273562282145, + -1.103368640208112e-16 + ], + [ + 0, + -0.06080621048493336, + -0.12136255520809289, + -0.1814201951597159, + -0.24073234061491783, + -0.29905526524560794, + -0.3561493076442506, + -0.4117798561439962, + -0.46571831288834387, + -0.5177430331887685, + -0.5676402363102881, + -0.6152048839423602, + -0.660241522745279, + -0.7025650875098751, + -0.7420016616301545, + -0.7783891917639383, + -0.8115781537448059, + -0.8414321670089682, + -0.8678285550122568, + -0.8906588493343588, + -0.9098292353988218, + -0.9252609379772722, + -0.9368905448937251, + -0.944670267598818, + -0.9485681375432105, + -0.9485681375432105, + -0.944670267598818, + -0.9368905448937251, + -0.9252609379772722, + -0.9098292353988219, + -0.8906588493343588, + -0.867828555012257, + -0.8414321670089683, + -0.811578153744806, + -0.7783891917639384, + -0.7420016616301546, + -0.7025650875098753, + -0.6602415227452791, + -0.6152048839423605, + -0.5676402363102884, + -0.5177430331887689, + -0.46571831288834414, + -0.4117798561439963, + -0.35614930764425096, + -0.29905526524560816, + -0.24073234061491824, + -0.18142019515971616, + -0.12136255520809337, + -0.06080621048493366, + -1.1622580827890157e-16 + ], + [ + 0, + -0.06288871111250068, + -0.12551899902145386, + -0.18763350243968704, + -0.24897697954913547, + -0.3092973568442219, + -0.3683467649559604, + -0.42588255720036167, + -0.4816683066657045, + -0.5354747777414302, + -0.5870808680964368, + -0.6362745172359838, + -0.6828535779037522, + -0.726626646748281, + -0.7674138508403942, + -0.8050475868096494, + -0.8393732095625379, + -0.8702496677523451, + -0.8975500833893896, + -0.9211622732098981, + -0.9409892096610991, + -0.9569494196082502, + -0.9689773191252241, + -0.9770234829929294, + -0.9810548477981369, + -0.9810548477981369, + -0.9770234829929294, + -0.9689773191252241, + -0.9569494196082502, + -0.9409892096610992, + -0.9211622732098982, + -0.8975500833893898, + -0.8702496677523452, + -0.839373209562538, + -0.8050475868096495, + -0.7674138508403943, + -0.7266266467482813, + -0.6828535779037523, + -0.6362745172359842, + -0.5870808680964369, + -0.5354747777414306, + -0.48166830666570476, + -0.4258825572003618, + -0.3683467649559608, + -0.3092973568442221, + -0.24897697954913592, + -0.1876335024396873, + -0.12551899902145436, + -0.062888711112501, + -1.2020632797828825e-16 + ], + [ + 0, + -0.063938580842253, + -0.1276144243410426, + -0.19076587279700669, + -0.25313342336249645, + -0.31446079439444075, + -0.37449597857058936, + -0.432992278441656, + -0.48970932016405333, + -0.5444140412475769, + -0.5968816482591685, + -0.6468965405473512, + -0.6942531961915519, + -0.7387570165357581, + -0.7802251258361357, + -0.818487122736688, + -0.8533857804849779, + -0.8847776930105793, + -0.9125338642113802, + -0.9365402380262364, + -0.9566981671157919, + -0.9729248182255554, + -0.985153512565511, + -0.993333999807569, + -0.9974326645749431, + -0.9974326645749431, + -0.993333999807569, + -0.985153512565511, + -0.9729248182255554, + -0.956698167115792, + -0.9365402380262365, + -0.9125338642113804, + -0.8847776930105794, + -0.853385780484978, + -0.8184871227366881, + -0.7802251258361358, + -0.7387570165357583, + -0.694253196191552, + -0.6468965405473516, + -0.5968816482591687, + -0.5444140412475773, + -0.4897093201640536, + -0.4329922784416561, + -0.37449597857058975, + -0.31446079439444097, + -0.2531334233624969, + -0.19076587279700694, + -0.1276144243410431, + -0.06393858084225332, + -1.2221306309555476e-16 + ], + [ + 0, + -0.063938580842253, + -0.1276144243410426, + -0.19076587279700669, + -0.25313342336249645, + -0.31446079439444075, + -0.37449597857058936, + -0.432992278441656, + -0.48970932016405333, + -0.5444140412475769, + -0.5968816482591685, + -0.6468965405473512, + -0.6942531961915519, + -0.7387570165357581, + -0.7802251258361357, + -0.818487122736688, + -0.8533857804849779, + -0.8847776930105793, + -0.9125338642113802, + -0.9365402380262364, + -0.9566981671157919, + -0.9729248182255554, + -0.985153512565511, + -0.993333999807569, + -0.9974326645749431, + -0.9974326645749431, + -0.993333999807569, + -0.985153512565511, + -0.9729248182255554, + -0.956698167115792, + -0.9365402380262365, + -0.9125338642113804, + -0.8847776930105794, + -0.853385780484978, + -0.8184871227366881, + -0.7802251258361358, + -0.7387570165357583, + -0.694253196191552, + -0.6468965405473516, + -0.5968816482591687, + -0.5444140412475773, + -0.4897093201640536, + -0.4329922784416561, + -0.37449597857058975, + -0.31446079439444097, + -0.2531334233624969, + -0.19076587279700694, + -0.1276144243410431, + -0.06393858084225332, + -1.2221306309555476e-16 + ], + [ + 0, + -0.06288871111250069, + -0.1255189990214539, + -0.18763350243968707, + -0.2489769795491355, + -0.30929735684422194, + -0.36834676495596047, + -0.4258825572003617, + -0.48166830666570454, + -0.5354747777414303, + -0.5870808680964368, + -0.6362745172359839, + -0.6828535779037523, + -0.726626646748281, + -0.7674138508403943, + -0.8050475868096495, + -0.8393732095625379, + -0.8702496677523452, + -0.8975500833893897, + -0.9211622732098982, + -0.9409892096610992, + -0.9569494196082503, + -0.9689773191252242, + -0.9770234829929295, + -0.981054847798137, + -0.981054847798137, + -0.9770234829929295, + -0.9689773191252242, + -0.9569494196082503, + -0.9409892096610993, + -0.9211622732098983, + -0.8975500833893899, + -0.8702496677523454, + -0.839373209562538, + -0.8050475868096496, + -0.7674138508403944, + -0.7266266467482813, + -0.6828535779037525, + -0.6362745172359843, + -0.587080868096437, + -0.5354747777414307, + -0.4816683066657048, + -0.42588255720036183, + -0.36834676495596086, + -0.30929735684422216, + -0.24897697954913595, + -0.18763350243968732, + -0.12551899902145436, + -0.062888711112501, + -1.2020632797828827e-16 + ], + [ + 0, + -0.06080621048493337, + -0.12136255520809291, + -0.18142019515971597, + -0.24073234061491788, + -0.299055265245608, + -0.3561493076442507, + -0.4117798561439963, + -0.465718312888344, + -0.5177430331887687, + -0.5676402363102884, + -0.6152048839423603, + -0.6602415227452793, + -0.7025650875098753, + -0.7420016616301547, + -0.7783891917639384, + -0.8115781537448061, + -0.8414321670089684, + -0.867828555012257, + -0.8906588493343589, + -0.909829235398822, + -0.9252609379772724, + -0.9368905448937254, + -0.9446702675988182, + -0.9485681375432107, + -0.9485681375432107, + -0.9446702675988182, + -0.9368905448937254, + -0.9252609379772724, + -0.9098292353988221, + -0.890658849334359, + -0.8678285550122572, + -0.8414321670089685, + -0.8115781537448062, + -0.7783891917639385, + -0.7420016616301548, + -0.7025650875098755, + -0.6602415227452794, + -0.6152048839423606, + -0.5676402363102885, + -0.517743033188769, + -0.46571831288834425, + -0.41177985614399637, + -0.35614930764425107, + -0.2990552652456082, + -0.2407323406149183, + -0.1814201951597162, + -0.1213625552080934, + -0.060806210484933676, + -1.162258082789016e-16 + ], + [ + 0, + -0.05772527356228187, + -0.11521334159346398, + -0.1722279732908543, + -0.228534883303208, + -0.2839026944594902, + -0.3381038885473013, + -0.3909157412340149, + -0.4421212372888344, + -0.49150996234492605, + -0.5388789675371861, + -0.58403360346266, + -0.6267883200366905, + -0.6669674289580173, + -0.7044058256496909, + -0.738949667709194, + -0.7704570070798734, + -0.7987983733459518, + -0.8238573057542381, + -0.8455308317763423, + -0.8637298902448828, + -0.8783796973249267, + -0.8894200538168083, + -0.8968055925275533, + -0.9005059646944064, + -0.9005059646944064, + -0.8968055925275533, + -0.8894200538168083, + -0.8783796973249267, + -0.8637298902448829, + -0.8455308317763424, + -0.8238573057542383, + -0.7987983733459519, + -0.7704570070798735, + -0.7389496677091941, + -0.704405825649691, + -0.6669674289580175, + -0.6267883200366906, + -0.5840336034626603, + -0.5388789675371863, + -0.49150996234492644, + -0.4421212372888346, + -0.390915741234015, + -0.3381038885473016, + -0.28390269445949035, + -0.22853488330320842, + -0.1722279732908545, + -0.11521334159346443, + -0.05772527356228215, + -1.1033686402081121e-16 + ], + [ + 0, + -0.05369648924363904, + -0.10717232809511515, + -0.16020777286205615, + -0.21258488952584742, + -0.26408844927926123, + -0.3145068129477918, + -0.36363280066042014, + -0.41126454319614364, + -0.45720631150790625, + -0.5012693210152367, + -0.5432725073605834, + -0.5830432704415981, + -0.6204181836619789, + -0.6552436654864096, + -0.6873766105400311, + -0.7166849776591231, + -0.7430483324765681, + -0.7663583423124994, + -0.7865192213365199, + -0.8034481241722247, + -0.8170754863266235, + -0.8273453100455642, + -0.8342153944205151, + -0.8376575088011512, + -0.8376575088011512, + -0.8342153944205151, + -0.8273453100455642, + -0.8170754863266235, + -0.8034481241722248, + -0.78651922133652, + -0.7663583423124997, + -0.7430483324765682, + -0.7166849776591232, + -0.6873766105400312, + -0.6552436654864097, + -0.620418183661979, + -0.5830432704415982, + -0.5432725073605837, + -0.5012693210152369, + -0.45720631150790664, + -0.41126454319614386, + -0.36363280066042025, + -0.31450681294779215, + -0.2640884492792614, + -0.2125848895258478, + -0.16020777286205637, + -0.10717232809511557, + -0.0536964892436393, + -1.0263619150592641e-16 + ], + [ + 0, + -0.04878601005613522, + -0.09737154793238345, + -0.145556965232046, + -0.1931442577396989, + -0.23993787906298605, + -0.2857455441746897, + -0.33037901955315263, + -0.3736548966741941, + -0.4153953456760774, + -0.4554288461005554, + -0.4935908917072252, + -0.5297246664649558, + -0.5636816889425971, + -0.5953224224510303, + -0.624516848429353, + -0.6511450007190356, + -0.675097458530599, + -0.6962757960771095, + -0.7145929870268493, + -0.7299737621131808, + -0.7423549184321082, + -0.7516855791565675, + -0.7579274026002214, + -0.7610547397716729, + -0.7610547397716729, + -0.7579274026002214, + -0.7516855791565675, + -0.7423549184321082, + -0.7299737621131809, + -0.7145929870268494, + -0.6962757960771097, + -0.6750974585305991, + -0.6511450007190356, + -0.6245168484293531, + -0.5953224224510303, + -0.5636816889425972, + -0.5297246664649558, + -0.4935908917072255, + -0.45542884610055556, + -0.4153953456760777, + -0.3736548966741943, + -0.33037901955315274, + -0.28574554417469, + -0.23993787906298622, + -0.19314425773969923, + -0.14555696523204617, + -0.09737154793238384, + -0.04878601005613546, + -9.325023556404495e-17 + ], + [ + 0, + -0.04307446593227171, + -0.08597192964458376, + -0.12851611625706513, + -0.17053220258122573, + -0.21184753550593735, + -0.2522923414661012, + -0.29170042407864333, + -0.32990984707910154, + -0.36676359975247147, + -0.402110242123913, + -0.4358045272580911, + -0.4677079981099876, + -0.4976895564745992, + -0.5256260016975817, + -0.551402536933165, + -0.5749132408690166, + -0.596061502979634, + -0.6147604205197167, + -0.6309331556261872, + -0.6445132510614523, + -0.6554449033004471, + -0.6636831918392895, + -0.669194263783266, + -0.6719554729556376, + -0.6719554729556376, + -0.669194263783266, + -0.6636831918392895, + -0.6554449033004471, + -0.6445132510614524, + -0.6309331556261873, + -0.6147604205197169, + -0.5960615029796341, + -0.5749132408690166, + -0.5514025369331651, + -0.5256260016975818, + -0.4976895564745994, + -0.4677079981099877, + -0.4358045272580913, + -0.40211024212391316, + -0.36676359975247175, + -0.3299098470791017, + -0.29170042407864344, + -0.25229234146610147, + -0.2118475355059375, + -0.17053220258122603, + -0.1285161162570653, + -0.0859719296445841, + -0.043074465932271926, + -8.233311333224379e-17 + ], + [ + 0, + -0.036655640268658196, + -0.07316065464884229, + -0.1093650362061631, + -0.14512001337098607, + -0.1802786612727224, + -0.21469650548563757, + -0.24823211570525627, + -0.2807476869158202, + -0.31210960566065704, + -0.34218899908853373, + -0.37086226451984566, + -0.39801157735653914, + -0.423525375248659, + -0.4472988165279741, + -0.4692342110248805, + -0.48924142149826294, + -0.5072382340287533, + -0.5231506958533595, + -0.5369134192532319, + -0.5484698502458255, + -0.5577725009773452, + -0.5647831448605226, + -0.5694729736558635, + -0.5718227158508826, + -0.5718227158508826, + -0.5694729736558635, + -0.5647831448605226, + -0.5577725009773452, + -0.5484698502458256, + -0.536913419253232, + -0.5231506958533596, + -0.5072382340287533, + -0.489241421498263, + -0.46923421102488055, + -0.4472988165279742, + -0.42352537524865913, + -0.3980115773565392, + -0.37086226451984583, + -0.3421889990885339, + -0.31210960566065726, + -0.28074768691582036, + -0.24823211570525633, + -0.2146965054856378, + -0.18027866127272255, + -0.14512001337098632, + -0.10936503620616324, + -0.07316065464884258, + -0.03665564026865838, + -7.006408365574896e-17 + ], + [ + 0, + -0.029634930005233154, + -0.05914808372640226, + -0.08841818528431541, + -0.11732495755325402, + -0.14574961640548187, + -0.1735753588207049, + -0.20068784285473598, + -0.2269756574950696, + -0.25233078047263013, + -0.276649022148446, + -0.2998304536512248, + -0.32177981750651996, + -0.3424069190701265, + -0.36162699715722013, + -0.37936107234424704, + -0.39553627151231663, + -0.41008612729847793, + -0.42295085122437137, + -0.43407757937991076, + -0.44342058965242936, + -0.45094148960864794, + -0.4566093742574184, + -0.4604009530449614, + -0.46230064556074807, + -0.46230064556074807, + -0.4604009530449614, + -0.4566093742574184, + -0.45094148960864794, + -0.4434205896524294, + -0.4340775793799108, + -0.4229508512243715, + -0.410086127298478, + -0.3955362715123167, + -0.3793610723442471, + -0.3616269971572202, + -0.3424069190701266, + -0.32177981750652, + -0.2998304536512249, + -0.2766490221484461, + -0.25233078047263036, + -0.22697565749506973, + -0.200687842854736, + -0.17357535882070507, + -0.14574961640548198, + -0.11732495755325423, + -0.08841818528431553, + -0.05914808372640249, + -0.029634930005233304, + -5.664460366265284e-17 + ], + [ + 0, + -0.0221276150104241, + -0.04416430290441184, + -0.06601951020455209, + -0.08760342917612128, + -0.10882736686632918, + -0.12960410956268634, + -0.14984828117285615, + -0.1694766940533311, + -0.1884086908453041, + -0.20656647591305627, + -0.2238754350229116, + -0.24026444194912755, + -0.2556661507468133, + -0.27001727249086316, + -0.28325883534372465, + -0.2953364268833292, + -0.30620041769540524, + -0.31580616531138717, + -0.32411419765389465, + -0.3310903752359649, + -0.33670603144752786, + -0.34093809035265565, + -0.34376916151353326, + -0.34518761145149796, + -0.34518761145149796, + -0.34376916151353326, + -0.34093809035265565, + -0.33670603144752786, + -0.33109037523596496, + -0.3241141976538947, + -0.3158061653113873, + -0.30620041769540524, + -0.29533642688332923, + -0.2832588353437247, + -0.2700172724908632, + -0.2556661507468134, + -0.24026444194912758, + -0.2238754350229117, + -0.20656647591305635, + -0.18840869084530423, + -0.1694766940533312, + -0.14984828117285617, + -0.12960410956268648, + -0.10882736686632927, + -0.08760342917612143, + -0.06601951020455217, + -0.044164302904412006, + -0.02212761501042421, + -4.2295020843440646e-17 + ], + [ + 0, + -0.014256965188894764, + -0.028455345449718922, + -0.042536796592437726, + -0.05644345491384394, + -0.07011817497192607, + -0.08350476440874718, + -0.09654821485689698, + -0.10919492798067262, + -0.12139293572313709, + -0.13309211385401212, + -0.14424438794089217, + -0.15480393089739888, + -0.16472735129650912, + -0.17397387167523598, + -0.18250549609797084, + -0.190287166289933, + -0.19728690569914065, + -0.203475950894922, + -0.20882886976302148, + -0.21332366601161265, + -0.21694186955877925, + -0.2196686124300437, + -0.22149268985406353, + -0.22240660630544004, + -0.22240660630544004, + -0.22149268985406353, + -0.2196686124300437, + -0.21694186955877925, + -0.21332366601161268, + -0.2088288697630215, + -0.20347595089492201, + -0.19728690569914067, + -0.19028716628993303, + -0.18250549609797087, + -0.173973871675236, + -0.16472735129650917, + -0.1548039308973989, + -0.14424438794089225, + -0.13309211385401218, + -0.12139293572313718, + -0.10919492798067268, + -0.096548214856897, + -0.08350476440874727, + -0.07011817497192611, + -0.05644345491384404, + -0.04253679659243778, + -0.028455345449719033, + -0.014256965188894835, + -2.7250954951288024e-17 + ], + [ + 0, + -0.006152216393118909, + -0.012279152009432215, + -0.01835562995626892, + -0.024356680682345033, + -0.030257644583005772, + -0.036034273331830534, + -0.041662829522207415, + -0.04712018420942863, + -0.05238391195248549, + -0.05743238296501571, + -0.062244851996735184, + -0.06680154358012118, + -0.07108373329205028, + -0.0750738246964694, + -0.07875542165192581, + -0.08211339568682949, + -0.08513394816558786, + -0.08780466699015921, + -0.090114577604026, + -0.09205418808900157, + -0.093615528169558, + -0.09479218196439791, + -0.09557931435068683, + -0.09597369083261015, + -0.09597369083261015, + -0.09557931435068683, + -0.09479218196439791, + -0.093615528169558, + -0.09205418808900158, + -0.09011457760402601, + -0.08780466699015924, + -0.08513394816558788, + -0.0821133956868295, + -0.07875542165192582, + -0.07507382469646941, + -0.07108373329205031, + -0.06680154358012118, + -0.06224485199673521, + -0.05743238296501573, + -0.05238391195248553, + -0.04712018420942866, + -0.04166282952220742, + -0.03603427333183057, + -0.030257644583005793, + -0.024356680682345075, + -0.018355629956268944, + -0.012279152009432264, + -0.00615221639311894, + -1.1759429132228667e-17 + ], + [ + 0, + 0.0020535516257448112, + 0.004098664767373994, + 0.006126935616313203, + 0.008130029572581412, + 0.010099715493450009, + 0.012027899516973842, + 0.013906658321406074, + 0.015728271683826792, + 0.01748525420419497, + 0.019170386064462846, + 0.02077674269635693, + 0.022297723235914352, + 0.023727077647848763, + 0.025058932408285974, + 0.02628781464033339, + 0.02740867460330512, + 0.028416906443189602, + 0.029308367119091704, + 0.030079393427876425, + 0.03072681705705635, + 0.031247977604067237, + 0.031640733508432835, + 0.03190347085189623, + 0.03203510999035615, + 0.03203510999035615, + 0.03190347085189623, + 0.031640733508432835, + 0.031247977604067237, + 0.030726817057056353, + 0.030079393427876428, + 0.02930836711909171, + 0.028416906443189605, + 0.027408674603305122, + 0.026287814640333394, + 0.025058932408285977, + 0.02372707764784877, + 0.022297723235914356, + 0.02077674269635694, + 0.019170386064462853, + 0.017485254204194983, + 0.0157282716838268, + 0.013906658321406078, + 0.012027899516973854, + 0.010099715493450017, + 0.008130029572581425, + 0.006126935616313211, + 0.004098664767374011, + 0.0020535516257448212, + 3.925186188075022e-18 + ], + [ + 0, + 0.010225600383687245, + 0.020409181582013516, + 0.030508897075463573, + 0.040483244966692644, + 0.05029123852072477, + 0.059892574588238406, + 0.06924779921985201, + 0.07831846979086489, + 0.08706731297024801, + 0.09545837788475632, + 0.10345718384877835, + 0.11103086205286938, + 0.11814829062873995, + 0.12478022253568818, + 0.13089940574296346, + 0.13648069521420642, + 0.1415011562337969, + 0.14594015865051987, + 0.149779461651282, + 0.15300328871652527, + 0.1555983924493298, + 0.15755410901180955, + 0.15886240194510934, + 0.15951789519293835, + 0.15951789519293835, + 0.15886240194510934, + 0.15755410901180955, + 0.1555983924493298, + 0.15300328871652527, + 0.14977946165128203, + 0.1459401586505199, + 0.14150115623379692, + 0.13648069521420644, + 0.1308994057429635, + 0.1247802225356882, + 0.11814829062874, + 0.1110308620528694, + 0.1034571838487784, + 0.09545837788475636, + 0.08706731297024808, + 0.07831846979086493, + 0.06924779921985204, + 0.05989257458823847, + 0.050291238520724806, + 0.04048324496669272, + 0.030508897075463615, + 0.020409181582013596, + 0.010225600383687295, + 1.9545350059688042e-17 + ], + [ + 0, + 0.01822974506603157, + 0.03638458019931877, + 0.054389903288098986, + 0.07217172659767072, + 0.08965698080186585, + 0.10677381524058402, + 0.1234518931695671, + 0.13962268078916837, + 0.15521972886443586, + 0.17017894577927192, + 0.18443886090263162, + 0.19794087718453077, + 0.21062951194389368, + 0.22245262485879053, + 0.23336163222220419, + 0.2433117065829037, + 0.25226196095105663, + 0.26017561681164075, + 0.2670201552552511, + 0.2727674506052739, + 0.277393885992325, + 0.28088045040103166, + 0.2832128167903728, + 0.2843814009665636, + 0.2843814009665636, + 0.2832128167903728, + 0.28088045040103166, + 0.277393885992325, + 0.2727674506052739, + 0.26702015525525113, + 0.2601756168116408, + 0.2522619609510567, + 0.24331170658290371, + 0.23336163222220424, + 0.22245262485879055, + 0.21062951194389376, + 0.19794087718453082, + 0.18443886090263173, + 0.170178945779272, + 0.15521972886443597, + 0.13962268078916845, + 0.12345189316956715, + 0.10677381524058413, + 0.0896569808018659, + 0.07217172659767085, + 0.054389903288099055, + 0.03638458019931891, + 0.01822974506603166, + 3.4844579823681456e-17 + ], + [ + 0, + 0.025934557838380112, + 0.051762545015657115, + 0.0773778287924337, + 0.10267515047320992, + 0.12755055793694103, + 0.1519018327986004, + 0.17562891044644935, + 0.19863429122899068, + 0.22082344110195024, + 0.2421051800889423, + 0.2623920569595507, + 0.28160070858519254, + 0.29965220249609525, + 0.31647236123174566, + 0.3319920671519862, + 0.34614754645622414, + 0.35888063124365766, + 0.3701389985376569, + 0.37987638529209883, + 0.38805277849614633, + 0.3946345795962933, + 0.3995947425600272, + 0.4029128850137784, + 0.40457537199846527, + 0.40457537199846527, + 0.4029128850137784, + 0.3995947425600272, + 0.3946345795962933, + 0.3880527784961464, + 0.3798763852920989, + 0.370138998537657, + 0.3588806312436577, + 0.3461475464562242, + 0.33199206715198626, + 0.3164723612317457, + 0.2996522024960953, + 0.2816007085851926, + 0.2623920569595508, + 0.24210518008894238, + 0.2208234411019504, + 0.1986342912289908, + 0.1756289104464494, + 0.15190183279860053, + 0.12755055793694114, + 0.1026751504732101, + 0.0773778287924338, + 0.051762545015657316, + 0.02593455783838024, + 4.957166255030033e-17 + ], + [ + 0, + 0.03321352588802205, + 0.06629057027389126, + 0.09909521248722232, + 0.13149265121658696, + 0.1633497584370174, + 0.19453562646161687, + 0.22492210586932454, + 0.2543843320983747, + 0.2828012385415645, + 0.31005605403491165, + 0.33603678269541437, + 0.36063666413615775, + 0.3837546121676437, + 0.40529563018262676, + 0.42517120151754934, + 0.44329965318649955, + 0.459606491493029, + 0.4740247081407304, + 0.4864950555847005, + 0.4969662904924109, + 0.505395384313553, + 0.5117477000935807, + 0.5159971348043865, + 0.5181262266072427, + 0.5181262266072427, + 0.5159971348043865, + 0.5117477000935807, + 0.505395384313553, + 0.496966290492411, + 0.4864950555847006, + 0.4740247081407305, + 0.45960649149302907, + 0.4432996531864996, + 0.4251712015175494, + 0.4052956301826268, + 0.38375461216764384, + 0.3606366641361578, + 0.33603678269541454, + 0.31005605403491177, + 0.28280123854156475, + 0.25438433209837485, + 0.2249221058693246, + 0.19453562646161707, + 0.16334975843701754, + 0.13149265121658718, + 0.09909521248722246, + 0.06629057027389151, + 0.03321352588802221, + 6.348477994832595e-17 + ], + [ + 0, + 0.039947128760820155, + 0.07973010620092985, + 0.11918545553260579, + 0.1581510462622982, + 0.1964667604196058, + 0.23397515051636128, + 0.27052208653213267, + 0.3059573892675379, + 0.3401354474627886, + 0.3729158161455901, + 0.4041637937496577, + 0.433750975632346, + 0.46155578171686845, + 0.4874639560909117, + 0.5113690365086866, + 0.5331727918671331, + 0.5527856258585923, + 0.5701269451412535, + 0.5851254905144833, + 0.5977196297381648, + 0.6078576107927938, + 0.6154977745396266, + 0.6206087259070174, + 0.623169462899502, + 0.623169462899502, + 0.6206087259070174, + 0.6154977745396266, + 0.6078576107927938, + 0.597719629738165, + 0.5851254905144833, + 0.5701269451412536, + 0.5527856258585923, + 0.5331727918671331, + 0.5113690365086867, + 0.48746395609091175, + 0.4615557817168686, + 0.43375097563234605, + 0.4041637937496579, + 0.3729158161455902, + 0.3401354474627889, + 0.30595738926753807, + 0.2705220865321327, + 0.23397515051636153, + 0.19646676041960595, + 0.15815104626229848, + 0.11918545553260594, + 0.07973010620093017, + 0.03994712876082035, + 7.635547901473152e-17 + ], + [ + 0, + 0.046024800883763525, + 0.09186047598840684, + 0.1373186766932035, + 0.18221260550070398, + 0.22635778362772077, + 0.26957280906821895, + 0.3116801020130696, + 0.35250663456357634, + 0.3918846417402253, + 0.4296523108649717, + 0.4656544464842423, + 0.49974310810034356, + 0.5317782180906999, + 0.5616281373168517, + 0.5891702060579108, + 0.6142912480456649, + 0.6368880355301402, + 0.6568677134645667, + 0.6741481810666847, + 0.6886584291884684, + 0.7003388321079469, + 0.7091413925440854, + 0.7150299388879086, + 0.7179802738394004, + 0.7179802738394004, + 0.7150299388879086, + 0.7091413925440854, + 0.7003388321079469, + 0.6886584291884685, + 0.6741481810666848, + 0.6568677134645668, + 0.6368880355301402, + 0.614291248045665, + 0.5891702060579108, + 0.5616281373168518, + 0.5317782180907001, + 0.4997431081003436, + 0.46565444648424253, + 0.42965231086497185, + 0.39188464174022564, + 0.3525066345635765, + 0.3116801020130697, + 0.26957280906821923, + 0.22635778362772094, + 0.18221260550070428, + 0.1373186766932037, + 0.0918604759884072, + 0.046024800883763754, + 8.797242322667628e-17 + ], + [ + 0, + 0.05134674704861985, + 0.10248249929977422, + 0.15319712897887866, + 0.20328223879432777, + 0.25253201828666755, + 0.3007440895479193, + 0.3477203388358138, + 0.3932677306656531, + 0.4371991010345236, + 0.4793339265183301, + 0.5194990660812682, + 0.5575294725494779, + 0.5932688708252851, + 0.6265704000550975, + 0.6572972171121542, + 0.685323058914286, + 0.710532761266004, + 0.7328227320928805, + 0.7521013771236045, + 0.768289476270488, + 0.7813205091618003, + 0.7911409284882431, + 0.7977103800403307, + 0.8010018685324927, + 0.8010018685324927, + 0.7977103800403307, + 0.7911409284882431, + 0.7813205091618003, + 0.768289476270488, + 0.7521013771236045, + 0.7328227320928807, + 0.7105327612660041, + 0.685323058914286, + 0.6572972171121543, + 0.6265704000550976, + 0.5932688708252852, + 0.557529472549478, + 0.5194990660812684, + 0.47933392651833034, + 0.437199101034524, + 0.39326773066565335, + 0.3477203388358139, + 0.3007440895479196, + 0.2525320182866677, + 0.20328223879432814, + 0.15319712897887888, + 0.10248249929977463, + 0.051346747048620106, + 9.814486268136802e-17 + ], + [ + 0, + 0.05582558104649524, + 0.11142176280592085, + 0.16656008864208377, + 0.22101398334698938, + 0.27455968418697146, + 0.3269771603917617, + 0.3780510173081213, + 0.4275713815026729, + 0.47533476317685625, + 0.5211448923501589, + 0.5648135253755662, + 0.6061612184730837, + 0.6450180651027219, + 0.6812243941469118, + 0.7146314260333778, + 0.7451018841023125, + 0.7725105587056179, + 0.7967448217202067, + 0.8177050893611189, + 0.8353052313926546, + 0.8494729250559877, + 0.8601499522588948, + 0.8672924388063838, + 0.8708710346891727, + 0.8708710346891727, + 0.8672924388063838, + 0.8601499522588948, + 0.8494729250559877, + 0.8353052313926547, + 0.817705089361119, + 0.7967448217202069, + 0.7725105587056179, + 0.7451018841023126, + 0.7146314260333779, + 0.6812243941469119, + 0.645018065102722, + 0.6061612184730838, + 0.5648135253755664, + 0.5211448923501592, + 0.47533476317685663, + 0.4275713815026731, + 0.3780510173081214, + 0.32697716039176206, + 0.2745596841869717, + 0.22101398334698977, + 0.166560088642084, + 0.11142176280592128, + 0.055825581046495515, + 1.067057662041928e-16 + ], + [ + 0, + 0.05938776054696869, + 0.11853148404721521, + 0.17718813625458812, + 0.23511668440335487, + 0.29207908766353763, + 0.3478412753017431, + 0.4021741085280141, + 0.45485432207626775, + 0.5056654416491639, + 0.5543986734574265, + 0.6008537621983102, + 0.6448398139475932, + 0.6861760805836591, + 0.724692702520299, + 0.7602314066961859, + 0.7926461569528328, + 0.821803754128493, + 0.8475843834020869, + 0.8698821066380014, + 0.8886052977086137, + 0.9036770190057027, + 0.9150353375935847, + 0.9226335797048302, + 0.9264405225327862, + 0.9264405225327862, + 0.9226335797048302, + 0.9150353375935847, + 0.9036770190057027, + 0.8886052977086139, + 0.8698821066380015, + 0.8475843834020871, + 0.8218037541284932, + 0.7926461569528329, + 0.760231406696186, + 0.7246927025202992, + 0.6861760805836592, + 0.6448398139475933, + 0.6008537621983105, + 0.5543986734574268, + 0.5056654416491643, + 0.454854322076268, + 0.4021741085280142, + 0.3478412753017434, + 0.29207908766353785, + 0.23511668440335529, + 0.17718813625458835, + 0.11853148404721567, + 0.05938776054696899, + 1.135145639959849e-16 + ], + [ + 0, + 0.06197479466112416, + 0.123694921597434, + 0.18490675956842254, + 0.24535877600196884, + 0.30480256059563066, + 0.36299384608786084, + 0.4196935120045802, + 0.4746685672564967, + 0.5276931075494679, + 0.5785492436737018, + 0.6270279968572569, + 0.6729301575046418, + 0.7160671037917741, + 0.756261576753514, + 0.7933484086787741, + 0.8271752018200732, + 0.8576029546285693, + 0.8845066329412397, + 0.9077756837730767, + 0.9273144896030167, + 0.9430427612868437, + 0.9548958679825051, + 0.962825102732105, + 0.9667978826092418, + 0.9667978826092418, + 0.962825102732105, + 0.9548958679825051, + 0.9430427612868437, + 0.9273144896030168, + 0.9077756837730768, + 0.8845066329412398, + 0.8576029546285694, + 0.8271752018200733, + 0.7933484086787742, + 0.7562615767535141, + 0.7160671037917743, + 0.6729301575046419, + 0.6270279968572572, + 0.578549243673702, + 0.5276931075494683, + 0.474668567256497, + 0.4196935120045803, + 0.3629938460878612, + 0.3048025605956309, + 0.24535877600196926, + 0.18490675956842278, + 0.12369492159743449, + 0.061974794661124474, + 1.1845945578524243e-16 + ], + [ + 0, + 0.06354420436032968, + 0.12682729195475367, + 0.18958921900216677, + 0.25157208328194003, + 0.31252118390946515, + 0.37218606795672254, + 0.4303215596170846, + 0.486688767685295, + 0.5410560672126732, + 0.593200051303712, + 0.642906449142932, + 0.6899710064796228, + 0.7342003249523721, + 0.7754126568044162, + 0.8134386517241577, + 0.848122052741921, + 0.879320338323358, + 0.9069053080210032, + 0.9307636092774118, + 0.9507972032151312, + 0.9669237674994793, + 0.9790770346186742, + 0.9872070641912557, + 0.9912804481818241, + 0.9912804481818241, + 0.9872070641912557, + 0.9790770346186742, + 0.9669237674994793, + 0.9507972032151313, + 0.9307636092774119, + 0.9069053080210034, + 0.8793203383233581, + 0.8481220527419211, + 0.8134386517241579, + 0.7754126568044163, + 0.7342003249523723, + 0.689971006479623, + 0.6429064491429324, + 0.5932000513037122, + 0.5410560672126736, + 0.4866887676852953, + 0.43032155961708474, + 0.37218606795672293, + 0.31252118390946537, + 0.2515720832819405, + 0.18958921900216702, + 0.12682729195475417, + 0.06354420436033, + 1.2145924658549475e-16 + ], + [ + 0, + 0.06407021998071291, + 0.127877161684506, + 0.1911586287013723, + 0.25365458390950735, + 0.31510821802362066, + 0.3752670048793741, + 0.4338837391175581, + 0.49071755200393785, + 0.5455349012105486, + 0.5981105304912159, + 0.6482283953077884, + 0.6956825506034864, + 0.7402779970753155, + 0.7818314824680298, + 0.8201722545969559, + 0.8551427630053461, + 0.886599306373, + 0.9144126230158124, + 0.9384684220497603, + 0.9586678530366606, + 0.9749279121818236, + 0.9871817834144502, + 0.9953791129491982, + 0.9994862162006879, + 0.9994862162006879, + 0.9953791129491982, + 0.9871817834144502, + 0.9749279121818236, + 0.9586678530366607, + 0.9384684220497604, + 0.9144126230158126, + 0.8865993063730001, + 0.8551427630053462, + 0.820172254596956, + 0.7818314824680299, + 0.7402779970753157, + 0.6956825506034865, + 0.6482283953077888, + 0.5981105304912161, + 0.545534901210549, + 0.49071755200393813, + 0.43388373911755823, + 0.3752670048793745, + 0.3151082180236209, + 0.2536545839095078, + 0.19115862870137254, + 0.1278771616845065, + 0.06407021998071323, + 1.2246467991473532e-16 + ] + ], + "y": [ + [ + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0, + 0 + ], + [ + 0, + 0.008193117879635491, + 0.01635256848048529, + 0.02444482286983383, + 0.03243662823861217, + 0.040295144544323105, + 0.04798807945782002, + 0.055483821059414, + 0.06275156773903254, + 0.06976145476664233, + 0.07648467701283086, + 0.08289360731526192, + 0.08896191000461155, + 0.09466464912348238, + 0.09997839089360126, + 0.10488130001024074, + 0.10935322936816984, + 0.11337580285043099, + 0.11693249083974627, + 0.12000867814226042, + 0.12259172404450727, + 0.12467101425681293, + 0.1262380045296886, + 0.12728625576398478, + 0.1278114604705305, + 0.1278114604705305, + 0.12728625576398478, + 0.1262380045296886, + 0.12467101425681293, + 0.12259172404450729, + 0.12000867814226043, + 0.1169324908397463, + 0.113375802850431, + 0.10935322936816985, + 0.10488130001024075, + 0.09997839089360128, + 0.09466464912348241, + 0.08896191000461157, + 0.08289360731526198, + 0.07648467701283089, + 0.06976145476664239, + 0.06275156773903258, + 0.05548382105941401, + 0.04798807945782007, + 0.04029514454432313, + 0.03243662823861222, + 0.024444822869833866, + 0.01635256848048535, + 0.008193117879635533, + 1.5660435674097883e-17 + ], + [ + 0, + 0.01625170499019834, + 0.03243662823861217, + 0.048488262423958595, + 0.06434064793830531, + 0.07992864392924783, + 0.0951881959776447, + 0.11005659931096544, + 0.12447275647065088, + 0.1383774283746759, + 0.15171347774364408, + 0.16442610389012471, + 0.17646306790643213, + 0.18777490732550264, + 0.1983151393727814, + 0.20804045197391335, + 0.21691088173334752, + 0.22488997815250114, + 0.2319449534126771, + 0.23804681710724387, + 0.24317049536943489, + 0.24729493390624518, + 0.25040318451503774, + 0.2524824747273434, + 0.25352426029367336, + 0.25352426029367336, + 0.2524824747273434, + 0.25040318451503774, + 0.24729493390624518, + 0.2431704953694349, + 0.2380468171072439, + 0.23194495341267715, + 0.22488997815250117, + 0.21691088173334755, + 0.20804045197391338, + 0.19831513937278142, + 0.1877749073255027, + 0.17646306790643215, + 0.1644261038901248, + 0.15171347774364413, + 0.138377428374676, + 0.12447275647065095, + 0.11005659931096547, + 0.0951881959776448, + 0.07992864392924788, + 0.06434064793830542, + 0.048488262423958664, + 0.03243662823861229, + 0.01625170499019842, + 3.106372742738319e-17 + ], + [ + 0, + 0.024043439554124763, + 0.04798807945782002, + 0.07173552604961234, + 0.0951881959776447, + 0.11824971719060093, + 0.14082532495113617, + 0.16282225124450975, + 0.18415010598225626, + 0.2047212484344478, + 0.22445114736425215, + 0.24325872838491666, + 0.26106670711181396, + 0.2778019067405557, + 0.2933955587461784, + 0.3077835854677631, + 0.32090686341728863, + 0.3327114662307263, + 0.34314888626303613, + 0.3521762339164859, + 0.35975641388320756, + 0.3658582775777744, + 0.3704567511334197, + 0.3735329384359338, + 0.37507419877185066, + 0.37507419877185066, + 0.3735329384359338, + 0.3704567511334197, + 0.3658582775777744, + 0.3597564138832076, + 0.35217623391648595, + 0.3431488862630362, + 0.33271146623072634, + 0.3209068634172887, + 0.30778358546776313, + 0.29339555874617845, + 0.27780190674055577, + 0.26106670711181396, + 0.2432587283849168, + 0.22445114736425223, + 0.20472124843444797, + 0.18415010598225637, + 0.1628222512445098, + 0.1408253249511363, + 0.11824971719060101, + 0.09518819597764487, + 0.07173552604961243, + 0.04798807945782021, + 0.024043439554124885, + 4.5956953635113964e-17 + ], + [ + 0, + 0.031440381505289224, + 0.06275156773903254, + 0.09380489432076711, + 0.12447275647065088, + 0.15462913336487424, + 0.18415010598225626, + 0.21291436631408334, + 0.24080371584473745, + 0.2677035512547505, + 0.2935033353504261, + 0.31809705128487886, + 0.3413836382039985, + 0.3632674065271771, + 0.38365843115632126, + 0.40247292099736864, + 0.41963356327586704, + 0.43506984123174786, + 0.4487183238878191, + 0.4605229267012568, + 0.4704351420270209, + 0.4784142384461746, + 0.48442742814002054, + 0.4884500016222817, + 0.49046542927568015, + 0.49046542927568015, + 0.4884500016222817, + 0.48442742814002054, + 0.4784142384461746, + 0.47043514202702097, + 0.46052292670125683, + 0.44871832388781924, + 0.4350698412317479, + 0.4196335632758671, + 0.4024729209973687, + 0.3836584311563213, + 0.3632674065271772, + 0.34138363820399853, + 0.31809705128487903, + 0.29350333535042616, + 0.2677035512547507, + 0.2408037158447376, + 0.2129143663140834, + 0.18415010598225645, + 0.15462913336487435, + 0.1244727564706511, + 0.09380489432076723, + 0.06275156773903279, + 0.03144038150528938, + 6.009556793470474e-17 + ], + [ + 0, + 0.038321073261353096, + 0.07648467701283086, + 0.11433398882055115, + 0.15171347774364408, + 0.18846954344424946, + 0.22445114736425215, + 0.259510433375115, + 0.2935033353504261, + 0.32629016916451425, + 0.3577362066844837, + 0.38771222939701094, + 0.41609505939493335, + 0.4427680655416917, + 0.46762164273368706, + 0.4905536622911618, + 0.5114698916268516, + 0.530284381467899, + 0.5469198190398518, + 0.5613078457614364, + 0.573389338144632, + 0.5831146507457641, + 0.5904438201692813, + 0.5953467292859208, + 0.5978032309904515, + 0.5978032309904515, + 0.5953467292859208, + 0.5904438201692813, + 0.5831146507457641, + 0.5733893381446321, + 0.5613078457614364, + 0.5469198190398519, + 0.5302843814678991, + 0.5114698916268517, + 0.49055366229116193, + 0.4676216427336871, + 0.44276806554169185, + 0.41609505939493346, + 0.3877122293970111, + 0.3577362066844838, + 0.32629016916451453, + 0.2935033353504263, + 0.2595104333751151, + 0.22445114736425237, + 0.1884695434442496, + 0.15171347774364433, + 0.11433398882055129, + 0.07648467701283117, + 0.03832107326135329, + 7.32474146702393e-17 + ], + [ + 0, + 0.04457253405390881, + 0.08896191000461155, + 0.1329857223848355, + 0.17646306790643213, + 0.2192152888307919, + 0.26106670711181396, + 0.3018453462946805, + 0.3413836382039985, + 0.37951911151737544, + 0.41609505939493335, + 0.4509611834213273, + 0.4839742112141724, + 0.5149984851609957, + 0.5439065198654639, + 0.5705795260122223, + 0.5949078984976719, + 0.6167916668208505, + 0.6361409058836646, + 0.6528761055124064, + 0.6669284971821122, + 0.6782403366011829, + 0.6867651409950631, + 0.692467880113934, + 0.6953251201795222, + 0.6953251201795222, + 0.692467880113934, + 0.6867651409950631, + 0.6782403366011829, + 0.6669284971821123, + 0.6528761055124065, + 0.6361409058836648, + 0.6167916668208506, + 0.5949078984976719, + 0.5705795260122224, + 0.543906519865464, + 0.5149984851609959, + 0.48397421121417245, + 0.4509611834213275, + 0.4160950593949335, + 0.3795191115173757, + 0.34138363820399864, + 0.30184534629468057, + 0.26106670711181423, + 0.21921528883079205, + 0.17646306790643243, + 0.13298572238483566, + 0.0889619100046119, + 0.044572534053909034, + 8.519654088192262e-17 + ], + [ + 0, + 0.05009211506957356, + 0.09997839089360126, + 0.14945383406414958, + 0.1983151393727814, + 0.2463615252352665, + 0.2933955587461784, + 0.33922396697305235, + 0.38365843115632126, + 0.4265163605514934, + 0.46762164273368706, + 0.5068053672813603, + 0.5439065198654639, + 0.5787726438918578, + 0.6112604669781572, + 0.6412364896906844, + 0.6685775341222768, + 0.6931712500567295, + 0.7149165766399322, + 0.7337241576605968, + 0.7495167087340957, + 0.7622293348805763, + 0.7718097971923531, + 0.7782187274947842, + 0.7814297901185455, + 0.7814297901185455, + 0.7782187274947842, + 0.7718097971923531, + 0.7622293348805763, + 0.7495167087340957, + 0.7337241576605968, + 0.7149165766399325, + 0.6931712500567296, + 0.6685775341222769, + 0.6412364896906845, + 0.6112604669781573, + 0.5787726438918579, + 0.543906519865464, + 0.5068053672813605, + 0.4676216427336872, + 0.4265163605514937, + 0.3836584311563215, + 0.33922396697305246, + 0.29339555874617873, + 0.24636152523526667, + 0.19831513937278172, + 0.14945383406414978, + 0.09997839089360165, + 0.05009211506957381, + 9.574674224771027e-17 + ], + [ + 0, + 0.054789184940667174, + 0.10935322936816984, + 0.16346791792000456, + 0.21691088173334752, + 0.26946251220641, + 0.32090686341728863, + 0.3710325394920794, + 0.41963356327586704, + 0.4665102227370371, + 0.5114698916268516, + 0.5543278210220239, + 0.5949078984976719, + 0.6330433718110487, + 0.6685775341222768, + 0.701364367936365, + 0.7312691451204175, + 0.7581689805304306, + 0.7819533369727077, + 0.8025244794248994, + 0.819797876650173, + 0.833702548554198, + 0.8441813578575781, + 0.8511912448851878, + 0.854703404507615, + 0.854703404507615, + 0.8511912448851878, + 0.8441813578575781, + 0.833702548554198, + 0.8197978766501731, + 0.8025244794248994, + 0.781953336972708, + 0.7581689805304307, + 0.7312691451204176, + 0.7013643679363651, + 0.6685775341222769, + 0.633043371811049, + 0.5949078984976719, + 0.5543278210220242, + 0.5114698916268519, + 0.4665102227370374, + 0.41963356327586726, + 0.3710325394920795, + 0.32090686341728897, + 0.26946251220641015, + 0.21691088173334788, + 0.16346791792000476, + 0.10935322936817027, + 0.054789184940667444, + 1.0472478475285208e-16 + ], + [ + 0, + 0.058586617909763807, + 0.11693249083974627, + 0.1747978630829276, + 0.2319449534126771, + 0.28813893217681746, + 0.34314888626303613, + 0.39674876797039477, + 0.4487183238878191, + 0.4988439999626098, + 0.5469198190398518, + 0.5927482272667257, + 0.6361409058836646, + 0.6769195450665312, + 0.7149165766399322, + 0.7499758626507951, + 0.7819533369727077, + 0.8107175973045347, + 0.8361504451306582, + 0.8581473714240319, + 0.8766179860961901, + 0.891486389429511, + 0.902691483965435, + 0.9101872255670289, + 0.9139428126242204, + 0.9139428126242204, + 0.9101872255670289, + 0.902691483965435, + 0.891486389429511, + 0.8766179860961902, + 0.8581473714240319, + 0.8361504451306584, + 0.8107175973045349, + 0.7819533369727079, + 0.7499758626507952, + 0.7149165766399324, + 0.6769195450665313, + 0.6361409058836647, + 0.592748227266726, + 0.546919819039852, + 0.49884399996261025, + 0.4487183238878194, + 0.3967487679703949, + 0.34314888626303647, + 0.28813893217681763, + 0.23194495341267748, + 0.17479786308292783, + 0.11693249083974673, + 0.0585866179097641, + 1.11983249187625e-16 + ], + [ + 0, + 0.0614220602324966, + 0.12259172404450727, + 0.18325763216657673, + 0.24317049536943489, + 0.3020841188469124, + 0.35975641388320756, + 0.415950392647348, + 0.4704351420270209, + 0.5229867725000833, + 0.573389338144632, + 0.6214357240071172, + 0.6669284971821122, + 0.709680718106472, + 0.7495167087340957, + 0.786272774434701, + 0.819797876650173, + 0.8499542535443964, + 0.8766179860961901, + 0.8996795073091464, + 0.9190440524459202, + 0.9346320484368628, + 0.9463794408628327, + 0.9542379571685435, + 0.958175305024849, + 0.958175305024849, + 0.9542379571685435, + 0.9463794408628327, + 0.9346320484368628, + 0.9190440524459204, + 0.8996795073091465, + 0.8766179860961903, + 0.8499542535443965, + 0.8197978766501731, + 0.7862727744347011, + 0.7495167087340958, + 0.7096807181064723, + 0.6669284971821123, + 0.6214357240071176, + 0.5733893381446322, + 0.5229867725000837, + 0.4704351420270212, + 0.41595039264734807, + 0.35975641388320795, + 0.30208411884691255, + 0.2431704953694353, + 0.18325763216657698, + 0.12259172404450776, + 0.061422060232496904, + 1.1740295176668117e-16 + ], + [ + 0, + 0.06324895402431631, + 0.1262380045296886, + 0.1887083159964814, + 0.25040318451503774, + 0.31106909263710725, + 0.3704567511334197, + 0.4283221233766011, + 0.48442742814002054, + 0.5385421166918553, + 0.5904438201692813, + 0.6399192633398297, + 0.6867651409950631, + 0.730788953375287, + 0.7718097971923531, + 0.8096591090000733, + 0.8441813578575781, + 0.8752346844393126, + 0.902691483965435, + 0.9264389305572274, + 0.9463794408628327, + 0.9624310750481792, + 0.9745278735053344, + 0.9826201278946829, + 0.9866745854071558, + 0.9866745854071558, + 0.9826201278946829, + 0.9745278735053344, + 0.9624310750481792, + 0.9463794408628328, + 0.9264389305572275, + 0.9026914839654352, + 0.8752346844393127, + 0.8441813578575782, + 0.8096591090000734, + 0.7718097971923532, + 0.7307889533752873, + 0.6867651409950633, + 0.6399192633398301, + 0.5904438201692815, + 0.5385421166918557, + 0.4844274281400208, + 0.4283221233766012, + 0.3704567511334201, + 0.31106909263710747, + 0.2504031845150382, + 0.18870831599648163, + 0.1262380045296891, + 0.06324895402431663, + 1.208949011235082e-16 + ], + [ + 0, + 0.06403730173966846, + 0.1278114604705305, + 0.19106041449484681, + 0.25352426029367336, + 0.31494632052617, + 0.37507419877185066, + 0.43366081668161455, + 0.49046542927568015, + 0.5452546142163472, + 0.5978032309904515, + 0.6478953460600252, + 0.6953251201795222, + 0.739897654233431, + 0.7814297901185455, + 0.8197508633798987, + 0.854703404507615, + 0.8861437860129042, + 0.9139428126242204, + 0.9379862521783452, + 0.958175305024849, + 0.9744270100150474, + 0.9866745854071558, + 0.9948677032867913, + 0.9989726963751682, + 0.9989726963751682, + 0.9948677032867913, + 0.9866745854071558, + 0.9744270100150474, + 0.9581753050248492, + 0.9379862521783453, + 0.9139428126242206, + 0.8861437860129043, + 0.8547034045076151, + 0.8197508633798988, + 0.7814297901185456, + 0.7398976542334312, + 0.6953251201795223, + 0.6478953460600255, + 0.5978032309904517, + 0.5452546142163477, + 0.49046542927568043, + 0.43366081668161466, + 0.37507419877185105, + 0.3149463205261702, + 0.2535242602936738, + 0.19106041449484706, + 0.127811460470531, + 0.06403730173966878, + 1.2240175954620718e-16 + ], + [ + 0, + 0.06377415873086202, + 0.12728625576398478, + 0.1902753062693571, + 0.2524824747273434, + 0.3136521385393541, + 0.3735329384359338, + 0.4318788113659163, + 0.4884500016222817, + 0.5430140460497843, + 0.5953467292859208, + 0.6452330051099486, + 0.692467880113934, + 0.7368572560646367, + 0.7782187274947842, + 0.8163823312462619, + 0.8511912448851878, + 0.8825024311189311, + 0.9101872255670289, + 0.9341318654707242, + 0.9542379571685435, + 0.9704228804169575, + 0.9826201278946829, + 0.9907795784955328, + 0.9948677032867913, + 0.9948677032867913, + 0.9907795784955328, + 0.9826201278946829, + 0.9704228804169575, + 0.9542379571685436, + 0.9341318654707244, + 0.9101872255670291, + 0.8825024311189312, + 0.8511912448851879, + 0.816382331246262, + 0.7782187274947843, + 0.7368572560646369, + 0.6924678801139341, + 0.645233005109949, + 0.595346729285921, + 0.5430140460497848, + 0.48845000162228197, + 0.43187881136591644, + 0.3735329384359342, + 0.3136521385393543, + 0.2524824747273438, + 0.19027530626935735, + 0.12728625576398528, + 0.06377415873086233, + 1.2189878446113675e-16 + ], + [ + 0, + 0.0624638457988266, + 0.12467101425681293, + 0.1863658827753693, + 0.24729493390624518, + 0.3072077971091034, + 0.3658582775777744, + 0.42300536790752397, + 0.4784142384461746, + 0.5318572022595175, + 0.5831146507457641, + 0.631975956054396, + 0.6782403366011829, + 0.7217176821227794, + 0.7622293348805763, + 0.7996088238036693, + 0.833702548554198, + 0.8643704107040818, + 0.891486389429511, + 0.9149390593575433, + 0.9346320484368628, + 0.9504844339512096, + 0.9624310750481792, + 0.9704228804169575, + 0.9744270100150474, + 0.9744270100150474, + 0.9704228804169575, + 0.9624310750481792, + 0.9504844339512096, + 0.9346320484368629, + 0.9149390593575434, + 0.8914863894295112, + 0.8643704107040819, + 0.8337025485541981, + 0.7996088238036694, + 0.7622293348805764, + 0.7217176821227796, + 0.678240336601183, + 0.6319759560543963, + 0.5831146507457643, + 0.5318572022595179, + 0.47841423844617487, + 0.4230053679075241, + 0.3658582775777748, + 0.30720779710910356, + 0.24729493390624563, + 0.18636588277536956, + 0.12467101425681341, + 0.06246384579882691, + 1.1939423470528823e-16 + ], + [ + 0, + 0.06012787824568068, + 0.12000867814226043, + 0.1793963366385729, + 0.2380468171072439, + 0.2957191121435392, + 0.35217623391648595, + 0.4071861880027047, + 0.46052292670125683, + 0.5119672779121355, + 0.5613078457614364, + 0.6083418792723485, + 0.6528761055124065, + 0.6947275237934285, + 0.7337241576605968, + 0.7697057615805996, + 0.8025244794248994, + 0.8320454520422814, + 0.8581473714240319, + 0.8807229791845672, + 0.8996795073091465, + 0.9149390593575434, + 0.9264389305572275, + 0.9341318654707244, + 0.9379862521783453, + 0.9379862521783453, + 0.9341318654707244, + 0.9264389305572275, + 0.9149390593575434, + 0.8996795073091466, + 0.8807229791845673, + 0.8581473714240321, + 0.8320454520422815, + 0.8025244794248995, + 0.7697057615805997, + 0.733724157660597, + 0.6947275237934287, + 0.6528761055124066, + 0.6083418792723488, + 0.5613078457614367, + 0.5119672779121359, + 0.46052292670125705, + 0.4071861880027048, + 0.35217623391648634, + 0.29571911214353935, + 0.23804681710724432, + 0.17939633663857313, + 0.12000867814226089, + 0.06012787824568098, + 1.1492923491641064e-16 + ], + [ + 0, + 0.0568046125940656, + 0.113375802850431, + 0.16948110761385055, + 0.22488997815250117, + 0.2793747275321742, + 0.33271146623072634, + 0.38468102214815075, + 0.4350698412317479, + 0.4836708650155355, + 0.5302843814678991, + 0.5747188456511682, + 0.6167916668208506, + 0.6563299587301685, + 0.6931712500567296, + 0.7271641520320408, + 0.7581689805304307, + 0.7860583300610848, + 0.8107175973045349, + 0.8320454520422814, + 0.8499542535443965, + 0.8643704107040819, + 0.8752346844393127, + 0.8825024311189312, + 0.8861437860129043, + 0.8861437860129043, + 0.8825024311189312, + 0.8752346844393127, + 0.8643704107040819, + 0.8499542535443966, + 0.8320454520422815, + 0.8107175973045351, + 0.7860583300610849, + 0.7581689805304308, + 0.7271641520320408, + 0.6931712500567297, + 0.6563299587301687, + 0.6167916668208506, + 0.5747188456511684, + 0.5302843814678994, + 0.4836708650155359, + 0.43506984123174813, + 0.38468102214815086, + 0.33271146623072667, + 0.27937472753217435, + 0.22488997815250156, + 0.16948110761385077, + 0.11337580285043145, + 0.056804612594065884, + 1.0857710026759582e-16 + ], + [ + 0, + 0.052548616774104245, + 0.10488130001024075, + 0.15678300348766688, + 0.20804045197391338, + 0.2584430176184621, + 0.30778358546776313, + 0.3558594045450051, + 0.4024729209973687, + 0.44743258988718326, + 0.49055366229116193, + 0.5316589444733557, + 0.5705795260122224, + 0.6071554738897803, + 0.6412364896906845, + 0.6726825272106539, + 0.7013643679363651, + 0.7271641520320408, + 0.7499758626507952, + 0.7697057615805996, + 0.7862727744347011, + 0.7996088238036694, + 0.8096591090000734, + 0.816382331246262, + 0.8197508633798988, + 0.8197508633798988, + 0.816382331246262, + 0.8096591090000734, + 0.7996088238036694, + 0.7862727744347012, + 0.7697057615805997, + 0.7499758626507954, + 0.7271641520320408, + 0.7013643679363651, + 0.672682527210654, + 0.6412364896906846, + 0.6071554738897805, + 0.5705795260122224, + 0.5316589444733559, + 0.4905536622911621, + 0.44743258988718365, + 0.4024729209973689, + 0.3558594045450052, + 0.30778358546776347, + 0.2584430176184623, + 0.20804045197391377, + 0.1567830034876671, + 0.10488130001024117, + 0.05254861677410451, + 1.0044213263416301e-16 + ], + [ + 0, + 0.047429774119497024, + 0.09466464912348241, + 0.14151052677871584, + 0.1877749073255027, + 0.2332676805004978, + 0.27780190674055577, + 0.32119458535749473, + 0.3632674065271772, + 0.40384748400282516, + 0.44276806554169185, + 0.4798692181257956, + 0.5149984851609959, + 0.548011512953841, + 0.5787726438918579, + 0.6071554738897804, + 0.633043371811049, + 0.6563299587301686, + 0.6769195450665313, + 0.6947275237934286, + 0.7096807181064723, + 0.7217176821227796, + 0.7307889533752873, + 0.7368572560646369, + 0.7398976542334312, + 0.7398976542334312, + 0.7368572560646369, + 0.7307889533752873, + 0.7217176821227796, + 0.7096807181064723, + 0.6947275237934287, + 0.6769195450665315, + 0.6563299587301687, + 0.6330433718110491, + 0.6071554738897805, + 0.578772643891858, + 0.5480115129538411, + 0.514998485160996, + 0.47986921812579586, + 0.442768065541692, + 0.4038474840028255, + 0.36326740652717737, + 0.32119458535749484, + 0.27780190674055605, + 0.23326768050049795, + 0.18777490732550303, + 0.14151052677871603, + 0.09466464912348277, + 0.04742977411949726, + 9.065790795974991e-17 + ], + [ + 0, + 0.041532135885114556, + 0.08289360731526198, + 0.12391445113232798, + 0.1644261038901248, + 0.20426209451774846, + 0.2432587283849168, + 0.281255759958318, + 0.31809705128487903, + 0.353631213596107, + 0.3877122293970111, + 0.4202000524833106, + 0.4509611834213275, + 0.4798692181257957, + 0.5068053672813605, + 0.5316589444733558, + 0.5543278210220242, + 0.5747188456511684, + 0.592748227266726, + 0.6083418792723487, + 0.6214357240071176, + 0.6319759560543963, + 0.6399192633398301, + 0.645233005109949, + 0.6478953460600255, + 0.6478953460600255, + 0.645233005109949, + 0.6399192633398301, + 0.6319759560543963, + 0.6214357240071177, + 0.6083418792723488, + 0.5927482272667262, + 0.5747188456511684, + 0.5543278210220243, + 0.5316589444733559, + 0.5068053672813606, + 0.47986921812579586, + 0.45096118342132757, + 0.4202000524833108, + 0.3877122293970113, + 0.3536312135961073, + 0.3180970512848792, + 0.28125575995831803, + 0.24325872838491705, + 0.2042620945177486, + 0.16442610389012507, + 0.12391445113232813, + 0.0828936073152623, + 0.041532135885114764, + 7.938508294301087e-17 + ], + [ + 0, + 0.03495254112771636, + 0.06976145476664239, + 0.10428370362414716, + 0.138377428374676, + 0.17190253059014804, + 0.20472124843444797, + 0.2366987227563607, + 0.2677035512547507, + 0.29760832843880325, + 0.32629016916451453, + 0.3536312135961071, + 0.3795191115173757, + 0.40384748400282533, + 0.4265163605514937, + 0.4474325898871836, + 0.4665102227370374, + 0.48367086501553586, + 0.49884399996261025, + 0.5119672779121358, + 0.5229867725000837, + 0.5318572022595179, + 0.5385421166918557, + 0.5430140460497848, + 0.5452546142163477, + 0.5452546142163477, + 0.5430140460497848, + 0.5385421166918557, + 0.5318572022595179, + 0.5229867725000839, + 0.5119672779121359, + 0.49884399996261036, + 0.4836708650155359, + 0.46651022273703746, + 0.44743258988718365, + 0.4265163605514938, + 0.4038474840028255, + 0.3795191115173758, + 0.3536312135961073, + 0.32629016916451464, + 0.2976083284388035, + 0.26770355125475087, + 0.23669872275636075, + 0.20472124843444817, + 0.17190253059014815, + 0.13837742837467626, + 0.1042837036241473, + 0.06976145476664265, + 0.034952541127716535, + 6.680875705906664e-17 + ], + [ + 0, + 0.027799026611316207, + 0.05548382105941401, + 0.08294062058553639, + 0.11005659931096547, + 0.13672033186275928, + 0.1628222512445098, + 0.18825509907063329, + 0.2129143663140834, + 0.23669872275636056, + 0.2595104333751151, + 0.28125575995831786, + 0.30184534629468057, + 0.32119458535749473, + 0.33922396697305246, + 0.35585940454500514, + 0.3710325394920795, + 0.3846810221481508, + 0.3967487679703949, + 0.40718618800270473, + 0.41595039264734807, + 0.4230053679075241, + 0.4283221233766012, + 0.43187881136591644, + 0.43366081668161466, + 0.43366081668161466, + 0.43187881136591644, + 0.4283221233766012, + 0.4230053679075241, + 0.4159503926473481, + 0.4071861880027048, + 0.396748767970395, + 0.38468102214815086, + 0.37103253949207954, + 0.3558594045450052, + 0.3392239669730525, + 0.32119458535749484, + 0.3018453462946806, + 0.28125575995831803, + 0.25951043337511515, + 0.23669872275636075, + 0.2129143663140835, + 0.18825509907063334, + 0.16282225124450997, + 0.1367203318627594, + 0.11005659931096566, + 0.0829406205855365, + 0.05548382105941423, + 0.027799026611316346, + 5.3135433231240294e-17 + ], + [ + 0, + 0.020189052846503835, + 0.04029514454432313, + 0.06023565484992841, + 0.07992864392924788, + 0.09929318906602172, + 0.11824971719060101, + 0.13672033186275934, + 0.15462913336487435, + 0.171902530590148, + 0.1884695434442496, + 0.2042620945177485, + 0.21921528883079205, + 0.2332676805004979, + 0.24636152523526667, + 0.2584430176184623, + 0.26946251220641015, + 0.27937472753217435, + 0.28813893217681763, + 0.29571911214353935, + 0.30208411884691255, + 0.30720779710910356, + 0.31106909263710747, + 0.3136521385393543, + 0.3149463205261702, + 0.3149463205261702, + 0.3136521385393543, + 0.31106909263710747, + 0.30720779710910356, + 0.3020841188469126, + 0.29571911214353935, + 0.28813893217681774, + 0.27937472753217435, + 0.2694625122064102, + 0.2584430176184623, + 0.2463615252352667, + 0.23326768050049795, + 0.21921528883079208, + 0.2042620945177486, + 0.18846954344424965, + 0.17190253059014815, + 0.15462913336487447, + 0.1367203318627594, + 0.11824971719060114, + 0.09929318906602179, + 0.07992864392924802, + 0.06023565484992849, + 0.04029514454432329, + 0.020189052846503935, + 3.8589627058765365e-17 + ], + [ + 0, + 0.01224757539210836, + 0.024444822869833866, + 0.03654162132698916, + 0.048488262423958664, + 0.06023565484992845, + 0.07173552604961243, + 0.08294062058553649, + 0.09380489432076723, + 0.10428370362414721, + 0.11433398882055129, + 0.12391445113232807, + 0.13298572238483566, + 0.14151052677871598, + 0.14945383406414978, + 0.15678300348766708, + 0.16346791792000476, + 0.16948110761385074, + 0.17479786308292783, + 0.1793963366385731, + 0.18325763216657698, + 0.18636588277536956, + 0.18870831599648163, + 0.19027530626935735, + 0.19106041449484706, + 0.19106041449484706, + 0.19027530626935735, + 0.18870831599648163, + 0.18636588277536956, + 0.183257632166577, + 0.17939633663857313, + 0.17479786308292786, + 0.16948110761385077, + 0.16346791792000478, + 0.1567830034876671, + 0.14945383406414978, + 0.14151052677871603, + 0.1329857223848357, + 0.12391445113232813, + 0.11433398882055133, + 0.1042837036241473, + 0.09380489432076727, + 0.0829406205855365, + 0.0717355260496125, + 0.06023565484992849, + 0.04848826242395875, + 0.03654162132698921, + 0.02444482286983396, + 0.01224757539210842, + 2.3410180276853326e-17 + ], + [ + 0, + 0.004104993088376964, + 0.008193117879635533, + 0.012247575392108405, + 0.01625170499019842, + 0.02018905284650392, + 0.024043439554124885, + 0.02779902661131634, + 0.03144038150528938, + 0.03495254112771651, + 0.03832107326135329, + 0.04153213588511474, + 0.044572534053909034, + 0.047429774119497246, + 0.05009211506957381, + 0.0525486167741045, + 0.054789184940667444, + 0.05680461259406588, + 0.0585866179097641, + 0.06012787824568097, + 0.061422060232496904, + 0.06246384579882691, + 0.06324895402431663, + 0.06377415873086233, + 0.06403730173966878, + 0.06403730173966878, + 0.06377415873086233, + 0.06324895402431663, + 0.06246384579882691, + 0.06142206023249691, + 0.06012787824568098, + 0.05858661790976411, + 0.056804612594065884, + 0.05478918494066745, + 0.05254861677410451, + 0.05009211506957382, + 0.04742977411949726, + 0.04457253405390904, + 0.041532135885114764, + 0.038321073261353304, + 0.034952541127716535, + 0.031440381505289404, + 0.027799026611316346, + 0.02404343955412491, + 0.020189052846503935, + 0.016251704990198446, + 0.01224757539210842, + 0.008193117879635564, + 0.004104993088376985, + 7.846338982004726e-18 + ], + [ + 0, + -0.004104993088376921, + -0.008193117879635446, + -0.012247575392108275, + -0.016251704990198245, + -0.020189052846503706, + -0.024043439554124628, + -0.027799026611316044, + -0.03144038150528905, + -0.03495254112771614, + -0.03832107326135288, + -0.0415321358851143, + -0.04457253405390856, + -0.04742977411949675, + -0.05009211506957328, + -0.05254861677410394, + -0.05478918494066686, + -0.056804612594065274, + -0.05858661790976347, + -0.06012787824568033, + -0.06142206023249625, + -0.062463845798826245, + -0.06324895402431596, + -0.06377415873086166, + -0.0640373017396681, + -0.0640373017396681, + -0.06377415873086166, + -0.06324895402431596, + -0.062463845798826245, + -0.06142206023249626, + -0.06012787824568034, + -0.05858661790976349, + -0.05680461259406528, + -0.05478918494066687, + -0.05254861677410395, + -0.050092115069573284, + -0.04742977411949676, + -0.04457253405390857, + -0.04153213588511432, + -0.038321073261352895, + -0.03495254112771617, + -0.031440381505289064, + -0.02779902661131605, + -0.024043439554124652, + -0.02018905284650372, + -0.016251704990198273, + -0.01224757539210829, + -0.008193117879635477, + -0.0041049930883769415, + -7.846338982004641e-18 + ], + [ + 0, + -0.012247575392108316, + -0.02444482286983378, + -0.036541621326989036, + -0.04848826242395849, + -0.06023565484992824, + -0.07173552604961218, + -0.0829406205855362, + -0.0938048943207669, + -0.10428370362414685, + -0.1143339888205509, + -0.12391445113232763, + -0.1329857223848352, + -0.14151052677871548, + -0.14945383406414925, + -0.15678300348766652, + -0.1634679179200042, + -0.16948110761385016, + -0.17479786308292722, + -0.1793963366385725, + -0.18325763216657634, + -0.18636588277536892, + -0.188708315996481, + -0.19027530626935668, + -0.1910604144948464, + -0.1910604144948464, + -0.19027530626935668, + -0.188708315996481, + -0.18636588277536892, + -0.18325763216657637, + -0.17939633663857252, + -0.17479786308292725, + -0.16948110761385018, + -0.16346791792000423, + -0.15678300348766655, + -0.14945383406414928, + -0.14151052677871553, + -0.13298572238483522, + -0.1239144511323277, + -0.11433398882055094, + -0.10428370362414693, + -0.09380489432076695, + -0.08294062058553621, + -0.07173552604961225, + -0.06023565484992828, + -0.048488262423958574, + -0.036541621326989085, + -0.024444822869833877, + -0.012247575392108377, + -2.3410180276853242e-17 + ], + [ + 0, + -0.020189052846503793, + -0.04029514454432305, + -0.06023565484992829, + -0.07992864392924771, + -0.09929318906602151, + -0.11824971719060076, + -0.13672033186275906, + -0.15462913336487405, + -0.17190253059014765, + -0.1884695434442492, + -0.20426209451774807, + -0.21921528883079158, + -0.2332676805004974, + -0.24636152523526614, + -0.2584430176184617, + -0.2694625122064096, + -0.27937472753217374, + -0.288138932176817, + -0.2957191121435387, + -0.30208411884691194, + -0.30720779710910295, + -0.3110690926371068, + -0.31365213853935364, + -0.31494632052616955, + -0.31494632052616955, + -0.31365213853935364, + -0.3110690926371068, + -0.30720779710910295, + -0.302084118846912, + -0.29571911214353874, + -0.28813893217681713, + -0.2793747275321738, + -0.2694625122064096, + -0.2584430176184617, + -0.24636152523526617, + -0.23326768050049748, + -0.2192152888307916, + -0.20426209451774816, + -0.18846954344424927, + -0.1719025305901478, + -0.15462913336487413, + -0.1367203318627591, + -0.11824971719060089, + -0.09929318906602158, + -0.07992864392924785, + -0.06023565484992836, + -0.0402951445443232, + -0.020189052846503894, + -3.858962705876528e-17 + ], + [ + 0, + -0.027799026611316193, + -0.05548382105941398, + -0.08294062058553635, + -0.11005659931096541, + -0.13672033186275923, + -0.16282225124450972, + -0.18825509907063318, + -0.21291436631408328, + -0.23669872275636045, + -0.2595104333751149, + -0.28125575995831775, + -0.30184534629468046, + -0.32119458535749457, + -0.3392239669730523, + -0.355859404545005, + -0.3710325394920793, + -0.38468102214815064, + -0.39674876797039466, + -0.40718618800270456, + -0.4159503926473479, + -0.42300536790752385, + -0.42832212337660097, + -0.4318788113659162, + -0.43366081668161444, + -0.43366081668161444, + -0.4318788113659162, + -0.42832212337660097, + -0.42300536790752385, + -0.41595039264734796, + -0.40718618800270456, + -0.39674876797039477, + -0.38468102214815064, + -0.37103253949207937, + -0.35585940454500503, + -0.3392239669730523, + -0.3211945853574947, + -0.30184534629468046, + -0.28125575995831786, + -0.25951043337511503, + -0.23669872275636064, + -0.2129143663140834, + -0.18825509907063323, + -0.16282225124450989, + -0.1367203318627593, + -0.1100565993109656, + -0.08294062058553646, + -0.0554838210594142, + -0.027799026611316332, + -5.3135433231240263e-17 + ], + [ + 0, + -0.03495254112771633, + -0.06976145476664232, + -0.10428370362414704, + -0.13837742837467587, + -0.17190253059014787, + -0.20472124843444775, + -0.23669872275636045, + -0.2677035512547504, + -0.29760832843880297, + -0.3262901691645142, + -0.3536312135961067, + -0.37951911151737533, + -0.40384748400282494, + -0.42651636055149333, + -0.44743258988718315, + -0.46651022273703696, + -0.48367086501553536, + -0.4988439999626097, + -0.5119672779121354, + -0.5229867725000832, + -0.5318572022595174, + -0.5385421166918551, + -0.5430140460497842, + -0.5452546142163471, + -0.5452546142163471, + -0.5430140460497842, + -0.5385421166918551, + -0.5318572022595174, + -0.5229867725000833, + -0.5119672779121354, + -0.49884399996260986, + -0.4836708650155354, + -0.466510222737037, + -0.4474325898871832, + -0.4265163605514934, + -0.40384748400282505, + -0.3795191115173754, + -0.3536312135961069, + -0.3262901691645143, + -0.2976083284388032, + -0.2677035512547506, + -0.23669872275636053, + -0.20472124843444797, + -0.17190253059014798, + -0.13837742837467612, + -0.10428370362414718, + -0.06976145476664258, + -0.0349525411277165, + -6.680875705906658e-17 + ], + [ + 0, + -0.04153213588511452, + -0.0828936073152619, + -0.12391445113232787, + -0.16442610389012466, + -0.2042620945177483, + -0.24325872838491658, + -0.2812557599583177, + -0.31809705128487875, + -0.35363121359610666, + -0.3877122293970108, + -0.42020005248331027, + -0.4509611834213271, + -0.4798692181257953, + -0.50680536728136, + -0.5316589444733554, + -0.5543278210220237, + -0.5747188456511678, + -0.5927482272667255, + -0.6083418792723483, + -0.621435724007117, + -0.6319759560543958, + -0.6399192633398295, + -0.6452330051099484, + -0.647895346060025, + -0.647895346060025, + -0.6452330051099484, + -0.6399192633398295, + -0.6319759560543958, + -0.6214357240071171, + -0.6083418792723483, + -0.5927482272667257, + -0.5747188456511679, + -0.5543278210220238, + -0.5316589444733555, + -0.5068053672813602, + -0.4798692181257954, + -0.4509611834213272, + -0.4202000524833105, + -0.38771222939701094, + -0.35363121359610694, + -0.3180970512848789, + -0.2812557599583178, + -0.24325872838491683, + -0.20426209451774843, + -0.16442610389012494, + -0.12391445113232803, + -0.08289360731526223, + -0.04153213588511473, + -7.938508294301079e-17 + ], + [ + 0, + -0.047429774119497, + -0.09466464912348235, + -0.14151052677871576, + -0.1877749073255026, + -0.23326768050049765, + -0.2778019067405556, + -0.32119458535749457, + -0.363267406527177, + -0.4038474840028249, + -0.44276806554169157, + -0.4798692181257953, + -0.5149984851609956, + -0.5480115129538407, + -0.5787726438918576, + -0.60715547388978, + -0.6330433718110486, + -0.6563299587301682, + -0.676919545066531, + -0.6947275237934282, + -0.7096807181064718, + -0.7217176821227792, + -0.7307889533752868, + -0.7368572560646365, + -0.7398976542334308, + -0.7398976542334308, + -0.7368572560646365, + -0.7307889533752868, + -0.7217176821227792, + -0.7096807181064719, + -0.6947275237934283, + -0.6769195450665311, + -0.6563299587301683, + -0.6330433718110487, + -0.6071554738897801, + -0.5787726438918577, + -0.5480115129538409, + -0.5149984851609957, + -0.4798692181257956, + -0.44276806554169174, + -0.4038474840028252, + -0.3632674065271772, + -0.3211945853574946, + -0.2778019067405559, + -0.23326768050049781, + -0.18777490732550292, + -0.14151052677871595, + -0.09466464912348271, + -0.04742977411949723, + -9.065790795974986e-17 + ], + [ + 0, + -0.052548616774104225, + -0.10488130001024071, + -0.15678300348766683, + -0.2080404519739133, + -0.258443017618462, + -0.307783585467763, + -0.355859404545005, + -0.40247292099736853, + -0.4474325898871831, + -0.4905536622911617, + -0.5316589444733555, + -0.5705795260122221, + -0.6071554738897801, + -0.6412364896906843, + -0.6726825272106536, + -0.7013643679363648, + -0.7271641520320404, + -0.7499758626507949, + -0.7697057615805992, + -0.7862727744347008, + -0.799608823803669, + -0.8096591090000731, + -0.8163823312462617, + -0.8197508633798984, + -0.8197508633798984, + -0.8163823312462617, + -0.8096591090000731, + -0.799608823803669, + -0.7862727744347009, + -0.7697057615805993, + -0.7499758626507951, + -0.7271641520320405, + -0.7013643679363649, + -0.6726825272106537, + -0.6412364896906843, + -0.6071554738897802, + -0.5705795260122222, + -0.5316589444733557, + -0.4905536622911619, + -0.4474325898871835, + -0.40247292099736875, + -0.35585940454500503, + -0.3077835854677633, + -0.25844301761846217, + -0.20804045197391366, + -0.15678300348766702, + -0.10488130001024112, + -0.05254861677410449, + -1.0044213263416298e-16 + ], + [ + 0, + -0.05680461259406559, + -0.11337580285043099, + -0.16948110761385052, + -0.22488997815250114, + -0.2793747275321741, + -0.3327114662307263, + -0.3846810221481507, + -0.43506984123174786, + -0.48367086501553547, + -0.530284381467899, + -0.574718845651168, + -0.6167916668208505, + -0.6563299587301684, + -0.6931712500567295, + -0.7271641520320407, + -0.7581689805304306, + -0.7860583300610847, + -0.8107175973045347, + -0.8320454520422813, + -0.8499542535443964, + -0.8643704107040818, + -0.8752346844393126, + -0.8825024311189311, + -0.8861437860129042, + -0.8861437860129042, + -0.8825024311189311, + -0.8752346844393126, + -0.8643704107040818, + -0.8499542535443965, + -0.8320454520422814, + -0.810717597304535, + -0.7860583300610848, + -0.7581689805304307, + -0.7271641520320408, + -0.6931712500567296, + -0.6563299587301686, + -0.6167916668208506, + -0.5747188456511684, + -0.5302843814678992, + -0.48367086501553586, + -0.4350698412317481, + -0.3846810221481508, + -0.3327114662307266, + -0.27937472753217435, + -0.22488997815250153, + -0.16948110761385074, + -0.11337580285043143, + -0.05680461259406588, + -1.085771002675958e-16 + ], + [ + 0, + -0.060127878245680666, + -0.1200086781422604, + -0.17939633663857285, + -0.23804681710724385, + -0.2957191121435391, + -0.3521762339164859, + -0.4071861880027046, + -0.4605229267012567, + -0.5119672779121354, + -0.5613078457614363, + -0.6083418792723484, + -0.6528761055124064, + -0.6947275237934284, + -0.7337241576605967, + -0.7697057615805993, + -0.8025244794248992, + -0.8320454520422812, + -0.8581473714240317, + -0.880722979184567, + -0.8996795073091463, + -0.9149390593575433, + -0.9264389305572273, + -0.9341318654707241, + -0.9379862521783451, + -0.9379862521783451, + -0.9341318654707241, + -0.9264389305572273, + -0.9149390593575433, + -0.8996795073091464, + -0.8807229791845671, + -0.858147371424032, + -0.8320454520422813, + -0.8025244794248994, + -0.7697057615805994, + -0.7337241576605968, + -0.6947275237934285, + -0.6528761055124064, + -0.6083418792723487, + -0.5613078457614366, + -0.5119672779121358, + -0.46052292670125694, + -0.4071861880027047, + -0.3521762339164862, + -0.2957191121435393, + -0.23804681710724426, + -0.1793963366385731, + -0.12000867814226086, + -0.060127878245680964, + -1.1492923491641061e-16 + ], + [ + 0, + -0.0624638457988266, + -0.12467101425681293, + -0.1863658827753693, + -0.24729493390624518, + -0.3072077971091034, + -0.3658582775777744, + -0.42300536790752397, + -0.4784142384461746, + -0.5318572022595175, + -0.5831146507457641, + -0.631975956054396, + -0.6782403366011829, + -0.7217176821227794, + -0.7622293348805763, + -0.7996088238036693, + -0.833702548554198, + -0.8643704107040818, + -0.891486389429511, + -0.9149390593575433, + -0.9346320484368628, + -0.9504844339512096, + -0.9624310750481792, + -0.9704228804169575, + -0.9744270100150474, + -0.9744270100150474, + -0.9704228804169575, + -0.9624310750481792, + -0.9504844339512096, + -0.9346320484368629, + -0.9149390593575434, + -0.8914863894295112, + -0.8643704107040819, + -0.8337025485541981, + -0.7996088238036694, + -0.7622293348805764, + -0.7217176821227796, + -0.678240336601183, + -0.6319759560543963, + -0.5831146507457643, + -0.5318572022595179, + -0.47841423844617487, + -0.4230053679075241, + -0.3658582775777748, + -0.30720779710910356, + -0.24729493390624563, + -0.18636588277536956, + -0.12467101425681341, + -0.06246384579882691, + -1.1939423470528823e-16 + ], + [ + 0, + -0.06377415873086201, + -0.12728625576398475, + -0.19027530626935707, + -0.25248247472734336, + -0.31365213853935403, + -0.37353293843593377, + -0.43187881136591627, + -0.48845000162228164, + -0.5430140460497843, + -0.5953467292859208, + -0.6452330051099486, + -0.6924678801139339, + -0.7368572560646366, + -0.778218727494784, + -0.8163823312462618, + -0.8511912448851877, + -0.8825024311189311, + -0.9101872255670288, + -0.9341318654707241, + -0.9542379571685434, + -0.9704228804169573, + -0.9826201278946828, + -0.9907795784955327, + -0.9948677032867912, + -0.9948677032867912, + -0.9907795784955327, + -0.9826201278946828, + -0.9704228804169573, + -0.9542379571685435, + -0.9341318654707242, + -0.910187225567029, + -0.8825024311189312, + -0.8511912448851878, + -0.8163823312462619, + -0.7782187274947842, + -0.7368572560646368, + -0.692467880113934, + -0.6452330051099489, + -0.595346729285921, + -0.5430140460497848, + -0.4884500016222819, + -0.4318788113659164, + -0.37353293843593416, + -0.31365213853935425, + -0.2524824747273438, + -0.19027530626935732, + -0.12728625576398525, + -0.06377415873086233, + -1.2189878446113672e-16 + ], + [ + 0, + -0.06403730173966846, + -0.1278114604705305, + -0.19106041449484681, + -0.25352426029367336, + -0.31494632052617, + -0.37507419877185066, + -0.43366081668161455, + -0.49046542927568015, + -0.5452546142163472, + -0.5978032309904515, + -0.6478953460600252, + -0.6953251201795222, + -0.739897654233431, + -0.7814297901185455, + -0.8197508633798987, + -0.854703404507615, + -0.8861437860129042, + -0.9139428126242204, + -0.9379862521783452, + -0.958175305024849, + -0.9744270100150474, + -0.9866745854071558, + -0.9948677032867913, + -0.9989726963751682, + -0.9989726963751682, + -0.9948677032867913, + -0.9866745854071558, + -0.9744270100150474, + -0.9581753050248492, + -0.9379862521783453, + -0.9139428126242206, + -0.8861437860129043, + -0.8547034045076151, + -0.8197508633798988, + -0.7814297901185456, + -0.7398976542334312, + -0.6953251201795223, + -0.6478953460600255, + -0.5978032309904517, + -0.5452546142163477, + -0.49046542927568043, + -0.43366081668161466, + -0.37507419877185105, + -0.3149463205261702, + -0.2535242602936738, + -0.19106041449484706, + -0.127811460470531, + -0.06403730173966878, + -1.2240175954620718e-16 + ], + [ + 0, + -0.06324895402431632, + -0.12623800452968864, + -0.1887083159964814, + -0.2504031845150378, + -0.31106909263710725, + -0.37045675113341975, + -0.42832212337660114, + -0.4844274281400206, + -0.5385421166918554, + -0.5904438201692814, + -0.6399192633398298, + -0.6867651409950633, + -0.7307889533752872, + -0.7718097971923532, + -0.8096591090000734, + -0.8441813578575782, + -0.8752346844393127, + -0.9026914839654351, + -0.9264389305572275, + -0.9463794408628328, + -0.9624310750481793, + -0.9745278735053345, + -0.982620127894683, + -0.9866745854071559, + -0.9866745854071559, + -0.982620127894683, + -0.9745278735053345, + -0.9624310750481793, + -0.9463794408628329, + -0.9264389305572275, + -0.9026914839654353, + -0.8752346844393128, + -0.8441813578575783, + -0.8096591090000735, + -0.7718097971923533, + -0.7307889533752874, + -0.6867651409950634, + -0.6399192633398302, + -0.5904438201692817, + -0.5385421166918558, + -0.4844274281400209, + -0.42832212337660125, + -0.37045675113342014, + -0.31106909263710747, + -0.25040318451503824, + -0.18870831599648166, + -0.12623800452968914, + -0.06324895402431663, + -1.2089490112350823e-16 + ], + [ + 0, + -0.06142206023249661, + -0.1225917240445073, + -0.18325763216657678, + -0.24317049536943494, + -0.30208411884691244, + -0.35975641388320767, + -0.41595039264734807, + -0.470435142027021, + -0.5229867725000835, + -0.5733893381446322, + -0.6214357240071173, + -0.6669284971821124, + -0.7096807181064722, + -0.7495167087340958, + -0.7862727744347012, + -0.8197978766501732, + -0.8499542535443966, + -0.8766179860961903, + -0.8996795073091466, + -0.9190440524459205, + -0.934632048436863, + -0.9463794408628329, + -0.9542379571685438, + -0.9581753050248493, + -0.9581753050248493, + -0.9542379571685438, + -0.9463794408628329, + -0.934632048436863, + -0.9190440524459206, + -0.8996795073091467, + -0.8766179860961906, + -0.8499542535443967, + -0.8197978766501732, + -0.7862727744347013, + -0.7495167087340959, + -0.7096807181064724, + -0.6669284971821126, + -0.6214357240071177, + -0.5733893381446323, + -0.5229867725000839, + -0.4704351420270213, + -0.4159503926473482, + -0.35975641388320806, + -0.30208411884691266, + -0.24317049536943536, + -0.18325763216657703, + -0.12259172404450779, + -0.06142206023249692, + -1.174029517666812e-16 + ], + [ + 0, + -0.058586617909763834, + -0.11693249083974633, + -0.1747978630829277, + -0.2319449534126772, + -0.2881389321768176, + -0.3431488862630363, + -0.39674876797039493, + -0.44871832388781935, + -0.4988439999626101, + -0.546919819039852, + -0.592748227266726, + -0.6361409058836649, + -0.6769195450665315, + -0.7149165766399326, + -0.7499758626507954, + -0.7819533369727081, + -0.8107175973045352, + -0.8361504451306586, + -0.8581473714240322, + -0.8766179860961906, + -0.8914863894295113, + -0.9026914839654354, + -0.9101872255670294, + -0.9139428126242208, + -0.9139428126242208, + -0.9101872255670294, + -0.9026914839654354, + -0.8914863894295113, + -0.8766179860961907, + -0.8581473714240323, + -0.8361504451306588, + -0.8107175973045353, + -0.7819533369727082, + -0.7499758626507955, + -0.7149165766399327, + -0.6769195450665316, + -0.636140905883665, + -0.5927482272667264, + -0.5469198190398522, + -0.4988439999626105, + -0.4487183238878196, + -0.39674876797039504, + -0.34314888626303663, + -0.2881389321768178, + -0.23194495341267762, + -0.1747978630829279, + -0.11693249083974679, + -0.058586617909764126, + -1.1198324918762505e-16 + ], + [ + 0, + -0.054789184940667195, + -0.10935322936816988, + -0.16346791792000462, + -0.2169108817333476, + -0.26946251220641004, + -0.3209068634172888, + -0.37103253949207954, + -0.4196335632758672, + -0.46651022273703724, + -0.5114698916268519, + -0.5543278210220242, + -0.5949078984976721, + -0.6330433718110491, + -0.668577534122277, + -0.7013643679363653, + -0.7312691451204177, + -0.7581689805304308, + -0.7819533369727081, + -0.8025244794248996, + -0.8197978766501733, + -0.8337025485541983, + -0.8441813578575784, + -0.8511912448851882, + -0.8547034045076153, + -0.8547034045076153, + -0.8511912448851882, + -0.8441813578575784, + -0.8337025485541983, + -0.8197978766501735, + -0.8025244794248997, + -0.7819533369727082, + -0.7581689805304309, + -0.7312691451204179, + -0.7013643679363654, + -0.6685775341222772, + -0.6330433718110492, + -0.5949078984976721, + -0.5543278210220244, + -0.5114698916268521, + -0.4665102227370376, + -0.4196335632758674, + -0.37103253949207965, + -0.3209068634172891, + -0.26946251220641027, + -0.21691088173334797, + -0.16346791792000484, + -0.10935322936817031, + -0.054789184940667465, + -1.0472478475285211e-16 + ], + [ + 0, + -0.05009211506957357, + -0.09997839089360128, + -0.14945383406414958, + -0.19831513937278142, + -0.24636152523526653, + -0.29339555874617845, + -0.3392239669730524, + -0.3836584311563213, + -0.42651636055149345, + -0.4676216427336871, + -0.5068053672813604, + -0.543906519865464, + -0.5787726438918578, + -0.6112604669781573, + -0.6412364896906845, + -0.6685775341222769, + -0.6931712500567296, + -0.7149165766399324, + -0.7337241576605968, + -0.7495167087340958, + -0.7622293348805764, + -0.7718097971923532, + -0.7782187274947843, + -0.7814297901185456, + -0.7814297901185456, + -0.7782187274947843, + -0.7718097971923532, + -0.7622293348805764, + -0.7495167087340958, + -0.733724157660597, + -0.7149165766399326, + -0.6931712500567297, + -0.6685775341222769, + -0.6412364896906846, + -0.6112604669781574, + -0.578772643891858, + -0.5439065198654641, + -0.5068053672813606, + -0.4676216427336873, + -0.4265163605514938, + -0.38365843115632153, + -0.3392239669730525, + -0.2933955587461788, + -0.2463615252352667, + -0.19831513937278175, + -0.14945383406414978, + -0.09997839089360167, + -0.05009211506957382, + -9.574674224771029e-17 + ], + [ + 0, + -0.04457253405390885, + -0.08896191000461162, + -0.1329857223848356, + -0.17646306790643226, + -0.21921528883079208, + -0.2610667071118141, + -0.30184534629468074, + -0.34138363820399875, + -0.3795191115173757, + -0.4160950593949337, + -0.4509611834213276, + -0.4839742112141728, + -0.5149984851609961, + -0.5439065198654643, + -0.5705795260122227, + -0.5949078984976723, + -0.616791666820851, + -0.6361409058836651, + -0.6528761055124069, + -0.6669284971821128, + -0.6782403366011833, + -0.6867651409950637, + -0.6924678801139346, + -0.6953251201795227, + -0.6953251201795227, + -0.6924678801139346, + -0.6867651409950637, + -0.6782403366011833, + -0.6669284971821129, + -0.652876105512407, + -0.6361409058836652, + -0.6167916668208511, + -0.5949078984976723, + -0.5705795260122228, + -0.5439065198654645, + -0.5149984851609963, + -0.48397421121417283, + -0.4509611834213279, + -0.41609505939493385, + -0.37951911151737605, + -0.3413836382039989, + -0.30184534629468085, + -0.2610667071118144, + -0.21921528883079222, + -0.17646306790643257, + -0.13298572238483578, + -0.08896191000461197, + -0.04457253405390907, + -8.519654088192268e-17 + ], + [ + 0, + -0.03832107326135312, + -0.0764846770128309, + -0.11433398882055121, + -0.15171347774364416, + -0.18846954344424957, + -0.22445114736425226, + -0.25951043337511515, + -0.2935033353504262, + -0.3262901691645144, + -0.35773620668448386, + -0.38771222939701117, + -0.41609505939493363, + -0.44276806554169196, + -0.46762164273368734, + -0.4905536622911621, + -0.511469891626852, + -0.5302843814678994, + -0.5469198190398521, + -0.5613078457614368, + -0.5733893381446323, + -0.5831146507457644, + -0.5904438201692817, + -0.5953467292859211, + -0.5978032309904519, + -0.5978032309904519, + -0.5953467292859211, + -0.5904438201692817, + -0.5831146507457644, + -0.5733893381446324, + -0.5613078457614368, + -0.5469198190398522, + -0.5302843814678995, + -0.511469891626852, + -0.49055366229116215, + -0.4676216427336874, + -0.44276806554169207, + -0.4160950593949337, + -0.38771222939701133, + -0.357736206684484, + -0.3262901691645147, + -0.2935033353504264, + -0.2595104333751152, + -0.22445114736425248, + -0.1884695434442497, + -0.1517134777436444, + -0.11433398882055136, + -0.07648467701283121, + -0.03832107326135331, + -7.324741467023933e-17 + ], + [ + 0, + -0.03144038150528928, + -0.06275156773903263, + -0.09380489432076725, + -0.12447275647065109, + -0.1546291333648745, + -0.18415010598225653, + -0.21291436631408367, + -0.24080371584473784, + -0.2677035512547509, + -0.29350333535042655, + -0.31809705128487936, + -0.341383638203999, + -0.36326740652717765, + -0.38365843115632187, + -0.40247292099736925, + -0.4196335632758677, + -0.4350698412317485, + -0.44871832388781985, + -0.4605229267012575, + -0.4704351420270217, + -0.47841423844617537, + -0.4844274281400213, + -0.48845000162228247, + -0.49046542927568093, + -0.49046542927568093, + -0.48845000162228247, + -0.4844274281400213, + -0.47841423844617537, + -0.47043514202702175, + -0.46052292670125755, + -0.44871832388781996, + -0.4350698412317486, + -0.41963356327586776, + -0.4024729209973693, + -0.3836584311563219, + -0.36326740652717776, + -0.34138363820399903, + -0.31809705128487953, + -0.29350333535042666, + -0.2677035512547511, + -0.24080371584473798, + -0.21291436631408373, + -0.18415010598225673, + -0.1546291333648746, + -0.1244727564706513, + -0.09380489432076737, + -0.06275156773903288, + -0.03144038150528943, + -6.009556793470482e-17 + ], + [ + 0, + -0.024043439554124794, + -0.04798807945782008, + -0.07173552604961243, + -0.09518819597764483, + -0.11824971719060108, + -0.14082532495113637, + -0.16282225124450997, + -0.1841501059822565, + -0.20472124843444808, + -0.22445114736425242, + -0.243258728384917, + -0.2610667071118143, + -0.27780190674055605, + -0.2933955587461788, + -0.30778358546776347, + -0.3209068634172891, + -0.3327114662307267, + -0.3431488862630366, + -0.3521762339164864, + -0.35975641388320806, + -0.3658582775777749, + -0.3704567511334202, + -0.3735329384359343, + -0.37507419877185116, + -0.37507419877185116, + -0.3735329384359343, + -0.3704567511334202, + -0.3658582775777749, + -0.3597564138832081, + -0.35217623391648645, + -0.3431488862630367, + -0.3327114662307268, + -0.32090686341728913, + -0.3077835854677635, + -0.29339555874617884, + -0.27780190674055616, + -0.26106670711181434, + -0.24325872838491713, + -0.2244511473642525, + -0.20472124843444825, + -0.1841501059822566, + -0.16282225124451002, + -0.1408253249511365, + -0.11824971719060116, + -0.095188195977645, + -0.07173552604961253, + -0.04798807945782027, + -0.024043439554124916, + -4.5956953635114025e-17 + ], + [ + 0, + -0.0162517049901984, + -0.03243662823861229, + -0.04848826242395879, + -0.06434064793830556, + -0.07992864392924813, + -0.09518819597764508, + -0.11005659931096587, + -0.12447275647065138, + -0.13837742837467645, + -0.15171347774364466, + -0.16442610389012535, + -0.17646306790643282, + -0.1877749073255034, + -0.19831513937278217, + -0.2080404519739142, + -0.21691088173334838, + -0.22488997815250203, + -0.231944953412678, + -0.23804681710724482, + -0.24317049536943583, + -0.24729493390624616, + -0.25040318451503873, + -0.25248247472734436, + -0.25352426029367436, + -0.25352426029367436, + -0.25248247472734436, + -0.25040318451503873, + -0.24729493390624616, + -0.24317049536943586, + -0.23804681710724485, + -0.23194495341267807, + -0.22488997815250206, + -0.2169108817333484, + -0.20804045197391421, + -0.1983151393727822, + -0.18777490732550345, + -0.17646306790643285, + -0.16442610389012544, + -0.15171347774364471, + -0.13837742837467656, + -0.12447275647065145, + -0.1100565993109659, + -0.09518819597764518, + -0.07992864392924819, + -0.06434064793830567, + -0.04848826242395885, + -0.03243662823861242, + -0.01625170499019848, + -3.1063727427383314e-17 + ], + [ + 0, + -0.008193117879635533, + -0.01635256848048537, + -0.024444822869833956, + -0.032436628238612326, + -0.04029514454432331, + -0.047988079457820264, + -0.055483821059414275, + -0.06275156773903286, + -0.06976145476664268, + -0.07648467701283125, + -0.08289360731526234, + -0.088961910004612, + -0.09466464912348285, + -0.09997839089360176, + -0.10488130001024126, + -0.10935322936817038, + -0.11337580285043156, + -0.11693249083974686, + -0.12000867814226102, + -0.1225917240445079, + -0.12467101425681354, + -0.12623800452968925, + -0.12728625576398542, + -0.12781146047053113, + -0.12781146047053113, + -0.12728625576398542, + -0.12623800452968925, + -0.12467101425681354, + -0.12259172404450791, + -0.12000867814226103, + -0.11693249083974688, + -0.11337580285043157, + -0.1093532293681704, + -0.10488130001024128, + -0.09997839089360178, + -0.09466464912348288, + -0.08896191000461201, + -0.08289360731526238, + -0.07648467701283128, + -0.06976145476664274, + -0.06275156773903288, + -0.05548382105941429, + -0.04798807945782031, + -0.040295144544323334, + -0.03243662823861238, + -0.024444822869833988, + -0.016352568480485434, + -0.008193117879635574, + -1.566043567409796e-17 + ], + [ + 0, + -1.5692677964009372e-17, + -3.1320871348195766e-17, + -4.682036055370659e-17, + -6.212745485476638e-17, + -7.717925411753067e-17, + -9.191390727022793e-17, + -1.0627086646248056e-16, + -1.2019113586940948e-16, + -1.3361751411813318e-16, + -1.464948293404786e-16, + -1.5877016588602166e-16, + -1.7039308176384524e-16, + -1.8131581591949977e-16, + -1.9149348449542055e-16, + -2.00884265268326e-16, + -2.0944956950570415e-16, + -2.171542005351916e-16, + -2.2396649837525e-16, + -2.2985846983282128e-16, + -2.3480590353336234e-16, + -2.3878846941057645e-16, + -2.417898022470164e-16, + -2.437975689222735e-16, + -2.4480351909241436e-16, + -2.4480351909241436e-16, + -2.437975689222735e-16, + -2.417898022470164e-16, + -2.3878846941057645e-16, + -2.3480590353336234e-16, + -2.2985846983282128e-16, + -2.2396649837525006e-16, + -2.1715420053519163e-16, + -2.0944956950570418e-16, + -2.0088426526832603e-16, + -1.9149348449542057e-16, + -1.8131581591949982e-16, + -1.7039308176384526e-16, + -1.5877016588602173e-16, + -1.4649482934047864e-16, + -1.3361751411813328e-16, + -1.2019113586940952e-16, + -1.0627086646248059e-16, + -9.191390727022803e-17, + -7.717925411753073e-17, + -6.212745485476649e-17, + -4.682036055370665e-17, + -3.132087134819589e-17, + -1.5692677964009452e-17, + -2.999519565323715e-32 + ] + ], + "z": [ + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ], + [ + 1, + 0.9979453927503363, + 0.9917900138232462, + 0.9815591569910653, + 0.9672948630390295, + 0.9490557470106686, + 0.9269167573460217, + 0.9009688679024191, + 0.8713187041233894, + 0.8380881048918407, + 0.8014136218679567, + 0.7614459583691344, + 0.7183493500977277, + 0.6723008902613169, + 0.6234898018587336, + 0.5721166601221697, + 0.5183925683105252, + 0.4625382902408354, + 0.404783343122394, + 0.3453650544213078, + 0.28452758663103267, + 0.22252093395631445, + 0.15959989503337932, + 0.09602302590768189, + 0.03205157757165533, + -0.032051577571654985, + -0.09602302590768154, + -0.15959989503337896, + -0.22252093395631434, + -0.28452758663103234, + -0.3453650544213075, + -0.40478334312239367, + -0.4625382902408351, + -0.518392568310525, + -0.5721166601221694, + -0.6234898018587335, + -0.6723008902613166, + -0.7183493500977275, + -0.7614459583691342, + -0.8014136218679565, + -0.8380881048918404, + -0.8713187041233892, + -0.900968867902419, + -0.9269167573460216, + -0.9490557470106686, + -0.9672948630390293, + -0.9815591569910653, + -0.991790013823246, + -0.9979453927503363, + -1 + ] + ] + }, + { + "line": { + "color": "grey" + }, + "marker": { + "color": [ + 0, + 0.07142857142857142, + 0.14285714285714285, + 0.21428571428571427, + 0.2857142857142857, + 0.3571428571428571, + 0.42857142857142855, + 0.5, + 0.5714285714285714, + 0.6428571428571428, + 0.7142857142857142, + 0.7857142857142857, + 0.8571428571428571, + 0.9285714285714285, + 1 + ], + "colorbar": { + "title": { + "text": "Time" + } + }, + "colorscale": [ + [ + 0, + "rgb(0,0,0)" + ], + [ + 0.3333333333333333, + "rgb(230,0,0)" + ], + [ + 0.6666666666666666, + "rgb(255,210,0)" + ], + [ + 1, + "rgb(255,255,255)" + ] + ], + "size": 5 + }, + "mode": "markers+lines", + "type": "scatter3d", + "x": [ + 0.9990520651470387, + 0.9954014652237735, + 0.9886995029197546, + 0.9790246247183779, + 0.9628512408584392, + 0.9489091580387646, + 0.9366935523756065, + 0.9124694002414021, + 0.885755051065365, + 0.8598031278633096, + 0.8338729831594988, + 0.7981335110234895, + 0.7580315779444392, + 0.725901272367667, + 0.6798015471372526 + ], + "y": [ + -0.04351261576799146, + -0.09574551698065353, + -0.14978008762401096, + -0.20370759566074248, + -0.26974204692854686, + -0.31487004049725087, + -0.34853749714102294, + -0.4079756940746538, + -0.4633064452066913, + -0.5095938914141421, + -0.5518165248803886, + -0.6024741344027326, + -0.65187334350698, + -0.6876804874315429, + -0.7332570029999579 + ], + "z": [ + 0.0012741249798499386, + 0.0029527967204729245, + -0.006262449806102719, + -0.00374161264149299, + 0.012518629963451593, + 0.020694622186032165, + 0.03356787191108118, + 0.0309099768262718, + 0.028020123877883357, + 0.03244452418916158, + 0.012424605652090383, + 0.0027957033096463035, + 0.02119601057026094, + 0.012762835927719434, + 0.014283699146848431 + ] + } + ], + "layout": { + "margin": { + "b": 0, + "l": 0, + "r": 0, + "t": 0 + }, + "scene": { + "camera": { + "eye": { + "x": 1.1, + "y": -1.1, + "z": 0.2 + } + } + }, + "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 + } + } + } + } + } + }, + "metadata": {}, + "output_type": "display_data" + } + ], + "source": [ + "import plotly.graph_objects as go\n", + "phi, theta = np.meshgrid(np.linspace(0, np.pi, 50), np.linspace(0, 2 * np.pi, 50))\n", + "fig = go.Figure(go.Surface(\n", + " x=np.sin(phi) * np.cos(theta), y=np.sin(phi) * np.sin(theta), z=np.cos(phi),\n", + " opacity=0.3, colorscale='Viridis', showscale=False\n", + "))\n", + "etas_np = np.array([R.matrix()[:,0] for R in rotations])\n", + "time_steps = np.linspace(0, 1, len(etas_np)) # Normalize time steps between 0 and 1\n", + "colors = time_steps # Use time steps as color values\n", + "\n", + "fig.add_trace(go.Scatter3d(\n", + " x=etas_np[:, 0], y=etas_np[:, 1], z=etas_np[:, 2],\n", + " mode='markers+lines',\n", + " marker=dict(size=5, color=colors, colorscale='Hot', colorbar=dict(title='Time')),\n", + " line=dict(color='grey')\n", + "))\n", + "fig.update_layout(scene_camera=dict(eye=dict(x=1.1, y=-1.1, z=0.2)), margin=dict(l=0, r=0, t=0, b=0))\n", + "fig.show()" + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [PreintegratedRotation.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegratedRotation.h)\n", + "- [PreintegratedRotation.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegratedRotation.cpp)" + ] + } + ], + "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" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/doc/PreintegrationParams.ipynb b/gtsam/navigation/doc/PreintegrationParams.ipynb new file mode 100644 index 000000000..aaf6480b5 --- /dev/null +++ b/gtsam/navigation/doc/PreintegrationParams.ipynb @@ -0,0 +1,70 @@ +{ + "cells": [ + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "# PreintegrationParams\n", + "\n", + "The `PreintegrationParams` class extends `PreintegratedRotationParams` to provide a complete configuration for IMU preintegration, including accelerometer measurements:\n", + "\n", + "| Parameter | Description |\n", + "|-----------|-------------|\n", + "| `accelerometerCovariance` | 3×3 continuous-time noise covariance matrix for accelerometer measurements (units: m²/s⁴/Hz) |\n", + "| `integrationCovariance` | 3×3 covariance matrix representing additional uncertainty during integration |\n", + "| `use2ndOrderCoriolis` | Boolean flag to enable more accurate Coriolis effect compensation |\n", + "| `n_gravity` | Gravity vector in the navigation frame (units: m/s²) |\n", + "\n", + "## Convenience API\n", + "\n", + "The class provides convenient factory methods for the two most common navigation frame conventions:\n", + "- `MakeSharedD()`: Creates parameters for a Z-down frame (like NED - North-East-Down)\n", + "- `MakeSharedU()`: Creates parameters for a Z-up frame (like ENU - East-North-Up)\n", + "\n", + "Both methods also take a [local gravity constant](https://www.sensorsone.com/local-gravity-calculator/), which decreases as one gets closer to the equator. The default is $9.81m/s^2$." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Detailed API\n", + "\n", + "- The constructor requires the navigation frame gravity vector as an argument.\n", + "\n", + "### Setters\n", + "- `setGyroscopeCovariance`: Sets the 3×3 continuous-time noise covariance matrix for gyroscope measurements.\n", + "- `setOmegaCoriolis`: Sets an optional Coriolis acceleration compensation vector.\n", + "- `setBodyPSensor`: Sets an optional pose transformation between the body frame and the sensor frame.\n", + "- `setAccelerometerCovariance`: Sets the accelerometer covariance matrix.\n", + "- `setIntegrationCovariance`: Sets the integration covariance matrix.\n", + "- `setUse2ndOrderCoriolis`: Sets the flag controlling the use of second order Coriolis compensation.\n", + "\n", + "### Getters\n", + "- `getGyroscopeCovariance`: Returns the gyroscope covariance matrix.\n", + "- `getOmegaCoriolis`: Returns the optional Coriolis acceleration vector.\n", + "- `getBodyPSensor`: Returns the optional body-to-sensor pose transformation.\n", + "- `getAccelerometerCovariance`: Returns the current accelerometer covariance matrix.\n", + "- `getIntegrationCovariance`: Returns the current integration covariance matrix.\n", + "- `getGravity`: Returns the navigation frame gravity vector.\n", + "- `isUsing2ndOrderCoriolis`: Returns the status of the second order Coriolis flag." + ] + }, + { + "cell_type": "markdown", + "metadata": {}, + "source": [ + "## Source\n", + "- [PreintegrationParams.h](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegrationParams.h)\n", + "- [PreintegrationParams.cpp](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegrationParams.cpp)" + ] + } + ], + "metadata": { + "language_info": { + "name": "python" + } + }, + "nbformat": 4, + "nbformat_minor": 2 +} diff --git a/gtsam/navigation/navigation.i b/gtsam/navigation/navigation.i index 99567509a..3796153e3 100644 --- a/gtsam/navigation/navigation.i +++ b/gtsam/navigation/navigation.i @@ -97,6 +97,29 @@ virtual class PreintegratedRotationParams { void serialize() const; }; +class PreintegratedRotation { + // Constructors + PreintegratedRotation(const gtsam::PreintegratedRotationParams* params); + + // Standard Interface + void resetIntegration(); + void integrateGyroMeasurement(const gtsam::Vector& measuredOmega, const gtsam::Vector& biasHat, double deltaT); + gtsam::Rot3 biascorrectedDeltaRij(const gtsam::Vector& biasOmegaIncr) const; + gtsam::Vector integrateCoriolis(const gtsam::Rot3& rot_i) const; + + // Access instance variables + double deltaTij() const; + gtsam::Rot3 deltaRij() const; + gtsam::Matrix delRdelBiasOmega() const; + + // Testable + void print(string s = "") const; + bool equals(const gtsam::PreintegratedRotation& expected, double tol) const; + + // enabling serialization functionality + void serialize() const; +}; + #include virtual class PreintegrationParams : gtsam::PreintegratedRotationParams { PreintegrationParams(gtsam::Vector n_gravity); @@ -291,10 +314,7 @@ class PreintegratedAhrsMeasurements { virtual class AHRSFactor : gtsam::NonlinearFactor { AHRSFactor(size_t rot_i, size_t rot_j,size_t bias, - const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, gtsam::Vector omegaCoriolis); - AHRSFactor(size_t rot_i, size_t rot_j, size_t bias, - const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, gtsam::Vector omegaCoriolis, - const gtsam::Pose3& body_P_sensor); + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements); // Standard Interface gtsam::PreintegratedAhrsMeasurements preintegratedMeasurements() const; @@ -306,6 +326,13 @@ virtual class AHRSFactor : gtsam::NonlinearFactor { // enable serialization functionality void serialize() const; + + // deprecated: + AHRSFactor(size_t rot_i, size_t rot_j,size_t bias, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, gtsam::Vector omegaCoriolis); + AHRSFactor(size_t rot_i, size_t rot_j, size_t bias, + const gtsam::PreintegratedAhrsMeasurements& preintegratedMeasurements, gtsam::Vector omegaCoriolis, + const gtsam::Pose3& body_P_sensor); }; #include diff --git a/gtsam/navigation/navigation.md b/gtsam/navigation/navigation.md new file mode 100644 index 000000000..8f75e5100 --- /dev/null +++ b/gtsam/navigation/navigation.md @@ -0,0 +1,36 @@ +# Navigation + +The `navigation` module in GTSAM provides specialized tools for inertial navigation, GPS integration, and sensor fusion. Here's an overview of key components organized by category: + +## Core Navigation Types + +- **[NavState](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/NavState.h)**: Represents the complete navigation state $\mathcal{SE}_2(3)$, i.e., attitude, position, and velocity. It also implements the group ${SE}_2(3)$. +- **[ImuBias](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ImuBias.h)**: Models constant biases in IMU measurements (accelerometer and gyroscope). + +## Attitude Estimation + +- **[PreintegrationParams](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegrationParams.h)**: Parameters for IMU preintegration. +- **[PreintegratedRotation](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegratedRotation.h)**: Handles gyroscope measurements to track rotation changes. +- **[AHRSFactor](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/AHRSFactor.h)**: Attitude and Heading Reference System factor for orientation estimation. +- **[AttitudeFactor](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/AttitudeFactor.h)**: Factors for attitude estimation from reference directions. + +## IMU Preintegration + +- **[PreintegrationBase](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/PreintegrationBase.h)**: Base class for IMU preintegration classes. +- **[ManifoldPreintegration](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ManifoldPreintegration.h)**: Implements IMU preintegration using manifold-based methods as in the Forster et al paper. +- **[TangentPreintegration](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/TangentPreintegration.h)**: Implements IMU preintegration using tangent space methods, developed at Skydio. +- **[CombinedImuFactor](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/CombinedImuFactor.h)**: Improved IMU factor with bias evolution. + +## GNSS Integration + +- **[GPSFactor](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/GPSFactor.h)**: Factor for incorporating GPS position measurements. +- **[BarometricFactor](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/BarometricFactor.h)**: Incorporates barometric altitude measurements. + +## Simulation Tools + +- **[Scenario](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/Scenario.h)**: Base class for defining motion scenarios. +- **[ConstantTwistScenario](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/Scenario.h)**: Implements constant twist (angular and linear velocity) motion. +- **[AcceleratingScenario](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/Scenario.h)**: Implements constantly accelerating motion. +- **[ScenarioRunner](https://github.com/borglab/gtsam/blob/develop/gtsam/navigation/ScenarioRunner.h)**: Executes scenarios and generates IMU measurements. + +These components together provide a comprehensive framework for fusing inertial data with other sensor measurements in navigation and robotics applications. \ No newline at end of file diff --git a/myst.yml b/myst.yml index 6f960a4e5..de5278d85 100644 --- a/myst.yml +++ b/myst.yml @@ -16,6 +16,9 @@ project: - file: ./gtsam/nonlinear/nonlinear.md children: - pattern: ./gtsam/nonlinear/doc/* + - file: ./gtsam/navigation/navigation.md + children: + - pattern: ./gtsam/navigation/doc/* - file: ./doc/examples.md children: - pattern: ./python/gtsam/examples/*.ipynb