From 182c967b189f786faf0f01a08dd7cd2da7999f2f Mon Sep 17 00:00:00 2001 From: JianKangEgon <87111711+JianKangEgon@users.noreply.github.com> Date: Thu, 23 Jan 2025 20:12:51 +0800 Subject: [PATCH] feat(autoware_utils): porting from autoware_universe_utils (#23) Signed-off-by: JianKangEgon Signed-off-by: NorahXiong Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> Co-authored-by: NorahXiong --- .../build-and-test-differential.yaml | 2 + .github/workflows/build-and-test.yaml | 2 + autoware_utils/CMakeLists.txt | 10 +- autoware_utils/README.md | 303 +- .../include/autoware_utils/autoware_utils.hpp | 34 + .../autoware_utils/geometry/alt_geometry.hpp | 200 + .../geometry/boost_geometry.hpp | 104 + .../geometry/boost_polygon_utils.hpp | 52 + .../autoware_utils/geometry/ear_clipping.hpp | 106 + .../autoware_utils/geometry/geometry.hpp | 593 ++ .../autoware_utils/geometry/gjk_2d.hpp | 29 + .../geometry/pose_deviation.hpp | 44 + .../geometry/random_concave_polygon.hpp | 47 + .../geometry/random_convex_polygon.hpp | 29 + .../autoware_utils/geometry/sat_2d.hpp | 30 + .../autoware_utils/math/accumulator.hpp | 93 + .../include/autoware_utils/math/sin_table.hpp | 30 + .../autoware_utils/math/trigonometry.hpp | 33 + .../autoware_utils/ros/debug_publisher.hpp | 77 + .../autoware_utils/ros/debug_traits.hpp | 91 + .../ros/diagnostics_interface.hpp | 61 + .../ros/logger_level_configure.hpp | 68 + .../ros/managed_transform_buffer.hpp | 228 + .../autoware_utils/ros/marker_helper.hpp | 81 + .../autoware_utils/ros/msg_covariance.hpp | 120 + .../autoware_utils/ros/msg_operation.hpp | 31 + .../include/autoware_utils/ros/parameter.hpp | 35 + .../autoware_utils/ros/pcl_conversion.hpp | 72 + .../autoware_utils/ros/polling_subscriber.hpp | 253 + .../ros/processing_time_publisher.hpp | 67 + .../ros/published_time_publisher.hpp | 114 + .../autoware_utils/ros/self_pose_listener.hpp | 58 + .../autoware_utils/ros/transform_listener.hpp | 87 + .../autoware_utils/ros/update_param.hpp | 43 + .../autoware_utils/ros/wait_for_param.hpp | 52 + .../autoware_utils/system/backtrace.hpp | 25 + .../autoware_utils/system/lru_cache.hpp | 142 + .../autoware_utils/system/stop_watch.hpp | 63 + .../autoware_utils/system/time_keeper.hpp | 215 + .../autoware_utils/transform/transforms.hpp | 51 + autoware_utils/package.xml | 18 + autoware_utils/src/geometry/alt_geometry.cpp | 647 ++ .../src/geometry/boost_polygon_utils.cpp | 267 + autoware_utils/src/geometry/ear_clipping.cpp | 634 ++ autoware_utils/src/geometry/geometry.cpp | 397 + autoware_utils/src/geometry/gjk_2d.cpp | 150 + .../src/geometry/pose_deviation.cpp | 85 + .../src/geometry/random_concave_polygon.cpp | 407 + .../src/geometry/random_convex_polygon.cpp | 113 + autoware_utils/src/geometry/sat_2d.cpp | 82 + autoware_utils/src/math/sin_table.cpp | 8215 +++++++++++++++++ autoware_utils/src/math/trigonometry.cpp | 125 + .../src/ros/diagnostics_interface.cpp | 106 + .../src/ros/logger_level_configure.cpp | 61 + autoware_utils/src/ros/marker_helper.cpp | 72 + autoware_utils/src/ros/msg_operation.cpp | 55 + autoware_utils/src/system/backtrace.cpp | 53 + autoware_utils/src/system/time_keeper.cpp | 205 + build_depends.repos | 9 + 59 files changed, 15463 insertions(+), 13 deletions(-) create mode 100644 autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/geometry.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp create mode 100644 autoware_utils/include/autoware_utils/geometry/sat_2d.hpp create mode 100644 autoware_utils/include/autoware_utils/math/accumulator.hpp create mode 100644 autoware_utils/include/autoware_utils/math/sin_table.hpp create mode 100644 autoware_utils/include/autoware_utils/math/trigonometry.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/debug_publisher.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/debug_traits.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/diagnostics_interface.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/logger_level_configure.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/managed_transform_buffer.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/marker_helper.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/msg_covariance.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/msg_operation.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/parameter.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/pcl_conversion.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/polling_subscriber.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/processing_time_publisher.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/published_time_publisher.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/self_pose_listener.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/transform_listener.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/update_param.hpp create mode 100644 autoware_utils/include/autoware_utils/ros/wait_for_param.hpp create mode 100644 autoware_utils/include/autoware_utils/system/backtrace.hpp create mode 100644 autoware_utils/include/autoware_utils/system/lru_cache.hpp create mode 100644 autoware_utils/include/autoware_utils/system/stop_watch.hpp create mode 100644 autoware_utils/include/autoware_utils/system/time_keeper.hpp create mode 100644 autoware_utils/include/autoware_utils/transform/transforms.hpp create mode 100644 autoware_utils/src/geometry/alt_geometry.cpp create mode 100644 autoware_utils/src/geometry/boost_polygon_utils.cpp create mode 100644 autoware_utils/src/geometry/ear_clipping.cpp create mode 100644 autoware_utils/src/geometry/geometry.cpp create mode 100644 autoware_utils/src/geometry/gjk_2d.cpp create mode 100644 autoware_utils/src/geometry/pose_deviation.cpp create mode 100644 autoware_utils/src/geometry/random_concave_polygon.cpp create mode 100644 autoware_utils/src/geometry/random_convex_polygon.cpp create mode 100644 autoware_utils/src/geometry/sat_2d.cpp create mode 100644 autoware_utils/src/math/sin_table.cpp create mode 100644 autoware_utils/src/math/trigonometry.cpp create mode 100644 autoware_utils/src/ros/diagnostics_interface.cpp create mode 100644 autoware_utils/src/ros/logger_level_configure.cpp create mode 100644 autoware_utils/src/ros/marker_helper.cpp create mode 100644 autoware_utils/src/ros/msg_operation.cpp create mode 100644 autoware_utils/src/system/backtrace.cpp create mode 100644 autoware_utils/src/system/time_keeper.cpp create mode 100644 build_depends.repos diff --git a/.github/workflows/build-and-test-differential.yaml b/.github/workflows/build-and-test-differential.yaml index 134a12d..43ce9d7 100644 --- a/.github/workflows/build-and-test-differential.yaml +++ b/.github/workflows/build-and-test-differential.yaml @@ -57,6 +57,7 @@ jobs: with: rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + build-depends-repos: build_depends.repos - name: Test id: test @@ -65,6 +66,7 @@ jobs: with: rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-modified-packages.outputs.modified-packages }} + build-depends-repos: build_depends.repos - name: Upload coverage to CodeCov if: ${{ steps.test.outputs.coverage-report-files != '' }} diff --git a/.github/workflows/build-and-test.yaml b/.github/workflows/build-and-test.yaml index 2778480..3acbf61 100644 --- a/.github/workflows/build-and-test.yaml +++ b/.github/workflows/build-and-test.yaml @@ -45,6 +45,7 @@ jobs: with: rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-self-packages.outputs.self-packages }} + build-depends-repos: build_depends.repos - name: Test if: ${{ steps.get-self-packages.outputs.self-packages != '' }} @@ -53,6 +54,7 @@ jobs: with: rosdistro: ${{ matrix.rosdistro }} target-packages: ${{ steps.get-self-packages.outputs.self-packages }} + build-depends-repos: build_depends.repos - name: Upload coverage to CodeCov if: ${{ steps.test.outputs.coverage-report-files != '' }} diff --git a/autoware_utils/CMakeLists.txt b/autoware_utils/CMakeLists.txt index 21eb4ad..26ce297 100644 --- a/autoware_utils/CMakeLists.txt +++ b/autoware_utils/CMakeLists.txt @@ -4,8 +4,16 @@ project(autoware_utils) find_package(autoware_cmake REQUIRED) autoware_package() +file(GLOB_RECURSE src_files + src/*.cpp + src/geometry/*.cpp + src/math/*.cpp + src/ros/*.cpp + src/system/*.cpp +) + ament_auto_add_library(autoware_utils SHARED - src/autoware_utils.cpp + ${src_files} ) if(BUILD_TESTING) diff --git a/autoware_utils/README.md b/autoware_utils/README.md index 35493ac..253aa6e 100644 --- a/autoware_utils/README.md +++ b/autoware_utils/README.md @@ -1,25 +1,304 @@ -# autoware_utils +# autoware_utils Library -Common utilities for Autoware. +## Overview + +The **autoware_utils** library is a comprehensive toolkit designed to facilitate the development of autonomous driving applications. This library provides essential utilities for geometry, mathematics, ROS (Robot Operating System) expansions, diagnostics, and more. It is extensively used in the Autoware project to handle common tasks such as geometric calculations, data normalization, message conversions, performance monitoring, and point cloud transformations. + +### Design + +#### Geometry Module + +The geometry module provides classes and functions for handling 2D and 3D points, vectors, polygons, and performing geometric operations: + +- **`boost_geometry.hpp`**: Integrates Boost.Geometry for advanced geometric computations, defining point, segment, box, linestring, ring, and polygon types. +- **`alt_geometry.hpp`**: Implements alternative geometric types and operations for 2D vectors and polygons, including vector arithmetic, polygon creation, and various geometric predicates. +- **`ear_clipping.hpp`**: Provides algorithms for triangulating polygons using the ear clipping method. +- **`gjk_2d.hpp`**: Implements the GJK algorithm for fast intersection detection between convex polygons. +- **`sat_2d.hpp`**: Implements the SAT (Separating Axis Theorem) algorithm for detecting intersections between convex polygons. +- **`random_concave_polygon.hpp` and `random_convex_polygon.hpp`**: Generate random concave and convex polygons for testing purposes. +- **`pose_deviation.hpp`**: Calculates deviations between poses in terms of lateral, longitudinal, and yaw angles. +- **`boost_polygon_utils.hpp`**: Utility functions for manipulating polygons, including: + - Checking if a polygon is clockwise. + - Rotating polygons around the origin. + - Converting poses and shapes to polygons. + - Expanding polygons by an offset. +- **`geometry.hpp`**: Comprehensive geometric operations, including: + - Distance calculations between points and segments. + - Curvature computation. + - Pose transformations and interpolations. + - Intersection checks for convex polygons using GJK. + - Conversion between different coordinate systems. + +#### Math Module + +The math module offers a variety of mathematical utilities: + +- **`accumulator.hpp`**: A class for accumulating statistical data, supporting min, max, and mean calculations. +- **`constants.hpp`**: Defines commonly used mathematical constants like π and gravity. +- **`normalization.hpp`**: Functions for normalizing angles and degrees. +- **`range.hpp`**: Functions for generating sequences of numbers (arange, linspace). +- **`trigonometry.hpp`**: Optimized trigonometric functions for faster computation. +- **`unit_conversion.hpp`**: Functions for converting between different units (e.g., degrees to radians, km/h to m/s). + +#### ROS Module + +The ROS module provides utilities for working with ROS messages and nodes: + +- **`debug_publisher.hpp`**: A helper class for publishing debug messages with timestamps. +- **`diagnostics_interface.hpp`**: An interface for publishing diagnostic messages. +- **`logger_level_configure.hpp`**: Utility for configuring logger levels dynamically. +- **`managed_transform_buffer.hpp`**: A managed buffer for handling static and dynamic transforms. +- **`marker_helper.hpp`**: Helper functions for creating and manipulating visualization markers. +- **`msg_covariance.hpp`**: Indices for accessing covariance matrices in ROS messages. +- **`msg_operation.hpp`**: Overloaded operators for quaternion messages. +- **`parameter.hpp`**: Simplifies parameter retrieval and declaration. +- **`polling_subscriber.hpp`**: A subscriber class with different polling policies (latest, newest, all). +- **`processing_time_publisher.hpp`**: Publishes processing times as diagnostic messages. +- **`published_time_publisher.hpp`**: Tracks and publishes the time when messages are published. +- **`self_pose_listener.hpp`**: Listens to the self-pose of the vehicle. +- **`transform_listener.hpp`**: Manages transformation listeners. +- **`update_param.hpp`**: Updates parameters from remote nodes. +- **`uuid_helper.hpp`**: Utilities for generating and managing UUIDs. +- **`wait_for_param.hpp`**: Waits for parameters from remote nodes. +- **`debug_traits.hpp`**: Traits for identifying debug message types. +- **`pcl_conversion.hpp`**: Efficient conversion and transformation of PointCloud2 messages to PCL point clouds. + +#### System Module + +The system module provides low-level utilities for performance monitoring and error handling: + +- **`backtrace.hpp`**: Prints backtraces for debugging. +- **`lru_cache.hpp`**: Implements an LRU (Least Recently Used) cache. +- **`stop_watch.hpp`**: Measures elapsed time for profiling. +- **`time_keeper.hpp`**: Tracks and reports the processing time of various functions. + +#### Transform Module + +Efficient methods for transforming and manipulating point clouds. ## Usage -To use all features, include `autoware_utils/autoware_utils.hpp`: +### Including Headers + +To use the Autoware Utils library in your project, include the necessary headers at the top of your source files: + +```cpp +#include "autoware_utils/geometry/boost_geometry.hpp" +#include "autoware_utils/math/accumulator.hpp" +#include "autoware_utils/ros/debug_publisher.hpp" +``` + +or you can include `autoware_utils/autoware_utils.hpp` for all features: + +```cpp +#include "autoware_utils/autoware_utils.hpp" +``` + +### Example Code Snippets + +#### Using Vector2d from alt_geometry.hpp + +```cpp +#include "autoware_utils/geometry/alt_geometry.hpp" + +using namespace autoware_utils::alt; + +int main() { + Vector2d vec1(3.0, 4.0); + Vector2d vec2(1.0, 2.0); + + // Compute the dot product + double dot_product = vec1.dot(vec2); + + // Compute the norm + double norm = vec1.norm(); + + return 0; +} +``` + +#### Using Accumulator from accumulator.hpp ```cpp -#include +#include "autoware_utils/math/accumulator.hpp" + +int main() { + autoware_utils::Accumulator acc; -using autoware_utils::deg2rad; -using autoware_utils::normalize_degree; -using autoware_utils::pi; + acc.add(1.0); + acc.add(2.0); + acc.add(3.0); + + std::cout << "Mean: " << acc.mean() << "\n"; + std::cout << "Min: " << acc.min() << "\n"; + std::cout << "Max: " << acc.max() << "\n"; + std::cout << "Count: " << acc.count() << "\n"; + + return 0; +} ``` -To select features, include necessary header files: +### Detailed Usage Examples + +#### Transform Point Clouds with ManagedTransformBuffer ```cpp -#include -#include +#include "autoware_utils/ros/managed_transform_buffer.hpp" +#include "sensor_msgs/msg/point_cloud2.hpp" +#include + +int main(int argc, char * argv[]) { + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("transform_node"); + + // Initialize ManagedTransformBuffer + autoware_utils::ManagedTransformBuffer transform_buffer(node, false); + + // Load point cloud data + sensor_msgs::msg::PointCloud2 cloud_in; // Assume this is populated with data + sensor_msgs::msg::PointCloud2 cloud_out; + + // Transform point cloud from "base_link" to "map" frame + if (transform_buffer.transform_pointcloud("map", cloud_in, cloud_out)) { + RCLCPP_INFO(node->get_logger(), "Point cloud transformed successfully."); + } else { + RCLCPP_ERROR(node->get_logger(), "Failed to transform point cloud."); + } + + rclcpp::shutdown(); + return 0; +} +``` + +#### Update Parameters Dynamically with update_param.hpp + +```cpp +#include "autoware_utils/ros/update_param.hpp" +#include + +int main(int argc, char * argv[]) { + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("param_node"); + + double param_value = 0.0; + std::vector params = node->get_parameters({"my_param"}); + + if (autoware_utils::update_param(params, "my_param", param_value)) { + RCLCPP_INFO(node->get_logger(), "Updated parameter value: %f", param_value); + } else { + RCLCPP_WARN(node->get_logger(), "Parameter 'my_param' not found."); + } + + rclcpp::shutdown(); + return 0; +} +``` + +#### Logging Processing Times with ProcessingTimePublisher + +```cpp +#include "autoware_utils/ros/processing_time_publisher.hpp" +#include +#include + +int main(int argc, char * argv[]) { + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("processing_time_node"); + + // Initialize ProcessingTimePublisher + autoware_utils::ProcessingTimePublisher processing_time_pub(node.get(), "~/debug/processing_time_ms"); + + // Simulate some processing times + std::map processing_times = { + {"node1", 0.1}, {"node2", 0.2}, {"node3", 0.3} + }; + + // Publish processing times + processing_time_pub.publish(processing_times); + + rclcpp::shutdown(); + return 0; +} +``` + +#### Manipulating Polygons with boost_polygon_utils.hpp + +```cpp +#include "autoware_utils/geometry/boost_polygon_utils.hpp" +#include "autoware_utils/geometry/boost_geometry.hpp" +#include + +int main(int argc, char * argv[]) { + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("polygon_node"); + + // Create a polygon + autoware_utils::Polygon2d polygon; + // Assume polygon is populated with points + + // Rotate the polygon by 90 degrees + autoware_utils::Polygon2d rotated_polygon = autoware_utils::rotate_polygon(polygon, M_PI / 2); + + // Expand the polygon by an offset + autoware_utils::Polygon2d expanded_polygon = autoware_utils::expand_polygon(polygon, 1.0); + + // Check if the polygon is clockwise + bool is_clockwise = autoware_utils::is_clockwise(polygon); + + rclcpp::shutdown(); + return 0; +} +``` + +#### Efficient Point Cloud Conversion with pcl_conversion.hpp + +```cpp +#include "autoware_utils/ros/pcl_conversion.hpp" +#include "sensor_msgs/msg/point_cloud2.hpp" +#include +#include +#include +#include + +int main(int argc, char * argv[]) { + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("pcl_conversion_node"); + + // Load point cloud data + sensor_msgs::msg::PointCloud2 cloud_in; // Assume this is populated with data + pcl::PointCloud pcl_cloud; + + // Define transformation matrix + Eigen::Matrix4f transform = Eigen::Matrix4f::Identity(); + // Populate transform matrix with actual values + + // Convert and transform point cloud + autoware_utils::transform_point_cloud_from_ros_msg(cloud_in, pcl_cloud, transform); + + rclcpp::shutdown(); + return 0; +} +``` + +#### Handling Debug Message Types with debug_traits.hpp + +```cpp +#include "autoware_utils/ros/debug_publisher.hpp" +#include "autoware_utils/ros/debug_traits.hpp" +#include + +int main(int argc, char * argv[]) { + rclcpp::init(argc, argv); + auto node = rclcpp::Node::make_shared("debug_node"); + + // Initialize DebugPublisher + autoware_utils::DebugPublisher debug_pub(node, "/debug"); + + // Publish a debug message with custom type + float debug_data = 42.0; + debug_pub.publish("example", debug_data); -using autoware_utils::normalize_degree; -using autoware_utils::pi; + rclcpp::shutdown(); + return 0; +} ``` diff --git a/autoware_utils/include/autoware_utils/autoware_utils.hpp b/autoware_utils/include/autoware_utils/autoware_utils.hpp index 77d2fec..d753e34 100644 --- a/autoware_utils/include/autoware_utils/autoware_utils.hpp +++ b/autoware_utils/include/autoware_utils/autoware_utils.hpp @@ -15,10 +15,44 @@ #ifndef AUTOWARE_UTILS__AUTOWARE_UTILS_HPP_ #define AUTOWARE_UTILS__AUTOWARE_UTILS_HPP_ +#include "autoware_utils/geometry/alt_geometry.hpp" +#include "autoware_utils/geometry/boost_geometry.hpp" +#include "autoware_utils/geometry/boost_polygon_utils.hpp" +#include "autoware_utils/geometry/ear_clipping.hpp" +#include "autoware_utils/geometry/geometry.hpp" +#include "autoware_utils/geometry/gjk_2d.hpp" +#include "autoware_utils/geometry/pose_deviation.hpp" +#include "autoware_utils/geometry/random_concave_polygon.hpp" +#include "autoware_utils/geometry/random_convex_polygon.hpp" +#include "autoware_utils/math/accumulator.hpp" #include "autoware_utils/math/constants.hpp" #include "autoware_utils/math/normalization.hpp" #include "autoware_utils/math/range.hpp" +#include "autoware_utils/math/sin_table.hpp" +#include "autoware_utils/math/trigonometry.hpp" #include "autoware_utils/math/unit_conversion.hpp" +#include "autoware_utils/ros/debug_publisher.hpp" +#include "autoware_utils/ros/debug_traits.hpp" +#include "autoware_utils/ros/diagnostics_interface.hpp" +#include "autoware_utils/ros/logger_level_configure.hpp" +#include "autoware_utils/ros/managed_transform_buffer.hpp" +#include "autoware_utils/ros/marker_helper.hpp" +#include "autoware_utils/ros/msg_covariance.hpp" +#include "autoware_utils/ros/msg_operation.hpp" +#include "autoware_utils/ros/parameter.hpp" +#include "autoware_utils/ros/pcl_conversion.hpp" +#include "autoware_utils/ros/polling_subscriber.hpp" +#include "autoware_utils/ros/processing_time_publisher.hpp" +#include "autoware_utils/ros/published_time_publisher.hpp" +#include "autoware_utils/ros/self_pose_listener.hpp" +#include "autoware_utils/ros/transform_listener.hpp" +#include "autoware_utils/ros/update_param.hpp" #include "autoware_utils/ros/uuid_helper.hpp" +#include "autoware_utils/ros/wait_for_param.hpp" +#include "autoware_utils/system/backtrace.hpp" +#include "autoware_utils/system/lru_cache.hpp" +#include "autoware_utils/system/stop_watch.hpp" +#include "autoware_utils/system/time_keeper.hpp" +#include "autoware_utils/transform/transforms.hpp" #endif // AUTOWARE_UTILS__AUTOWARE_UTILS_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp b/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp new file mode 100644 index 0000000..6879818 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/alt_geometry.hpp @@ -0,0 +1,200 @@ +// Copyright 2020-2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ + +#include "autoware_utils/geometry/boost_geometry.hpp" + +#include +#include +#include +#include + +namespace autoware_utils +{ +// Alternatives for Boost.Geometry ---------------------------------------------------------------- +// TODO(mitukou1109): remove namespace +namespace alt +{ +class Vector2d +{ +public: + Vector2d() : x_(0.0), y_(0.0) {} + + Vector2d(const double x, const double y) : x_(x), y_(y) {} + + explicit Vector2d(const autoware_utils::Point2d & point) : x_(point.x()), y_(point.y()) {} + + double cross(const Vector2d & other) const { return x_ * other.y() - y_ * other.x(); } + + double dot(const Vector2d & other) const { return x_ * other.x() + y_ * other.y(); } + + double norm2() const { return x_ * x_ + y_ * y_; } + + double norm() const { return std::sqrt(norm2()); } + + Vector2d vector_triple(const Vector2d & v1, const Vector2d & v2) const + { + const auto tmp = this->cross(v1); + return {-v2.y() * tmp, v2.x() * tmp}; + } + + const double & x() const { return x_; } + + double & x() { return x_; } + + const double & y() const { return y_; } + + double & y() { return y_; } + +private: + double x_; + double y_; +}; + +inline Vector2d operator+(const Vector2d & v1, const Vector2d & v2) +{ + return {v1.x() + v2.x(), v1.y() + v2.y()}; +} + +inline Vector2d operator-(const Vector2d & v1, const Vector2d & v2) +{ + return {v1.x() - v2.x(), v1.y() - v2.y()}; +} + +inline Vector2d operator-(const Vector2d & v) +{ + return {-v.x(), -v.y()}; +} + +inline Vector2d operator*(const double & s, const Vector2d & v) +{ + return {s * v.x(), s * v.y()}; +} + +// We use Vector2d to represent points, but we do not name the class Point2d directly +// as it has some vector operation functions. +using Point2d = Vector2d; +using Points2d = std::vector; +using PointList2d = std::list; + +class Polygon2d +{ +public: + static std::optional create( + const PointList2d & outer, const std::vector & inners) noexcept; + + static std::optional create( + PointList2d && outer, std::vector && inners) noexcept; + + static std::optional create(const autoware_utils::Polygon2d & polygon) noexcept; + + const PointList2d & outer() const noexcept { return outer_; } + + PointList2d & outer() noexcept { return outer_; } + + const std::vector & inners() const noexcept { return inners_; } + + std::vector & inners() noexcept { return inners_; } + + autoware_utils::Polygon2d to_boost() const; + +protected: + Polygon2d(const PointList2d & outer, const std::vector & inners) + : outer_(outer), inners_(inners) + { + } + + Polygon2d(PointList2d && outer, std::vector && inners) + : outer_(std::move(outer)), inners_(std::move(inners)) + { + } + + PointList2d outer_; + + std::vector inners_; +}; + +class ConvexPolygon2d : public Polygon2d +{ +public: + static std::optional create(const PointList2d & vertices) noexcept; + + static std::optional create(PointList2d && vertices) noexcept; + + static std::optional create(const autoware_utils::Polygon2d & polygon) noexcept; + + const PointList2d & vertices() const noexcept { return outer(); } + + PointList2d & vertices() noexcept { return outer(); } + +private: + explicit ConvexPolygon2d(const PointList2d & vertices) : Polygon2d(vertices, {}) {} + + explicit ConvexPolygon2d(PointList2d && vertices) : Polygon2d(std::move(vertices), {}) {} +}; +} // namespace alt + +double area(const alt::ConvexPolygon2d & poly); + +std::optional convex_hull(const alt::Points2d & points); + +void correct(alt::Polygon2d & poly); + +bool covered_by(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); + +bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2); + +double distance( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end); + +double distance(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); + +std::optional envelope(const alt::Polygon2d & poly); + +bool equals(const alt::Point2d & point1, const alt::Point2d & point2); + +bool equals(const alt::Polygon2d & poly1, const alt::Polygon2d & poly2); + +alt::Points2d::const_iterator find_farthest( + const alt::Points2d & points, const alt::Point2d & seg_start, const alt::Point2d & seg_end); + +bool intersects( + const alt::Point2d & seg1_start, const alt::Point2d & seg1_end, const alt::Point2d & seg2_start, + const alt::Point2d & seg2_end); + +bool intersects(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2); + +bool is_above( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end); + +bool is_clockwise(const alt::PointList2d & vertices); + +bool is_convex(const alt::Polygon2d & poly); + +alt::PointList2d simplify(const alt::PointList2d & line, const double max_distance); + +bool touches( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end); + +bool touches(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); + +bool within(const alt::Point2d & point, const alt::ConvexPolygon2d & poly); + +bool within( + const alt::ConvexPolygon2d & poly_contained, const alt::ConvexPolygon2d & poly_containing); +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__GEOMETRY__ALT_GEOMETRY_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp b/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp new file mode 100644 index 0000000..3742eb8 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/boost_geometry.hpp @@ -0,0 +1,104 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_ + +#include +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include + +#include + +namespace autoware_utils +{ +// 2D +struct Point2d; +using Segment2d = boost::geometry::model::segment; +using Box2d = boost::geometry::model::box; +using LineString2d = boost::geometry::model::linestring; +using LinearRing2d = boost::geometry::model::ring; +using Polygon2d = boost::geometry::model::polygon; +using Line2d = boost::geometry::model::linestring; +using MultiPoint2d = boost::geometry::model::multi_point; +using MultiLineString2d = boost::geometry::model::multi_linestring; +using MultiPolygon2d = boost::geometry::model::multi_polygon; + +// 3D +struct Point3d; +using Segment3d = boost::geometry::model::segment; +using Box3d = boost::geometry::model::box; +using LineString3d = boost::geometry::model::linestring; +using LinearRing3d = boost::geometry::model::ring; +using Polygon3d = boost::geometry::model::polygon; +using MultiPoint3d = boost::geometry::model::multi_point; +using MultiLineString3d = boost::geometry::model::multi_linestring; +using MultiPolygon3d = boost::geometry::model::multi_polygon; + +struct Point2d : public Eigen::Vector2d +{ + Point2d() = default; + Point2d(const double x, const double y) : Eigen::Vector2d(x, y) {} + + [[nodiscard]] Point3d to_3d(const double z = 0.0) const; +}; + +struct Point3d : public Eigen::Vector3d +{ + Point3d() = default; + Point3d(const double x, const double y, const double z) : Eigen::Vector3d(x, y, z) {} + + [[nodiscard]] Point2d to_2d() const; +}; + +inline Point3d Point2d::to_3d(const double z) const +{ + return Point3d{x(), y(), z}; +} + +inline Point2d Point3d::to_2d() const +{ + return Point2d{x(), y()}; +} + +inline geometry_msgs::msg::Point to_msg(const Point3d & point) +{ + geometry_msgs::msg::Point msg; + msg.x = point.x(); + msg.y = point.y(); + msg.z = point.z(); + return msg; +} + +inline Point3d from_msg(const geometry_msgs::msg::Point & msg) +{ + Point3d point; + point.x() = msg.x; + point.y() = msg.y; + point.z() = msg.z; + return point; +} +} // namespace autoware_utils + +BOOST_GEOMETRY_REGISTER_POINT_2D( // NOLINT + autoware_utils::Point2d, double, cs::cartesian, x(), y()) // NOLINT +BOOST_GEOMETRY_REGISTER_POINT_3D( // NOLINT + autoware_utils::Point3d, double, cs::cartesian, x(), y(), z()) // NOLINT +BOOST_GEOMETRY_REGISTER_RING(autoware_utils::LinearRing2d) // NOLINT + +#endif // AUTOWARE_UTILS__GEOMETRY__BOOST_GEOMETRY_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp b/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp new file mode 100644 index 0000000..51c32a3 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/boost_polygon_utils.hpp @@ -0,0 +1,52 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ + +#include "autoware_utils/geometry/boost_geometry.hpp" + +#include +#include +#include +#include + +#include + +namespace autoware_utils +{ +bool is_clockwise(const Polygon2d & polygon); +Polygon2d inverse_clockwise(const Polygon2d & polygon); +geometry_msgs::msg::Polygon rotate_polygon( + const geometry_msgs::msg::Polygon & polygon, const double & angle); +/// @brief rotate a polygon by some angle around the origin +/// @param[in] polygon input polygon +/// @param[in] angle angle of rotation [rad] +/// @return rotated polygon +Polygon2d rotate_polygon(const Polygon2d & polygon, const double angle); +Polygon2d to_polygon2d( + const geometry_msgs::msg::Pose & pose, const autoware_perception_msgs::msg::Shape & shape); +Polygon2d to_polygon2d( + const geometry_msgs::msg::Pose & pose, const autoware_perception_msgs::msg::Shape & shape); +Polygon2d to_polygon2d(const autoware_perception_msgs::msg::DetectedObject & object); +Polygon2d to_polygon2d(const autoware_perception_msgs::msg::TrackedObject & object); +Polygon2d to_polygon2d(const autoware_perception_msgs::msg::PredictedObject & object); +Polygon2d to_footprint( + const geometry_msgs::msg::Pose & base_link_pose, const double base_to_front, + const double base_to_rear, const double width); +double get_area(const autoware_perception_msgs::msg::Shape & shape); +Polygon2d expand_polygon(const Polygon2d & input_polygon, const double offset); +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__GEOMETRY__BOOST_POLYGON_UTILS_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp b/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp new file mode 100644 index 0000000..f351321 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/ear_clipping.hpp @@ -0,0 +1,106 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ + +#include "autoware_utils/geometry/alt_geometry.hpp" + +#include +#include + +namespace autoware_utils +{ +struct LinkedPoint +{ + explicit LinkedPoint(const alt::Point2d & point) + : pt(point), steiner(false), prev_index(std::nullopt), next_index(std::nullopt) + { + } + + alt::Point2d pt; + bool steiner; + std::optional prev_index; + std::optional next_index; + [[nodiscard]] double x() const { return pt.x(); } + [[nodiscard]] double y() const { return pt.y(); } +}; + +/** + * @brief main ear slicing loop which triangulates a polygon using linked list + * @details iterates over the linked list of polygon points, cutting off triangular ears one by one + * handles different stages for fixing intersections and splitting if necessary + */ +void ear_clipping_linked( + std::size_t ear_index, std::vector & indices, std::vector & points, + const int pass = 0); +void split_ear_clipping( + std::vector & points, std::size_t start_index, std::vector & indices); + +/** + * @brief creates a linked list from a ring of points + * @details converts a polygon ring into a doubly linked list with optional clockwise ordering + * @return the last index of the created linked list + */ +std::size_t linked_list( + const alt::PointList2d & ring, const bool clockwise, std::size_t & vertices, + std::vector & points); + +/** + * @brief David Eberly's algorithm for finding a bridge between hole and outer polygon + * @details connects a hole to the outer polygon by finding the closest bridge point + * @return index of the bridge point + */ +std::size_t find_hole_bridge( + const std::size_t hole_index, const std::size_t outer_point_index, + const std::vector & points); + +/** + * @brief eliminates a single hole by connecting it to the outer polygon + * @details finds a bridge and modifies the linked list to remove the hole + * @return the updated outer_index after the hole is eliminated + */ +std::size_t eliminate_hole( + const std::size_t hole_index, const std::size_t outer_index, std::vector & points); + +/** + * @brief eliminates all holes from a polygon + * @details processes multiple holes by connecting each to the outer polygon in sequence + * @return the updated outer_index after all holes are eliminated + */ +std::size_t eliminate_holes( + const std::vector & inners, std::size_t outer_index, std::size_t & vertices, + std::vector & points); + +/** + * @brief triangulates a polygon into convex triangles + * @details simplifies a concave polygon, with or without holes, into a set of triangles + * the size of the `points` vector at the end of the perform_triangulation algorithm is described as + * follow: + * - `outer_points`: Number of points in the initial outer linked list. + * - `hole_points`: Number of points in all inner polygons. + * - `2 * n_holes`: Additional points for bridging holes, where `n_holes` is the number of holes. + * the final size of `points` vector is: `outer_points + hole_points + 2 * n_holes`. + * @return A vector of convex triangles representing the triangulated polygon. + */ +std::vector triangulate(const alt::Polygon2d & polygon); + +/** + * @brief Boost.Geometry version of triangulate() + * @return A vector of convex triangles representing the triangulated polygon. + */ +std::vector triangulate(const Polygon2d & polygon); +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__GEOMETRY__EAR_CLIPPING_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/geometry.hpp b/autoware_utils/include/autoware_utils/geometry/geometry.hpp new file mode 100644 index 0000000..56cc14f --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/geometry.hpp @@ -0,0 +1,593 @@ +// Copyright 2020-2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_ + +#include "autoware_utils/geometry/boost_geometry.hpp" +#include "autoware_utils/math/constants.hpp" +#include "autoware_utils/math/normalization.hpp" +#include "autoware_utils/ros/msg_covariance.hpp" + +#include +#include +#include + +#define EIGEN_MPL2_ONLY +#include + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +// TODO(wep21): Remove these apis +// after they are implemented in ros2 geometry2. +namespace tf2 +{ +void fromMsg(const geometry_msgs::msg::PoseStamped & msg, tf2::Stamped & out); +#ifdef ROS_DISTRO_GALACTIC +// Remove after this commit is released +// https://github.com/ros2/geometry2/commit/e9da371d81e388a589540357c050e262442f1b4a +inline geometry_msgs::msg::Point & toMsg(const tf2::Vector3 & in, geometry_msgs::msg::Point & out) +{ + out.x = in.getX(); + out.y = in.getY(); + out.z = in.getZ(); + return out; +} + +// Remove after this commit is released +// https://github.com/ros2/geometry2/commit/e9da371d81e388a589540357c050e262442f1b4a +inline void fromMsg(const geometry_msgs::msg::Point & in, tf2::Vector3 & out) +{ + out = tf2::Vector3(in.x, in.y, in.z); +} + +template <> +inline void doTransform( + const geometry_msgs::msg::Point & t_in, geometry_msgs::msg::Point & t_out, + const geometry_msgs::msg::TransformStamped & transform) +{ + tf2::Transform t; + fromMsg(transform.transform, t); + tf2::Vector3 v_in; + fromMsg(t_in, v_in); + tf2::Vector3 v_out = t * v_in; + toMsg(v_out, t_out); +} + +template <> +inline void doTransform( + const geometry_msgs::msg::Pose & t_in, geometry_msgs::msg::Pose & t_out, + const geometry_msgs::msg::TransformStamped & transform) +{ + tf2::Vector3 v; + fromMsg(t_in.position, v); + tf2::Quaternion r; + fromMsg(t_in.orientation, r); + + tf2::Transform t; + fromMsg(transform.transform, t); + tf2::Transform v_out = t * tf2::Transform(r, v); + toMsg(v_out, t_out); +} +#endif +} // namespace tf2 + +namespace autoware_utils +{ +template +geometry_msgs::msg::Point get_point(const T & p) +{ + return geometry_msgs::build().x(p.x).y(p.y).z(p.z); +} + +template <> +inline geometry_msgs::msg::Point get_point(const geometry_msgs::msg::Point & p) +{ + return p; +} + +template <> +inline geometry_msgs::msg::Point get_point(const geometry_msgs::msg::Pose & p) +{ + return p.position; +} + +template <> +inline geometry_msgs::msg::Point get_point(const geometry_msgs::msg::PoseStamped & p) +{ + return p.pose.position; +} + +template <> +inline geometry_msgs::msg::Point get_point(const geometry_msgs::msg::PoseWithCovarianceStamped & p) +{ + return p.pose.pose.position; +} + +template <> +inline geometry_msgs::msg::Point get_point(const autoware_planning_msgs::msg::PathPoint & p) +{ + return p.pose.position; +} + +template <> +inline geometry_msgs::msg::Point get_point( + const autoware_internal_planning_msgs::msg::PathPointWithLaneId & p) +{ + return p.point.pose.position; +} + +template <> +inline geometry_msgs::msg::Point get_point(const autoware_planning_msgs::msg::TrajectoryPoint & p) +{ + return p.pose.position; +} + +template +geometry_msgs::msg::Pose get_pose([[maybe_unused]] const T & p) +{ + static_assert(sizeof(T) == 0, "Only specializations of get_pose can be used."); + throw std::logic_error("Only specializations of get_pose can be used."); +} + +template <> +inline geometry_msgs::msg::Pose get_pose(const geometry_msgs::msg::Pose & p) +{ + return p; +} + +template <> +inline geometry_msgs::msg::Pose get_pose(const geometry_msgs::msg::PoseStamped & p) +{ + return p.pose; +} + +template <> +inline geometry_msgs::msg::Pose get_pose(const autoware_planning_msgs::msg::PathPoint & p) +{ + return p.pose; +} + +template <> +inline geometry_msgs::msg::Pose get_pose( + const autoware_internal_planning_msgs::msg::PathPointWithLaneId & p) +{ + return p.point.pose; +} + +template <> +inline geometry_msgs::msg::Pose get_pose(const autoware_planning_msgs::msg::TrajectoryPoint & p) +{ + return p.pose; +} + +template +double get_longitudinal_velocity([[maybe_unused]] const T & p) +{ + static_assert(sizeof(T) == 0, "Only specializations of getVelocity can be used."); + throw std::logic_error("Only specializations of getVelocity can be used."); +} + +template <> +inline double get_longitudinal_velocity(const autoware_planning_msgs::msg::PathPoint & p) +{ + return p.longitudinal_velocity_mps; +} + +template <> +inline double get_longitudinal_velocity( + const autoware_internal_planning_msgs::msg::PathPointWithLaneId & p) +{ + return p.point.longitudinal_velocity_mps; +} + +template <> +inline double get_longitudinal_velocity(const autoware_planning_msgs::msg::TrajectoryPoint & p) +{ + return p.longitudinal_velocity_mps; +} + +template +void set_pose([[maybe_unused]] const geometry_msgs::msg::Pose & pose, [[maybe_unused]] T & p) +{ + static_assert(sizeof(T) == 0, "Only specializations of get_pose can be used."); + throw std::logic_error("Only specializations of get_pose can be used."); +} + +template <> +inline void set_pose(const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::Pose & p) +{ + p = pose; +} + +template <> +inline void set_pose(const geometry_msgs::msg::Pose & pose, geometry_msgs::msg::PoseStamped & p) +{ + p.pose = pose; +} + +template <> +inline void set_pose( + const geometry_msgs::msg::Pose & pose, autoware_planning_msgs::msg::PathPoint & p) +{ + p.pose = pose; +} + +template <> +inline void set_pose( + const geometry_msgs::msg::Pose & pose, + autoware_internal_planning_msgs::msg::PathPointWithLaneId & p) +{ + p.point.pose = pose; +} + +template <> +inline void set_pose( + const geometry_msgs::msg::Pose & pose, autoware_planning_msgs::msg::TrajectoryPoint & p) +{ + p.pose = pose; +} + +template +inline void set_orientation(const geometry_msgs::msg::Quaternion & orientation, T & p) +{ + auto pose = get_pose(p); + pose.orientation = orientation; + set_pose(pose, p); +} + +template +void set_longitudinal_velocity([[maybe_unused]] const float velocity, [[maybe_unused]] T & p) +{ + static_assert(sizeof(T) == 0, "Only specializations of getLongitudinalVelocity can be used."); + throw std::logic_error("Only specializations of getLongitudinalVelocity can be used."); +} + +template <> +inline void set_longitudinal_velocity( + const float velocity, autoware_planning_msgs::msg::TrajectoryPoint & p) +{ + p.longitudinal_velocity_mps = velocity; +} + +template <> +inline void set_longitudinal_velocity( + const float velocity, autoware_planning_msgs::msg::PathPoint & p) +{ + p.longitudinal_velocity_mps = velocity; +} + +template <> +inline void set_longitudinal_velocity( + const float velocity, autoware_internal_planning_msgs::msg::PathPointWithLaneId & p) +{ + p.point.longitudinal_velocity_mps = velocity; +} + +inline geometry_msgs::msg::Point create_point(const double x, const double y, const double z) +{ + geometry_msgs::msg::Point p; + p.x = x; + p.y = y; + p.z = z; + return p; +} + +geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Quaternion & quat); + +geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Pose & pose); + +geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseStamped & pose); + +geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseWithCovarianceStamped & pose); + +geometry_msgs::msg::Quaternion create_quaternion( + const double x, const double y, const double z, const double w); + +geometry_msgs::msg::Vector3 create_translation(const double x, const double y, const double z); + +// Revival of tf::create_quaternion_from_rpy +// https://answers.ros.org/question/304397/recommended-way-to-construct-quaternion-from-rollpitchyaw-with-tf2/ +geometry_msgs::msg::Quaternion create_quaternion_from_rpy( + const double roll, const double pitch, const double yaw); + +geometry_msgs::msg::Quaternion create_quaternion_from_yaw(const double yaw); + +template +double calc_distance2d(const Point1 & point1, const Point2 & point2) +{ + const auto p1 = get_point(point1); + const auto p2 = get_point(point2); + return std::hypot(p1.x - p2.x, p1.y - p2.y); +} + +template +double calc_squared_distance2d(const Point1 & point1, const Point2 & point2) +{ + const auto p1 = get_point(point1); + const auto p2 = get_point(point2); + const auto dx = p1.x - p2.x; + const auto dy = p1.y - p2.y; + return dx * dx + dy * dy; +} + +template +double calc_distance3d(const Point1 & point1, const Point2 & point2) +{ + const auto p1 = get_point(point1); + const auto p2 = get_point(point2); + // To be replaced by std::hypot(dx, dy, dz) in C++17 + return std::hypot(std::hypot(p1.x - p2.x, p1.y - p2.y), p1.z - p2.z); +} + +/** + * @brief calculate elevation angle of two points. + * @details This function returns the elevation angle of the position of the two input points + * with respect to the origin of their coordinate system. + * If the two points are in the same position, the calculation result will be unstable. + * @param p_from source point + * @param p_to target point + * @return -pi/2 <= elevation angle <= pi/2 + */ +double calc_elevation_angle( + const geometry_msgs::msg::Point & p_from, const geometry_msgs::msg::Point & p_to); + +/** + * @brief calculate azimuth angle of two points. + * @details This function returns the azimuth angle of the position of the two input points + * with respect to the origin of their coordinate system. + * If x and y of the two points are the same, the calculation result will be unstable. + * @param p_from source point + * @param p_to target point + * @return -pi < azimuth angle < pi. + */ +double calc_azimuth_angle( + const geometry_msgs::msg::Point & p_from, const geometry_msgs::msg::Point & p_to); + +geometry_msgs::msg::Pose transform2pose(const geometry_msgs::msg::Transform & transform); + +geometry_msgs::msg::PoseStamped transform2pose( + const geometry_msgs::msg::TransformStamped & transform); + +geometry_msgs::msg::Transform pose2transform(const geometry_msgs::msg::Pose & pose); + +geometry_msgs::msg::TransformStamped pose2transform( + const geometry_msgs::msg::PoseStamped & pose, const std::string & child_frame_id); + +template +tf2::Vector3 point_2_tf_vector(const Point1 & src, const Point2 & dst) +{ + const auto src_p = get_point(src); + const auto dst_p = get_point(dst); + + double dx = dst_p.x - src_p.x; + double dy = dst_p.y - src_p.y; + double dz = dst_p.z - src_p.z; + return tf2::Vector3(dx, dy, dz); +} + +Point3d transform_point(const Point3d & point, const geometry_msgs::msg::Transform & transform); + +Point2d transform_point(const Point2d & point, const geometry_msgs::msg::Transform & transform); + +Eigen::Vector3d transform_point( + const Eigen::Vector3d & point, const geometry_msgs::msg::Pose & pose); + +geometry_msgs::msg::Point transform_point( + const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & pose); + +geometry_msgs::msg::Point32 transform_point( + const geometry_msgs::msg::Point32 & point32, const geometry_msgs::msg::Pose & pose); + +template +T transform_vector(const T & points, const geometry_msgs::msg::Transform & transform) +{ + T transformed; + for (const auto & point : points) { + transformed.push_back(transform_point(point, transform)); + } + return transformed; +} + +geometry_msgs::msg::Pose transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::TransformStamped & transform); + +geometry_msgs::msg::Pose transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Transform & transform); + +geometry_msgs::msg::Pose transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Pose & pose_transform); + +// Transform pose in world coordinates to local coordinates +/* +geometry_msgs::msg::Pose inverse_transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::TransformStamped & transform); +*/ + +// Transform pose in world coordinates to local coordinates +geometry_msgs::msg::Pose inverse_transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Transform & transform); + +// Transform pose in world coordinates to local coordinates +geometry_msgs::msg::Pose inverse_transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Pose & transform_pose); + +// Transform point in world coordinates to local coordinates +Eigen::Vector3d inverse_transform_point( + const Eigen::Vector3d & point, const geometry_msgs::msg::Pose & pose); + +// Transform point in world coordinates to local coordinates +geometry_msgs::msg::Point inverse_transform_point( + const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & pose); + +double calc_curvature( + const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, + const geometry_msgs::msg::Point & p3); + +template +bool is_driving_forward(const Pose1 & src_pose, const Pose2 & dst_pose) +{ + // check the first point direction + const double src_yaw = tf2::getYaw(get_pose(src_pose).orientation); + const double pose_direction_yaw = calc_azimuth_angle(get_point(src_pose), get_point(dst_pose)); + return std::fabs(normalize_radian(src_yaw - pose_direction_yaw)) < pi / 2.0; +} + +/** + * @brief Calculate offset pose. The offset values are defined in the local coordinate of the input + * pose. + */ +geometry_msgs::msg::Pose calc_offset_pose( + const geometry_msgs::msg::Pose & p, const double x, const double y, const double z, + const double yaw = 0.0); + +/** + * @brief Calculate a point by linear interpolation. + * @param src source point + * @param dst destination point + * @param ratio interpolation ratio, which should be [0.0, 1.0] + * @return interpolated point + */ +template +geometry_msgs::msg::Point calc_interpolated_point( + const Point1 & src, const Point2 & dst, const double ratio) +{ + const auto src_point = get_point(src); + const auto dst_point = get_point(dst); + + tf2::Vector3 src_vec; + src_vec.setX(src_point.x); + src_vec.setY(src_point.y); + src_vec.setZ(src_point.z); + + tf2::Vector3 dst_vec; + dst_vec.setX(dst_point.x); + dst_vec.setY(dst_point.y); + dst_vec.setZ(dst_point.z); + + // Get pose by linear interpolation + const double clamped_ratio = std::clamp(ratio, 0.0, 1.0); + const auto & vec = tf2::lerp(src_vec, dst_vec, clamped_ratio); + + geometry_msgs::msg::Point point; + point.x = vec.x(); + point.y = vec.y(); + point.z = vec.z(); + + return point; +} + +/** + * @brief Calculate a pose by linear interpolation. + * Note that if dist(src_pose, dst_pose)<=0.01 + * the orientation of the output pose is same as the orientation + * of the dst_pose + * @param src source point + * @param dst destination point + * @param ratio interpolation ratio, which should be [0.0, 1.0] + * @param set_orientation_from_position_direction set position by spherical interpolation if false + * @return interpolated point + */ +template +geometry_msgs::msg::Pose calc_interpolated_pose( + const Pose1 & src_pose, const Pose2 & dst_pose, const double ratio, + const bool set_orientation_from_position_direction = true) +{ + const double clamped_ratio = std::clamp(ratio, 0.0, 1.0); + + geometry_msgs::msg::Pose output_pose; + output_pose.position = + calc_interpolated_point(get_point(src_pose), get_point(dst_pose), clamped_ratio); + + if (set_orientation_from_position_direction) { + const double input_poses_dist = calc_distance2d(get_point(src_pose), get_point(dst_pose)); + const bool is_driving_forward_flag = is_driving_forward(src_pose, dst_pose); + + // Get orientation from interpolated point and src_pose + if ((is_driving_forward_flag && clamped_ratio > 1.0 - (1e-6)) || input_poses_dist < 1e-3) { + output_pose.orientation = get_pose(dst_pose).orientation; + } else if (!is_driving_forward_flag && clamped_ratio < 1e-6) { + output_pose.orientation = get_pose(src_pose).orientation; + } else { + const auto & base_pose = is_driving_forward_flag ? dst_pose : src_pose; + const double pitch = calc_elevation_angle(get_point(output_pose), get_point(base_pose)); + const double yaw = calc_azimuth_angle(get_point(output_pose), get_point(base_pose)); + output_pose.orientation = create_quaternion_from_rpy(0.0, pitch, yaw); + } + } else { + // Get orientation by spherical linear interpolation + tf2::Transform src_tf; + tf2::Transform dst_tf; + tf2::fromMsg(get_pose(src_pose), src_tf); + tf2::fromMsg(get_pose(dst_pose), dst_tf); + const auto & quaternion = tf2::slerp(src_tf.getRotation(), dst_tf.getRotation(), clamped_ratio); + output_pose.orientation = tf2::toMsg(quaternion); + } + + return output_pose; +} + +inline geometry_msgs::msg::Vector3 create_vector3(const double x, double y, double z) +{ + return geometry_msgs::build().x(x).y(y).z(z); +} + +inline geometry_msgs::msg::Twist create_twist( + const geometry_msgs::msg::Vector3 & velocity, geometry_msgs::msg::Vector3 & angular) +{ + return geometry_msgs::build().linear(velocity).angular(angular); +} + +inline double calc_norm(const geometry_msgs::msg::Vector3 & v) +{ + return std::hypot(v.x, v.y, v.z); +} + +/** + * @brief Judge whether twist covariance is valid. + * + * @param twist_with_covariance source twist with covariance + * @return If all element of covariance is 0, return false. + */ +// +bool is_twist_covariance_valid( + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance); + +// NOTE: much faster than boost::geometry::intersects() +std::optional intersect( + const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, + const geometry_msgs::msg::Point & p3, const geometry_msgs::msg::Point & p4); + +/** + * @brief Check if 2 convex polygons intersect using the GJK algorithm + * @details much faster than boost::geometry::intersects() + */ +bool intersects_convex(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__GEOMETRY__GEOMETRY_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp b/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp new file mode 100644 index 0000000..40e2557 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/gjk_2d.hpp @@ -0,0 +1,29 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__GJK_2D_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__GJK_2D_HPP_ + +#include "autoware_utils/geometry/boost_geometry.hpp" + +namespace autoware_utils::gjk +{ +/** + * @brief Check if 2 convex polygons intersect using the GJK algorithm + * @details much faster than boost::geometry::overlaps() but limited to convex polygons + */ +bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); +} // namespace autoware_utils::gjk + +#endif // AUTOWARE_UTILS__GEOMETRY__GJK_2D_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp b/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp new file mode 100644 index 0000000..c7d7e67 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/pose_deviation.hpp @@ -0,0 +1,44 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_ + +#include +#include + +namespace autoware_utils +{ +struct PoseDeviation +{ + double lateral{0.0}; + double longitudinal{0.0}; + double yaw{0.0}; +}; + +double calc_lateral_deviation( + const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Point & target_point); + +double calc_longitudinal_deviation( + const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Point & target_point); + +double calc_yaw_deviation( + const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & target_pose); + +PoseDeviation calc_pose_deviation( + const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & target_pose); + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__GEOMETRY__POSE_DEVIATION_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp b/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp new file mode 100644 index 0000000..300fa11 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/random_concave_polygon.hpp @@ -0,0 +1,47 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ + +#include + +#include +#include + +namespace autoware_utils +{ +/// @brief generate a random non-convex polygon +/// @param vertices number of vertices for the desired polygon +/// @param max points will be generated in the range [-max, max] +/// @details algorithm from +/// https://digitalscholarship.unlv.edu/cgi/viewcontent.cgi?article=3183&context=thesesdissertations +std::optional random_concave_polygon(const size_t vertices, const double max); + +/// @brief checks for collisions between two vectors of convex polygons using a specified collision +/// detection algorithm +/// @param polygons1 A vector of convex polygons to check for collisions. +/// @param polygons2 A vector of convex polygons to check for collisions. +/// @param intersection_func A function that takes two polygons and returns true if they intersect, +/// otherwise false. +/// @return True if at least one pair of polygons intersects, otherwise false. +bool test_intersection( + const std::vector & polygons1, + const std::vector & polygons2, + const std::function< + bool(const autoware_utils::Polygon2d &, const autoware_utils::Polygon2d &)> &); + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__GEOMETRY__RANDOM_CONCAVE_POLYGON_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp b/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp new file mode 100644 index 0000000..f7fbf86 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/random_convex_polygon.hpp @@ -0,0 +1,29 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ + +#include + +namespace autoware_utils +{ +/// @brief generate a random convex polygon +/// @param vertices number of vertices for the desired polygon +/// @param max points will be generated in the range [-max,max] +/// @details algorithm from https://cglab.ca/~sander/misc/ConvexGeneration/convex.html +Polygon2d random_convex_polygon(const size_t vertices, const double max); +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__GEOMETRY__RANDOM_CONVEX_POLYGON_HPP_ diff --git a/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp b/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp new file mode 100644 index 0000000..48eef84 --- /dev/null +++ b/autoware_utils/include/autoware_utils/geometry/sat_2d.hpp @@ -0,0 +1,30 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__GEOMETRY__SAT_2D_HPP_ +#define AUTOWARE_UTILS__GEOMETRY__SAT_2D_HPP_ + +#include "autoware_utils/geometry/boost_geometry.hpp" + +namespace autoware_utils::sat +{ +/** + * @brief Check if 2 convex polygons intersect using the SAT algorithm + * @details faster than boost::geometry::overlap() but speed decline sharply as vertices increase + */ +bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2); + +} // namespace autoware_utils::sat + +#endif // AUTOWARE_UTILS__GEOMETRY__SAT_2D_HPP_ diff --git a/autoware_utils/include/autoware_utils/math/accumulator.hpp b/autoware_utils/include/autoware_utils/math/accumulator.hpp new file mode 100644 index 0000000..4a2225e --- /dev/null +++ b/autoware_utils/include/autoware_utils/math/accumulator.hpp @@ -0,0 +1,93 @@ +// Copyright 2021-2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include +#include + +#ifndef AUTOWARE_UTILS__MATH__ACCUMULATOR_HPP_ +#define AUTOWARE_UTILS__MATH__ACCUMULATOR_HPP_ + +namespace autoware_utils +{ +/** + * @brief class to accumulate statistical data, supporting min, max and mean. + * @typedef T type of the values (default to double) + */ +template +class Accumulator +{ +public: + /** + * @brief add a value + * @param value value to add + */ + void add(const T & value) + { + if (value < min_) { + min_ = value; + } + if (value > max_) { + max_ = value; + } + ++count_; + mean_ = mean_ + (value - mean_) / count_; + } + + /** + * @brief get the mean value + */ + long double mean() const { return mean_; } + + /** + * @brief get the minimum value + */ + T min() const { return min_; } + + /** + * @brief get the maximum value + */ + T max() const { return max_; } + + /** + * @brief get the number of values used to build this statistic + */ + unsigned int count() const { return count_; } + + template + friend std::ostream & operator<<(std::ostream & os, const Accumulator & accumulator); + +private: + T min_ = std::numeric_limits::max(); + T max_ = std::numeric_limits::lowest(); + long double mean_ = 0.0; + unsigned int count_ = 0; +}; + +/** + * @brief overload << operator for easy print to output stream + */ +template +std::ostream & operator<<(std::ostream & os, const Accumulator & accumulator) +{ + if (accumulator.count() == 0) { + os << "None None None"; + } else { + os << accumulator.min() << " " << accumulator.max() << " " << accumulator.mean(); + } + return os; +} + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__MATH__ACCUMULATOR_HPP_ diff --git a/autoware_utils/include/autoware_utils/math/sin_table.hpp b/autoware_utils/include/autoware_utils/math/sin_table.hpp new file mode 100644 index 0000000..bb8dac5 --- /dev/null +++ b/autoware_utils/include/autoware_utils/math/sin_table.hpp @@ -0,0 +1,30 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__MATH__SIN_TABLE_HPP_ +#define AUTOWARE_UTILS__MATH__SIN_TABLE_HPP_ + +#include + +namespace autoware_utils +{ + +constexpr size_t sin_table_size = 32769; +constexpr size_t discrete_arcs_num_90 = 32768; +constexpr size_t discrete_arcs_num_360 = 131072; +extern const float g_sin_table[sin_table_size]; + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__MATH__SIN_TABLE_HPP_ diff --git a/autoware_utils/include/autoware_utils/math/trigonometry.hpp b/autoware_utils/include/autoware_utils/math/trigonometry.hpp new file mode 100644 index 0000000..8ee5930 --- /dev/null +++ b/autoware_utils/include/autoware_utils/math/trigonometry.hpp @@ -0,0 +1,33 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__MATH__TRIGONOMETRY_HPP_ +#define AUTOWARE_UTILS__MATH__TRIGONOMETRY_HPP_ + +#include + +namespace autoware_utils +{ + +float sin(float radian); + +float cos(float radian); + +std::pair sin_and_cos(float radian); + +float opencv_fast_atan2(float dy, float dx); + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__MATH__TRIGONOMETRY_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/debug_publisher.hpp b/autoware_utils/include/autoware_utils/ros/debug_publisher.hpp new file mode 100644 index 0000000..8afdb55 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/debug_publisher.hpp @@ -0,0 +1,77 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__DEBUG_PUBLISHER_HPP_ +#define AUTOWARE_UTILS__ROS__DEBUG_PUBLISHER_HPP_ + +#include "autoware_utils/ros/debug_traits.hpp" + +#include +#include +#include + +#include +#include +#include + +namespace autoware_utils +{ +namespace debug_publisher +{ +template < + class T_msg, class T, + std::enable_if_t::value, std::nullptr_t> = + nullptr> +T_msg to_debug_msg(const T & data, const rclcpp::Time & stamp) +{ + T_msg msg; + msg.stamp = stamp; + msg.data = data; + return msg; +} +} // namespace debug_publisher + +class DebugPublisher +{ +public: + explicit DebugPublisher(rclcpp::Node * node, const char * ns) : node_(node), ns_(ns) {} + + template < + class T, + std::enable_if_t::value, std::nullptr_t> = nullptr> + void publish(const std::string & name, const T & data, const rclcpp::QoS & qos = rclcpp::QoS(1)) + { + if (pub_map_.count(name) == 0) { + pub_map_[name] = node_->create_publisher(std::string(ns_) + "/" + name, qos); + } + + std::dynamic_pointer_cast>(pub_map_.at(name))->publish(data); + } + + template < + class T_msg, class T, + std::enable_if_t::value, std::nullptr_t> = nullptr> + void publish(const std::string & name, const T & data, const rclcpp::QoS & qos = rclcpp::QoS(1)) + { + publish(name, debug_publisher::to_debug_msg(data, node_->now()), qos); + } + +private: + rclcpp::Node * node_; + const char * ns_; + std::unordered_map> pub_map_; +}; +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__DEBUG_PUBLISHER_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/debug_traits.hpp b/autoware_utils/include/autoware_utils/ros/debug_traits.hpp new file mode 100644 index 0000000..b82194c --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/debug_traits.hpp @@ -0,0 +1,91 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__DEBUG_TRAITS_HPP_ +#define AUTOWARE_UTILS__ROS__DEBUG_TRAITS_HPP_ + +#include +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include + +namespace autoware_utils::debug_traits +{ +template +struct is_debug_message : std::false_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message +: std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message +: std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; + +template <> +struct is_debug_message : std::true_type +{ +}; +} // namespace autoware_utils::debug_traits + +#endif // AUTOWARE_UTILS__ROS__DEBUG_TRAITS_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/diagnostics_interface.hpp b/autoware_utils/include/autoware_utils/ros/diagnostics_interface.hpp new file mode 100644 index 0000000..96be191 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/diagnostics_interface.hpp @@ -0,0 +1,61 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__DIAGNOSTICS_INTERFACE_HPP_ +#define AUTOWARE_UTILS__ROS__DIAGNOSTICS_INTERFACE_HPP_ + +#include + +#include + +#include +#include + +namespace autoware_utils +{ +class DiagnosticsInterface +{ +public: + DiagnosticsInterface(rclcpp::Node * node, const std::string & diagnostic_name); + void clear(); + void add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg); + template + void add_key_value(const std::string & key, const T & value); + void add_key_value(const std::string & key, const std::string & value); + void add_key_value(const std::string & key, bool value); + void update_level_and_message(const int8_t level, const std::string & message); + void publish(const rclcpp::Time & publish_time_stamp); + +private: + [[nodiscard]] diagnostic_msgs::msg::DiagnosticArray create_diagnostics_array( + const rclcpp::Time & publish_time_stamp) const; + + rclcpp::Clock::SharedPtr clock_; + rclcpp::Publisher::SharedPtr diagnostics_pub_; + + diagnostic_msgs::msg::DiagnosticStatus diagnostics_status_msg_; +}; + +template +void DiagnosticsInterface::add_key_value(const std::string & key, const T & value) +{ + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = key; + key_value.value = std::to_string(value); + add_key_value(key_value); +} + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__DIAGNOSTICS_INTERFACE_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/logger_level_configure.hpp b/autoware_utils/include/autoware_utils/ros/logger_level_configure.hpp new file mode 100644 index 0000000..1537d39 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/logger_level_configure.hpp @@ -0,0 +1,68 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +// =============== Note =============== +// This is a util class implementation of the logger_config_component provided by ROS 2 +// https://github.com/ros2/demos/blob/humble/logging_demo/src/logger_config_component.cpp +// +// When ROS 2 officially supports the set_logger_level option in release version, this class can be +// removed. +// https://github.com/ros2/ros2/issues/1355 + +// =============== How to use =============== +// ___In your_node.hpp___ +// #include "autoware/universe_utils/ros/logger_level_configure.hpp" +// class YourNode : public rclcpp::Node { +// ... +// +// // Define logger_configure as a node class member variable +// std::unique_ptr logger_configure_; +// } +// +// ___In your_node.cpp___ +// YourNode::YourNode() { +// ... +// +// // Set up logger_configure +// logger_configure_ = std::make_unique(this); +// } + +#ifndef AUTOWARE_UTILS__ROS__LOGGER_LEVEL_CONFIGURE_HPP_ +#define AUTOWARE_UTILS__ROS__LOGGER_LEVEL_CONFIGURE_HPP_ + +#include "logging_demo/srv/config_logger.hpp" + +#include + +namespace autoware_utils +{ +class LoggerLevelConfigure +{ +private: + using ConfigLogger = logging_demo::srv::ConfigLogger; + +public: + explicit LoggerLevelConfigure(rclcpp::Node * node); + +private: + rclcpp::Logger ros_logger_; + rclcpp::Service::SharedPtr srv_config_logger_; + + void on_logger_config_service( + const ConfigLogger::Request::SharedPtr request, + const ConfigLogger::Response::SharedPtr response); +}; + +} // namespace autoware_utils +#endif // AUTOWARE_UTILS__ROS__LOGGER_LEVEL_CONFIGURE_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/managed_transform_buffer.hpp b/autoware_utils/include/autoware_utils/ros/managed_transform_buffer.hpp new file mode 100644 index 0000000..a14dbf8 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/managed_transform_buffer.hpp @@ -0,0 +1,228 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ +#define AUTOWARE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ + +#include "autoware_utils/ros/transform_listener.hpp" + +#include +#include +#include + +#include + +#include + +#include +#include +#include +#include +#include +#include +#include + +namespace std +{ +template <> +struct hash> +{ + size_t operator()(const std::pair & p) const + { + size_t h1 = std::hash{}(p.first); + size_t h2 = std::hash{}(p.second); + return h1 ^ (h2 << 1u); + } +}; +} // namespace std + +namespace autoware_utils +{ +using std::chrono_literals::operator""ms; +using Key = std::pair; +struct PairEqual +{ + bool operator()(const Key & p1, const Key & p2) const + { + return p1.first == p2.first && p1.second == p2.second; + } +}; +using TFMap = std::unordered_map, PairEqual>; +constexpr std::array warn_frames = {"map", "odom", "world"}; + +class ManagedTransformBuffer +{ +public: + explicit ManagedTransformBuffer(rclcpp::Node * node, const bool & has_static_tf_only) + : node_(node) + { + if (has_static_tf_only) { + get_transform_ = [this]( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) { + return get_static_transform(target_frame, source_frame, eigen_transform); + }; + } else { + tf_listener_ = std::make_unique(node); + get_transform_ = [this]( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) { + return get_dynamic_transform(target_frame, source_frame, eigen_transform); + }; + } + } + + bool get_transform( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) + { + return get_transform_(target_frame, source_frame, eigen_transform); + } + + /** + * Transforms a point cloud from one frame to another. + * + * @param target_frame The target frame to transform the point cloud to. + * @param cloud_in The input point cloud to be transformed. + * @param cloud_out The transformed point cloud. + * @return True if the transformation is successful, false otherwise. + */ + bool transform_pointcloud( + const std::string & target_frame, const sensor_msgs::msg::PointCloud2 & cloud_in, + sensor_msgs::msg::PointCloud2 & cloud_out) + { + if ( + pcl::getFieldIndex(cloud_in, "x") == -1 || pcl::getFieldIndex(cloud_in, "y") == -1 || + pcl::getFieldIndex(cloud_in, "z") == -1) { + RCLCPP_ERROR(node_->get_logger(), "Input pointcloud does not have xyz fields"); + return false; + } + if (target_frame == cloud_in.header.frame_id) { + cloud_out = cloud_in; + return true; + } + Eigen::Matrix4f eigen_transform; + if (!get_transform(target_frame, cloud_in.header.frame_id, eigen_transform)) { + return false; + } + pcl_ros::transformPointCloud(eigen_transform, cloud_in, cloud_out); + cloud_out.header.frame_id = target_frame; + return true; + } + +private: + /** + * @brief Retrieves a transform between two static frames. + * + * This function attempts to retrieve a transform between the target frame and the source frame. + * If success, the transform matrix is set to the output parameter and the function returns true. + * Otherwise, transform matrix is set to identity and the function returns false. Transform + * Listener is destroyed after function call. + * + * @param target_frame The target frame. + * @param source_frame The source frame. + * @param eigen_transform The output Eigen transform matrix. It is set to the identity if the + * transform is not found. + * @return True if the transform was successfully retrieved, false otherwise. + */ + bool get_static_transform( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) + { + if ( + std::find(warn_frames.begin(), warn_frames.end(), target_frame) != warn_frames.end() || + std::find(warn_frames.begin(), warn_frames.end(), source_frame) != warn_frames.end()) { + RCLCPP_WARN( + node_->get_logger(), "Using %s -> %s transform. This may not be a static transform.", + target_frame.c_str(), source_frame.c_str()); + } + + auto key = std::make_pair(target_frame, source_frame); + auto key_inv = std::make_pair(source_frame, target_frame); + + // Check if the transform is already in the buffer + auto it = buffer_.find(key); + if (it != buffer_.end()) { + eigen_transform = it->second; + return true; + } + + // Check if the inverse transform is already in the buffer + auto it_inv = buffer_.find(key_inv); + if (it_inv != buffer_.end()) { + eigen_transform = it_inv->second.inverse(); + buffer_[key] = eigen_transform; + return true; + } + + // Check if transform is needed + if (target_frame == source_frame) { + eigen_transform = Eigen::Matrix4f::Identity(); + buffer_[key] = eigen_transform; + return true; + } + + // Get the transform from the TF tree + tf_listener_ = std::make_unique(node_); + auto tf = tf_listener_->get_transform( + target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms)); + tf_listener_.reset(); + RCLCPP_DEBUG( + node_->get_logger(), "Trying to enqueue %s -> %s transform to static TFs buffer...", + target_frame.c_str(), source_frame.c_str()); + if (tf == nullptr) { + eigen_transform = Eigen::Matrix4f::Identity(); + return false; + } + pcl_ros::transformAsMatrix(*tf, eigen_transform); + buffer_[key] = eigen_transform; + return true; + } + + /** @brief Retrieves a transform between two dynamic frames. + * + * This function attempts to retrieve a transform between the target frame and the source frame. + * If successful, the transformation matrix is assigned to the output parameter, and the function + * returns true. Otherwise, the transformation matrix is set to the identity and the function + * returns false. + * + * @param target_frame The target frame. + * @param source_frame The source frame. + * @param eigen_transform The output Eigen transformation matrix. It is set to the identity if the + * transform is not found. + * @return True if the transform was successfully retrieved, false otherwise. + */ + bool get_dynamic_transform( + const std::string & target_frame, const std::string & source_frame, + Eigen::Matrix4f & eigen_transform) + { + auto tf = tf_listener_->get_transform( + target_frame, source_frame, rclcpp::Time(0), rclcpp::Duration(1000ms)); + if (tf == nullptr) { + eigen_transform = Eigen::Matrix4f::Identity(); + return false; + } + pcl_ros::transformAsMatrix(*tf, eigen_transform); + return true; + } + + TFMap buffer_; + rclcpp::Node * const node_; + std::unique_ptr tf_listener_; + std::function get_transform_; +}; + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__MANAGED_TRANSFORM_BUFFER_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/marker_helper.hpp b/autoware_utils/include/autoware_utils/ros/marker_helper.hpp new file mode 100644 index 0000000..bc2c015 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/marker_helper.hpp @@ -0,0 +1,81 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__MARKER_HELPER_HPP_ +#define AUTOWARE_UTILS__ROS__MARKER_HELPER_HPP_ + +#include + +#include + +#include +#include + +namespace autoware_utils +{ +inline geometry_msgs::msg::Point create_marker_position(double x, double y, double z) +{ + geometry_msgs::msg::Point point; + point.x = x; + point.y = y; + point.z = z; + return point; +} + +inline geometry_msgs::msg::Quaternion create_marker_orientation( + double x, double y, double z, double w) +{ + geometry_msgs::msg::Quaternion quaternion; + quaternion.x = x; + quaternion.y = y; + quaternion.z = z; + quaternion.w = w; + return quaternion; +} + +inline geometry_msgs::msg::Vector3 create_marker_scale(double x, double y, double z) +{ + geometry_msgs::msg::Vector3 scale; + scale.x = x; + scale.y = y; + scale.z = z; + return scale; +} + +inline std_msgs::msg::ColorRGBA create_marker_color(float r, float g, float b, float a) +{ + std_msgs::msg::ColorRGBA color; + color.r = r; + color.g = g; + color.b = b; + color.a = a; + return color; +} + +visualization_msgs::msg::Marker create_default_marker( + const std::string & frame_id, const rclcpp::Time & now, const std::string & ns, const int32_t id, + const int32_t type, const geometry_msgs::msg::Vector3 & scale, + const std_msgs::msg::ColorRGBA & color); + +visualization_msgs::msg::Marker create_deleted_default_marker( + const rclcpp::Time & now, const std::string & ns, const int32_t id); + +void append_marker_array( + const visualization_msgs::msg::MarkerArray & additional_marker_array, + visualization_msgs::msg::MarkerArray * marker_array, + const std::optional & current_time = {}); + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__MARKER_HELPER_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/msg_covariance.hpp b/autoware_utils/include/autoware_utils/ros/msg_covariance.hpp new file mode 100644 index 0000000..e566860 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/msg_covariance.hpp @@ -0,0 +1,120 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__MSG_COVARIANCE_HPP_ +#define AUTOWARE_UTILS__ROS__MSG_COVARIANCE_HPP_ + +namespace autoware_utils +{ +namespace xyz_covariance_index +{ +/// Covariance for x-y-z. +/// Used at +/// - sensor_msgs/msg/Imu.msg: msg.linear_acceleration_covariance +enum XYZ_COV_IDX { + X_X = 0, + X_Y = 1, + X_Z = 2, + Y_X = 3, + Y_Y = 4, + Y_Z = 5, + Z_X = 6, + Z_Y = 7, + Z_Z = 8, +}; +} // namespace xyz_covariance_index + +namespace rpy_covariance_index +{ +/// Covariance for roll-pitch-yaw. +/// Used at +/// - sensor_msgs/msg/Imu.msg: msg.angular_velocity_covariance +/// - sensor_msgs/msg/Imu.msg: msg.orientation_covariance +enum RPY_COV_IDX { + ROLL_ROLL = 0, + ROLL_PITCH = 1, + ROLL_YAW = 2, + PITCH_ROLL = 3, + PITCH_PITCH = 4, + PITCH_YAW = 5, + YAW_ROLL = 6, + YAW_PITCH = 7, + YAW_YAW = 8 +}; +} // namespace rpy_covariance_index + +namespace xyzrpy_covariance_index +{ +/// Covariance for 6-DOF. +/// Used at +/// - geometry_msgs/msg/AccelWithCovariance.msg: msg.covariance +/// - geometry_msgs/msg/TwistWithCovariance.msg: msg.covariance +/// - geometry_msgs/msg/PoseWithCovariance.msg: msg.covariance +enum XYZRPY_COV_IDX { + X_X = 0, + X_Y = 1, + X_Z = 2, + X_ROLL = 3, + X_PITCH = 4, + X_YAW = 5, + Y_X = 6, + Y_Y = 7, + Y_Z = 8, + Y_ROLL = 9, + Y_PITCH = 10, + Y_YAW = 11, + Z_X = 12, + Z_Y = 13, + Z_Z = 14, + Z_ROLL = 15, + Z_PITCH = 16, + Z_YAW = 17, + ROLL_X = 18, + ROLL_Y = 19, + ROLL_Z = 20, + ROLL_ROLL = 21, + ROLL_PITCH = 22, + ROLL_YAW = 23, + PITCH_X = 24, + PITCH_Y = 25, + PITCH_Z = 26, + PITCH_ROLL = 27, + PITCH_PITCH = 28, + PITCH_YAW = 29, + YAW_X = 30, + YAW_Y = 31, + YAW_Z = 32, + YAW_ROLL = 33, + YAW_PITCH = 34, + YAW_YAW = 35 +}; +} // namespace xyzrpy_covariance_index + +namespace xyz_upper_covariance_index +{ +/// Upper-triangle covariance about the x, y, z axes +/// Used at +/// - radar_msgs/msg/RadarTrack.msg: msg.{position, velocity, acceleration}_covariance +enum XYZ_UPPER_COV_IDX { + X_X = 0, + X_Y = 1, + X_Z = 2, + Y_Y = 3, + Y_Z = 4, + Z_Z = 5, +}; +} // namespace xyz_upper_covariance_index +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__MSG_COVARIANCE_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/msg_operation.hpp b/autoware_utils/include/autoware_utils/ros/msg_operation.hpp new file mode 100644 index 0000000..132414b --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/msg_operation.hpp @@ -0,0 +1,31 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_ +#define AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_ + +#include "geometry_msgs/msg/quaternion.hpp" + +// NOTE: Do not use autoware_utils namespace +namespace geometry_msgs +{ +namespace msg +{ +Quaternion operator+(Quaternion a, Quaternion b) noexcept; +Quaternion operator-(Quaternion a) noexcept; +Quaternion operator-(Quaternion a, Quaternion b) noexcept; +} // namespace msg +} // namespace geometry_msgs + +#endif // AUTOWARE_UTILS__ROS__MSG_OPERATION_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/parameter.hpp b/autoware_utils/include/autoware_utils/ros/parameter.hpp new file mode 100644 index 0000000..2481d77 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/parameter.hpp @@ -0,0 +1,35 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__PARAMETER_HPP_ +#define AUTOWARE_UTILS__ROS__PARAMETER_HPP_ + +#include + +#include + +namespace autoware_utils +{ +template +T get_or_declare_parameter(rclcpp::Node & node, const std::string & name) +{ + if (node.has_parameter(name)) { + return node.get_parameter(name).get_value(); + } + + return node.declare_parameter(name); +} +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__PARAMETER_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/pcl_conversion.hpp b/autoware_utils/include/autoware_utils/ros/pcl_conversion.hpp new file mode 100644 index 0000000..77c5c6b --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/pcl_conversion.hpp @@ -0,0 +1,72 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ +#define AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ + +#include +#include + +#include + +namespace autoware_utils +{ +/** + * @brief a faster implementation of converting sensor_msgs::msg::PointCloud2 to + * pcl::PointCloud and transform the cloud + * + * @tparam Scalar + * @param cloud input PointCloud2 message + * @param pcl_cloud output transformed pcl cloud + * @param transform eigen transformation matrix + */ +template +void transform_point_cloud_from_ros_msg( + const sensor_msgs::msg::PointCloud2 & cloud, pcl::PointCloud & pcl_cloud, + const Eigen::Matrix & transform) +{ + // Copy info fields + pcl_conversions::toPCL(cloud.header, pcl_cloud.header); + pcl_cloud.width = cloud.width; + pcl_cloud.height = cloud.height; + pcl_cloud.is_dense = cloud.is_dense == 1; + + pcl::MsgFieldMap field_map; + std::vector msg_fields; + pcl_conversions::toPCL(cloud.fields, msg_fields); + pcl::createMapping(msg_fields, field_map); + + // transform point data + std::uint32_t num_points = cloud.width * cloud.height; + pcl_cloud.points.resize(num_points); + std::uint8_t * cloud_data = reinterpret_cast(&pcl_cloud.points[0]); + pcl::detail::Transformer tf(transform); + + for (std::uint32_t row = 0; row < cloud.height; ++row) { + const std::uint8_t * row_data = &cloud.data[row * cloud.row_step]; + for (std::uint32_t col = 0; col < cloud.width; ++col) { + const std::uint8_t * msg_data = row_data + col * cloud.point_step; + for (const pcl::detail::FieldMapping & mapping : field_map) { + const float * msg_ptr = reinterpret_cast(msg_data); + float * pcl_ptr = reinterpret_cast(cloud_data + mapping.struct_offset); + tf.se3(msg_ptr, pcl_ptr); + } + cloud_data += sizeof(pcl::PointXYZ); + } + } +} + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__PCL_CONVERSION_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/polling_subscriber.hpp b/autoware_utils/include/autoware_utils/ros/polling_subscriber.hpp new file mode 100644 index 0000000..2dbe1e9 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/polling_subscriber.hpp @@ -0,0 +1,253 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ +#define AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ + +#include + +#include +#include +#include +#include + +namespace autoware_utils +{ + +/** + * @brief Creates a SensorDataQoS profile with a single depth. + * @return rclcpp::SensorDataQoS The QoS profile with depth set to 1. + */ +inline rclcpp::SensorDataQoS single_depth_sensor_qos() +{ + rclcpp::SensorDataQoS qos; + qos.get_rmw_qos_profile().depth = 1; + return qos; +} + +namespace polling_policy +{ + +/** + * @brief Polling policy that keeps the latest received message. + * + * This policy retains the latest received message and provides it when requested. If a new message + * is received, it overwrites the previously stored message. + * + * @tparam MessageT The message type. + */ +template +class Latest +{ +private: + typename MessageT::ConstSharedPtr data_{nullptr}; ///< Data pointer to store the latest data + +protected: + /** + * @brief Check the QoS settings for the subscription. + * + * @param qos The QoS profile to check. + * @throws std::invalid_argument If the QoS depth is not 1. + */ + void check_qos(const rclcpp::QoS & qos) + { + if (qos.get_rmw_qos_profile().depth > 1) { + throw std::invalid_argument( + "InterProcessPollingSubscriber will be used with depth > 1, which may cause inefficient " + "serialization while updateLatestData()"); + } + } + +public: + /** + * @brief Retrieve the latest data. If no new data has been received, the previously received data + * + * @return typename MessageT::ConstSharedPtr The latest data. + */ + typename MessageT::ConstSharedPtr take_data(); +}; + +/** + * @brief Polling policy that keeps the newest received message. + * + * @tparam MessageT The message type. + */ +template +class Newest +{ +protected: + /** + * @brief Check the QoS settings for the subscription. + * + * @param qos The QoS profile to check. + * @throws std::invalid_argument If the QoS depth is not 1. + */ + void check_qos(const rclcpp::QoS & qos) + { + if (qos.get_rmw_qos_profile().depth > 1) { + throw std::invalid_argument( + "InterProcessPollingSubscriber will be used with depth > 1, which may cause inefficient " + "serialization while updateLatestData()"); + } + } + +public: + /** + * @brief Retrieve the newest data. If no new data has been received, nullptr is returned. + * + * @return typename MessageT::ConstSharedPtr The newest data. + */ + typename MessageT::ConstSharedPtr take_data(); +}; + +/** + * @brief Polling policy that keeps all received messages. + * + * @tparam MessageT The message type. + */ +template +class All +{ +protected: + /** + * @brief Check the QoS settings for the subscription. + * + * @param qos The QoS profile to check. + */ + void check_qos(const rclcpp::QoS &) {} + +public: + /** + * @brief Retrieve all data. + * + * @return std::vector The list of all received data. + */ + std::vector take_data(); +}; + +} // namespace polling_policy + +/** + * @brief Subscriber class that uses a specified polling policy. + * + * @tparam MessageT The message type. + * @tparam PollingPolicy The polling policy to use. + */ +template class PollingPolicy = polling_policy::Latest> +class InterProcessPollingSubscriber : public PollingPolicy +{ + friend PollingPolicy; + +private: + typename rclcpp::Subscription::SharedPtr subscriber_; ///< Subscription object + +public: + using SharedPtr = std::shared_ptr>; + + /** + * @brief Construct a new InterProcessPollingSubscriber object. + * + * @param node The node to attach the subscriber to. + * @param topic_name The topic name to subscribe to. + * @param qos The QoS profile to use for the subscription. + */ + explicit InterProcessPollingSubscriber( + rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos = rclcpp::QoS{1}) + { + this->check_qos(qos); + + auto noexec_callback_group = + node->create_callback_group(rclcpp::CallbackGroupType::MutuallyExclusive, false); + + auto noexec_subscription_options = rclcpp::SubscriptionOptions(); + noexec_subscription_options.callback_group = noexec_callback_group; + + subscriber_ = node->create_subscription( + topic_name, qos, + [node]([[maybe_unused]] const typename MessageT::ConstSharedPtr msg) { assert(false); }, + noexec_subscription_options); + } + + /** + * @brief Create a subscription. + * + * @param node The node to attach the subscriber to. + * @param topic_name The topic name to subscribe to. + * @param qos The QoS profile to use for the subscription. + * @return SharedPtr The created subscription. + */ + static SharedPtr create_subscription( + rclcpp::Node * node, const std::string & topic_name, const rclcpp::QoS & qos = rclcpp::QoS{1}) + { + return std::make_shared>( + node, topic_name, qos); + } + + typename rclcpp::Subscription::SharedPtr subscriber() { return subscriber_; } +}; + +namespace polling_policy +{ + +template +typename MessageT::ConstSharedPtr Latest::take_data() +{ + auto & subscriber = + static_cast *>(this)->subscriber_; + auto new_data = std::make_shared(); + rclcpp::MessageInfo message_info; + const bool success = subscriber->take(*new_data, message_info); + if (success) { + data_ = new_data; + } + + return data_; +} + +template +typename MessageT::ConstSharedPtr Newest::take_data() +{ + auto & subscriber = + static_cast *>(this)->subscriber_; + auto new_data = std::make_shared(); + rclcpp::MessageInfo message_info; + const bool success = subscriber->take(*new_data, message_info); + if (success) { + return new_data; + } + return nullptr; +} + +template +std::vector All::take_data() +{ + auto & subscriber = + static_cast *>(this)->subscriber_; + std::vector data; + rclcpp::MessageInfo message_info; + for (;;) { + auto datum = std::make_shared(); + if (subscriber->take(*datum, message_info)) { + data.push_back(datum); + } else { + break; + } + } + return data; +} + +} // namespace polling_policy + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__POLLING_SUBSCRIBER_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/processing_time_publisher.hpp b/autoware_utils/include/autoware_utils/ros/processing_time_publisher.hpp new file mode 100644 index 0000000..2da2fa5 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/processing_time_publisher.hpp @@ -0,0 +1,67 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__PROCESSING_TIME_PUBLISHER_HPP_ +#define AUTOWARE_UTILS__ROS__PROCESSING_TIME_PUBLISHER_HPP_ + +#include + +#include + +#include +#include +#include + +namespace autoware_utils +{ +class ProcessingTimePublisher +{ +public: + explicit ProcessingTimePublisher( + rclcpp::Node * node, const std::string & name = "~/debug/processing_time_ms", + const rclcpp::QoS & qos = rclcpp::QoS(1)) + { + pub_processing_time_ = + node->create_publisher(name, qos); + } + + void publish(const std::map & processing_time_map) + { + diagnostic_msgs::msg::DiagnosticStatus status; + + for (const auto & m : processing_time_map) { + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = m.first; + key_value.value = to_string_with_precision(m.second, 3); + status.values.push_back(key_value); + } + + pub_processing_time_->publish(status); + } + +private: + rclcpp::Publisher::SharedPtr pub_processing_time_; + + template + std::string to_string_with_precision(const T & value, const int precision) + { + std::ostringstream oss; + oss.precision(precision); + oss << std::fixed << value; + return oss.str(); + } +}; +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__PROCESSING_TIME_PUBLISHER_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/published_time_publisher.hpp b/autoware_utils/include/autoware_utils/ros/published_time_publisher.hpp new file mode 100644 index 0000000..faf09e8 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/published_time_publisher.hpp @@ -0,0 +1,114 @@ +// Copyright 2024 The Autoware Contributors +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__PUBLISHED_TIME_PUBLISHER_HPP_ +#define AUTOWARE_UTILS__ROS__PUBLISHED_TIME_PUBLISHER_HPP_ + +#include + +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware_utils +{ + +class PublishedTimePublisher +{ +public: + explicit PublishedTimePublisher( + rclcpp::Node * node, std::string publisher_topic_suffix = "/debug/published_time", + const rclcpp::QoS & qos = rclcpp::QoS(1)) + : node_(node), publisher_topic_suffix_(std::move(publisher_topic_suffix)), qos_(qos) + { + } + + void publish_if_subscribed( + const rclcpp::PublisherBase::ConstSharedPtr & publisher, const rclcpp::Time & stamp) + { + const auto & gid_key = publisher->get_gid(); + + // if the publisher is not in the map, create a new publisher for published time + ensure_publisher_exists(gid_key, publisher->get_topic_name()); + + const auto & pub_published_time = publishers_[gid_key]; + + // Check if there are any subscribers, otherwise don't do anything + if (pub_published_time->get_subscription_count() > 0) { + PublishedTime published_time; + + published_time.header.stamp = stamp; + published_time.published_stamp = rclcpp::Clock().now(); + + pub_published_time->publish(published_time); + } + } + + void publish_if_subscribed( + const rclcpp::PublisherBase::ConstSharedPtr & publisher, const std_msgs::msg::Header & header) + { + const auto & gid_key = publisher->get_gid(); + + // if the publisher is not in the map, create a new publisher for published time + ensure_publisher_exists(gid_key, publisher->get_topic_name()); + + const auto & pub_published_time = publishers_[gid_key]; + + // Check if there are any subscribers, otherwise don't do anything + if (pub_published_time->get_subscription_count() > 0) { + PublishedTime published_time; + + published_time.header = header; + published_time.published_stamp = rclcpp::Clock().now(); + + pub_published_time->publish(published_time); + } + } + +private: + rclcpp::Node * node_; + std::string publisher_topic_suffix_; + rclcpp::QoS qos_; + + using PublishedTime = autoware_internal_msgs::msg::PublishedTime; + + // Custom comparison struct for rmw_gid_t + struct GidCompare + { + bool operator()(const rmw_gid_t & lhs, const rmw_gid_t & rhs) const + { + return std::memcmp(lhs.data, rhs.data, RMW_GID_STORAGE_SIZE) < 0; + } + }; + + // ensure that the publisher exists in publisher_ map, if not, create a new one + void ensure_publisher_exists(const rmw_gid_t & gid_key, const std::string & topic_name) + { + if (publishers_.find(gid_key) == publishers_.end()) { + publishers_[gid_key] = + node_->create_publisher(topic_name + publisher_topic_suffix_, qos_); + } + } + + // store them for each different publisher of the node + std::map::SharedPtr, GidCompare> publishers_; +}; +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__PUBLISHED_TIME_PUBLISHER_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/self_pose_listener.hpp b/autoware_utils/include/autoware_utils/ros/self_pose_listener.hpp new file mode 100644 index 0000000..23f878c --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/self_pose_listener.hpp @@ -0,0 +1,58 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__SELF_POSE_LISTENER_HPP_ +#define AUTOWARE_UTILS__ROS__SELF_POSE_LISTENER_HPP_ + +#include "autoware_utils/geometry/geometry.hpp" +#include "autoware_utils/ros/transform_listener.hpp" + +#include + +#include + +namespace autoware_utils +{ +class SelfPoseListener +{ +public: + explicit SelfPoseListener(rclcpp::Node * node) : transform_listener_(node) {} + + void wait_for_first_pose() + { + while (rclcpp::ok()) { + if (get_current_pose()) { + return; + } + RCLCPP_INFO(transform_listener_.get_logger(), "waiting for self pose..."); + rclcpp::Rate(0.2).sleep(); + } + } + + geometry_msgs::msg::PoseStamped::ConstSharedPtr get_current_pose() + { + const auto tf = transform_listener_.get_latest_transform("map", "base_link"); + if (!tf) { + return {}; + } + + return std::make_shared(transform2pose(*tf)); + } + +private: + TransformListener transform_listener_; +}; +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__SELF_POSE_LISTENER_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/transform_listener.hpp b/autoware_utils/include/autoware_utils/ros/transform_listener.hpp new file mode 100644 index 0000000..4b75545 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/transform_listener.hpp @@ -0,0 +1,87 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__TRANSFORM_LISTENER_HPP_ +#define AUTOWARE_UTILS__ROS__TRANSFORM_LISTENER_HPP_ + +#include + +#include + +#include +#include +#include + +#include +#include + +namespace autoware_utils +{ +class TransformListener +{ +public: + explicit TransformListener(rclcpp::Node * node) + : clock_(node->get_clock()), logger_(node->get_logger()) + { + tf_buffer_ = std::make_shared(clock_); + auto timer_interface = std::make_shared( + node->get_node_base_interface(), node->get_node_timers_interface()); + tf_buffer_->setCreateTimerInterface(timer_interface); + tf_listener_ = std::make_shared(*tf_buffer_); + } + + geometry_msgs::msg::TransformStamped::ConstSharedPtr get_latest_transform( + const std::string & from, const std::string & to) + { + geometry_msgs::msg::TransformStamped tf; + try { + tf = tf_buffer_->lookupTransform(from, to, tf2::TimePointZero); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_THROTTLE( + logger_, *clock_, 5000, "failed to get transform from %s to %s: %s", from.c_str(), + to.c_str(), ex.what()); + return {}; + } + + return std::make_shared(tf); + } + + geometry_msgs::msg::TransformStamped::ConstSharedPtr get_transform( + const std::string & from, const std::string & to, const rclcpp::Time & time, + const rclcpp::Duration & duration) + { + geometry_msgs::msg::TransformStamped tf; + try { + tf = tf_buffer_->lookupTransform(from, to, time, duration); + } catch (tf2::TransformException & ex) { + RCLCPP_WARN_THROTTLE( + logger_, *clock_, 5000, "failed to get transform from %s to %s: %s", from.c_str(), + to.c_str(), ex.what()); + return {}; + } + + return std::make_shared(tf); + } + + rclcpp::Logger get_logger() { return logger_; } + +private: + rclcpp::Clock::SharedPtr clock_; + rclcpp::Logger logger_; + std::shared_ptr tf_buffer_; + std::shared_ptr tf_listener_; +}; +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__TRANSFORM_LISTENER_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/update_param.hpp b/autoware_utils/include/autoware_utils/ros/update_param.hpp new file mode 100644 index 0000000..e02de83 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/update_param.hpp @@ -0,0 +1,43 @@ +// Copyright 2021 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__UPDATE_PARAM_HPP_ +#define AUTOWARE_UTILS__ROS__UPDATE_PARAM_HPP_ + +#include + +#include +#include + +namespace autoware_utils +{ +template +bool update_param( + const std::vector & params, const std::string & name, T & value) +{ + const auto itr = std::find_if( + params.cbegin(), params.cend(), + [&name](const rclcpp::Parameter & p) { return p.get_name() == name; }); + + // Not found + if (itr == params.cend()) { + return false; + } + + value = itr->template get_value(); + return true; +} +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__UPDATE_PARAM_HPP_ diff --git a/autoware_utils/include/autoware_utils/ros/wait_for_param.hpp b/autoware_utils/include/autoware_utils/ros/wait_for_param.hpp new file mode 100644 index 0000000..0cd1d73 --- /dev/null +++ b/autoware_utils/include/autoware_utils/ros/wait_for_param.hpp @@ -0,0 +1,52 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__ROS__WAIT_FOR_PARAM_HPP_ +#define AUTOWARE_UTILS__ROS__WAIT_FOR_PARAM_HPP_ + +#include + +#include +#include +#include + +namespace autoware_utils +{ +template +T wait_for_param( + rclcpp::Node * node, const std::string & remote_node_name, const std::string & param_name) +{ + std::chrono::seconds sec(1); + + auto param_client = std::make_shared(node, remote_node_name); + + while (!param_client->wait_for_service(sec)) { + if (!rclcpp::ok()) { + RCLCPP_ERROR(node->get_logger(), "Interrupted while waiting for the service."); + return {}; + } + RCLCPP_INFO_THROTTLE( + node->get_logger(), *node->get_clock(), 1000 /* ms */, "waiting for node: %s, param: %s\n", + remote_node_name.c_str(), param_name.c_str()); + } + + if (param_client->has_parameter(param_name)) { + return param_client->get_parameter(param_name); + } + + return {}; +} +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__ROS__WAIT_FOR_PARAM_HPP_ diff --git a/autoware_utils/include/autoware_utils/system/backtrace.hpp b/autoware_utils/include/autoware_utils/system/backtrace.hpp new file mode 100644 index 0000000..3338e35 --- /dev/null +++ b/autoware_utils/include/autoware_utils/system/backtrace.hpp @@ -0,0 +1,25 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__SYSTEM__BACKTRACE_HPP_ +#define AUTOWARE_UTILS__SYSTEM__BACKTRACE_HPP_ + +namespace autoware_utils +{ + +void print_backtrace(); + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__SYSTEM__BACKTRACE_HPP_ diff --git a/autoware_utils/include/autoware_utils/system/lru_cache.hpp b/autoware_utils/include/autoware_utils/system/lru_cache.hpp new file mode 100644 index 0000000..25874d7 --- /dev/null +++ b/autoware_utils/include/autoware_utils/system/lru_cache.hpp @@ -0,0 +1,142 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef AUTOWARE_UTILS__SYSTEM__LRU_CACHE_HPP_ +#define AUTOWARE_UTILS__SYSTEM__LRU_CACHE_HPP_ + +#include +#include +#include +#include +#include + +namespace autoware_utils +{ + +/** + * @brief A template class for LRU (Least Recently Used) Cache. + * + * This class implements a simple LRU cache using a combination of a list and a hash map. + * + * @tparam Key The type of keys. + * @tparam Value The type of values. + * @tparam Map The type of underlying map, defaulted to std::unordered_map. + */ +template class Map = std::unordered_map> +class LRUCache +{ +private: + size_t capacity_; ///< The maximum capacity of the cache. + std::list> cache_list_; ///< List to maintain the order of elements. + Map>::iterator> + cache_map_; ///< Map for fast access to elements. + +public: + /** + * @brief Construct a new LRUCache object. + * + * @param size The capacity of the cache. + */ + explicit LRUCache(size_t size) : capacity_(size) {} + + /** + * @brief Get the capacity of the cache. + * + * @return The capacity of the cache. + */ + [[nodiscard]] size_t capacity() const { return capacity_; } + + /** + * @brief Insert a key-value pair into the cache. + * + * If the key already exists, its value is updated and it is moved to the front. + * If the cache exceeds its capacity, the least recently used element is removed. + * + * @param key The key to insert. + * @param value The value to insert. + */ + void put(const Key & key, const Value & value) + { + auto it = cache_map_.find(key); + if (it != cache_map_.end()) { + cache_list_.erase(it->second); + } + cache_list_.push_front({key, value}); + cache_map_[key] = cache_list_.begin(); + + if (cache_map_.size() > capacity_) { + auto last = cache_list_.back(); + cache_map_.erase(last.first); + cache_list_.pop_back(); + } + } + + /** + * @brief Retrieve a value from the cache. + * + * If the key does not exist in the cache, std::nullopt is returned. + * If the key exists, the value is returned and the element is moved to the front. + * + * @param key The key to retrieve. + * @return The value associated with the key, or std::nullopt if the key does not exist. + */ + std::optional get(const Key & key) + { + auto it = cache_map_.find(key); + if (it == cache_map_.end()) { + return std::nullopt; + } + cache_list_.splice(cache_list_.begin(), cache_list_, it->second); + return it->second->second; + } + + /** + * @brief Clear the cache. + * + * This removes all elements from the cache. + */ + void clear() + { + cache_list_.clear(); + cache_map_.clear(); + } + + /** + * @brief Get the current size of the cache. + * + * @return The number of elements in the cache. + */ + [[nodiscard]] size_t size() const { return cache_map_.size(); } + + /** + * @brief Check if the cache is empty. + * + * @return True if the cache is empty, false otherwise. + */ + [[nodiscard]] bool empty() const { return cache_map_.empty(); } + + /** + * @brief Check if a key exists in the cache. + * + * @param key The key to check. + * @return True if the key exists, false otherwise. + */ + [[nodiscard]] bool contains(const Key & key) const + { + return cache_map_.find(key) != cache_map_.end(); + } +}; + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__SYSTEM__LRU_CACHE_HPP_ diff --git a/autoware_utils/include/autoware_utils/system/stop_watch.hpp b/autoware_utils/include/autoware_utils/system/stop_watch.hpp new file mode 100644 index 0000000..bde2bdc --- /dev/null +++ b/autoware_utils/include/autoware_utils/system/stop_watch.hpp @@ -0,0 +1,63 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__SYSTEM__STOP_WATCH_HPP_ +#define AUTOWARE_UTILS__SYSTEM__STOP_WATCH_HPP_ + +#include +#include +#include + +namespace autoware_utils +{ +template < + class OutputUnit = std::chrono::seconds, class InternalUnit = std::chrono::microseconds, + class Clock = std::chrono::steady_clock> +class StopWatch +{ +public: + StopWatch() { tic(default_name); } + + void tic(const std::string & name = default_name) { t_start_[name] = Clock::now(); } + + void tic(const char * name) { tic(std::string(name)); } + + double toc(const std::string & name, const bool reset = false) + { + const auto t_start = t_start_.at(name); + const auto t_end = Clock::now(); + const auto duration = std::chrono::duration_cast(t_end - t_start).count(); + + if (reset) { + t_start_[name] = Clock::now(); + } + + const auto one_sec = std::chrono::duration_cast(OutputUnit(1)).count(); + + return static_cast(duration) / one_sec; + } + + double toc(const char * name, const bool reset = false) { return toc(std::string(name), reset); } + + double toc(const bool reset = false) { return toc(default_name, reset); } + +private: + using Time = std::chrono::time_point; + static constexpr const char * default_name{"__auto__"}; + + std::unordered_map t_start_; +}; +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__SYSTEM__STOP_WATCH_HPP_ diff --git a/autoware_utils/include/autoware_utils/system/time_keeper.hpp b/autoware_utils/include/autoware_utils/system/time_keeper.hpp new file mode 100644 index 0000000..b5f0edc --- /dev/null +++ b/autoware_utils/include/autoware_utils/system/time_keeper.hpp @@ -0,0 +1,215 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. +#ifndef AUTOWARE_UTILS__SYSTEM__TIME_KEEPER_HPP_ +#define AUTOWARE_UTILS__SYSTEM__TIME_KEEPER_HPP_ + +#include "autoware_utils/system/stop_watch.hpp" + +#include + +#include +#include +#include + +#include +#include +#include +#include +#include + +namespace autoware_utils +{ +/** + * @brief Class representing a node in the time tracking tree + */ +class ProcessingTimeNode : public std::enable_shared_from_this +{ +public: + /** + * @brief Construct a new ProcessingTimeNode object + * + * @param name Name of the node + */ + explicit ProcessingTimeNode(const std::string & name); + + /** + * @brief Add a child node + * + * @param name Name of the child node + * @return std::shared_ptr Shared pointer to the newly added child node + */ + std::shared_ptr add_child(const std::string & name); + + /** + * @brief Get the result string representing the node and its children in a tree structure + * + * @return std::string Result string representing the node and its children + */ + std::string to_string() const; + + /** + * @brief Construct a ProcessingTimeTree message from the node and its children + * + * @return autoware_internal_debug_msgs::msg::ProcessingTimeTree Constructed ProcessingTimeTree + * message + */ + autoware_internal_debug_msgs::msg::ProcessingTimeTree to_msg() const; + + /** + * @brief Get the parent node + * + * @return std::weak_ptr Weak pointer to the parent node + */ + std::weak_ptr get_parent_node() const; + + /** + * @brief Get the child nodes + * + * @return std::vector> Vector of shared pointers to the child + * nodes + */ + std::vector> get_child_nodes() const; + + /** + * @brief Set the processing time for the node + * + * @param processing_time Processing time to be set + */ + void set_time(const double processing_time); + + /** + * @brief Set the comment for the node + * + * @param comment Comment to be set + */ + void set_comment(const std::string & comment); + + /** + * @brief Get the name of the node + * + * @return std::string Name of the node + */ + std::string get_name() const; + +private: + const std::string name_; //!< Name of the node + double processing_time_{0.0}; //!< Processing time of the node + std::string comment_; //!< Comment for the node + std::weak_ptr parent_node_; //!< Weak pointer to the parent node + std::vector> + child_nodes_; //!< Vector of shared pointers to the child nodes +}; + +using ProcessingTimeDetail = + autoware_internal_debug_msgs::msg::ProcessingTimeTree; //!< Alias for the ProcessingTimeTree + //!< message + +/** + * @brief Class for tracking and reporting the processing time of various functions + */ +class TimeKeeper +{ +public: + template + explicit TimeKeeper(Reporters... reporters) : current_time_node_(nullptr), root_node_(nullptr) + { + reporters_.reserve(sizeof...(Reporters)); + (add_reporter(reporters), ...); + } + + /** + * @brief Add a reporter to output processing times to an ostream + * + * @param os Pointer to the ostream object + */ + void add_reporter(std::ostream * os); + + /** + * @brief Add a reporter to publish processing times to an rclcpp publisher + * + * @param publisher Shared pointer to the rclcpp publisher + */ + void add_reporter(rclcpp::Publisher::SharedPtr publisher); + + /** + * @brief Start tracking the processing time of a function + * + * @param func_name Name of the function to be tracked + */ + void start_track(const std::string & func_name); + + /** + * @brief End tracking the processing time of a function + * + * @param func_name Name of the function to end tracking + */ + void end_track(const std::string & func_name); + + /** + * @brief Comment the current time node + * + * @param comment Comment to be added to the current time node + */ + void comment(const std::string & comment); + +private: + /** + * @brief Report the processing times to all registered reporters + */ + void report(); + + std::shared_ptr + current_time_node_; //!< Shared pointer to the current time node + std::shared_ptr root_node_; //!< Shared pointer to the root time node + std::thread::id root_node_thread_id_; //!< ID of the thread that started the tracking + autoware_utils::StopWatch< + std::chrono::milliseconds, std::chrono::microseconds, std::chrono::steady_clock> + stop_watch_; //!< StopWatch object for tracking the processing time + + std::vector &)>> + reporters_; //!< Vector of functions for reporting the processing times +}; + +/** + * @brief Class for automatically tracking the processing time of a function within a scope + */ +class ScopedTimeTrack +{ +public: + /** + * @brief Construct a new ScopedTimeTrack object + * + * @param func_name Name of the function to be tracked + * @param time_keeper Reference to the TimeKeeper object + */ + ScopedTimeTrack(const std::string & func_name, TimeKeeper & time_keeper); + + ScopedTimeTrack(const ScopedTimeTrack &) = delete; + ScopedTimeTrack & operator=(const ScopedTimeTrack &) = delete; + ScopedTimeTrack(ScopedTimeTrack &&) = delete; + ScopedTimeTrack & operator=(ScopedTimeTrack &&) = delete; + + /** + * @brief Destroy the ScopedTimeTrack object, ending the tracking of the function + */ + ~ScopedTimeTrack(); + +private: + const std::string func_name_; //!< Name of the function being tracked + TimeKeeper & time_keeper_; //!< Reference to the TimeKeeper object +}; + +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__SYSTEM__TIME_KEEPER_HPP_ diff --git a/autoware_utils/include/autoware_utils/transform/transforms.hpp b/autoware_utils/include/autoware_utils/transform/transforms.hpp new file mode 100644 index 0000000..042d67e --- /dev/null +++ b/autoware_utils/include/autoware_utils/transform/transforms.hpp @@ -0,0 +1,51 @@ +// Copyright 2020 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#ifndef AUTOWARE_UTILS__TRANSFORM__TRANSFORMS_HPP_ +#define AUTOWARE_UTILS__TRANSFORM__TRANSFORMS_HPP_ + +#include +#include + +#include +#include + +namespace autoware_utils +{ +template +void transform_pointcloud( + const pcl::PointCloud & cloud_in, pcl::PointCloud & cloud_out, + const Eigen::Matrix & transform) +{ + if (cloud_in.empty() || cloud_in.width == 0) { + RCLCPP_WARN(rclcpp::get_logger("transform_pointcloud"), "input point cloud is empty!"); + } else { + pcl::transformPointCloud(cloud_in, cloud_out, transform); + } +} + +template +void transform_pointcloud( + const pcl::PointCloud & cloud_in, pcl::PointCloud & cloud_out, + const Eigen::Affine3f & transform) +{ + if (cloud_in.empty() || cloud_in.width == 0) { + RCLCPP_WARN(rclcpp::get_logger("transform_pointcloud"), "input point cloud is empty!"); + } else { + pcl::transformPointCloud(cloud_in, cloud_out, transform); + } +} +} // namespace autoware_utils + +#endif // AUTOWARE_UTILS__TRANSFORM__TRANSFORMS_HPP_ diff --git a/autoware_utils/package.xml b/autoware_utils/package.xml index 4678e1d..8ef7cf8 100644 --- a/autoware_utils/package.xml +++ b/autoware_utils/package.xml @@ -4,6 +4,7 @@ autoware_utils 1.0.0 The autoware_utils package + Jian Kang Ryohsuke Mitsudome Esteve Fernandez Yutaka Kondo @@ -12,12 +13,29 @@ ament_cmake_auto autoware_cmake + autoware_internal_debug_msgs + autoware_internal_msgs + autoware_internal_planning_msgs + autoware_perception_msgs + autoware_planning_msgs + autoware_vehicle_msgs builtin_interfaces + diagnostic_msgs + geometry_msgs libboost-system-dev + logging_demo + pcl_conversions + pcl_ros rclcpp + tf2 + tf2_eigen + tf2_geometry_msgs unique_identifier_msgs + visualization_msgs ament_cmake_ros + ament_lint_auto + autoware_lint_common ament_cmake diff --git a/autoware_utils/src/geometry/alt_geometry.cpp b/autoware_utils/src/geometry/alt_geometry.cpp new file mode 100644 index 0000000..7c5738e --- /dev/null +++ b/autoware_utils/src/geometry/alt_geometry.cpp @@ -0,0 +1,647 @@ +// Copyright 2023-2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/geometry/alt_geometry.hpp" + +#include +#include +#include +#include + +namespace autoware_utils +{ +// Alternatives for Boost.Geometry ---------------------------------------------------------------- +namespace alt +{ +std::optional Polygon2d::create( + const PointList2d & outer, const std::vector & inners) noexcept +{ + Polygon2d poly(outer, inners); + correct(poly); + + if (poly.outer().size() < 4) { + return std::nullopt; + } + + for (const auto & inner : poly.inners()) { + if (inner.size() < 4) { + return std::nullopt; + } + } + + return poly; +} + +std::optional Polygon2d::create( + PointList2d && outer, std::vector && inners) noexcept +{ + Polygon2d poly(std::move(outer), std::move(inners)); + correct(poly); + + if (poly.outer().size() < 4) { + return std::nullopt; + } + + for (const auto & inner : poly.inners()) { + if (inner.size() < 4) { + return std::nullopt; + } + } + + return poly; +} + +std::optional Polygon2d::create(const autoware_utils::Polygon2d & polygon) noexcept +{ + PointList2d outer; + for (const auto & point : polygon.outer()) { + outer.push_back(Point2d(point)); + } + + std::vector inners; + for (const auto & inner : polygon.inners()) { + PointList2d _inner; + if (inner.empty()) { + continue; + } + for (const auto & point : inner) { + _inner.push_back(Point2d(point)); + } + inners.push_back(_inner); + } + + return Polygon2d::create(outer, inners); +} + +autoware_utils::Polygon2d Polygon2d::to_boost() const +{ + autoware_utils::Polygon2d polygon; + + for (const auto & point : outer_) { + polygon.outer().emplace_back(point.x(), point.y()); + } + + for (const auto & inner : inners_) { + autoware_utils::LinearRing2d _inner; + for (const auto & point : inner) { + _inner.emplace_back(point.x(), point.y()); + } + polygon.inners().push_back(_inner); + } + + return polygon; +} + +std::optional ConvexPolygon2d::create(const PointList2d & vertices) noexcept +{ + ConvexPolygon2d poly(vertices); + correct(poly); + + if (poly.vertices().size() < 4) { + return std::nullopt; + } + + if (!is_convex(poly)) { + return std::nullopt; + } + + return poly; +} + +std::optional ConvexPolygon2d::create(PointList2d && vertices) noexcept +{ + ConvexPolygon2d poly(std::move(vertices)); + correct(poly); + + if (poly.vertices().size() < 4) { + return std::nullopt; + } + + if (!is_convex(poly)) { + return std::nullopt; + } + + return poly; +} + +std::optional ConvexPolygon2d::create( + const autoware_utils::Polygon2d & polygon) noexcept +{ + PointList2d vertices; + for (const auto & point : polygon.outer()) { + vertices.push_back(Point2d(point)); + } + + return ConvexPolygon2d::create(vertices); +} +} // namespace alt + +double area(const alt::ConvexPolygon2d & poly) +{ + const auto & vertices = poly.vertices(); + + double area = 0.; + for (auto it = std::next(vertices.cbegin()); it != std::prev(vertices.cend(), 2); ++it) { + area += (*std::next(it) - vertices.front()).cross(*it - vertices.front()) / 2; + } + + return area; +} + +std::optional convex_hull(const alt::Points2d & points) +{ + if (points.size() < 3) { + return std::nullopt; + } + + // QuickHull algorithm + + const auto p_minmax_itr = std::minmax_element( + points.begin(), points.end(), [](const auto & a, const auto & b) { return a.x() < b.x(); }); + const auto & p_min = *p_minmax_itr.first; + const auto & p_max = *p_minmax_itr.second; + + alt::PointList2d vertices; + + if (points.size() == 3) { + std::rotate_copy( + points.begin(), p_minmax_itr.first, points.end(), std::back_inserter(vertices)); + } else { + auto make_hull = [&vertices]( + auto self, const alt::Point2d & p1, const alt::Point2d & p2, + const alt::Points2d & points) { + if (points.empty()) { + return; + } + + const auto & farthest = *find_farthest(points, p1, p2); + + alt::Points2d subset1, subset2; + for (const auto & point : points) { + if (is_above(point, p1, farthest)) { + subset1.push_back(point); + } else if (is_above(point, farthest, p2)) { + subset2.push_back(point); + } + } + + self(self, p1, farthest, subset1); + vertices.push_back(farthest); + self(self, farthest, p2, subset2); + }; + + alt::Points2d above_points, below_points; + for (const auto & point : points) { + if (is_above(point, p_min, p_max)) { + above_points.push_back(point); + } else if (is_above(point, p_max, p_min)) { + below_points.push_back(point); + } + } + + vertices.push_back(p_min); + make_hull(make_hull, p_min, p_max, above_points); + vertices.push_back(p_max); + make_hull(make_hull, p_max, p_min, below_points); + } + + auto hull = alt::ConvexPolygon2d::create(vertices); + if (!hull) { + return std::nullopt; + } + + return hull; +} + +void correct(alt::Polygon2d & poly) +{ + auto correct_vertices = [](alt::PointList2d & vertices) { + // remove adjacent duplicate points + const auto it = std::unique( + vertices.begin(), vertices.end(), + [](const auto & a, const auto & b) { return equals(a, b); }); + vertices.erase(it, vertices.end()); + + if (!equals(vertices.front(), vertices.back())) { + vertices.push_back(vertices.front()); + } + + if (!is_clockwise(vertices)) { + std::reverse(std::next(vertices.begin()), std::prev(vertices.end())); + } + }; + + correct_vertices(poly.outer()); + for (auto & inner : poly.inners()) { + correct_vertices(inner); + } +} + +bool covered_by(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) +{ + constexpr double epsilon = 1e-6; + + const auto & vertices = poly.vertices(); + std::size_t winding_number = 0; + + const auto [y_min_vertex, y_max_vertex] = std::minmax_element( + vertices.begin(), std::prev(vertices.end()), + [](const auto & a, const auto & b) { return a.y() < b.y(); }); + if (point.y() < y_min_vertex->y() || point.y() > y_max_vertex->y()) { + return false; + } + + double cross; + for (auto it = vertices.cbegin(); it != std::prev(vertices.cend()); ++it) { + const auto & p1 = *it; + const auto & p2 = *std::next(it); + + if (p1.y() <= point.y() && p2.y() >= point.y()) { // upward edge + cross = (p2 - p1).cross(point - p1); + if (cross > 0) { // point is to the left of edge + winding_number++; + continue; + } + } else if (p1.y() >= point.y() && p2.y() <= point.y()) { // downward edge + cross = (p2 - p1).cross(point - p1); + if (cross < 0) { // point is to the left of edge + winding_number--; + continue; + } + } else { + continue; + } + + if (std::abs(cross) < epsilon) { // point is on edge + return true; + } + } + + return winding_number != 0; +} + +bool disjoint(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2) +{ + if (equals(poly1, poly2)) { + return false; + } + + if (intersects(poly1, poly2)) { + return false; + } + + for (const auto & vertex : poly1.vertices()) { + if (touches(vertex, poly2)) { + return false; + } + } + + return true; +} + +double distance( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end) +{ + constexpr double epsilon = 1e-3; + + const auto seg_vec = seg_end - seg_start; + const auto point_vec = point - seg_start; + + const double seg_vec_norm = seg_vec.norm(); + const double seg_point_dot = seg_vec.dot(point_vec); + + if (seg_vec_norm < epsilon || seg_point_dot < 0) { + return point_vec.norm(); + } else if (seg_point_dot > std::pow(seg_vec_norm, 2)) { + return (point - seg_end).norm(); + } else { + return std::abs(seg_vec.cross(point_vec)) / seg_vec_norm; + } +} + +double distance(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) +{ + if (covered_by(point, poly)) { + return 0.0; + } + + // TODO(mitukou1109): Use plane sweep method to improve performance? + const auto & vertices = poly.vertices(); + double min_distance = std::numeric_limits::max(); + for (auto it = vertices.cbegin(); it != std::prev(vertices.cend()); ++it) { + min_distance = std::min(min_distance, distance(point, *it, *std::next(it))); + } + + return min_distance; +} + +std::optional envelope(const alt::Polygon2d & poly) +{ + const auto [x_min_vertex, x_max_vertex] = std::minmax_element( + poly.outer().begin(), std::prev(poly.outer().end()), + [](const auto & a, const auto & b) { return a.x() < b.x(); }); + + const auto [y_min_vertex, y_max_vertex] = std::minmax_element( + poly.outer().begin(), std::prev(poly.outer().end()), + [](const auto & a, const auto & b) { return a.y() < b.y(); }); + + return alt::ConvexPolygon2d::create(alt::PointList2d{ + {x_min_vertex->x(), y_min_vertex->y()}, + {x_min_vertex->x(), y_max_vertex->y()}, + {x_max_vertex->x(), y_max_vertex->y()}, + {x_max_vertex->x(), y_min_vertex->y()}}); +} + +bool equals(const alt::Point2d & point1, const alt::Point2d & point2) +{ + constexpr double epsilon = 1e-3; + return std::abs(point1.x() - point2.x()) < epsilon && std::abs(point1.y() - point2.y()) < epsilon; +} + +bool equals(const alt::Polygon2d & poly1, const alt::Polygon2d & poly2) +{ + const auto outer_equals = std::equal( + poly1.outer().begin(), std::prev(poly1.outer().end()), poly2.outer().begin(), + std::prev(poly2.outer().end()), [](const auto & a, const auto & b) { return equals(a, b); }); + + auto inners_equal = true; + for (const auto & inner1 : poly1.inners()) { + inners_equal &= + std::any_of(poly2.inners().begin(), poly2.inners().end(), [&](const auto & inner2) { + return std::equal( + inner1.begin(), std::prev(inner1.end()), inner2.begin(), std::prev(inner2.end()), + [](const auto & a, const auto & b) { return equals(a, b); }); + }); + } + + return outer_equals && inners_equal; +} + +alt::Points2d::const_iterator find_farthest( + const alt::Points2d & points, const alt::Point2d & seg_start, const alt::Point2d & seg_end) +{ + const auto seg_vec = seg_end - seg_start; + return std::max_element(points.begin(), points.end(), [&](const auto & a, const auto & b) { + return std::abs(seg_vec.cross(a - seg_start)) < std::abs(seg_vec.cross(b - seg_start)); + }); +} + +bool intersects( + const alt::Point2d & seg1_start, const alt::Point2d & seg1_end, const alt::Point2d & seg2_start, + const alt::Point2d & seg2_end) +{ + constexpr double epsilon = 1e-6; + + const auto v1 = seg1_end - seg1_start; + const auto v2 = seg2_end - seg2_start; + + const auto det = v1.cross(v2); + if (std::abs(det) < epsilon) { + return false; + } + + const auto v12 = seg2_end - seg1_end; + const double t = v2.cross(v12) / det; + const double s = v1.cross(v12) / det; + if (t < 0 || 1 < t || s < 0 || 1 < s) { + return false; + } + + return true; +} + +bool intersects(const alt::ConvexPolygon2d & poly1, const alt::ConvexPolygon2d & poly2) +{ + if (equals(poly1, poly2)) { + return true; + } + + // GJK algorithm + + auto find_support_vector = []( + const alt::ConvexPolygon2d & poly1, + const alt::ConvexPolygon2d & poly2, + const alt::Vector2d & direction) { + auto find_farthest_vertex = + [](const alt::ConvexPolygon2d & poly, const alt::Vector2d & direction) { + return std::max_element( + poly.vertices().begin(), std::prev(poly.vertices().end()), + [&](const auto & a, const auto & b) { return direction.dot(a) <= direction.dot(b); }); + }; + return *find_farthest_vertex(poly1, direction) - *find_farthest_vertex(poly2, -direction); + }; + + alt::Vector2d direction = {1.0, 0.0}; + auto a = find_support_vector(poly1, poly2, direction); + direction = -a; + auto b = find_support_vector(poly1, poly2, direction); + if (b.dot(direction) <= 0.0) { + return false; + } + + direction = (b - a).vector_triple(-a, b - a); + while (true) { + auto c = find_support_vector(poly1, poly2, direction); + if (c.dot(direction) <= 0.0) { + return false; + } + + auto n_ca = (b - c).vector_triple(a - c, a - c); + if (n_ca.dot(-c) > 0.0) { + b = c; + direction = n_ca; + } else { + auto n_cb = (a - c).vector_triple(b - c, b - c); + if (n_cb.dot(-c) > 0.0) { + a = c; + direction = n_cb; + } else { + break; + } + } + } + + return true; +} + +bool is_above( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end) +{ + return (seg_end - seg_start).cross(point - seg_start) > 0; +} + +bool is_clockwise(const alt::PointList2d & vertices) +{ + double sum = 0.; + for (auto it = vertices.cbegin(); it != std::prev(vertices.cend()); ++it) { + sum += (std::next(it)->x() - it->x()) * (std::next(it)->y() + it->y()); + } + + return sum > 0; +} + +bool is_convex(const alt::Polygon2d & poly) +{ + constexpr double epsilon = 1e-6; + + if (!poly.inners().empty()) { + return false; + } + + const auto & outer = poly.outer(); + + for (auto it = std::next(outer.cbegin()); it != std::prev(outer.cend()); ++it) { + const auto & p1 = *--it; + const auto & p2 = *it; + const auto & p3 = *++it; + + if ((p2 - p1).cross(p3 - p2) > epsilon) { + return false; + } + } + + return true; +} + +alt::PointList2d simplify(const alt::PointList2d & line, const double max_distance) +{ + if (line.size() < 3) { + return line; + } + + alt::Points2d pending(std::next(line.begin()), std::prev(line.end())); + alt::PointList2d simplified; + + // Douglas-Peucker algorithm + + auto douglas_peucker = [&max_distance, &pending, &simplified]( + auto self, const alt::Point2d & seg_start, + const alt::Point2d & seg_end) { + if (pending.empty()) { + return; + } + + const auto farthest_itr = find_farthest(pending, seg_start, seg_end); + const auto farthest = *farthest_itr; + pending.erase(farthest_itr); + + if (distance(farthest, seg_start, seg_end) <= max_distance) { + return; + } + + self(self, seg_start, farthest); + simplified.push_back(farthest); + self(self, farthest, seg_end); + }; + + simplified.push_back(line.front()); + douglas_peucker(douglas_peucker, line.front(), line.back()); + simplified.push_back(line.back()); + + return simplified; +} + +bool touches( + const alt::Point2d & point, const alt::Point2d & seg_start, const alt::Point2d & seg_end) +{ + constexpr double epsilon = 1e-6; + + // if the cross product of the vectors from the start point and the end point to the point is 0 + // and the vectors opposite each other, the point is on the segment + const auto start_vec = point - seg_start; + const auto end_vec = point - seg_end; + return std::abs(start_vec.cross(end_vec)) < epsilon && start_vec.dot(end_vec) <= 0; +} + +bool touches(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) +{ + const auto & vertices = poly.vertices(); + + const auto [y_min_vertex, y_max_vertex] = std::minmax_element( + vertices.begin(), std::prev(vertices.end()), + [](const auto & a, const auto & b) { return a.y() < b.y(); }); + if (point.y() < y_min_vertex->y() || point.y() > y_max_vertex->y()) { + return false; + } + + for (auto it = vertices.cbegin(); it != std::prev(vertices.cend()); ++it) { + // check if the point is on each edge of the polygon + if (touches(point, *it, *std::next(it))) { + return true; + } + } + + return false; +} + +bool within(const alt::Point2d & point, const alt::ConvexPolygon2d & poly) +{ + constexpr double epsilon = 1e-6; + + const auto & vertices = poly.vertices(); + int64_t winding_number = 0; + + const auto [y_min_vertex, y_max_vertex] = std::minmax_element( + vertices.begin(), std::prev(vertices.end()), + [](const auto & a, const auto & b) { return a.y() < b.y(); }); + if (point.y() <= y_min_vertex->y() || point.y() >= y_max_vertex->y()) { + return false; + } + + double cross; + for (auto it = vertices.cbegin(); it != std::prev(vertices.cend()); ++it) { + const auto & p1 = *it; + const auto & p2 = *std::next(it); + + if (p1.y() < point.y() && p2.y() > point.y()) { // upward edge + cross = (p2 - p1).cross(point - p1); + if (cross > 0) { // point is to the left of edge + winding_number++; + continue; + } + } else if (p1.y() > point.y() && p2.y() < point.y()) { // downward edge + cross = (p2 - p1).cross(point - p1); + if (cross < 0) { // point is to the left of edge + winding_number--; + continue; + } + } else { + continue; + } + + if (std::abs(cross) < epsilon) { // point is on edge + return false; + } + } + + return winding_number != 0; +} + +bool within( + const alt::ConvexPolygon2d & poly_contained, const alt::ConvexPolygon2d & poly_containing) +{ + if (equals(poly_contained, poly_containing)) { + return true; + } + + // check if all points of poly_contained are within poly_containing + for (const auto & vertex : poly_contained.vertices()) { + if (!within(vertex, poly_containing)) { + return false; + } + } + + return true; +} +} // namespace autoware_utils diff --git a/autoware_utils/src/geometry/boost_polygon_utils.cpp b/autoware_utils/src/geometry/boost_polygon_utils.cpp new file mode 100644 index 0000000..4e4bbcc --- /dev/null +++ b/autoware_utils/src/geometry/boost_polygon_utils.cpp @@ -0,0 +1,267 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/geometry/boost_polygon_utils.hpp" + +#include "autoware_utils/geometry/geometry.hpp" + +#include + +#include + +namespace +{ +namespace bg = boost::geometry; +using autoware_utils::Point2d; +using autoware_utils::Polygon2d; + +void append_point_to_polygon(Polygon2d & polygon, const geometry_msgs::msg::Point & geom_point) +{ + Point2d point; + point.x() = geom_point.x; + point.y() = geom_point.y; + + bg::append(polygon.outer(), point); +} + +void append_point_to_polygon(Polygon2d & polygon, const Point2d & point) +{ + bg::append(polygon.outer(), point); +} + +/* + * NOTE: Area is negative when footprint.points is clock wise. + * Area is positive when footprint.points is anti clock wise. + */ +double get_polygon_area(const geometry_msgs::msg::Polygon & footprint) +{ + double area = 0.0; + + for (size_t i = 0; i < footprint.points.size(); ++i) { + size_t j = (i + 1) % footprint.points.size(); + area += 0.5 * (footprint.points.at(i).x * footprint.points.at(j).y - + footprint.points.at(j).x * footprint.points.at(i).y); + } + + return area; +} + +double get_rectangle_area(const geometry_msgs::msg::Vector3 & dimensions) +{ + return static_cast(dimensions.x * dimensions.y); +} + +double get_circle_area(const geometry_msgs::msg::Vector3 & dimensions) +{ + return static_cast((dimensions.x / 2.0) * (dimensions.x / 2.0) * M_PI); +} +} // namespace + +namespace autoware_utils +{ +bool is_clockwise(const Polygon2d & polygon) +{ + const int n = polygon.outer().size(); + const double x_offset = polygon.outer().at(0).x(); + const double y_offset = polygon.outer().at(0).y(); + double sum = 0.0; + for (std::size_t i = 0; i < polygon.outer().size(); ++i) { + sum += + (polygon.outer().at(i).x() - x_offset) * (polygon.outer().at((i + 1) % n).y() - y_offset) - + (polygon.outer().at(i).y() - y_offset) * (polygon.outer().at((i + 1) % n).x() - x_offset); + } + + return sum < 0.0; +} + +Polygon2d inverse_clockwise(const Polygon2d & polygon) +{ + auto output_polygon = polygon; + boost::geometry::reverse(output_polygon); + return output_polygon; +} + +geometry_msgs::msg::Polygon rotate_polygon( + const geometry_msgs::msg::Polygon & polygon, const double & angle) +{ + const double cos = std::cos(angle); + const double sin = std::sin(angle); + geometry_msgs::msg::Polygon rotated_polygon; + for (const auto & point : polygon.points) { + auto rotated_point = point; + rotated_point.x = cos * point.x - sin * point.y; + rotated_point.y = sin * point.x + cos * point.y; + rotated_polygon.points.push_back(rotated_point); + } + return rotated_polygon; +} + +Polygon2d rotate_polygon(const Polygon2d & polygon, const double angle) +{ + Polygon2d rotated_polygon; + const boost::geometry::strategy::transform::rotate_transformer< + boost::geometry::radian, double, 2, 2> + rotation(-angle); + boost::geometry::transform(polygon, rotated_polygon, rotation); + return rotated_polygon; +} + +Polygon2d to_polygon2d( + const geometry_msgs::msg::Pose & pose, const autoware_perception_msgs::msg::Shape & shape) +{ + Polygon2d polygon; + + if (shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { + const auto point0 = autoware_utils::calc_offset_pose( + pose, shape.dimensions.x / 2.0, shape.dimensions.y / 2.0, 0.0) + .position; + const auto point1 = autoware_utils::calc_offset_pose( + pose, -shape.dimensions.x / 2.0, shape.dimensions.y / 2.0, 0.0) + .position; + const auto point2 = autoware_utils::calc_offset_pose( + pose, -shape.dimensions.x / 2.0, -shape.dimensions.y / 2.0, 0.0) + .position; + const auto point3 = autoware_utils::calc_offset_pose( + pose, shape.dimensions.x / 2.0, -shape.dimensions.y / 2.0, 0.0) + .position; + + append_point_to_polygon(polygon, point0); + append_point_to_polygon(polygon, point1); + append_point_to_polygon(polygon, point2); + append_point_to_polygon(polygon, point3); + } else if (shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { + const double radius = shape.dimensions.x / 2.0; + constexpr int circle_discrete_num = 6; + for (int i = 0; i < circle_discrete_num; ++i) { + geometry_msgs::msg::Point point; + point.x = std::cos( + (static_cast(i) / static_cast(circle_discrete_num)) * 2.0 * M_PI + + M_PI / static_cast(circle_discrete_num)) * + radius + + pose.position.x; + point.y = std::sin( + (static_cast(i) / static_cast(circle_discrete_num)) * 2.0 * M_PI + + M_PI / static_cast(circle_discrete_num)) * + radius + + pose.position.y; + append_point_to_polygon(polygon, point); + } + } else if (shape.type == autoware_perception_msgs::msg::Shape::POLYGON) { + const double poly_yaw = tf2::getYaw(pose.orientation); + const auto rotated_footprint = rotate_polygon(shape.footprint, poly_yaw); + for (const auto rel_point : rotated_footprint.points) { + geometry_msgs::msg::Point abs_point; + abs_point.x = pose.position.x + rel_point.x; + abs_point.y = pose.position.y + rel_point.y; + + append_point_to_polygon(polygon, abs_point); + } + } else { + throw std::logic_error("The shape type is not supported in autoware_utils."); + } + + // NOTE: push back the first point in order to close polygon + if (!polygon.outer().empty()) { + append_point_to_polygon(polygon, polygon.outer().front()); + } + + return is_clockwise(polygon) ? polygon : inverse_clockwise(polygon); +} + +autoware_utils::Polygon2d to_polygon2d(const autoware_perception_msgs::msg::DetectedObject & object) +{ + return autoware_utils::to_polygon2d(object.kinematics.pose_with_covariance.pose, object.shape); +} + +autoware_utils::Polygon2d to_polygon2d(const autoware_perception_msgs::msg::TrackedObject & object) +{ + return autoware_utils::to_polygon2d(object.kinematics.pose_with_covariance.pose, object.shape); +} + +autoware_utils::Polygon2d to_polygon2d( + const autoware_perception_msgs::msg::PredictedObject & object) +{ + return autoware_utils::to_polygon2d( + object.kinematics.initial_pose_with_covariance.pose, object.shape); +} + +Polygon2d to_footprint( + const geometry_msgs::msg::Pose & base_link_pose, const double base_to_front, + const double base_to_rear, const double width) +{ + Polygon2d polygon; + const auto point0 = + autoware_utils::calc_offset_pose(base_link_pose, base_to_front, width / 2.0, 0.0).position; + const auto point1 = + autoware_utils::calc_offset_pose(base_link_pose, base_to_front, -width / 2.0, 0.0).position; + const auto point2 = + autoware_utils::calc_offset_pose(base_link_pose, -base_to_rear, -width / 2.0, 0.0).position; + const auto point3 = + autoware_utils::calc_offset_pose(base_link_pose, -base_to_rear, width / 2.0, 0.0).position; + + append_point_to_polygon(polygon, point0); + append_point_to_polygon(polygon, point1); + append_point_to_polygon(polygon, point2); + append_point_to_polygon(polygon, point3); + append_point_to_polygon(polygon, point0); + + return is_clockwise(polygon) ? polygon : inverse_clockwise(polygon); +} + +double get_area(const autoware_perception_msgs::msg::Shape & shape) +{ + if (shape.type == autoware_perception_msgs::msg::Shape::BOUNDING_BOX) { + return get_rectangle_area(shape.dimensions); + } else if (shape.type == autoware_perception_msgs::msg::Shape::CYLINDER) { + return get_circle_area(shape.dimensions); + } else if (shape.type == autoware_perception_msgs::msg::Shape::POLYGON) { + return get_polygon_area(shape.footprint); + } + + throw std::logic_error("The shape type is not supported in autoware_utils."); +} + +// NOTE: The number of vertices on the expanded polygon by boost::geometry::buffer +// is larger than the original one. +// This function fixes the issue. +Polygon2d expand_polygon(const Polygon2d & input_polygon, const double offset) +{ + // NOTE: input_polygon is supposed to have a duplicated point. + const size_t num_points = input_polygon.outer().size() - 1; + + Polygon2d expanded_polygon; + for (size_t i = 0; i < num_points; ++i) { + const auto & curr_p = input_polygon.outer().at(i); + const auto & next_p = input_polygon.outer().at(i + 1); + const auto & prev_p = + i == 0 ? input_polygon.outer().at(num_points - 1) : input_polygon.outer().at(i - 1); + + Eigen::Vector2d current_to_next(next_p.x() - curr_p.x(), next_p.y() - curr_p.y()); + Eigen::Vector2d current_to_prev(prev_p.x() - curr_p.x(), prev_p.y() - curr_p.y()); + current_to_next.normalize(); + current_to_prev.normalize(); + + const Eigen::Vector2d offset_vector = (-current_to_next - current_to_prev).normalized(); + const double theta = std::acos(offset_vector.dot(current_to_next)); + const double scaled_offset = offset / std::sin(theta); + const Eigen::Vector2d offset_point = + Eigen::Vector2d(curr_p.x(), curr_p.y()) + offset_vector * scaled_offset; + + expanded_polygon.outer().push_back(Point2d(offset_point.x(), offset_point.y())); + } + + boost::geometry::correct(expanded_polygon); + return expanded_polygon; +} +} // namespace autoware_utils diff --git a/autoware_utils/src/geometry/ear_clipping.cpp b/autoware_utils/src/geometry/ear_clipping.cpp new file mode 100644 index 0000000..8bf8e32 --- /dev/null +++ b/autoware_utils/src/geometry/ear_clipping.cpp @@ -0,0 +1,634 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/geometry/ear_clipping.hpp" + +#include +#include +#include + +namespace autoware_utils +{ + +void remove_point(const std::size_t p_index, std::vector & points) +{ + std::size_t prev_index = points[p_index].prev_index.value(); + std::size_t next_index = points[p_index].next_index.value(); + + points[prev_index].next_index = next_index; + points[next_index].prev_index = prev_index; +} + +std::size_t get_leftmost(const std::size_t start_idx, const std::vector & points) +{ + std::optional p_idx = points[start_idx].next_index; + std::size_t left_most_idx = start_idx; + + while (p_idx.has_value() && p_idx.value() != start_idx) { + if ( + points[p_idx.value()].x() < points[left_most_idx].x() || + (points[p_idx.value()].x() == points[left_most_idx].x() && + points[p_idx.value()].y() < points[left_most_idx].y())) { + left_most_idx = p_idx.value(); + } + p_idx = points[p_idx.value()].next_index; + } + + return left_most_idx; +} + +bool point_in_triangle( + const double ax, const double ay, const double bx, const double by, const double cx, + const double cy, const double px, const double py) +{ + return (cx - px) * (ay - py) >= (ax - px) * (cy - py) && + (ax - px) * (by - py) >= (bx - px) * (ay - py) && + (bx - px) * (cy - py) >= (cx - px) * (by - py); +} + +double area( + const std::vector & points, const std::size_t p_idx, const std::size_t q_idx, + const std::size_t r_idx) +{ + const LinkedPoint & p = points[p_idx]; + const LinkedPoint & q = points[q_idx]; + const LinkedPoint & r = points[r_idx]; + return (q.y() - p.y()) * (r.x() - q.x()) - (q.x() - p.x()) * (r.y() - q.y()); +} + +bool middle_inside( + const std::size_t a_idx, const std::size_t b_idx, const std::vector & points) +{ + std::optional p_idx = a_idx; + bool inside = false; + double px = (points[a_idx].x() + points[b_idx].x()) / 2; + double py = (points[a_idx].y() + points[b_idx].y()) / 2; + std::size_t start_idx = a_idx; + + while (p_idx.has_value()) { + std::size_t current_idx = p_idx.value(); + std::size_t next_idx = points[current_idx].next_index.value(); + + if ( + ((points[current_idx].y() > py) != (points[next_idx].y() > py)) && + points[next_idx].y() != points[current_idx].y() && + (px < (points[next_idx].x() - points[current_idx].x()) * (py - points[current_idx].y()) / + (points[next_idx].y() - points[current_idx].y()) + + points[current_idx].x())) { + inside = !inside; + } + + if (next_idx == start_idx) { + break; // Break the loop if we have cycled back to the start index + } + + p_idx = next_idx; + } + + return inside; +} + +bool equals( + const std::size_t p1_idx, const std::size_t p2_idx, const std::vector & points) +{ + return points[p1_idx].x() == points[p2_idx].x() && points[p1_idx].y() == points[p2_idx].y(); +} + +int sign(const double val) +{ + return (0.0 < val) - (val < 0.0); +} + +bool on_segment( + const std::vector & points, const std::size_t p_idx, const std::size_t q_idx, + const std::size_t r_idx) +{ + const LinkedPoint & p = points[p_idx]; + const LinkedPoint & q = points[q_idx]; + const LinkedPoint & r = points[r_idx]; + return q.x() <= std::max(p.x(), r.x()) && q.x() >= std::min(p.x(), r.x()) && + q.y() <= std::max(p.y(), r.y()) && q.y() >= std::min(p.y(), r.y()); +} + +bool locally_inside( + const std::size_t a_idx, const std::size_t b_idx, const std::vector & points) +{ + const auto & prev_idx = points[a_idx].prev_index; + const auto & next_idx = points[a_idx].next_index; + + if (!prev_idx.has_value() || !next_idx.has_value()) { + return false; + } + + double area_prev = area(points, prev_idx.value(), a_idx, next_idx.value()); + double area_a_b_next = area(points, a_idx, b_idx, next_idx.value()); + double area_a_prev_b = area(points, a_idx, prev_idx.value(), b_idx); + double area_a_b_prev = area(points, a_idx, b_idx, prev_idx.value()); + double area_a_next_b = area(points, a_idx, next_idx.value(), b_idx); + + return area_prev < 0 ? area_a_b_next >= 0 && area_a_prev_b >= 0 + : area_a_b_prev < 0 || area_a_next_b < 0; +} + +bool intersects( + const std::size_t p1_idx, const std::size_t q1_idx, const std::size_t p2_idx, + const std::size_t q2_idx, const std::vector & points) +{ + int o1 = sign(area(points, p1_idx, q1_idx, p2_idx)); + int o2 = sign(area(points, p1_idx, q1_idx, q2_idx)); + int o3 = sign(area(points, p2_idx, q2_idx, p1_idx)); + int o4 = sign(area(points, p2_idx, q2_idx, q1_idx)); + + if (o1 != o2 && o3 != o4) return true; + + if (o1 == 0 && on_segment(points, p1_idx, p2_idx, q1_idx)) return true; + if (o2 == 0 && on_segment(points, p1_idx, q2_idx, q1_idx)) return true; + if (o3 == 0 && on_segment(points, p2_idx, p1_idx, q2_idx)) return true; + if (o4 == 0 && on_segment(points, p2_idx, q1_idx, q2_idx)) return true; + + return false; +} + +bool intersects_polygon( + const std::vector & points, const std::size_t a_idx, const std::size_t b_idx) +{ + std::size_t p_idx = a_idx; + std::optional p_next_opt = points[p_idx].next_index; + + while (p_next_opt.has_value() && p_next_opt.value() != a_idx) { + std::size_t p_next_idx = p_next_opt.value(); + + if (p_idx != a_idx && p_next_idx != a_idx && p_idx != b_idx && p_next_idx != b_idx) { + if (intersects(p_idx, p_next_idx, a_idx, b_idx, points)) { + return true; + } + } + + p_idx = p_next_idx; + p_next_opt = points[p_idx].next_index; + } + + return false; +} + +bool is_valid_diagonal( + const std::size_t a_idx, const std::size_t b_idx, const std::vector & points) +{ + if ( + !points[a_idx].next_index.has_value() || !points[a_idx].prev_index.has_value() || + !points[b_idx].next_index.has_value() || !points[b_idx].prev_index.has_value()) { + return false; + } + + std::size_t a_next_idx = points[a_idx].next_index.value(); + std::size_t a_prev_idx = points[a_idx].prev_index.value(); + std::size_t b_next_idx = points[b_idx].next_index.value(); + std::size_t b_prev_idx = points[b_idx].prev_index.value(); + + if (a_next_idx == b_idx || a_prev_idx == b_idx || intersects_polygon(points, a_idx, b_idx)) { + return false; + } + + bool is_locally_inside_ab = locally_inside(a_idx, b_idx, points); + bool is_locally_inside_ba = locally_inside(b_idx, a_idx, points); + bool is_middle_inside = middle_inside(a_idx, b_idx, points); + + bool is_valid_diagonal = + (is_locally_inside_ab && is_locally_inside_ba && is_middle_inside && + (area(points, a_prev_idx, a_idx, b_prev_idx) != 0.0 || + area(points, a_idx, b_prev_idx, b_idx) != 0.0)) || + (equals(a_idx, b_idx, points) && area(points, a_prev_idx, a_idx, a_next_idx) > 0 && + area(points, b_prev_idx, b_idx, b_next_idx) > 0); + + return is_valid_diagonal; +} + +std::size_t insert_point( + const alt::Point2d & pt, std::vector & points, + const std::optional last_index) +{ + std::size_t p_idx = points.size(); + points.push_back(LinkedPoint(pt)); + + // Making sure all next_index and prev_index will always have values + if (!last_index.has_value()) { + points[p_idx].prev_index = p_idx; + points[p_idx].next_index = p_idx; + } else { + std::size_t last = last_index.value(); + std::size_t next = points[last].next_index.value(); + points[p_idx].prev_index = last; + points[p_idx].next_index = next; + points[last].next_index = p_idx; + if (next != p_idx) { + points[next].prev_index = p_idx; + } + } + + return p_idx; +} + +std::size_t linked_list( + const alt::PointList2d & ring, const bool forward, std::size_t & vertices, + std::vector & points) +{ + const std::size_t len = ring.size(); + std::optional last_index = std::nullopt; + + // create forward linked list if forward is true and ring is counter-clockwise, or + // forward is false and ring is clockwise + // create reverse linked list if forward is true and ring is clockwise, or + // forward is false and ring is counter-clockwise + if (forward == !is_clockwise(ring)) { + for (auto it = ring.begin(); it != ring.end(); ++it) { + last_index = insert_point(*it, points, last_index); + } + } else { + for (auto it = ring.rbegin(); it != ring.rend(); ++it) { + last_index = insert_point(*it, points, last_index); + } + } + + if (last_index.has_value()) { + std::size_t last_idx_value = last_index.value(); + std::optional next_index = points[last_idx_value].next_index; + + if (next_index.has_value() && equals(last_idx_value, next_index.value(), points)) { + std::size_t next_idx_value = next_index.value(); + remove_point(last_idx_value, points); + last_index = next_idx_value; + } + } + + vertices += len; + return last_index.value(); +} + +bool sector_contains_sector( + const std::size_t m_idx, const std::size_t p_idx, const std::vector & points) +{ + if (!points[m_idx].prev_index.has_value() || !points[m_idx].next_index.has_value()) { + return false; + } + + std::size_t m_prev_idx = points[m_idx].prev_index.value(); + std::size_t m_next_idx = points[m_idx].next_index.value(); + + return area(points, m_prev_idx, m_idx, p_idx) < 0 && area(points, p_idx, m_next_idx, m_idx) < 0; +} + +std::size_t find_hole_bridge( + const std::size_t hole_index, const std::size_t outer_point_index, + const std::vector & points) +{ + std::size_t p = outer_point_index; + double hx = points[hole_index].x(); + double hy = points[hole_index].y(); + double qx = -std::numeric_limits::infinity(); + std::optional bridge_index = std::nullopt; + std::size_t next_index = points[p].next_index.value(); + + while (p != outer_point_index) { + if ( + hy <= points[p].y() && hy >= points[next_index].y() && + points[next_index].y() != points[p].y()) { + double x = points[p].x() + (hy - points[p].y()) * (points[next_index].x() - points[p].x()) / + (points[next_index].y() - points[p].y()); + if (x <= hx && x > qx) { + qx = x; + bridge_index = (points[p].x() < points[next_index].x()) ? p : next_index; + if (x == hx) return bridge_index.value(); + } + } + p = next_index; + next_index = points[p].next_index.value(); + } + + if (!bridge_index.has_value()) return outer_point_index; + + const std::size_t stop = bridge_index.value(); + double min_tan = std::numeric_limits::infinity(); + + p = bridge_index.value(); + double mx = points[p].x(); + double my = points[p].y(); + next_index = points[p].next_index.value(); + + while (p != stop) { + if ( + hx >= points[p].x() && points[p].x() >= mx && hx != points[p].x() && + point_in_triangle( + hy < my ? hx : qx, hy, mx, my, hy < my ? qx : hx, hy, points[p].x(), points[p].y())) { + double current_tan = std::abs(hy - points[p].y()) / (hx - points[p].x()); + + if ( + locally_inside(p, hole_index, points) && + (current_tan < min_tan || + (current_tan == min_tan && (points[p].x() > points[bridge_index.value()].x() || + sector_contains_sector(bridge_index.value(), p, points))))) { + bridge_index = p; + min_tan = current_tan; + } + } + + p = next_index; + next_index = points[p].next_index.value(); + } + + return bridge_index.value(); +} + +std::size_t split_polygon( + std::size_t a_index, std::size_t b_index, std::vector & points) +{ + std::size_t an_idx = points[a_index].next_index.value(); + std::size_t bp_idx = points[b_index].prev_index.value(); + + std::size_t a2_idx = points.size(); + std::size_t b2_idx = points.size() + 1; + points.push_back(points[a_index]); + points.push_back(points[b_index]); + + points[a_index].next_index = b_index; + points[a2_idx].prev_index = b2_idx; + points[a2_idx].next_index = an_idx; + + points[b_index].prev_index = a_index; + points[an_idx].prev_index = b2_idx; + points[b2_idx].next_index = a2_idx; + points[b2_idx].prev_index = bp_idx; + + if (bp_idx != b_index) { + points[bp_idx].next_index = b2_idx; + } + + return b2_idx; +} + +std::size_t filter_points( + const std::size_t start_index, const std::size_t end_index, std::vector & points) +{ + auto p = start_index; + bool again = true; + + while (again && p != end_index) { + again = false; + + if ( + !points[p].steiner && + (equals(p, points[p].next_index.value(), points) || + area(points, points[p].prev_index.value(), p, points[p].next_index.value()) == 0)) { + remove_point(p, points); + p = points[p].prev_index.value(); + + if (p == points[p].next_index.value()) { + break; + } + again = true; + } else { + p = points[p].next_index.value(); + } + } + + return end_index; +} + +std::size_t eliminate_hole( + const std::size_t hole_index, const std::size_t outer_index, std::vector & points) +{ + auto bridge = find_hole_bridge(hole_index, outer_index, points); + auto bridge_reverse = split_polygon(bridge, hole_index, points); + + auto next_index_bridge_reverse = points[bridge_reverse].next_index.value(); + filter_points(bridge_reverse, next_index_bridge_reverse, points); + + auto next_index_bridge = points[bridge].next_index.value(); + return filter_points(bridge, next_index_bridge, points); +} + +std::size_t eliminate_holes( + const std::vector & inners, std::size_t outer_index, std::size_t & vertices, + std::vector & points) +{ + std::vector queue; + + for (const auto & ring : inners) { + if (ring.empty()) { + continue; + } + auto inner_index = linked_list(ring, false, vertices, points); + + if (points[inner_index].next_index.value() == inner_index) { + points[inner_index].steiner = true; + } + + queue.push_back(get_leftmost(inner_index, points)); + } + + std::sort(queue.begin(), queue.end(), [&](std::size_t a, std::size_t b) { + return points[a].x() < points[b].x(); + }); + + for (const auto & q : queue) { + outer_index = eliminate_hole(q, outer_index, points); + } + + return outer_index; +} + +bool is_ear(const std::size_t ear_index, const std::vector & points) +{ + const auto a_index = points[ear_index].prev_index.value(); + const auto b_index = ear_index; + const auto c_index = points[ear_index].next_index.value(); + + const auto a = points[a_index]; + const auto b = points[b_index]; + const auto c = points[c_index]; + + if (area(points, a_index, b_index, c_index) >= 0) return false; + auto p_index = points[c_index].next_index.value(); + while (p_index != a_index) { + const auto p = points[p_index]; + if ( + point_in_triangle(a.x(), a.y(), b.x(), b.y(), c.x(), c.y(), p.x(), p.y()) && + area(points, p.prev_index.value(), p_index, p.next_index.value()) >= 0) { + return false; + } + p_index = points[p_index].next_index.value(); + } + + return true; +} + +std::size_t cure_local_intersections( + std::size_t start_index, std::vector & indices, std::vector & points) +{ + auto p = start_index; + bool updated = false; + + while (p != start_index || updated) { + updated = false; + auto a_idx = points[p].prev_index.value(); + auto b_idx = points[points[p].next_index.value()].next_index.value(); + + if ( + !equals(a_idx, b_idx, points) && + intersects( + a_idx, p, points[points[p].next_index.value()].next_index.value(), b_idx, points) && + locally_inside(a_idx, b_idx, points) && locally_inside(b_idx, a_idx, points)) { + indices.push_back(a_idx); + indices.push_back(p); + indices.push_back(b_idx); + + remove_point(p, points); + remove_point(points[p].next_index.value(), points); + + p = start_index = b_idx; + updated = true; + } else { + p = points[p].next_index.value(); + } + } + + return filter_points(p, p, points); +} + +void split_ear_clipping( + std::vector & points, const std::size_t start_idx, + std::vector & indices) +{ + std::size_t a_idx = start_idx; + do { + std::size_t b_idx = points[points[a_idx].next_index.value()].next_index.value(); + while (b_idx != points[a_idx].prev_index.value()) { + if (a_idx != b_idx && is_valid_diagonal(a_idx, b_idx, points)) { + std::size_t c_idx = split_polygon(a_idx, b_idx, points); + + a_idx = filter_points(start_idx, points[a_idx].next_index.value(), points); + c_idx = filter_points(start_idx, points[c_idx].next_index.value(), points); + + ear_clipping_linked(a_idx, indices, points); + ear_clipping_linked(c_idx, indices, points); + return; + } + b_idx = points[b_idx].next_index.value(); + } + a_idx = points[a_idx].next_index.value(); + } while (a_idx != start_idx); +} + +void ear_clipping_linked( + std::size_t ear_index, std::vector & indices, std::vector & points, + const int pass) +{ + auto stop = ear_index; + std::optional next = std::nullopt; + + while (points[ear_index].prev_index.value() != points[ear_index].next_index.value()) { + next = points[ear_index].next_index; + + if (is_ear(ear_index, points)) { + indices.push_back(points[ear_index].prev_index.value()); + indices.push_back(ear_index); + indices.push_back(next.value()); + + remove_point(ear_index, points); + + ear_index = points[next.value()].next_index.value(); + stop = points[next.value()].next_index.value(); + continue; + } + + ear_index = next.value(); + + if (ear_index == stop) { + if (pass == 0) { + ear_clipping_linked(filter_points(ear_index, ear_index, points), indices, points, 1); + } else if (pass == 1) { + ear_index = + cure_local_intersections(filter_points(ear_index, ear_index, points), indices, points); + ear_clipping_linked(ear_index, indices, points, 2); + } else if (pass == 2) { + split_ear_clipping(points, ear_index, indices); + } + break; + } + } +} + +std::vector perform_triangulation( + const alt::Polygon2d & polygon, std::vector & indices) +{ + indices.clear(); + std::vector points; + std::size_t vertices = 0; + const auto & outer_ring = polygon.outer(); + std::size_t len = outer_ring.size(); + points.reserve(len * 3 / 2); + + if (polygon.outer().empty()) return points; + + indices.reserve(len + outer_ring.size()); + auto outer_point_index = linked_list(outer_ring, true, vertices, points); + if ( + !points[outer_point_index].prev_index.has_value() || + outer_point_index == points[outer_point_index].prev_index.value()) { + return points; + } + + if (!polygon.inners().empty()) { + outer_point_index = eliminate_holes(polygon.inners(), outer_point_index, vertices, points); + } + + ear_clipping_linked(outer_point_index, indices, points); + return points; +} + +std::vector triangulate(const alt::Polygon2d & poly) +{ + std::vector indices; + auto points = perform_triangulation(poly, indices); + + std::vector triangles; + const std::size_t num_indices = indices.size(); + + if (num_indices % 3 != 0) { + throw std::runtime_error("Indices size should be a multiple of 3"); + } + + for (std::size_t i = 0; i < num_indices; i += 3) { + alt::PointList2d vertices; + vertices.push_back(points[indices[i]].pt); + vertices.push_back(points[indices[i + 1]].pt); + vertices.push_back(points[indices[i + 2]].pt); + vertices.push_back(points[indices[i]].pt); + + triangles.push_back(alt::ConvexPolygon2d::create(vertices).value()); + } + points.clear(); + return triangles; +} + +std::vector triangulate(const Polygon2d & poly) +{ + const auto alt_poly = alt::Polygon2d::create(poly); + const auto alt_triangles = triangulate(alt_poly.value()); + std::vector triangles; + for (const auto & alt_triangle : alt_triangles) { + triangles.push_back(alt_triangle.to_boost()); + } + return triangles; +} +} // namespace autoware_utils diff --git a/autoware_utils/src/geometry/geometry.cpp b/autoware_utils/src/geometry/geometry.cpp new file mode 100644 index 0000000..72048d2 --- /dev/null +++ b/autoware_utils/src/geometry/geometry.cpp @@ -0,0 +1,397 @@ +// Copyright 2023-2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/geometry/geometry.hpp" + +#include "autoware_utils/geometry/gjk_2d.hpp" + +#include + +#include + +#include + +#include + +namespace tf2 +{ +void fromMsg(const geometry_msgs::msg::PoseStamped & msg, tf2::Stamped & out) +{ + out.stamp_ = tf2_ros::fromMsg(msg.header.stamp); + out.frame_id_ = msg.header.frame_id; + tf2::Transform tmp; + fromMsg(msg.pose, tmp); + out.setData(tmp); +} +} // namespace tf2 + +namespace autoware_utils +{ +geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Quaternion & quat) +{ + geometry_msgs::msg::Vector3 rpy; + tf2::Quaternion q(quat.x, quat.y, quat.z, quat.w); + tf2::Matrix3x3(q).getRPY(rpy.x, rpy.y, rpy.z); + return rpy; +} + +geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::Pose & pose) +{ + return get_rpy(pose.orientation); +} + +geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseStamped & pose) +{ + return get_rpy(pose.pose); +} + +geometry_msgs::msg::Vector3 get_rpy(const geometry_msgs::msg::PoseWithCovarianceStamped & pose) +{ + return get_rpy(pose.pose.pose); +} + +geometry_msgs::msg::Quaternion create_quaternion( + const double x, const double y, const double z, const double w) +{ + geometry_msgs::msg::Quaternion q; + q.x = x; + q.y = y; + q.z = z; + q.w = w; + return q; +} + +geometry_msgs::msg::Vector3 create_translation(const double x, const double y, const double z) +{ + geometry_msgs::msg::Vector3 v; + v.x = x; + v.y = y; + v.z = z; + return v; +} + +// Revival of tf::create_quaternion_from_rpy +// https://answers.ros.org/question/304397/recommended-way-to-construct-quaternion-from-rollpitchyaw-with-tf2/ +geometry_msgs::msg::Quaternion create_quaternion_from_rpy( + const double roll, const double pitch, const double yaw) +{ + tf2::Quaternion q; + q.setRPY(roll, pitch, yaw); + return tf2::toMsg(q); +} + +geometry_msgs::msg::Quaternion create_quaternion_from_yaw(const double yaw) +{ + tf2::Quaternion q; + q.setRPY(0, 0, yaw); + return tf2::toMsg(q); +} + +double calc_elevation_angle( + const geometry_msgs::msg::Point & p_from, const geometry_msgs::msg::Point & p_to) +{ + const double dz = p_to.z - p_from.z; + const double dist_2d = calc_distance2d(p_from, p_to); + return std::atan2(dz, dist_2d); +} + +/** + * @brief calculate azimuth angle of two points. + * @details This function returns the azimuth angle of the position of the two input points + * with respect to the origin of their coordinate system. + * If x and y of the two points are the same, the calculation result will be unstable. + * @param p_from source point + * @param p_to target point + * @return -pi < azimuth angle < pi. + */ +double calc_azimuth_angle( + const geometry_msgs::msg::Point & p_from, const geometry_msgs::msg::Point & p_to) +{ + const double dx = p_to.x - p_from.x; + const double dy = p_to.y - p_from.y; + return std::atan2(dy, dx); +} + +geometry_msgs::msg::Pose transform2pose(const geometry_msgs::msg::Transform & transform) +{ + geometry_msgs::msg::Pose pose; + pose.position.x = transform.translation.x; + pose.position.y = transform.translation.y; + pose.position.z = transform.translation.z; + pose.orientation = transform.rotation; + return pose; +} + +geometry_msgs::msg::PoseStamped transform2pose( + const geometry_msgs::msg::TransformStamped & transform) +{ + geometry_msgs::msg::PoseStamped pose; + pose.header = transform.header; + pose.pose = transform2pose(transform.transform); + return pose; +} + +geometry_msgs::msg::Transform pose2transform(const geometry_msgs::msg::Pose & pose) +{ + geometry_msgs::msg::Transform transform; + transform.translation.x = pose.position.x; + transform.translation.y = pose.position.y; + transform.translation.z = pose.position.z; + transform.rotation = pose.orientation; + return transform; +} + +geometry_msgs::msg::TransformStamped pose2transform( + const geometry_msgs::msg::PoseStamped & pose, const std::string & child_frame_id) +{ + geometry_msgs::msg::TransformStamped transform; + transform.header = pose.header; + transform.transform = pose2transform(pose.pose); + transform.child_frame_id = child_frame_id; + return transform; +} + +Point3d transform_point(const Point3d & point, const geometry_msgs::msg::Transform & transform) +{ + const auto & translation = transform.translation; + const auto & rotation = transform.rotation; + + const Eigen::Translation3d T(translation.x, translation.y, translation.z); + const Eigen::Quaterniond R(rotation.w, rotation.x, rotation.y, rotation.z); + + const Eigen::Vector3d transformed(T * R * point); + + return Point3d{transformed.x(), transformed.y(), transformed.z()}; +} + +Point2d transform_point(const Point2d & point, const geometry_msgs::msg::Transform & transform) +{ + Point3d point_3d{point.x(), point.y(), 0}; + const auto transformed = transform_point(point_3d, transform); + return Point2d{transformed.x(), transformed.y()}; +} + +Eigen::Vector3d transform_point( + const Eigen::Vector3d & point, const geometry_msgs::msg::Pose & pose) +{ + geometry_msgs::msg::Transform transform; + transform.translation.x = pose.position.x; + transform.translation.y = pose.position.y; + transform.translation.z = pose.position.z; + transform.rotation = pose.orientation; + + Point3d p = transform_point(Point3d(point.x(), point.y(), point.z()), transform); + return Eigen::Vector3d(p.x(), p.y(), p.z()); +} + +geometry_msgs::msg::Point transform_point( + const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & pose) +{ + const Eigen::Vector3d vec = Eigen::Vector3d(point.x, point.y, point.z); + auto transformed_vec = transform_point(vec, pose); + + geometry_msgs::msg::Point transformed_point; + transformed_point.x = transformed_vec.x(); + transformed_point.y = transformed_vec.y(); + transformed_point.z = transformed_vec.z(); + return transformed_point; +} + +geometry_msgs::msg::Point32 transform_point( + const geometry_msgs::msg::Point32 & point32, const geometry_msgs::msg::Pose & pose) +{ + const auto point = + geometry_msgs::build().x(point32.x).y(point32.y).z(point32.z); + const auto transformed_point = autoware_utils::transform_point(point, pose); + return geometry_msgs::build() + .x(transformed_point.x) + .y(transformed_point.y) + .z(transformed_point.z); +} + +geometry_msgs::msg::Pose transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::TransformStamped & transform) +{ + geometry_msgs::msg::Pose transformed_pose; + tf2::doTransform(pose, transformed_pose, transform); + + return transformed_pose; +} + +geometry_msgs::msg::Pose transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Transform & transform) +{ + geometry_msgs::msg::TransformStamped transform_stamped; + transform_stamped.transform = transform; + + return transform_pose(pose, transform_stamped); +} + +geometry_msgs::msg::Pose transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Pose & pose_transform) +{ + tf2::Transform transform; + tf2::convert(pose_transform, transform); + + geometry_msgs::msg::TransformStamped transform_msg; + transform_msg.transform = tf2::toMsg(transform); + + return transform_pose(pose, transform_msg); +} + +// Transform pose in world coordinates to local coordinates +/* +geometry_msgs::msg::Pose inverse_transform_pose( +const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::TransformStamped & transform) +{ +tf2::Transform tf; +tf2::fromMsg(transform, tf); +geometry_msgs::msg::TransformStamped transform_stamped; +transform_stamped.transform = tf2::toMsg(tf.inverse()); + +return transform_pose(pose, transform_stamped); +} +*/ + +// Transform pose in world coordinates to local coordinates +geometry_msgs::msg::Pose inverse_transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Transform & transform) +{ + tf2::Transform tf; + tf2::fromMsg(transform, tf); + geometry_msgs::msg::TransformStamped transform_stamped; + transform_stamped.transform = tf2::toMsg(tf.inverse()); + + return transform_pose(pose, transform_stamped); +} + +// Transform pose in world coordinates to local coordinates +geometry_msgs::msg::Pose inverse_transform_pose( + const geometry_msgs::msg::Pose & pose, const geometry_msgs::msg::Pose & transform_pose) +{ + tf2::Transform transform; + tf2::convert(transform_pose, transform); + + return inverse_transform_pose(pose, tf2::toMsg(transform)); +} + +// Transform point in world coordinates to local coordinates +Eigen::Vector3d inverse_transform_point( + const Eigen::Vector3d & point, const geometry_msgs::msg::Pose & pose) +{ + const Eigen::Quaterniond q( + pose.orientation.w, pose.orientation.x, pose.orientation.y, pose.orientation.z); + const Eigen::Matrix3d R = q.normalized().toRotationMatrix(); + + const Eigen::Vector3d local_origin(pose.position.x, pose.position.y, pose.position.z); + Eigen::Vector3d local_point = R.transpose() * point - R.transpose() * local_origin; + + return local_point; +} + +// Transform point in world coordinates to local coordinates +geometry_msgs::msg::Point inverseTransformPoint( + const geometry_msgs::msg::Point & point, const geometry_msgs::msg::Pose & pose) +{ + const Eigen::Vector3d local_vec = + inverse_transform_point(Eigen::Vector3d(point.x, point.y, point.z), pose); + geometry_msgs::msg::Point local_point; + local_point.x = local_vec.x(); + local_point.y = local_vec.y(); + local_point.z = local_vec.z(); + return local_point; +} + +double calc_curvature( + const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, + const geometry_msgs::msg::Point & p3) +{ + // Calculation details are described in the following page + // https://en.wikipedia.org/wiki/Menger_curvature + const double denominator = + calc_distance2d(p1, p2) * calc_distance2d(p2, p3) * calc_distance2d(p3, p1); + if (std::fabs(denominator) < 1e-10) { + throw std::runtime_error("points are too close for curvature calculation."); + } + return 2.0 * ((p2.x - p1.x) * (p3.y - p1.y) - (p2.y - p1.y) * (p3.x - p1.x)) / denominator; +} + +/** + * @brief Calculate offset pose. The offset values are defined in the local coordinate of the input + * pose. + */ +geometry_msgs::msg::Pose calc_offset_pose( + const geometry_msgs::msg::Pose & p, const double x, const double y, const double z, + const double yaw) +{ + geometry_msgs::msg::Pose pose; + geometry_msgs::msg::Transform transform; + transform.translation = create_translation(x, y, z); + transform.rotation = create_quaternion_from_yaw(yaw); + tf2::Transform tf_pose; + tf2::Transform tf_offset; + tf2::fromMsg(transform, tf_offset); + tf2::fromMsg(p, tf_pose); + tf2::toMsg(tf_pose * tf_offset, pose); + return pose; +} + +/** + * @brief Judge whether twist covariance is valid. + * + * @param twist_with_covariance source twist with covariance + * @return If all element of covariance is 0, return false. + */ +// +bool is_twist_covariance_valid( + const geometry_msgs::msg::TwistWithCovariance & twist_with_covariance) +{ + for (const auto & c : twist_with_covariance.covariance) { + if (c != 0.0) { + return true; + } + } + return false; +} + +// NOTE: much faster than boost::geometry::intersects() +std::optional intersect( + const geometry_msgs::msg::Point & p1, const geometry_msgs::msg::Point & p2, + const geometry_msgs::msg::Point & p3, const geometry_msgs::msg::Point & p4) +{ + // calculate intersection point + const double det = (p1.x - p2.x) * (p4.y - p3.y) - (p4.x - p3.x) * (p1.y - p2.y); + if (det == 0.0) { + return std::nullopt; + } + + const double t = ((p4.y - p3.y) * (p4.x - p2.x) + (p3.x - p4.x) * (p4.y - p2.y)) / det; + const double s = ((p2.y - p1.y) * (p4.x - p2.x) + (p1.x - p2.x) * (p4.y - p2.y)) / det; + if (t < 0 || 1 < t || s < 0 || 1 < s) { + return std::nullopt; + } + + geometry_msgs::msg::Point intersect_point; + intersect_point.x = t * p1.x + (1.0 - t) * p2.x; + intersect_point.y = t * p1.y + (1.0 - t) * p2.y; + intersect_point.z = t * p1.z + (1.0 - t) * p2.z; + return intersect_point; +} + +bool intersects_convex(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2) +{ + return gjk::intersects(convex_polygon1, convex_polygon2); +} + +} // namespace autoware_utils diff --git a/autoware_utils/src/geometry/gjk_2d.cpp b/autoware_utils/src/geometry/gjk_2d.cpp new file mode 100644 index 0000000..ca9ec6e --- /dev/null +++ b/autoware_utils/src/geometry/gjk_2d.cpp @@ -0,0 +1,150 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/geometry/gjk_2d.hpp" + +#include "autoware_utils/geometry/boost_geometry.hpp" + +#include + +namespace autoware_utils::gjk +{ + +namespace +{ +/// @brief structure with all variables updated during the GJK loop +/// @details for performance we only want to reserve their space in memory once +struct SimplexSearch +{ + // current triangle simplex + Point2d a; + Point2d b; + Point2d c; + Point2d co; // vector from C to the origin + Point2d ca; // vector from C to A + Point2d cb; // vector from C to B + Point2d ca_perpendicular; // perpendicular to CA + Point2d cb_perpendicular; // perpendicular to CB + Point2d direction; // current search direction +}; + +/// @brief calculate the dot product between 2 points +double dot_product(const Point2d & p1, const Point2d & p2) +{ + return p1.x() * p2.x() + p1.y() * p2.y(); +} + +/// @brief calculate the index of the furthest polygon vertex in the given direction +size_t furthest_vertex_idx(const Polygon2d & poly, const Point2d & direction) +{ + auto furthest_distance = dot_product(poly.outer()[0], direction); + size_t furthest_idx = 0UL; + for (auto i = 1UL; i < poly.outer().size(); ++i) { + const auto distance = dot_product(poly.outer()[i], direction); + if (distance > furthest_distance) { + furthest_distance = distance; + furthest_idx = i; + } + } + return furthest_idx; +} + +/// @brief calculate the next Minkowski difference vertex in the given direction +Point2d support_vertex(const Polygon2d & poly1, const Polygon2d & poly2, const Point2d & direction) +{ + const auto opposite_direction = Point2d(-direction.x(), -direction.y()); + const auto idx1 = furthest_vertex_idx(poly1, direction); + const auto idx2 = furthest_vertex_idx(poly2, opposite_direction); + return Point2d( + poly1.outer()[idx1].x() - poly2.outer()[idx2].x(), + poly1.outer()[idx1].y() - poly2.outer()[idx2].y()); +} + +/// @brief return true if both points are in the same direction +bool same_direction(const Point2d & p1, const Point2d & p2) +{ + return dot_product(p1, p2) > 0.0; +} + +/// @brief return the triple cross product of the given points +Point2d cross_product(const Point2d & p1, const Point2d & p2, const Point2d & p3) +{ + const auto tmp = p1.x() * p2.y() - p1.y() * p2.x(); + return Point2d(-p3.y() * tmp, p3.x() * tmp); +} + +/// @brief update the search simplex and search direction to try to surround the origin +bool update_search_simplex_and_direction(SimplexSearch & search) +{ + bool continue_search = false; + search.co.x() = -search.c.x(); + search.co.y() = -search.c.y(); + search.ca.x() = search.a.x() - search.c.x(); + search.ca.y() = search.a.y() - search.c.y(); + search.cb.x() = search.b.x() - search.c.x(); + search.cb.y() = search.b.y() - search.c.y(); + search.ca_perpendicular = cross_product(search.cb, search.ca, search.ca); + search.cb_perpendicular = cross_product(search.ca, search.cb, search.cb); + if (same_direction(search.ca_perpendicular, search.co)) { + search.b.x() = search.c.x(); + search.b.y() = search.c.y(); + search.direction.x() = search.ca_perpendicular.x(); + search.direction.y() = search.ca_perpendicular.y(); + continue_search = true; + } else if (same_direction(search.cb_perpendicular, search.co)) { + search.a.x() = search.c.x(); + search.a.y() = search.c.y(); + search.direction.x() = search.cb_perpendicular.x(); + search.direction.y() = search.cb_perpendicular.y(); + continue_search = true; + } + return continue_search; +} +} // namespace + +/// @brief return true if the two given polygons intersect +/// @details if the intersection area is 0 (e.g., only one point or one edge intersect), the return +/// value is false +bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2) +{ + if (convex_polygon1.outer().empty() || convex_polygon2.outer().empty()) { + return false; + } + if (boost::geometry::equals(convex_polygon1, convex_polygon2)) { + return true; + } + + SimplexSearch search; + search.direction = {1.0, 0.0}; + search.a = support_vertex(convex_polygon1, convex_polygon2, search.direction); + search.direction = {-search.a.x(), -search.a.y()}; + search.b = support_vertex(convex_polygon1, convex_polygon2, search.direction); + if (dot_product(search.b, search.direction) <= 0.0) { // the Minkowski difference does not cross + // the origin + return false; // no collision + } + Point2d ab = {search.b.x() - search.a.x(), search.b.y() - search.a.y()}; + Point2d ao = {-search.a.x(), -search.a.y()}; + search.direction = cross_product(ab, ao, ab); + bool continue_search = true; + while (continue_search) { + search.c = support_vertex(convex_polygon1, convex_polygon2, search.direction); + if (!same_direction(search.c, search.direction)) { // no more vertex in the search direction + return false; // no collision + } + continue_search = update_search_simplex_and_direction(search); + } + return true; +} +} // namespace autoware_utils::gjk diff --git a/autoware_utils/src/geometry/pose_deviation.cpp b/autoware_utils/src/geometry/pose_deviation.cpp new file mode 100644 index 0000000..0563d23 --- /dev/null +++ b/autoware_utils/src/geometry/pose_deviation.cpp @@ -0,0 +1,85 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/geometry/pose_deviation.hpp" + +#include "autoware_utils/math/normalization.hpp" + +#include + +#define EIGEN_MPL2_ONLY +#include +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +namespace autoware_utils +{ + +double calc_lateral_deviation( + const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Point & target_point) +{ + const auto & base_point = base_pose.position; + + const auto yaw = tf2::getYaw(base_pose.orientation); + const Eigen::Vector3d base_unit_vec{std::cos(yaw), std::sin(yaw), 0}; + + const auto dx = target_point.x - base_point.x; + const auto dy = target_point.y - base_point.y; + const Eigen::Vector3d diff_vec{dx, dy, 0}; + + const Eigen::Vector3d cross_vec = base_unit_vec.cross(diff_vec); + + return cross_vec.z(); +} + +double calc_longitudinal_deviation( + const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Point & target_point) +{ + const auto & base_point = base_pose.position; + + const auto yaw = tf2::getYaw(base_pose.orientation); + const Eigen::Vector3d base_unit_vec{std::cos(yaw), std::sin(yaw), 0}; + + const auto dx = target_point.x - base_point.x; + const auto dy = target_point.y - base_point.y; + const Eigen::Vector3d diff_vec{dx, dy, 0}; + + return base_unit_vec.dot(diff_vec); +} + +double calc_yaw_deviation( + const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & target_pose) +{ + const auto base_yaw = tf2::getYaw(base_pose.orientation); + const auto target_yaw = tf2::getYaw(target_pose.orientation); + return normalize_radian(target_yaw - base_yaw); +} + +PoseDeviation calc_pose_deviation( + const geometry_msgs::msg::Pose & base_pose, const geometry_msgs::msg::Pose & target_pose) +{ + PoseDeviation deviation{}; + + deviation.lateral = calc_lateral_deviation(base_pose, target_pose.position); + deviation.longitudinal = calc_longitudinal_deviation(base_pose, target_pose.position); + deviation.yaw = calc_yaw_deviation(base_pose, target_pose); + + return deviation; +} +} // namespace autoware_utils diff --git a/autoware_utils/src/geometry/random_concave_polygon.cpp b/autoware_utils/src/geometry/random_concave_polygon.cpp new file mode 100644 index 0000000..b40e421 --- /dev/null +++ b/autoware_utils/src/geometry/random_concave_polygon.cpp @@ -0,0 +1,407 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/geometry/random_concave_polygon.hpp" + +#include "autoware_utils/geometry/boost_geometry.hpp" + +#include +#include +#include +#include +#include + +#include +#include +#include +#include +#include +#include + +namespace autoware_utils +{ +namespace +{ +/// @brief define Edge as a pair of Points +struct Edge +{ + Point2d first; + Point2d second; + bool valid = true; + bool operator==(const Edge & other) const + { + return (first == other.first && second == other.second) || + (first == other.second && second == other.first); + } +}; + +/// @brief structure to hold a polygon and its edges +struct PolygonWithEdges +{ + Polygon2d polygon; + std::vector edges; +}; + +/// @brief prepares coordinate vectors for a given number of vertices +std::vector prepare_coordinate_vectors( + const size_t nb_vertices, + std::uniform_real_distribution & + random_double, // cppcheck-suppress constParameterReference + std::uniform_int_distribution & random_bool, // cppcheck-suppress constParameterReference + std::default_random_engine & random_engine) +{ + std::vector v; + v.reserve(nb_vertices); + for (auto i = 0UL; i < nb_vertices; ++i) { + v.push_back(random_double(random_engine)); + } + std::sort(v.begin(), v.end()); + const auto min_v = v.front(); + const auto max_v = v.back(); + std::vector v1; + v1.push_back(min_v); + std::vector v2; + v2.push_back(min_v); + for (auto i = 1UL; i + 1 < v.size(); ++i) { + if (random_bool(random_engine) == 0) { + v1.push_back((v[i])); + } else { + v2.push_back((v[i])); + } + } + v1.push_back(max_v); + v2.push_back(max_v); + std::vector diffs; + for (auto i = 0UL; i + 1 < v1.size(); ++i) { + diffs.push_back(v1[i + 1] - v1[i]); + } + for (auto i = 0UL; i + 1 < v2.size(); ++i) { + diffs.push_back(v2[i] - v2[i + 1]); + } + std::vector vectors; + vectors = diffs; + return vectors; +} + +/// @brief calculates the distance from a point to an edge +double dist(const Edge & edge, const Point2d & point) +{ + double x = point.x(); + double y = point.y(); + double x1 = edge.first.x(); + double y1 = edge.first.y(); + double x2 = edge.second.x(); + double y2 = edge.second.y(); + + double dx = x2 - x1; + double dy = y2 - y1; + + if (dx == 0.0 && dy == 0.0) { + dx = x - x1; + dy = y - y1; + return std::sqrt(dx * dx + dy * dy); + } + + double t = ((x - x1) * dx + (y - y1) * dy) / (dx * dx + dy * dy); + t = std::max(0.0, std::min(1.0, t)); + dx = x - (x1 + t * dx); + dy = y - (y1 + t * dy); + return std::sqrt(dx * dx + dy * dy); +} + +/// @brief checks if an edge intersects with a polygon +bool intersecting(const Edge & e, const Polygon2d & polygon) +{ + Segment2d edge_segment{e.first, e.second}; + if (boost::geometry::intersects(edge_segment, polygon)) { + // additional check: ensure it's not just a single point intersection + for (size_t i = 0; i < polygon.outer().size(); ++i) { + const Point2d & p1 = polygon.outer()[i]; + const Point2d & p2 = polygon.outer()[(i + 1) % polygon.outer().size()]; + Segment2d poly_segment{p1, p2}; + + if (boost::geometry::intersects(edge_segment, poly_segment)) { + if (!(e.first == p1 || e.first == p2 || e.second == p1 || e.second == p2)) { + return true; + } + } + } + return false; + } + + return false; +} + +/// @brief checks if an edge is valid for a given polygon and set of points +bool is_valid(const Edge & e, const Polygon2d & P, const std::list & Q) +{ + for (const Point2d & q : Q) { + Edge e1 = {e.first, q}; + Edge e2 = {q, e.second}; + bool intersects_e1 = intersecting(e1, P); + bool intersects_e2 = intersecting(e2, P); + if (intersects_e1 || intersects_e2) { + return false; + } + } + + return true; +} + +/// @brief finds the nearest node from a set of points to an edge +Point2d get_nearest_node(const std::list & Q, const Edge & e) +{ + double min_distance = std::numeric_limits::max(); + Point2d nearest_node(0, 0); + + for (const auto & node : Q) { + double distance = dist(e, node); + + if (distance < min_distance) { + min_distance = distance; + nearest_node = node; + } + } + return nearest_node; +} + +/// @brief finds the edge that is closest to the given set of points +Edge get_breaking_edge(const PolygonWithEdges & polygon_with_edges, const std::list & Q) +{ + double min_distance = std::numeric_limits::max(); + Edge e_breaking; + e_breaking.valid = false; + + for (const auto & edge : polygon_with_edges.edges) { + if (is_valid(edge, polygon_with_edges.polygon, Q)) { + Point2d nearest_node = get_nearest_node(Q, edge); + double distance = dist(edge, nearest_node); + if (distance < min_distance) { + min_distance = distance; + e_breaking = edge; + } + } + } + return e_breaking; +} + +/// @brief updates the polygon's outer ring based on its edges +void update_polygon_from_edges(PolygonWithEdges & polygon_with_edges) +{ + LinearRing2d new_outer_ring; + + for (const auto & edge : polygon_with_edges.edges) { + if (edge.valid) { + new_outer_ring.push_back(edge.first); + } + } + + polygon_with_edges.polygon.outer() = new_outer_ring; + boost::geometry::correct(polygon_with_edges.polygon); +} + +/// @brief inserts a node into the polygon's edges +void insert_node(PolygonWithEdges & polygon_with_edges, const Point2d & w, const Edge & e) +{ + std::vector new_edges; + for (const Edge & current_edge : polygon_with_edges.edges) { + if (current_edge == e) { + new_edges.push_back({e.first, w}); + new_edges.push_back({w, e.second}); + } else { + new_edges.push_back(current_edge); + } + } + + polygon_with_edges.edges = std::move(new_edges); +} + +/// @brief removes a node from a set of points +void remove_node(std::list & Q, const Point2d & w) +{ + const double epsilon = 1e-9; + + Q.erase( + std::remove_if( + Q.begin(), Q.end(), + [&](const Point2d & p) { + return std::abs(p.x() - w.x()) < epsilon && std::abs(p.y() - w.y()) < epsilon; + }), + Q.end()); +} + +/// @brief marks edges as valid if they are valid according to the polygon and points +void mark_valid_edges(PolygonWithEdges & polygon_with_edges, const std::list & Q) +{ + for (auto & edge : polygon_with_edges.edges) { + if (is_valid(edge, polygon_with_edges.polygon, Q)) { + edge.valid = true; + } + } +} + +/// @brief performs inward denting on a linear ring to create a new polygon +Polygon2d inward_denting(LinearRing2d & ring) +{ + LinearRing2d convex_ring; + std::list q; + boost::geometry::strategy::convex_hull::graham_andrew strategy; + boost::geometry::convex_hull(ring, convex_ring, strategy); + PolygonWithEdges polygon_with_edges; + polygon_with_edges.polygon.outer() = convex_ring; + polygon_with_edges.edges.resize(polygon_with_edges.polygon.outer().size()); + + for (const auto & point : ring) { + if (boost::geometry::within(point, polygon_with_edges.polygon)) { + q.push_back(point); + } + } + for (size_t i = 0; i < polygon_with_edges.edges.size(); ++i) { + polygon_with_edges.edges[i] = { + polygon_with_edges.polygon.outer()[i], + polygon_with_edges.polygon.outer()[(i + 1) % polygon_with_edges.polygon.outer().size()]}; + } + while (!q.empty()) { + Edge e = get_breaking_edge(polygon_with_edges, q); + Point2d w = get_nearest_node(q, e); + insert_node(polygon_with_edges, w, e); + remove_node(q, w); + mark_valid_edges(polygon_with_edges, q); + update_polygon_from_edges(polygon_with_edges); + } + + return polygon_with_edges.polygon; +} + +} // namespace + +/// @brief checks if a polygon is convex +bool is_convex(const autoware_utils::Polygon2d & polygon) +{ + const auto & outer_ring = polygon.outer(); + size_t num_points = outer_ring.size(); + + if (num_points < 4) { + return true; + } + + bool is_positive = false; + bool is_negative = false; + + for (size_t i = 0; i < num_points; ++i) { + auto p1 = outer_ring[i]; + auto p2 = outer_ring[(i + 1) % num_points]; + auto p3 = outer_ring[(i + 2) % num_points]; + + double cross_product = + (p2.x() - p1.x()) * (p3.y() - p2.y()) - (p2.y() - p1.y()) * (p3.x() - p2.x()); + + if (cross_product > 0) { + is_positive = true; + } else if (cross_product < 0) { + is_negative = true; + } + + if (is_positive && is_negative) { + return false; + } + } + + return true; +} + +/// @brief checks for collisions between two vectors of convex polygons using a specified collision +/// detection algorithm +bool test_intersection( + const std::vector & polygons1, + const std::vector & polygons2, + const std::function & + intersection_func) +{ + for (const auto & poly1 : polygons1) { + for (const auto & poly2 : polygons2) { + if (intersection_func(poly1, poly2)) { + return true; + } + } + } + return false; +} + +std::optional random_concave_polygon(const size_t vertices, const double max) +{ + if (vertices < 4) { + return Polygon2d(); + } + + std::random_device r; + std::default_random_engine random_engine(r()); + std::uniform_real_distribution uniform_dist(-max, max); + std::uniform_int_distribution random_bool(0, 1); + + Polygon2d poly; + bool is_non_convex = false; + int max_attempts = 100; + int attempt = 0; + + while (!is_non_convex && attempt < max_attempts) { + auto xs = prepare_coordinate_vectors(vertices, uniform_dist, random_bool, random_engine); + auto ys = prepare_coordinate_vectors(vertices, uniform_dist, random_bool, random_engine); + + std::shuffle(ys.begin(), ys.end(), random_engine); + + LinearRing2d vectors; + for (size_t i = 0; i < xs.size(); ++i) { + vectors.emplace_back(xs[i], ys[i]); + } + + LinearRing2d points; + for (const auto & p : vectors) { + points.emplace_back(p.x(), p.y()); + } + // apply inward denting algorithm + poly = inward_denting(points); + // check for convexity + if (!is_convex(poly) && boost::geometry::is_valid(poly) && poly.outer().size() != vertices) { + is_non_convex = true; + } + LinearRing2d poly_outer = poly.outer(); + poly.outer() = poly_outer; + + // shift polygon to ensure all coordinates are positive + double min_x = std::numeric_limits::max(); + double min_y = std::numeric_limits::max(); + for (const auto & point : poly.outer()) { + if (point.x() < min_x) { + min_x = point.x(); + } + if (point.y() < min_y) { + min_y = point.y(); + } + } + + double shift_x = -min_x + std::abs(min_x - (-max)); + double shift_y = -min_y + std::abs(min_y - (-max)); + + for (auto & point : poly.outer()) { + point.x() += shift_x; + point.y() += shift_y; + } + + boost::geometry::correct(poly); + ++attempt; + } + return poly; +} +} // namespace autoware_utils diff --git a/autoware_utils/src/geometry/random_convex_polygon.cpp b/autoware_utils/src/geometry/random_convex_polygon.cpp new file mode 100644 index 0000000..13e3f0a --- /dev/null +++ b/autoware_utils/src/geometry/random_convex_polygon.cpp @@ -0,0 +1,113 @@ +// Copyright 2024 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/geometry/random_convex_polygon.hpp" + +#include + +#include +#include +#include + +namespace autoware_utils +{ +namespace +{ +struct VectorsWithMin +{ + std::vector vectors; + double min{}; +}; + +VectorsWithMin prepare_coordinate_vectors( + const size_t nb_vertices, + std::uniform_real_distribution & + random_double, // cppcheck-suppress constParameterReference + std::uniform_int_distribution & random_bool, // cppcheck-suppress constParameterReference + std::default_random_engine & random_engine) +{ + std::vector v; + v.reserve(nb_vertices); + for (auto i = 0UL; i < nb_vertices; ++i) { + v.push_back(random_double(random_engine)); + } + std::sort(v.begin(), v.end()); + const auto min_v = v.front(); + const auto max_v = v.back(); + std::vector v1; + v1.push_back(min_v); + std::vector v2; + v2.push_back(min_v); + for (auto i = 1UL; i + 1 < v.size(); ++i) { + if (random_bool(random_engine) == 0) { + v1.push_back((v[i])); + } else { + v2.push_back((v[i])); + } + } + v1.push_back(max_v); + v2.push_back(max_v); + std::vector diffs; + for (auto i = 0UL; i + 1 < v1.size(); ++i) { + diffs.push_back(v1[i + 1] - v1[i]); + } + for (auto i = 0UL; i + 1 < v2.size(); ++i) { + diffs.push_back(v2[i] - v2[i + 1]); + } + VectorsWithMin vectors; + vectors.vectors = diffs; + vectors.min = min_v; + return vectors; +} +} // namespace +Polygon2d random_convex_polygon(const size_t vertices, const double max) +{ + std::random_device r; + std::default_random_engine random_engine(r()); + std::uniform_real_distribution uniform_dist(-max, max); + std::uniform_int_distribution random_bool(0, 1); + auto xs = prepare_coordinate_vectors(vertices, uniform_dist, random_bool, random_engine); + auto ys = prepare_coordinate_vectors(vertices, uniform_dist, random_bool, random_engine); + std::shuffle(ys.vectors.begin(), ys.vectors.end(), random_engine); + LinearRing2d vectors; + for (auto i = 0UL; i < xs.vectors.size(); ++i) { + vectors.emplace_back(xs.vectors[i], ys.vectors[i]); + } + std::sort(vectors.begin(), vectors.end(), [](const Point2d & p1, const Point2d & p2) { + return std::atan2(p1.y(), p1.x()) < std::atan2(p2.y(), p2.x()); + }); + auto min_x = max; + auto min_y = max; + auto x = 0.0; + auto y = 0.0; + LinearRing2d points; + for (const auto & p : vectors) { + points.emplace_back(x, y); + x += p.x(); + y += p.y(); + min_x = std::min(p.x(), min_x); + min_y = std::min(p.y(), min_y); + } + const auto shift_x = min_x - xs.min; + const auto shift_y = min_y - ys.min; + for (auto & p : points) { + p.x() += shift_x; + p.y() += shift_y; + } + Polygon2d poly; + poly.outer() = points; + boost::geometry::correct(poly); + return poly; +} +} // namespace autoware_utils diff --git a/autoware_utils/src/geometry/sat_2d.cpp b/autoware_utils/src/geometry/sat_2d.cpp new file mode 100644 index 0000000..4628966 --- /dev/null +++ b/autoware_utils/src/geometry/sat_2d.cpp @@ -0,0 +1,82 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/geometry/sat_2d.hpp" + +#include + +namespace autoware_utils::sat +{ + +namespace +{ +/// @brief calculate the edge normal of two points +Point2d edge_normal(const Point2d & p1, const Point2d & p2) +{ + return {p2.y() - p1.y(), p1.x() - p2.x()}; +} + +/// @brief project a polygon onto an axis and return the minimum and maximum values +std::pair project_polygon(const Polygon2d & poly, const Point2d & axis) +{ + double min = poly.outer()[0].dot(axis); + double max = min; + for (const auto & point : poly.outer()) { + double projection = point.dot(axis); + if (projection < min) { + min = projection; + } + if (projection > max) { + max = projection; + } + } + return {min, max}; +} + +/// @brief check if two projections overlap +bool projections_overlap( + const std::pair & proj1, const std::pair & proj2) +{ + return proj1.second >= proj2.first && proj2.second >= proj1.first; +} + +/// @brief check is all edges of a polygon can be separated from the other polygon with a separating +/// axis +bool has_no_separating_axis(const Polygon2d & polygon, const Polygon2d & other) +{ + for (size_t i = 0; i < polygon.outer().size(); ++i) { + const size_t next_i = (i + 1) % polygon.outer().size(); + const Point2d edge = edge_normal(polygon.outer()[i], polygon.outer()[next_i]); + const auto projection1 = project_polygon(polygon, edge); + const auto projection2 = project_polygon(other, edge); + if (!projections_overlap(projection1, projection2)) { + return false; + } + } + return true; +} +} // namespace + +/// @brief check if two convex polygons intersect using the SAT algorithm +/// @details this function uses the Separating Axis Theorem (SAT) to determine if two convex +/// polygons intersect. If projections overlap on all tested axes, the function returns `true`; +/// otherwise, it returns `false`. Note that touching polygons (e.g., at a point or along an edge) +/// will be considered as not intersecting. +bool intersects(const Polygon2d & convex_polygon1, const Polygon2d & convex_polygon2) +{ + return has_no_separating_axis(convex_polygon1, convex_polygon2) && + has_no_separating_axis(convex_polygon2, convex_polygon1); +} + +} // namespace autoware_utils::sat diff --git a/autoware_utils/src/math/sin_table.cpp b/autoware_utils/src/math/sin_table.cpp new file mode 100644 index 0000000..7b733f2 --- /dev/null +++ b/autoware_utils/src/math/sin_table.cpp @@ -0,0 +1,8215 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/math/sin_table.hpp" + +namespace autoware_utils +{ + +const float g_sin_table[sin_table_size] = { + 0.0000000000000000f, 0.0000479368996031f, 0.0000958737990960f, 0.0001438106983686f, + 0.0001917475973107f, 0.0002396844958122f, 0.0002876213937629f, 0.0003355582910527f, + 0.0003834951875714f, 0.0004314320832088f, 0.0004793689778549f, 0.0005273058713993f, + 0.0005752427637321f, 0.0006231796547429f, 0.0006711165443218f, 0.0007190534323584f, + 0.0007669903187427f, 0.0008149272033645f, 0.0008628640861136f, 0.0009108009668800f, + 0.0009587378455533f, 0.0010066747220235f, 0.0010546115961805f, 0.0011025484679140f, + 0.0011504853371138f, 0.0011984222036700f, 0.0012463590674722f, 0.0012942959284104f, + 0.0013422327863743f, 0.0013901696412539f, 0.0014381064929389f, 0.0014860433413193f, + 0.0015339801862848f, 0.0015819170277253f, 0.0016298538655306f, 0.0016777906995906f, + 0.0017257275297951f, 0.0017736643560340f, 0.0018216011781972f, 0.0018695379961743f, + 0.0019174748098554f, 0.0019654116191302f, 0.0020133484238887f, 0.0020612852240205f, + 0.0021092220194156f, 0.0021571588099639f, 0.0022050955955551f, 0.0022530323760791f, + 0.0023009691514258f, 0.0023489059214850f, 0.0023968426861465f, 0.0024447794453002f, + 0.0024927161988359f, 0.0025406529466435f, 0.0025885896886128f, 0.0026365264246337f, + 0.0026844631545960f, 0.0027323998783895f, 0.0027803365959041f, 0.0028282733070296f, + 0.0028762100116560f, 0.0029241467096729f, 0.0029720834009704f, 0.0030200200854381f, + 0.0030679567629660f, 0.0031158934334439f, 0.0031638300967616f, 0.0032117667528090f, + 0.0032597034014760f, 0.0033076400426523f, 0.0033555766762279f, 0.0034035133020925f, + 0.0034514499201360f, 0.0034993865302483f, 0.0035473231323191f, 0.0035952597262385f, + 0.0036431963118961f, 0.0036911328891818f, 0.0037390694579855f, 0.0037870060181970f, + 0.0038349425697062f, 0.0038828791124029f, 0.0039308156461770f, 0.0039787521709182f, + 0.0040266886865165f, 0.0040746251928617f, 0.0041225616898436f, 0.0041704981773521f, + 0.0042184346552770f, 0.0042663711235081f, 0.0043143075819354f, 0.0043622440304486f, + 0.0044101804689376f, 0.0044581168972923f, 0.0045060533154024f, 0.0045539897231579f, + 0.0046019261204486f, 0.0046498625071642f, 0.0046977988831948f, 0.0047457352484300f, + 0.0047936716027598f, 0.0048416079460740f, 0.0048895442782625f, 0.0049374805992150f, + 0.0049854169088215f, 0.0050333532069718f, 0.0050812894935556f, 0.0051292257684630f, + 0.0051771620315837f, 0.0052250982828075f, 0.0052730345220243f, 0.0053209707491240f, + 0.0053689069639963f, 0.0054168431665313f, 0.0054647793566185f, 0.0055127155341481f, + 0.0055606516990097f, 0.0056085878510932f, 0.0056565239902885f, 0.0057044601164854f, + 0.0057523962295737f, 0.0058003323294434f, 0.0058482684159842f, 0.0058962044890860f, + 0.0059441405486386f, 0.0059920765945320f, 0.0060400126266558f, 0.0060879486449000f, + 0.0061358846491545f, 0.0061838206393090f, 0.0062317566152534f, 0.0062796925768776f, + 0.0063276285240714f, 0.0063755644567246f, 0.0064235003747271f, 0.0064714362779688f, + 0.0065193721663395f, 0.0065673080397290f, 0.0066152438980271f, 0.0066631797411238f, + 0.0067111155689089f, 0.0067590513812722f, 0.0068069871781035f, 0.0068549229592928f, + 0.0069028587247298f, 0.0069507944743044f, 0.0069987302079064f, 0.0070466659254258f, + 0.0070946016267522f, 0.0071425373117757f, 0.0071904729803860f, 0.0072384086324730f, + 0.0072863442679265f, 0.0073342798866364f, 0.0073822154884925f, 0.0074301510733847f, + 0.0074780866412027f, 0.0075260221918366f, 0.0075739577251760f, 0.0076218932411109f, + 0.0076698287395311f, 0.0077177642203264f, 0.0077656996833868f, 0.0078136351286019f, + 0.0078615705558618f, 0.0079095059650562f, 0.0079574413560749f, 0.0080053767288079f, + 0.0080533120831450f, 0.0081012474189760f, 0.0081491827361907f, 0.0081971180346791f, + 0.0082450533143309f, 0.0082929885750360f, 0.0083409238166843f, 0.0083888590391656f, + 0.0084367942423698f, 0.0084847294261867f, 0.0085326645905061f, 0.0085805997352178f, + 0.0086285348602119f, 0.0086764699653780f, 0.0087244050506061f, 0.0087723401157859f, + 0.0088202751608074f, 0.0088682101855604f, 0.0089161451899347f, 0.0089640801738201f, + 0.0090120151371066f, 0.0090599500796840f, 0.0091078850014421f, 0.0091558199022707f, + 0.0092037547820598f, 0.0092516896406992f, 0.0092996244780786f, 0.0093475592940880f, + 0.0093954940886173f, 0.0094434288615561f, 0.0094913636127945f, 0.0095392983422223f, + 0.0095872330497292f, 0.0096351677352052f, 0.0096831023985401f, 0.0097310370396238f, + 0.0097789716583460f, 0.0098269062545967f, 0.0098748408282657f, 0.0099227753792429f, + 0.0099707099074180f, 0.0100186444126810f, 0.0100665788949217f, 0.0101145133540299f, + 0.0101624477898955f, 0.0102103822024084f, 0.0102583165914583f, 0.0103062509569352f, + 0.0103541852987288f, 0.0104021196167291f, 0.0104500539108259f, 0.0104979881809091f, + 0.0105459224268684f, 0.0105938566485937f, 0.0106417908459750f, 0.0106897250189019f, + 0.0107376591672645f, 0.0107855932909525f, 0.0108335273898558f, 0.0108814614638642f, + 0.0109293955128676f, 0.0109773295367558f, 0.0110252635354187f, 0.0110731975087462f, + 0.0111211314566280f, 0.0111690653789541f, 0.0112169992756143f, 0.0112649331464984f, + 0.0113128669914963f, 0.0113608008104978f, 0.0114087346033928f, 0.0114566683700712f, + 0.0115046021104227f, 0.0115525358243373f, 0.0116004695117048f, 0.0116484031724150f, + 0.0116963368063578f, 0.0117442704134231f, 0.0117922039935007f, 0.0118401375464804f, + 0.0118880710722521f, 0.0119360045707057f, 0.0119839380417309f, 0.0120318714852177f, + 0.0120798049010560f, 0.0121277382891354f, 0.0121756716493460f, 0.0122236049815776f, + 0.0122715382857199f, 0.0123194715616629f, 0.0123674048092965f, 0.0124153380285104f, + 0.0124632712191945f, 0.0125112043812387f, 0.0125591375145328f, 0.0126070706189667f, + 0.0126550036944302f, 0.0127029367408132f, 0.0127508697580056f, 0.0127988027458971f, + 0.0128467357043777f, 0.0128946686333371f, 0.0129426015326653f, 0.0129905344022521f, + 0.0130384672419873f, 0.0130864000517609f, 0.0131343328314626f, 0.0131822655809823f, + 0.0132301983002098f, 0.0132781309890351f, 0.0133260636473480f, 0.0133739962750382f, + 0.0134219288719958f, 0.0134698614381104f, 0.0135177939732721f, 0.0135657264773706f, + 0.0136136589502957f, 0.0136615913919375f, 0.0137095238021856f, 0.0137574561809299f, + 0.0138053885280604f, 0.0138533208434668f, 0.0139012531270390f, 0.0139491853786669f, + 0.0139971175982404f, 0.0140450497856492f, 0.0140929819407832f, 0.0141409140635323f, + 0.0141888461537863f, 0.0142367782114352f, 0.0142847102363687f, 0.0143326422284767f, + 0.0143805741876490f, 0.0144285061137756f, 0.0144764380067462f, 0.0145243698664507f, + 0.0145723016927791f, 0.0146202334856210f, 0.0146681652448665f, 0.0147160969704053f, + 0.0147640286621272f, 0.0148119603199223f, 0.0148598919436802f, 0.0149078235332910f, + 0.0149557550886443f, 0.0150036866096301f, 0.0150516180961383f, 0.0150995495480586f, + 0.0151474809652810f, 0.0151954123476953f, 0.0152433436951913f, 0.0152912750076590f, + 0.0153392062849881f, 0.0153871375270686f, 0.0154350687337902f, 0.0154829999050429f, + 0.0155309310407164f, 0.0155788621407008f, 0.0156267932048857f, 0.0156747242331611f, + 0.0157226552254169f, 0.0157705861815428f, 0.0158185171014287f, 0.0158664479849646f, + 0.0159143788320402f, 0.0159623096425454f, 0.0160102404163701f, 0.0160581711534041f, + 0.0161061018535373f, 0.0161540325166595f, 0.0162019631426607f, 0.0162498937314306f, + 0.0162978242828591f, 0.0163457547968361f, 0.0163936852732514f, 0.0164416157119949f, + 0.0164895461129564f, 0.0165374764760259f, 0.0165854068010931f, 0.0166333370880480f, + 0.0166812673367803f, 0.0167291975471800f, 0.0167771277191369f, 0.0168250578525408f, + 0.0168729879472817f, 0.0169209180032494f, 0.0169688480203336f, 0.0170167779984244f, + 0.0170647079374116f, 0.0171126378371849f, 0.0171605676976343f, 0.0172084975186497f, + 0.0172564273001209f, 0.0173043570419377f, 0.0173522867439900f, 0.0174002164061677f, + 0.0174481460283607f, 0.0174960756104587f, 0.0175440051523517f, 0.0175919346539296f, + 0.0176398641150821f, 0.0176877935356991f, 0.0177357229156705f, 0.0177836522548862f, + 0.0178315815532360f, 0.0178795108106098f, 0.0179274400268975f, 0.0179753692019888f, + 0.0180232983357737f, 0.0180712274281421f, 0.0181191564789837f, 0.0181670854881885f, + 0.0182150144556463f, 0.0182629433812470f, 0.0183108722648804f, 0.0183588011064364f, + 0.0184067299058048f, 0.0184546586628756f, 0.0185025873775386f, 0.0185505160496836f, + 0.0185984446792005f, 0.0186463732659792f, 0.0186943018099095f, 0.0187422303108814f, + 0.0187901587687846f, 0.0188380871835090f, 0.0188860155549445f, 0.0189339438829809f, + 0.0189818721675082f, 0.0190298004084161f, 0.0190777286055946f, 0.0191256567589335f, + 0.0191735848683226f, 0.0192215129336519f, 0.0192694409548112f, 0.0193173689316903f, + 0.0193652968641792f, 0.0194132247521676f, 0.0194611525955455f, 0.0195090803942027f, + 0.0195570081480291f, 0.0196049358569145f, 0.0196528635207489f, 0.0197007911394220f, + 0.0197487187128237f, 0.0197966462408440f, 0.0198445737233726f, 0.0198925011602995f, + 0.0199404285515144f, 0.0199883558969074f, 0.0200362831963681f, 0.0200842104497866f, + 0.0201321376570526f, 0.0201800648180560f, 0.0202279919326868f, 0.0202759190008347f, + 0.0203238460223896f, 0.0203717729972414f, 0.0204196999252800f, 0.0204676268063952f, + 0.0205155536404769f, 0.0205634804274149f, 0.0206114071670992f, 0.0206593338594196f, + 0.0207072605042659f, 0.0207551871015280f, 0.0208031136510959f, 0.0208510401528593f, + 0.0208989666067081f, 0.0209468930125323f, 0.0209948193702216f, 0.0210427456796659f, + 0.0210906719407551f, 0.0211385981533791f, 0.0211865243174277f, 0.0212344504327909f, + 0.0212823764993584f, 0.0213303025170201f, 0.0213782284856660f, 0.0214261544051858f, + 0.0214740802754695f, 0.0215220060964069f, 0.0215699318678879f, 0.0216178575898023f, + 0.0216657832620401f, 0.0217137088844910f, 0.0217616344570450f, 0.0218095599795920f, + 0.0218574854520217f, 0.0219054108742242f, 0.0219533362460891f, 0.0220012615675065f, + 0.0220491868383661f, 0.0220971120585579f, 0.0221450372279718f, 0.0221929623464975f, + 0.0222408874140250f, 0.0222888124304441f, 0.0223367373956447f, 0.0223846623095167f, + 0.0224325871719499f, 0.0224805119828343f, 0.0225284367420596f, 0.0225763614495159f, + 0.0226242861050928f, 0.0226722107086804f, 0.0227201352601684f, 0.0227680597594468f, + 0.0228159842064053f, 0.0228639086009340f, 0.0229118329429227f, 0.0229597572322612f, + 0.0230076814688394f, 0.0230556056525472f, 0.0231035297832744f, 0.0231514538609110f, + 0.0231993778853467f, 0.0232473018564716f, 0.0232952257741753f, 0.0233431496383480f, + 0.0233910734488793f, 0.0234389972056591f, 0.0234869209085774f, 0.0235348445575241f, + 0.0235827681523889f, 0.0236306916930618f, 0.0236786151794326f, 0.0237265386113912f, + 0.0237744619888276f, 0.0238223853116314f, 0.0238703085796928f, 0.0239182317929014f, + 0.0239661549511472f, 0.0240140780543201f, 0.0240620011023099f, 0.0241099240950065f, + 0.0241578470322999f, 0.0242057699140797f, 0.0242536927402361f, 0.0243016155106587f, + 0.0243495382252375f, 0.0243974608838624f, 0.0244453834864233f, 0.0244933060328099f, + 0.0245412285229123f, 0.0245891509566202f, 0.0246370733338236f, 0.0246849956544123f, + 0.0247329179182762f, 0.0247808401253052f, 0.0248287622753892f, 0.0248766843684180f, + 0.0249246064042815f, 0.0249725283828696f, 0.0250204503040721f, 0.0250683721677790f, + 0.0251162939738802f, 0.0251642157222654f, 0.0252121374128247f, 0.0252600590454477f, + 0.0253079806200246f, 0.0253559021364450f, 0.0254038235945990f, 0.0254517449943763f, + 0.0254996663356669f, 0.0255475876183606f, 0.0255955088423473f, 0.0256434300075169f, + 0.0256913511137593f, 0.0257392721609643f, 0.0257871931490219f, 0.0258351140778219f, + 0.0258830349472542f, 0.0259309557572087f, 0.0259788765075752f, 0.0260267971982436f, + 0.0260747178291039f, 0.0261226384000459f, 0.0261705589109594f, 0.0262184793617344f, + 0.0262663997522608f, 0.0263143200824283f, 0.0263622403521270f, 0.0264101605612467f, + 0.0264580807096772f, 0.0265060007973085f, 0.0265539208240304f, 0.0266018407897328f, + 0.0266497606943056f, 0.0266976805376387f, 0.0267456003196220f, 0.0267935200401453f, + 0.0268414396990985f, 0.0268893592963716f, 0.0269372788318543f, 0.0269851983054366f, + 0.0270331177170084f, 0.0270810370664596f, 0.0271289563536799f, 0.0271768755785594f, + 0.0272247947409879f, 0.0272727138408552f, 0.0273206328780514f, 0.0273685518524661f, + 0.0274164707639894f, 0.0274643896125112f, 0.0275123083979212f, 0.0275602271201094f, + 0.0276081457789657f, 0.0276560643743800f, 0.0277039829062421f, 0.0277519013744420f, + 0.0277998197788694f, 0.0278477381194144f, 0.0278956563959668f, 0.0279435746084164f, + 0.0279914927566532f, 0.0280394108405671f, 0.0280873288600479f, 0.0281352468149855f, + 0.0281831647052699f, 0.0282310825307908f, 0.0282790002914382f, 0.0283269179871020f, + 0.0283748356176721f, 0.0284227531830383f, 0.0284706706830906f, 0.0285185881177187f, + 0.0285665054868127f, 0.0286144227902624f, 0.0286623400279577f, 0.0287102571997885f, + 0.0287581743056446f, 0.0288060913454160f, 0.0288540083189926f, 0.0289019252262641f, + 0.0289498420671206f, 0.0289977588414520f, 0.0290456755491480f, 0.0290935921900986f, + 0.0291415087641937f, 0.0291894252713232f, 0.0292373417113770f, 0.0292852580842449f, + 0.0293331743898168f, 0.0293810906279827f, 0.0294290067986325f, 0.0294769229016559f, + 0.0295248389369430f, 0.0295727549043835f, 0.0296206708038675f, 0.0296685866352848f, + 0.0297165023985252f, 0.0297644180934787f, 0.0298123337200352f, 0.0298602492780845f, + 0.0299081647675166f, 0.0299560801882213f, 0.0300039955400885f, 0.0300519108230082f, + 0.0300998260368702f, 0.0301477411815644f, 0.0301956562569807f, 0.0302435712630091f, + 0.0302914861995393f, 0.0303394010664613f, 0.0303873158636650f, 0.0304352305910403f, + 0.0304831452484770f, 0.0305310598358651f, 0.0305789743530945f, 0.0306268888000550f, + 0.0306748031766366f, 0.0307227174827292f, 0.0307706317182225f, 0.0308185458830067f, + 0.0308664599769714f, 0.0309143740000067f, 0.0309622879520024f, 0.0310102018328484f, + 0.0310581156424347f, 0.0311060293806511f, 0.0311539430473875f, 0.0312018566425338f, + 0.0312497701659799f, 0.0312976836176157f, 0.0313455969973311f, 0.0313935103050160f, + 0.0314414235405603f, 0.0314893367038539f, 0.0315372497947867f, 0.0315851628132486f, + 0.0316330757591295f, 0.0316809886323193f, 0.0317289014327078f, 0.0317768141601851f, + 0.0318247268146409f, 0.0318726393959652f, 0.0319205519040479f, 0.0319684643387789f, + 0.0320163767000481f, 0.0320642889877453f, 0.0321122012017606f, 0.0321601133419837f, + 0.0322080254083046f, 0.0322559374006132f, 0.0323038493187994f, 0.0323517611627530f, + 0.0323996729323641f, 0.0324475846275224f, 0.0324954962481180f, 0.0325434077940406f, + 0.0325913192651802f, 0.0326392306614268f, 0.0326871419826701f, 0.0327350532288001f, + 0.0327829643997067f, 0.0328308754952799f, 0.0328787865154094f, 0.0329266974599853f, + 0.0329746083288973f, 0.0330225191220355f, 0.0330704298392897f, 0.0331183404805499f, + 0.0331662510457059f, 0.0332141615346476f, 0.0332620719472649f, 0.0333099822834478f, + 0.0333578925430861f, 0.0334058027260698f, 0.0334537128322888f, 0.0335016228616329f, + 0.0335495328139921f, 0.0335974426892562f, 0.0336453524873153f, 0.0336932622080591f, + 0.0337411718513776f, 0.0337890814171607f, 0.0338369909052983f, 0.0338849003156803f, + 0.0339328096481967f, 0.0339807189027372f, 0.0340286280791919f, 0.0340765371774506f, + 0.0341244461974033f, 0.0341723551389399f, 0.0342202640019501f, 0.0342681727863241f, + 0.0343160814919517f, 0.0343639901187227f, 0.0344118986665271f, 0.0344598071352548f, + 0.0345077155247957f, 0.0345556238350398f, 0.0346035320658769f, 0.0346514402171969f, + 0.0346993482888898f, 0.0347472562808454f, 0.0347951641929537f, 0.0348430720251046f, + 0.0348909797771880f, 0.0349388874490938f, 0.0349867950407119f, 0.0350347025519322f, + 0.0350826099826446f, 0.0351305173327391f, 0.0351784246021056f, 0.0352263317906339f, + 0.0352742388982139f, 0.0353221459247357f, 0.0353700528700891f, 0.0354179597341640f, + 0.0354658665168504f, 0.0355137732180380f, 0.0355616798376170f, 0.0356095863754770f, + 0.0356574928315082f, 0.0357053992056004f, 0.0357533054976435f, 0.0358012117075274f, + 0.0358491178351420f, 0.0358970238803773f, 0.0359449298431232f, 0.0359928357232695f, + 0.0360407415207062f, 0.0360886472353233f, 0.0361365528670105f, 0.0361844584156579f, + 0.0362323638811554f, 0.0362802692633928f, 0.0363281745622601f, 0.0363760797776473f, + 0.0364239849094441f, 0.0364718899575406f, 0.0365197949218266f, 0.0365676998021921f, + 0.0366156045985270f, 0.0366635093107212f, 0.0367114139386647f, 0.0367593184822472f, + 0.0368072229413588f, 0.0368551273158894f, 0.0369030316057289f, 0.0369509358107672f, + 0.0369988399308943f, 0.0370467439660000f, 0.0370946479159742f, 0.0371425517807070f, + 0.0371904555600881f, 0.0372383592540076f, 0.0372862628623553f, 0.0373341663850212f, + 0.0373820698218952f, 0.0374299731728672f, 0.0374778764378272f, 0.0375257796166649f, + 0.0375736827092705f, 0.0376215857155337f, 0.0376694886353446f, 0.0377173914685930f, + 0.0377652942151689f, 0.0378131968749621f, 0.0378610994478626f, 0.0379090019337604f, + 0.0379569043325453f, 0.0380048066441073f, 0.0380527088683363f, 0.0381006110051222f, + 0.0381485130543549f, 0.0381964150159244f, 0.0382443168897206f, 0.0382922186756334f, + 0.0383401203735527f, 0.0383880219833685f, 0.0384359235049707f, 0.0384838249382492f, + 0.0385317262830939f, 0.0385796275393948f, 0.0386275287070417f, 0.0386754297859247f, + 0.0387233307759336f, 0.0387712316769584f, 0.0388191324888890f, 0.0388670332116153f, + 0.0389149338450272f, 0.0389628343890147f, 0.0390107348434677f, 0.0390586352082761f, + 0.0391065354833299f, 0.0391544356685189f, 0.0392023357637332f, 0.0392502357688626f, + 0.0392981356837971f, 0.0393460355084265f, 0.0393939352426409f, 0.0394418348863301f, + 0.0394897344393841f, 0.0395376339016928f, 0.0395855332731462f, 0.0396334325536341f, + 0.0396813317430465f, 0.0397292308412734f, 0.0397771298482046f, 0.0398250287637301f, + 0.0398729275877398f, 0.0399208263201237f, 0.0399687249607716f, 0.0400166235095736f, + 0.0400645219664195f, 0.0401124203311993f, 0.0401603186038029f, 0.0402082167841203f, + 0.0402561148720413f, 0.0403040128674559f, 0.0403519107702541f, 0.0403998085803257f, + 0.0404477062975608f, 0.0404956039218492f, 0.0405435014530808f, 0.0405913988911457f, + 0.0406392962359337f, 0.0406871934873348f, 0.0407350906452389f, 0.0407829877095360f, + 0.0408308846801159f, 0.0408787815568687f, 0.0409266783396842f, 0.0409745750284524f, + 0.0410224716230632f, 0.0410703681234066f, 0.0411182645293725f, 0.0411661608408508f, + 0.0412140570577315f, 0.0412619531799045f, 0.0413098492072598f, 0.0413577451396872f, + 0.0414056409770767f, 0.0414535367193183f, 0.0415014323663020f, 0.0415493279179175f, + 0.0415972233740549f, 0.0416451187346041f, 0.0416930139994551f, 0.0417409091684978f, + 0.0417888042416221f, 0.0418366992187179f, 0.0418845940996753f, 0.0419324888843841f, + 0.0419803835727344f, 0.0420282781646159f, 0.0420761726599187f, 0.0421240670585328f, + 0.0421719613603479f, 0.0422198555652542f, 0.0422677496731415f, 0.0423156436838999f, + 0.0423635375974191f, 0.0424114314135892f, 0.0424593251323000f, 0.0425072187534417f, + 0.0425551122769040f, 0.0426030057025770f, 0.0426508990303505f, 0.0426987922601146f, + 0.0427466853917591f, 0.0427945784251741f, 0.0428424713602494f, 0.0428903641968750f, + 0.0429382569349408f, 0.0429861495743369f, 0.0430340421149530f, 0.0430819345566793f, + 0.0431298268994055f, 0.0431777191430218f, 0.0432256112874180f, 0.0432735033324840f, + 0.0433213952781098f, 0.0433692871241854f, 0.0434171788706007f, 0.0434650705172457f, + 0.0435129620640102f, 0.0435608535107843f, 0.0436087448574579f, 0.0436566361039210f, + 0.0437045272500634f, 0.0437524182957752f, 0.0438003092409463f, 0.0438482000854666f, + 0.0438960908292261f, 0.0439439814721147f, 0.0439918720140224f, 0.0440397624548392f, + 0.0440876527944549f, 0.0441355430327596f, 0.0441834331696432f, 0.0442313232049956f, + 0.0442792131387068f, 0.0443271029706668f, 0.0443749927007655f, 0.0444228823288928f, + 0.0444707718549387f, 0.0445186612787931f, 0.0445665506003461f, 0.0446144398194875f, + 0.0446623289361073f, 0.0447102179500955f, 0.0447581068613420f, 0.0448059956697368f, + 0.0448538843751698f, 0.0449017729775310f, 0.0449496614767103f, 0.0449975498725977f, + 0.0450454381650832f, 0.0450933263540567f, 0.0451412144394081f, 0.0451891024210274f, + 0.0452369902988046f, 0.0452848780726296f, 0.0453327657423924f, 0.0453806533079829f, + 0.0454285407692912f, 0.0454764281262070f, 0.0455243153786205f, 0.0455722025264216f, + 0.0456200895695001f, 0.0456679765077462f, 0.0457158633410497f, 0.0457637500693006f, + 0.0458116366923889f, 0.0458595232102044f, 0.0459074096226373f, 0.0459552959295773f, + 0.0460031821309146f, 0.0460510682265391f, 0.0460989542163406f, 0.0461468401002092f, + 0.0461947258780349f, 0.0462426115497076f, 0.0462904971151172f, 0.0463383825741537f, + 0.0463862679267072f, 0.0464341531726674f, 0.0464820383119245f, 0.0465299233443684f, + 0.0465778082698889f, 0.0466256930883762f, 0.0466735777997202f, 0.0467214624038107f, + 0.0467693469005379f, 0.0468172312897916f, 0.0468651155714618f, 0.0469129997454385f, + 0.0469608838116116f, 0.0470087677698711f, 0.0470566516201071f, 0.0471045353622093f, + 0.0471524189960679f, 0.0472003025215727f, 0.0472481859386138f, 0.0472960692470810f, + 0.0473439524468645f, 0.0473918355378541f, 0.0474397185199397f, 0.0474876013930115f, + 0.0475354841569593f, 0.0475833668116731f, 0.0476312493570429f, 0.0476791317929586f, + 0.0477270141193103f, 0.0477748963359878f, 0.0478227784428812f, 0.0478706604398803f, + 0.0479185423268753f, 0.0479664241037561f, 0.0480143057704126f, 0.0480621873267347f, + 0.0481100687726126f, 0.0481579501079361f, 0.0482058313325952f, 0.0482537124464799f, + 0.0483015934494801f, 0.0483494743414859f, 0.0483973551223872f, 0.0484452357920740f, + 0.0484931163504362f, 0.0485409967973638f, 0.0485888771327468f, 0.0486367573564752f, + 0.0486846374684389f, 0.0487325174685280f, 0.0487803973566323f, 0.0488282771326419f, + 0.0488761567964468f, 0.0489240363479368f, 0.0489719157870021f, 0.0490197951135325f, + 0.0490676743274180f, 0.0491155534285487f, 0.0491634324168144f, 0.0492113112921053f, + 0.0492591900543111f, 0.0493070687033220f, 0.0493549472390279f, 0.0494028256613188f, + 0.0494507039700847f, 0.0494985821652154f, 0.0495464602466011f, 0.0495943382141317f, + 0.0496422160676972f, 0.0496900938071875f, 0.0497379714324926f, 0.0497858489435025f, + 0.0498337263401073f, 0.0498816036221968f, 0.0499294807896610f, 0.0499773578423900f, + 0.0500252347802737f, 0.0500731116032021f, 0.0501209883110652f, 0.0501688649037529f, + 0.0502167413811553f, 0.0502646177431623f, 0.0503124939896639f, 0.0503603701205501f, + 0.0504082461357109f, 0.0504561220350362f, 0.0505039978184160f, 0.0505518734857404f, + 0.0505997490368993f, 0.0506476244717827f, 0.0506954997902805f, 0.0507433749922828f, + 0.0507912500776796f, 0.0508391250463608f, 0.0508869998982164f, 0.0509348746331364f, + 0.0509827492510108f, 0.0510306237517296f, 0.0510784981351827f, 0.0511263724012602f, + 0.0511742465498521f, 0.0512221205808482f, 0.0512699944941387f, 0.0513178682896135f, + 0.0513657419671626f, 0.0514136155266760f, 0.0514614889680436f, 0.0515093622911555f, + 0.0515572354959016f, 0.0516051085821720f, 0.0516529815498566f, 0.0517008543988454f, + 0.0517487271290285f, 0.0517965997402957f, 0.0518444722325371f, 0.0518923446056427f, + 0.0519402168595025f, 0.0519880889940065f, 0.0520359610090446f, 0.0520838329045069f, + 0.0521317046802833f, 0.0521795763362639f, 0.0522274478723386f, 0.0522753192883974f, + 0.0523231905843303f, 0.0523710617600274f, 0.0524189328153786f, 0.0524668037502738f, + 0.0525146745646032f, 0.0525625452582567f, 0.0526104158311242f, 0.0526582862830959f, + 0.0527061566140616f, 0.0527540268239114f, 0.0528018969125353f, 0.0528497668798233f, + 0.0528976367256653f, 0.0529455064499514f, 0.0529933760525716f, 0.0530412455334158f, + 0.0530891148923741f, 0.0531369841293365f, 0.0531848532441929f, 0.0532327222368334f, + 0.0532805911071479f, 0.0533284598550266f, 0.0533763284803592f, 0.0534241969830359f, + 0.0534720653629467f, 0.0535199336199816f, 0.0535678017540305f, 0.0536156697649835f, + 0.0536635376527305f, 0.0537114054171616f, 0.0537592730581668f, 0.0538071405756361f, + 0.0538550079694594f, 0.0539028752395269f, 0.0539507423857284f, 0.0539986094079540f, + 0.0540464763060937f, 0.0540943430800375f, 0.0541422097296753f, 0.0541900762548973f, + 0.0542379426555935f, 0.0542858089316537f, 0.0543336750829680f, 0.0543815411094265f, + 0.0544294070109191f, 0.0544772727873359f, 0.0545251384385668f, 0.0545730039645019f, + 0.0546208693650311f, 0.0546687346400445f, 0.0547165997894321f, 0.0547644648130839f, + 0.0548123297108899f, 0.0548601944827400f, 0.0549080591285244f, 0.0549559236481331f, + 0.0550037880414559f, 0.0550516523083830f, 0.0550995164488044f, 0.0551473804626100f, + 0.0551952443496899f, 0.0552431081099341f, 0.0552909717432326f, 0.0553388352494755f, + 0.0553866986285526f, 0.0554345618803541f, 0.0554824250047699f, 0.0555302880016901f, + 0.0555781508710047f, 0.0556260136126037f, 0.0556738762263770f, 0.0557217387122148f, + 0.0557696010700070f, 0.0558174632996437f, 0.0558653254010148f, 0.0559131873740105f, + 0.0559610492185206f, 0.0560089109344352f, 0.0560567725216443f, 0.0561046339800380f, + 0.0561524953095063f, 0.0562003565099391f, 0.0562482175812266f, 0.0562960785232586f, + 0.0563439393359253f, 0.0563918000191166f, 0.0564396605727226f, 0.0564875209966333f, + 0.0565353812907387f, 0.0565832414549288f, 0.0566311014890937f, 0.0566789613931233f, + 0.0567268211669077f, 0.0567746808103370f, 0.0568225403233010f, 0.0568703997056900f, + 0.0569182589573937f, 0.0569661180783024f, 0.0570139770683060f, 0.0570618359272946f, + 0.0571096946551581f, 0.0571575532517865f, 0.0572054117170700f, 0.0572532700508986f, + 0.0573011282531622f, 0.0573489863237508f, 0.0573968442625546f, 0.0574447020694635f, + 0.0574925597443676f, 0.0575404172871568f, 0.0575882746977213f, 0.0576361319759510f, + 0.0576839891217359f, 0.0577318461349662f, 0.0577797030155317f, 0.0578275597633226f, + 0.0578754163782289f, 0.0579232728601405f, 0.0579711292089476f, 0.0580189854245402f, + 0.0580668415068082f, 0.0581146974556417f, 0.0581625532709308f, 0.0582104089525655f, + 0.0582582645004358f, 0.0583061199144317f, 0.0583539751944432f, 0.0584018303403605f, + 0.0584496853520735f, 0.0584975402294722f, 0.0585453949724468f, 0.0585932495808871f, + 0.0586411040546833f, 0.0586889583937254f, 0.0587368125979035f, 0.0587846666671075f, + 0.0588325206012274f, 0.0588803744001534f, 0.0589282280637755f, 0.0589760815919836f, + 0.0590239349846679f, 0.0590717882417184f, 0.0591196413630250f, 0.0591674943484779f, + 0.0592153471979671f, 0.0592631999113825f, 0.0593110524886143f, 0.0593589049295525f, + 0.0594067572340871f, 0.0594546094021082f, 0.0595024614335058f, 0.0595503133281699f, + 0.0595981650859906f, 0.0596460167068579f, 0.0596938681906618f, 0.0597417195372925f, + 0.0597895707466399f, 0.0598374218185940f, 0.0598852727530450f, 0.0599331235498828f, + 0.0599809742089976f, 0.0600288247302792f, 0.0600766751136179f, 0.0601245253589035f, + 0.0601723754660263f, 0.0602202254348761f, 0.0602680752653431f, 0.0603159249573173f, + 0.0603637745106887f, 0.0604116239253475f, 0.0604594732011835f, 0.0605073223380869f, + 0.0605551713359478f, 0.0606030201946561f, 0.0606508689141019f, 0.0606987174941753f, + 0.0607465659347663f, 0.0607944142357649f, 0.0608422623970612f, 0.0608901104185453f, + 0.0609379583001072f, 0.0609858060416369f, 0.0610336536430245f, 0.0610815011041601f, + 0.0611293484249336f, 0.0611771956052352f, 0.0612250426449548f, 0.0612728895439826f, + 0.0613207363022086f, 0.0613685829195228f, 0.0614164293958153f, 0.0614642757309761f, + 0.0615121219248954f, 0.0615599679774631f, 0.0616078138885692f, 0.0616556596581040f, + 0.0617035052859573f, 0.0617513507720193f, 0.0617991961161800f, 0.0618470413183294f, + 0.0618948863783577f, 0.0619427312961549f, 0.0619905760716109f, 0.0620384207046160f, + 0.0620862651950601f, 0.0621341095428333f, 0.0621819537478256f, 0.0622297978099272f, + 0.0622776417290280f, 0.0623254855050181f, 0.0623733291377876f, 0.0624211726272266f, + 0.0624690159732250f, 0.0625168591756730f, 0.0625647022344606f, 0.0626125451494779f, + 0.0626603879206149f, 0.0627082305477617f, 0.0627560730308083f, 0.0628039153696449f, + 0.0628517575641614f, 0.0628995996142480f, 0.0629474415197946f, 0.0629952832806914f, + 0.0630431248968285f, 0.0630909663680958f, 0.0631388076943835f, 0.0631866488755815f, + 0.0632344899115801f, 0.0632823308022692f, 0.0633301715475388f, 0.0633780121472792f, + 0.0634258526013802f, 0.0634736929097321f, 0.0635215330722248f, 0.0635693730887485f, + 0.0636172129591931f, 0.0636650526834488f, 0.0637128922614056f, 0.0637607316929536f, + 0.0638085709779829f, 0.0638564101163835f, 0.0639042491080455f, 0.0639520879528589f, + 0.0639999266507139f, 0.0640477652015005f, 0.0640956036051088f, 0.0641434418614288f, + 0.0641912799703506f, 0.0642391179317643f, 0.0642869557455600f, 0.0643347934116277f, + 0.0643826309298575f, 0.0644304683001394f, 0.0644783055223636f, 0.0645261425964201f, + 0.0645739795221990f, 0.0646218162995903f, 0.0646696529284842f, 0.0647174894087707f, + 0.0647653257403399f, 0.0648131619230818f, 0.0648609979568866f, 0.0649088338416442f, + 0.0649566695772449f, 0.0650045051635786f, 0.0650523406005354f, 0.0651001758880055f, + 0.0651480110258788f, 0.0651958460140455f, 0.0652436808523957f, 0.0652915155408194f, + 0.0653393500792066f, 0.0653871844674476f, 0.0654350187054323f, 0.0654828527930509f, + 0.0655306867301933f, 0.0655785205167498f, 0.0656263541526103f, 0.0656741876376650f, + 0.0657220209718040f, 0.0657698541549172f, 0.0658176871868949f, 0.0658655200676271f, + 0.0659133527970038f, 0.0659611853749152f, 0.0660090178012513f, 0.0660568500759022f, + 0.0661046821987581f, 0.0661525141697089f, 0.0662003459886448f, 0.0662481776554558f, + 0.0662960091700321f, 0.0663438405322638f, 0.0663916717420408f, 0.0664395027992533f, + 0.0664873337037915f, 0.0665351644555453f, 0.0665829950544048f, 0.0666308255002602f, + 0.0666786557930016f, 0.0667264859325189f, 0.0667743159187024f, 0.0668221457514421f, + 0.0668699754306281f, 0.0669178049561505f, 0.0669656343278993f, 0.0670134635457648f, + 0.0670612926096368f, 0.0671091215194056f, 0.0671569502749613f, 0.0672047788761939f, + 0.0672526073229935f, 0.0673004356152502f, 0.0673482637528542f, 0.0673960917356954f, + 0.0674439195636641f, 0.0674917472366502f, 0.0675395747545439f, 0.0675874021172353f, + 0.0676352293246145f, 0.0676830563765715f, 0.0677308832729965f, 0.0677787100137796f, + 0.0678265365988109f, 0.0678743630279804f, 0.0679221893011782f, 0.0679700154182945f, + 0.0680178413792194f, 0.0680656671838429f, 0.0681134928320552f, 0.0681613183237463f, + 0.0682091436588063f, 0.0682569688371254f, 0.0683047938585937f, 0.0683526187231012f, + 0.0684004434305380f, 0.0684482679807943f, 0.0684960923737602f, 0.0685439166093257f, + 0.0685917406873809f, 0.0686395646078161f, 0.0686873883705212f, 0.0687352119753863f, + 0.0687830354223016f, 0.0688308587111572f, 0.0688786818418432f, 0.0689265048142497f, + 0.0689743276282667f, 0.0690221502837845f, 0.0690699727806930f, 0.0691177951188825f, + 0.0691656172982430f, 0.0692134393186646f, 0.0692612611800374f, 0.0693090828822516f, + 0.0693569044251972f, 0.0694047258087644f, 0.0694525470328432f, 0.0695003680973238f, + 0.0695481890020963f, 0.0695960097470508f, 0.0696438303320774f, 0.0696916507570662f, + 0.0697394710219073f, 0.0697872911264909f, 0.0698351110707070f, 0.0698829308544458f, + 0.0699307504775973f, 0.0699785699400517f, 0.0700263892416992f, 0.0700742083824298f, + 0.0701220273621335f, 0.0701698461807007f, 0.0702176648380212f, 0.0702654833339854f, + 0.0703133016684832f, 0.0703611198414049f, 0.0704089378526405f, 0.0704567557020801f, + 0.0705045733896139f, 0.0705523909151319f, 0.0706002082785243f, 0.0706480254796813f, + 0.0706958425184929f, 0.0707436593948492f, 0.0707914761086404f, 0.0708392926597565f, + 0.0708871090480878f, 0.0709349252735243f, 0.0709827413359562f, 0.0710305572352735f, + 0.0710783729713664f, 0.0711261885441250f, 0.0711740039534395f, 0.0712218191991999f, + 0.0712696342812964f, 0.0713174491996191f, 0.0713652639540581f, 0.0714130785445036f, + 0.0714608929708457f, 0.0715087072329744f, 0.0715565213307800f, 0.0716043352641526f, + 0.0716521490329822f, 0.0716999626371590f, 0.0717477760765732f, 0.0717955893511148f, + 0.0718434024606740f, 0.0718912154051410f, 0.0719390281844057f, 0.0719868407983585f, + 0.0720346532468893f, 0.0720824655298884f, 0.0721302776472458f, 0.0721780895988518f, + 0.0722259013845963f, 0.0722737130043696f, 0.0723215244580618f, 0.0723693357455630f, + 0.0724171468667634f, 0.0724649578215530f, 0.0725127686098221f, 0.0725605792314607f, + 0.0726083896863590f, 0.0726561999744071f, 0.0727040100954952f, 0.0727518200495133f, + 0.0727996298363517f, 0.0728474394559004f, 0.0728952489080496f, 0.0729430581926894f, + 0.0729908673097100f, 0.0730386762590016f, 0.0730864850404541f, 0.0731342936539578f, + 0.0731821020994029f, 0.0732299103766794f, 0.0732777184856775f, 0.0733255264262873f, + 0.0733733341983990f, 0.0734211418019027f, 0.0734689492366886f, 0.0735167565026468f, + 0.0735645635996674f, 0.0736123705276406f, 0.0736601772864565f, 0.0737079838760053f, + 0.0737557902961771f, 0.0738035965468620f, 0.0738514026279503f, 0.0738992085393319f, + 0.0739470142808972f, 0.0739948198525362f, 0.0740426252541390f, 0.0740904304855959f, + 0.0741382355467970f, 0.0741860404376323f, 0.0742338451579922f, 0.0742816497077666f, + 0.0743294540868458f, 0.0743772582951198f, 0.0744250623324790f, 0.0744728661988133f, + 0.0745206698940130f, 0.0745684734179682f, 0.0746162767705690f, 0.0746640799517056f, + 0.0747118829612682f, 0.0747596857991469f, 0.0748074884652318f, 0.0748552909594132f, + 0.0749030932815811f, 0.0749508954316257f, 0.0749986974094372f, 0.0750464992149057f, + 0.0750943008479213f, 0.0751421023083743f, 0.0751899035961548f, 0.0752377047111529f, + 0.0752855056532588f, 0.0753333064223626f, 0.0753811070183546f, 0.0754289074411248f, + 0.0754767076905634f, 0.0755245077665606f, 0.0755723076690065f, 0.0756201073977914f, + 0.0756679069528052f, 0.0757157063339383f, 0.0757635055410808f, 0.0758113045741228f, + 0.0758591034329544f, 0.0759069021174660f, 0.0759547006275475f, 0.0760024989630892f, + 0.0760502971239813f, 0.0760980951101138f, 0.0761458929213770f, 0.0761936905576610f, + 0.0762414880188561f, 0.0762892853048522f, 0.0763370824155397f, 0.0763848793508087f, + 0.0764326761105493f, 0.0764804726946517f, 0.0765282691030061f, 0.0765760653355026f, + 0.0766238613920315f, 0.0766716572724828f, 0.0767194529767468f, 0.0767672485047136f, + 0.0768150438562733f, 0.0768628390313163f, 0.0769106340297325f, 0.0769584288514122f, + 0.0770062234962456f, 0.0770540179641229f, 0.0771018122549341f, 0.0771496063685695f, + 0.0771974003049192f, 0.0772451940638735f, 0.0772929876453224f, 0.0773407810491562f, + 0.0773885742752650f, 0.0774363673235391f, 0.0774841601938685f, 0.0775319528861435f, + 0.0775797454002542f, 0.0776275377360909f, 0.0776753298935436f, 0.0777231218725025f, + 0.0777709136728579f, 0.0778187052945000f, 0.0778664967373188f, 0.0779142880012046f, + 0.0779620790860475f, 0.0780098699917377f, 0.0780576607181655f, 0.0781054512652209f, + 0.0781532416327942f, 0.0782010318207756f, 0.0782488218290552f, 0.0782966116575231f, + 0.0783444013060697f, 0.0783921907745850f, 0.0784399800629593f, 0.0784877691710827f, + 0.0785355580988455f, 0.0785833468461377f, 0.0786311354128496f, 0.0786789237988714f, + 0.0787267120040933f, 0.0787745000284054f, 0.0788222878716979f, 0.0788700755338610f, + 0.0789178630147849f, 0.0789656503143599f, 0.0790134374324759f, 0.0790612243690234f, + 0.0791090111238924f, 0.0791567976969731f, 0.0792045840881558f, 0.0792523702973305f, + 0.0793001563243876f, 0.0793479421692172f, 0.0793957278317094f, 0.0794435133117546f, + 0.0794912986092428f, 0.0795390837240642f, 0.0795868686561091f, 0.0796346534052677f, + 0.0796824379714301f, 0.0797302223544866f, 0.0797780065543272f, 0.0798257905708423f, + 0.0798735744039220f, 0.0799213580534565f, 0.0799691415193360f, 0.0800169248014508f, + 0.0800647078996909f, 0.0801124908139466f, 0.0801602735441081f, 0.0802080560900656f, + 0.0802558384517093f, 0.0803036206289294f, 0.0803514026216161f, 0.0803991844296596f, + 0.0804469660529500f, 0.0804947474913776f, 0.0805425287448327f, 0.0805903098132053f, + 0.0806380906963857f, 0.0806858713942641f, 0.0807336519067307f, 0.0807814322336757f, + 0.0808292123749893f, 0.0808769923305618f, 0.0809247721002832f, 0.0809725516840438f, + 0.0810203310817339f, 0.0810681102932436f, 0.0811158893184631f, 0.0811636681572826f, + 0.0812114468095924f, 0.0812592252752827f, 0.0813070035542436f, 0.0813547816463654f, + 0.0814025595515383f, 0.0814503372696524f, 0.0814981148005980f, 0.0815458921442654f, + 0.0815936693005447f, 0.0816414462693260f, 0.0816892230504998f, 0.0817369996439560f, + 0.0817847760495851f, 0.0818325522672771f, 0.0818803282969223f, 0.0819281041384109f, + 0.0819758797916331f, 0.0820236552564791f, 0.0820714305328392f, 0.0821192056206035f, + 0.0821669805196623f, 0.0822147552299058f, 0.0822625297512242f, 0.0823103040835077f, + 0.0823580782266465f, 0.0824058521805310f, 0.0824536259450511f, 0.0825013995200973f, + 0.0825491729055597f, 0.0825969461013285f, 0.0826447191072939f, 0.0826924919233463f, + 0.0827402645493757f, 0.0827880369852724f, 0.0828358092309267f, 0.0828835812862287f, + 0.0829313531510687f, 0.0829791248253369f, 0.0830268963089235f, 0.0830746676017188f, + 0.0831224387036129f, 0.0831702096144962f, 0.0832179803342587f, 0.0832657508627908f, + 0.0833135211999827f, 0.0833612913457246f, 0.0834090612999066f, 0.0834568310624192f, + 0.0835046006331524f, 0.0835523700119966f, 0.0836001391988418f, 0.0836479081935785f, + 0.0836956769960967f, 0.0837434456062868f, 0.0837912140240389f, 0.0838389822492433f, + 0.0838867502817902f, 0.0839345181215699f, 0.0839822857684725f, 0.0840300532223884f, + 0.0840778204832077f, 0.0841255875508207f, 0.0841733544251176f, 0.0842211211059886f, + 0.0842688875933241f, 0.0843166538870141f, 0.0843644199869490f, 0.0844121858930190f, + 0.0844599516051143f, 0.0845077171231252f, 0.0845554824469419f, 0.0846032475764546f, + 0.0846510125115536f, 0.0846987772521291f, 0.0847465417980714f, 0.0847943061492707f, + 0.0848420703056171f, 0.0848898342670011f, 0.0849375980333128f, 0.0849853616044424f, + 0.0850331249802803f, 0.0850808881607166f, 0.0851286511456415f, 0.0851764139349454f, + 0.0852241765285185f, 0.0852719389262510f, 0.0853197011280331f, 0.0853674631337551f, + 0.0854152249433073f, 0.0854629865565799f, 0.0855107479734632f, 0.0855585091938473f, + 0.0856062702176225f, 0.0856540310446792f, 0.0857017916749074f, 0.0857495521081976f, + 0.0857973123444399f, 0.0858450723835246f, 0.0858928322253418f, 0.0859405918697820f, + 0.0859883513167353f, 0.0860361105660920f, 0.0860838696177423f, 0.0861316284715766f, + 0.0861793871274849f, 0.0862271455853576f, 0.0862749038450850f, 0.0863226619065573f, + 0.0863704197696648f, 0.0864181774342976f, 0.0864659349003461f, 0.0865136921677006f, + 0.0865614492362512f, 0.0866092061058882f, 0.0866569627765020f, 0.0867047192479826f, + 0.0867524755202205f, 0.0868002315931059f, 0.0868479874665290f, 0.0868957431403801f, + 0.0869434986145494f, 0.0869912538889272f, 0.0870390089634038f, 0.0870867638378694f, + 0.0871345185122143f, 0.0871822729863288f, 0.0872300272601030f, 0.0872777813334274f, + 0.0873255352061921f, 0.0873732888782874f, 0.0874210423496035f, 0.0874687956200308f, + 0.0875165486894595f, 0.0875643015577799f, 0.0876120542248822f, 0.0876598066906567f, + 0.0877075589549937f, 0.0877553110177834f, 0.0878030628789161f, 0.0878508145382821f, + 0.0878985659957716f, 0.0879463172512749f, 0.0879940683046823f, 0.0880418191558841f, + 0.0880895698047705f, 0.0881373202512318f, 0.0881850704951582f, 0.0882328205364401f, + 0.0882805703749677f, 0.0883283200106313f, 0.0883760694433212f, 0.0884238186729276f, + 0.0884715676993408f, 0.0885193165224510f, 0.0885670651421487f, 0.0886148135583240f, + 0.0886625617708671f, 0.0887103097796685f, 0.0887580575846184f, 0.0888058051856070f, + 0.0888535525825246f, 0.0889012997752615f, 0.0889490467637080f, 0.0889967935477544f, + 0.0890445401272909f, 0.0890922865022078f, 0.0891400326723955f, 0.0891877786377441f, + 0.0892355243981440f, 0.0892832699534855f, 0.0893310153036588f, 0.0893787604485542f, + 0.0894265053880620f, 0.0894742501220725f, 0.0895219946504760f, 0.0895697389731627f, + 0.0896174830900230f, 0.0896652270009471f, 0.0897129707058253f, 0.0897607142045480f, + 0.0898084574970053f, 0.0898562005830876f, 0.0899039434626852f, 0.0899516861356884f, + 0.0899994286019873f, 0.0900471708614725f, 0.0900949129140341f, 0.0901426547595624f, + 0.0901903963979477f, 0.0902381378290803f, 0.0902858790528505f, 0.0903336200691487f, + 0.0903813608778650f, 0.0904291014788898f, 0.0904768418721133f, 0.0905245820574260f, + 0.0905723220347180f, 0.0906200618038797f, 0.0906678013648013f, 0.0907155407173732f, + 0.0907632798614856f, 0.0908110187970289f, 0.0908587575238934f, 0.0909064960419693f, + 0.0909542343511469f, 0.0910019724513166f, 0.0910497103423687f, 0.0910974480241934f, + 0.0911451854966810f, 0.0911929227597219f, 0.0912406598132064f, 0.0912883966570247f, + 0.0913361332910672f, 0.0913838697152241f, 0.0914316059293859f, 0.0914793419334426f, + 0.0915270777272848f, 0.0915748133108027f, 0.0916225486838865f, 0.0916702838464267f, + 0.0917180187983135f, 0.0917657535394371f, 0.0918134880696880f, 0.0918612223889565f, + 0.0919089564971327f, 0.0919566903941071f, 0.0920044240797700f, 0.0920521575540117f, + 0.0920998908167224f, 0.0921476238677925f, 0.0921953567071123f, 0.0922430893345722f, + 0.0922908217500624f, 0.0923385539534732f, 0.0923862859446949f, 0.0924340177236180f, + 0.0924817492901326f, 0.0925294806441291f, 0.0925772117854979f, 0.0926249427141292f, + 0.0926726734299133f, 0.0927204039327406f, 0.0927681342225014f, 0.0928158642990860f, + 0.0928635941623847f, 0.0929113238122879f, 0.0929590532486858f, 0.0930067824714688f, + 0.0930545114805272f, 0.0931022402757514f, 0.0931499688570316f, 0.0931976972242581f, + 0.0932454253773214f, 0.0932931533161117f, 0.0933408810405193f, 0.0933886085504345f, + 0.0934363358457478f, 0.0934840629263494f, 0.0935317897921296f, 0.0935795164429787f, + 0.0936272428787872f, 0.0936749690994453f, 0.0937226951048433f, 0.0937704208948716f, + 0.0938181464694205f, 0.0938658718283804f, 0.0939135969716415f, 0.0939613218990942f, + 0.0940090466106288f, 0.0940567711061357f, 0.0941044953855052f, 0.0941522194486276f, + 0.0941999432953932f, 0.0942476669256924f, 0.0942953903394156f, 0.0943431135364530f, + 0.0943908365166949f, 0.0944385592800318f, 0.0944862818263540f, 0.0945340041555518f, + 0.0945817262675154f, 0.0946294481621354f, 0.0946771698393020f, 0.0947248912989055f, + 0.0947726125408362f, 0.0948203335649846f, 0.0948680543712410f, 0.0949157749594957f, + 0.0949634953296390f, 0.0950112154815613f, 0.0950589354151529f, 0.0951066551303042f, + 0.0951543746269055f, 0.0952020939048471f, 0.0952498129640195f, 0.0952975318043129f, + 0.0953452504256176f, 0.0953929688278241f, 0.0954406870108227f, 0.0954884049745037f, + 0.0955361227187575f, 0.0955838402434744f, 0.0956315575485447f, 0.0956792746338588f, + 0.0957269914993072f, 0.0957747081447800f, 0.0958224245701677f, 0.0958701407753606f, + 0.0959178567602490f, 0.0959655725247234f, 0.0960132880686740f, 0.0960610033919913f, + 0.0961087184945655f, 0.0961564333762870f, 0.0962041480370463f, 0.0962518624767335f, + 0.0962995766952391f, 0.0963472906924535f, 0.0963950044682670f, 0.0964427180225699f, + 0.0964904313552526f, 0.0965381444662055f, 0.0965858573553189f, 0.0966335700224832f, + 0.0966812824675887f, 0.0967289946905259f, 0.0967767066911850f, 0.0968244184694564f, + 0.0968721300252305f, 0.0969198413583976f, 0.0969675524688482f, 0.0970152633564725f, + 0.0970629740211609f, 0.0971106844628039f, 0.0971583946812917f, 0.0972061046765147f, + 0.0972538144483633f, 0.0973015239967278f, 0.0973492333214987f, 0.0973969424225663f, + 0.0974446512998209f, 0.0974923599531529f, 0.0975400683824527f, 0.0975877765876107f, + 0.0976354845685172f, 0.0976831923250626f, 0.0977308998571373f, 0.0977786071646316f, + 0.0978263142474359f, 0.0978740211054406f, 0.0979217277385360f, 0.0979694341466125f, + 0.0980171403295606f, 0.0980648462872705f, 0.0981125520196327f, 0.0981602575265375f, + 0.0982079628078753f, 0.0982556678635364f, 0.0983033726934113f, 0.0983510772973904f, + 0.0983987816753639f, 0.0984464858272223f, 0.0984941897528560f, 0.0985418934521553f, + 0.0985895969250106f, 0.0986373001713123f, 0.0986850031909508f, 0.0987327059838164f, + 0.0987804085497996f, 0.0988281108887907f, 0.0988758130006802f, 0.0989235148853582f, + 0.0989712165427154f, 0.0990189179726421f, 0.0990666191750285f, 0.0991143201497652f, + 0.0991620208967425f, 0.0992097214158508f, 0.0992574217069805f, 0.0993051217700219f, + 0.0993528216048655f, 0.0994005212114017f, 0.0994482205895208f, 0.0994959197391132f, + 0.0995436186600693f, 0.0995913173522796f, 0.0996390158156343f, 0.0996867140500239f, + 0.0997344120553388f, 0.0997821098314694f, 0.0998298073783060f, 0.0998775046957391f, + 0.0999252017836591f, 0.0999728986419563f, 0.1000205952705211f, 0.1000682916692440f, + 0.1001159878380153f, 0.1001636837767255f, 0.1002113794852648f, 0.1002590749635238f, + 0.1003067702113929f, 0.1003544652287623f, 0.1004021600155226f, 0.1004498545715641f, + 0.1004975488967772f, 0.1005452429910524f, 0.1005929368542799f, 0.1006406304863503f, + 0.1006883238871540f, 0.1007360170565812f, 0.1007837099945225f, 0.1008314027008683f, + 0.1008790951755089f, 0.1009267874183347f, 0.1009744794292362f, 0.1010221712081038f, + 0.1010698627548278f, 0.1011175540692987f, 0.1011652451514069f, 0.1012129360010428f, + 0.1012606266180968f, 0.1013083170024593f, 0.1013560071540208f, 0.1014036970726716f, + 0.1014513867583021f, 0.1014990762108028f, 0.1015467654300640f, 0.1015944544159762f, + 0.1016421431684298f, 0.1016898316873153f, 0.1017375199725229f, 0.1017852080239432f, + 0.1018328958414665f, 0.1018805834249834f, 0.1019282707743840f, 0.1019759578895590f, + 0.1020236447703988f, 0.1020713314167936f, 0.1021190178286340f, 0.1021667040058104f, + 0.1022143899482132f, 0.1022620756557328f, 0.1023097611282596f, 0.1023574463656841f, + 0.1024051313678967f, 0.1024528161347878f, 0.1025005006662478f, 0.1025481849621672f, + 0.1025958690224363f, 0.1026435528469456f, 0.1026912364355856f, 0.1027389197882466f, + 0.1027866029048190f, 0.1028342857851934f, 0.1028819684292601f, 0.1029296508369096f, + 0.1029773330080322f, 0.1030250149425185f, 0.1030726966402588f, 0.1031203781011436f, + 0.1031680593250632f, 0.1032157403119082f, 0.1032634210615690f, 0.1033111015739360f, + 0.1033587818488996f, 0.1034064618863503f, 0.1034541416861785f, 0.1035018212482746f, + 0.1035495005725291f, 0.1035971796588323f, 0.1036448585070749f, 0.1036925371171471f, + 0.1037402154889394f, 0.1037878936223422f, 0.1038355715172461f, 0.1038832491735414f, + 0.1039309265911185f, 0.1039786037698680f, 0.1040262807096802f, 0.1040739574104456f, + 0.1041216338720546f, 0.1041693100943977f, 0.1042169860773653f, 0.1042646618208478f, + 0.1043123373247358f, 0.1043600125889196f, 0.1044076876132897f, 0.1044553623977365f, + 0.1045030369421506f, 0.1045507112464222f, 0.1045983853104419f, 0.1046460591341002f, + 0.1046937327172874f, 0.1047414060598940f, 0.1047890791618105f, 0.1048367520229274f, + 0.1048844246431350f, 0.1049320970223238f, 0.1049797691603842f, 0.1050274410572069f, + 0.1050751127126820f, 0.1051227841267003f, 0.1051704552991519f, 0.1052181262299276f, + 0.1052657969189176f, 0.1053134673660125f, 0.1053611375711026f, 0.1054088075340786f, + 0.1054564772548307f, 0.1055041467332495f, 0.1055518159692255f, 0.1055994849626490f, + 0.1056471537134106f, 0.1056948222214007f, 0.1057424904865098f, 0.1057901585086283f, + 0.1058378262876467f, 0.1058854938234554f, 0.1059331611159450f, 0.1059808281650058f, + 0.1060284949705284f, 0.1060761615324032f, 0.1061238278505207f, 0.1061714939247713f, + 0.1062191597550455f, 0.1062668253412337f, 0.1063144906832266f, 0.1063621557809144f, + 0.1064098206341877f, 0.1064574852429369f, 0.1065051496070526f, 0.1065528137264251f, + 0.1066004776009450f, 0.1066481412305026f, 0.1066958046149886f, 0.1067434677542934f, + 0.1067911306483074f, 0.1068387932969211f, 0.1068864557000250f, 0.1069341178575095f, + 0.1069817797692652f, 0.1070294414351825f, 0.1070771028551519f, 0.1071247640290639f, + 0.1071724249568088f, 0.1072200856382774f, 0.1072677460733599f, 0.1073154062619468f, + 0.1073630662039288f, 0.1074107258991961f, 0.1074583853476394f, 0.1075060445491491f, + 0.1075537035036156f, 0.1076013622109295f, 0.1076490206709813f, 0.1076966788836614f, + 0.1077443368488603f, 0.1077919945664685f, 0.1078396520363764f, 0.1078873092584747f, + 0.1079349662326537f, 0.1079826229588039f, 0.1080302794368158f, 0.1080779356665800f, + 0.1081255916479869f, 0.1081732473809269f, 0.1082209028652907f, 0.1082685581009686f, + 0.1083162130878512f, 0.1083638678258289f, 0.1084115223147923f, 0.1084591765546318f, + 0.1085068305452379f, 0.1085544842865012f, 0.1086021377783121f, 0.1086497910205611f, + 0.1086974440131387f, 0.1087450967559354f, 0.1087927492488418f, 0.1088404014917482f, + 0.1088880534845452f, 0.1089357052271233f, 0.1089833567193730f, 0.1090310079611848f, + 0.1090786589524492f, 0.1091263096930567f, 0.1091739601828978f, 0.1092216104218630f, + 0.1092692604098428f, 0.1093169101467277f, 0.1093645596324082f, 0.1094122088667748f, + 0.1094598578497180f, 0.1095075065811283f, 0.1095551550608963f, 0.1096028032889124f, + 0.1096504512650671f, 0.1096980989892510f, 0.1097457464613545f, 0.1097933936812682f, + 0.1098410406488826f, 0.1098886873640881f, 0.1099363338267754f, 0.1099839800368348f, + 0.1100316259941570f, 0.1100792716986324f, 0.1101269171501515f, 0.1101745623486049f, + 0.1102222072938831f, 0.1102698519858765f, 0.1103174964244757f, 0.1103651406095713f, + 0.1104127845410536f, 0.1104604282188133f, 0.1105080716427409f, 0.1105557148127269f, + 0.1106033577286617f, 0.1106510003904360f, 0.1106986427979402f, 0.1107462849510649f, + 0.1107939268497006f, 0.1108415684937377f, 0.1108892098830669f, 0.1109368510175786f, + 0.1109844918971634f, 0.1110321325217118f, 0.1110797728911143f, 0.1111274130052614f, + 0.1111750528640437f, 0.1112226924673517f, 0.1112703318150759f, 0.1113179709071069f, + 0.1113656097433352f, 0.1114132483236512f, 0.1114608866479456f, 0.1115085247161088f, + 0.1115561625280315f, 0.1116038000836040f, 0.1116514373827171f, 0.1116990744252611f, + 0.1117467112111266f, 0.1117943477402042f, 0.1118419840123843f, 0.1118896200275576f, + 0.1119372557856146f, 0.1119848912864457f, 0.1120325265299416f, 0.1120801615159927f, + 0.1121277962444897f, 0.1121754307153229f, 0.1122230649283831f, 0.1122706988835606f, + 0.1123183325807462f, 0.1123659660198302f, 0.1124135992007033f, 0.1124612321232559f, + 0.1125088647873787f, 0.1125564971929621f, 0.1126041293398968f, 0.1126517612280732f, + 0.1126993928573819f, 0.1127470242277134f, 0.1127946553389583f, 0.1128422861910072f, + 0.1128899167837505f, 0.1129375471170789f, 0.1129851771908828f, 0.1130328070050529f, + 0.1130804365594796f, 0.1131280658540536f, 0.1131756948886653f, 0.1132233236632054f, + 0.1132709521775643f, 0.1133185804316327f, 0.1133662084253011f, 0.1134138361584600f, + 0.1134614636309999f, 0.1135090908428116f, 0.1135567177937854f, 0.1136043444838120f, + 0.1136519709127819f, 0.1136995970805856f, 0.1137472229871138f, 0.1137948486322570f, + 0.1138424740159057f, 0.1138900991379505f, 0.1139377239982820f, 0.1139853485967907f, + 0.1140329729333672f, 0.1140805970079020f, 0.1141282208202858f, 0.1141758443704090f, + 0.1142234676581623f, 0.1142710906834361f, 0.1143187134461211f, 0.1143663359461079f, + 0.1144139581832869f, 0.1144615801575488f, 0.1145092018687842f, 0.1145568233168835f, + 0.1146044445017374f, 0.1146520654232364f, 0.1146996860812712f, 0.1147473064757322f, + 0.1147949266065101f, 0.1148425464734954f, 0.1148901660765786f, 0.1149377854156505f, + 0.1149854044906015f, 0.1150330233013221f, 0.1150806418477031f, 0.1151282601296349f, + 0.1151758781470082f, 0.1152234958997135f, 0.1152711133876413f, 0.1153187306106824f, + 0.1153663475687271f, 0.1154139642616662f, 0.1154615806893902f, 0.1155091968517897f, + 0.1155568127487553f, 0.1156044283801775f, 0.1156520437459469f, 0.1156996588459541f, + 0.1157472736800897f, 0.1157948882482443f, 0.1158425025503085f, 0.1158901165861728f, + 0.1159377303557278f, 0.1159853438588641f, 0.1160329570954724f, 0.1160805700654431f, + 0.1161281827686669f, 0.1161757952050344f, 0.1162234073744361f, 0.1162710192767627f, + 0.1163186309119048f, 0.1163662422797528f, 0.1164138533801975f, 0.1164614642131294f, + 0.1165090747784390f, 0.1165566850760171f, 0.1166042951057542f, 0.1166519048675408f, + 0.1166995143612677f, 0.1167471235868253f, 0.1167947325441043f, 0.1168423412329953f, + 0.1168899496533888f, 0.1169375578051755f, 0.1169851656882460f, 0.1170327733024908f, + 0.1170803806478006f, 0.1171279877240659f, 0.1171755945311775f, 0.1172232010690258f, + 0.1172708073375015f, 0.1173184133364951f, 0.1173660190658974f, 0.1174136245255988f, + 0.1174612297154900f, 0.1175088346354616f, 0.1175564392854042f, 0.1176040436652084f, + 0.1176516477747649f, 0.1176992516139641f, 0.1177468551826968f, 0.1177944584808536f, + 0.1178420615083250f, 0.1178896642650017f, 0.1179372667507742f, 0.1179848689655332f, + 0.1180324709091694f, 0.1180800725815732f, 0.1181276739826354f, 0.1181752751122465f, + 0.1182228759702972f, 0.1182704765566780f, 0.1183180768712797f, 0.1183656769139927f, + 0.1184132766847078f, 0.1184608761833155f, 0.1185084754097065f, 0.1185560743637714f, + 0.1186036730454007f, 0.1186512714544852f, 0.1186988695909154f, 0.1187464674545820f, + 0.1187940650453756f, 0.1188416623631868f, 0.1188892594079063f, 0.1189368561794246f, + 0.1189844526776323f, 0.1190320489024203f, 0.1190796448536789f, 0.1191272405312989f, + 0.1191748359351709f, 0.1192224310651855f, 0.1192700259212334f, 0.1193176205032051f, + 0.1193652148109914f, 0.1194128088444828f, 0.1194604026035699f, 0.1195079960881435f, + 0.1195555892980941f, 0.1196031822333124f, 0.1196507748936890f, 0.1196983672791145f, + 0.1197459593894796f, 0.1197935512246749f, 0.1198411427845911f, 0.1198887340691187f, + 0.1199363250781485f, 0.1199839158115710f, 0.1200315062692769f, 0.1200790964511569f, + 0.1201266863571015f, 0.1201742759870015f, 0.1202218653407474f, 0.1202694544182299f, + 0.1203170432193397f, 0.1203646317439674f, 0.1204122199920035f, 0.1204598079633389f, + 0.1205073956578641f, 0.1205549830754698f, 0.1206025702160466f, 0.1206501570794851f, + 0.1206977436656761f, 0.1207453299745101f, 0.1207929160058779f, 0.1208405017596700f, + 0.1208880872357771f, 0.1209356724340898f, 0.1209832573544989f, 0.1210308419968950f, + 0.1210784263611686f, 0.1211260104472106f, 0.1211735942549115f, 0.1212211777841619f, + 0.1212687610348526f, 0.1213163440068742f, 0.1213639267001173f, 0.1214115091144727f, + 0.1214590912498308f, 0.1215066731060826f, 0.1215542546831185f, 0.1216018359808293f, + 0.1216494169991055f, 0.1216969977378380f, 0.1217445781969172f, 0.1217921583762340f, + 0.1218397382756789f, 0.1218873178951426f, 0.1219348972345158f, 0.1219824762936892f, + 0.1220300550725534f, 0.1220776335709990f, 0.1221252117889168f, 0.1221727897261974f, + 0.1222203673827316f, 0.1222679447584098f, 0.1223155218531229f, 0.1223630986667615f, + 0.1224106751992162f, 0.1224582514503778f, 0.1225058274201369f, 0.1225534031083841f, + 0.1226009785150102f, 0.1226485536399059f, 0.1226961284829617f, 0.1227437030440685f, + 0.1227912773231168f, 0.1228388513199973f, 0.1228864250346007f, 0.1229339984668178f, + 0.1229815716165391f, 0.1230291444836553f, 0.1230767170680571f, 0.1231242893696353f, + 0.1231718613882805f, 0.1232194331238833f, 0.1232670045763345f, 0.1233145757455247f, + 0.1233621466313447f, 0.1234097172336850f, 0.1234572875524365f, 0.1235048575874897f, + 0.1235524273387354f, 0.1235999968060642f, 0.1236475659893669f, 0.1236951348885341f, + 0.1237427035034565f, 0.1237902718340248f, 0.1238378398801298f, 0.1238854076416620f, + 0.1239329751185122f, 0.1239805423105710f, 0.1240281092177293f, 0.1240756758398776f, + 0.1241232421769066f, 0.1241708082287071f, 0.1242183739951697f, 0.1242659394761852f, + 0.1243135046716442f, 0.1243610695814375f, 0.1244086342054557f, 0.1244561985435895f, + 0.1245037625957297f, 0.1245513263617669f, 0.1245988898415918f, 0.1246464530350952f, + 0.1246940159421676f, 0.1247415785627000f, 0.1247891408965829f, 0.1248367029437070f, + 0.1248842647039631f, 0.1249318261772419f, 0.1249793873634340f, 0.1250269482624302f, + 0.1250745088741212f, 0.1251220691983976f, 0.1251696292351503f, 0.1252171889842699f, + 0.1252647484456471f, 0.1253123076191726f, 0.1253598665047372f, 0.1254074251022315f, + 0.1254549834115462f, 0.1255025414325722f, 0.1255500991652000f, 0.1255976566093205f, + 0.1256452137648243f, 0.1256927706316021f, 0.1257403272095447f, 0.1257878834985428f, + 0.1258354394984870f, 0.1258829952092682f, 0.1259305506307770f, 0.1259781057629041f, + 0.1260256606055403f, 0.1260732151585763f, 0.1261207694219029f, 0.1261683233954106f, + 0.1262158770789904f, 0.1262634304725327f, 0.1263109835759286f, 0.1263585363890685f, + 0.1264060889118434f, 0.1264536411441438f, 0.1265011930858605f, 0.1265487447368843f, + 0.1265962960971058f, 0.1266438471664159f, 0.1266913979447052f, 0.1267389484318645f, + 0.1267864986277844f, 0.1268340485323558f, 0.1268815981454693f, 0.1269291474670158f, + 0.1269766964968859f, 0.1270242452349703f, 0.1270717936811598f, 0.1271193418353452f, + 0.1271668896974172f, 0.1272144372672664f, 0.1272619845447837f, 0.1273095315298598f, + 0.1273570782223854f, 0.1274046246222513f, 0.1274521707293482f, 0.1274997165435668f, + 0.1275472620647980f, 0.1275948072929323f, 0.1276423522278607f, 0.1276898968694738f, + 0.1277374412176623f, 0.1277849852723171f, 0.1278325290333288f, 0.1278800725005882f, + 0.1279276156739861f, 0.1279751585534132f, 0.1280227011387602f, 0.1280702434299179f, + 0.1281177854267771f, 0.1281653271292285f, 0.1282128685371628f, 0.1282604096504709f, + 0.1283079504690434f, 0.1283554909927711f, 0.1284030312215448f, 0.1284505711552553f, + 0.1284981107937932f, 0.1285456501370493f, 0.1285931891849144f, 0.1286407279372793f, + 0.1286882663940347f, 0.1287358045550714f, 0.1287833424202801f, 0.1288308799895515f, + 0.1288784172627765f, 0.1289259542398459f, 0.1289734909206503f, 0.1290210273050806f, + 0.1290685633930274f, 0.1291160991843816f, 0.1291636346790340f, 0.1292111698768752f, + 0.1292587047777961f, 0.1293062393816875f, 0.1293537736884400f, 0.1294013076979445f, + 0.1294488414100918f, 0.1294963748247726f, 0.1295439079418776f, 0.1295914407612977f, + 0.1296389732829236f, 0.1296865055066461f, 0.1297340374323560f, 0.1297815690599440f, + 0.1298291003893009f, 0.1298766314203176f, 0.1299241621528846f, 0.1299716925868930f, + 0.1300192227222333f, 0.1300667525587965f, 0.1301142820964733f, 0.1301618113351544f, + 0.1302093402747306f, 0.1302568689150928f, 0.1303043972561317f, 0.1303519252977381f, + 0.1303994530398027f, 0.1304469804822164f, 0.1304945076248699f, 0.1305420344676541f, + 0.1305895610104597f, 0.1306370872531774f, 0.1306846131956981f, 0.1307321388379126f, + 0.1307796641797117f, 0.1308271892209861f, 0.1308747139616267f, 0.1309222384015242f, + 0.1309697625405694f, 0.1310172863786531f, 0.1310648099156661f, 0.1311123331514993f, + 0.1311598560860433f, 0.1312073787191890f, 0.1312549010508272f, 0.1313024230808486f, + 0.1313499448091442f, 0.1313974662356046f, 0.1314449873601207f, 0.1314925081825833f, + 0.1315400287028831f, 0.1315875489209110f, 0.1316350688365578f, 0.1316825884497143f, + 0.1317301077602712f, 0.1317776267681194f, 0.1318251454731497f, 0.1318726638752529f, + 0.1319201819743198f, 0.1319676997702412f, 0.1320152172629078f, 0.1320627344522106f, + 0.1321102513380404f, 0.1321577679202878f, 0.1322052841988438f, 0.1322528001735992f, + 0.1323003158444447f, 0.1323478312112711f, 0.1323953462739694f, 0.1324428610324303f, + 0.1324903754865445f, 0.1325378896362030f, 0.1325854034812966f, 0.1326329170217160f, + 0.1326804302573521f, 0.1327279431880956f, 0.1327754558138375f, 0.1328229681344685f, + 0.1328704801498794f, 0.1329179918599611f, 0.1329655032646044f, 0.1330130143637001f, + 0.1330605251571391f, 0.1331080356448121f, 0.1331555458266099f, 0.1332030557024235f, + 0.1332505652721436f, 0.1332980745356610f, 0.1333455834928666f, 0.1333930921436512f, + 0.1334406004879057f, 0.1334881085255208f, 0.1335356162563874f, 0.1335831236803963f, + 0.1336306307974383f, 0.1336781376074044f, 0.1337256441101853f, 0.1337731503056718f, + 0.1338206561937547f, 0.1338681617743250f, 0.1339156670472735f, 0.1339631720124909f, + 0.1340106766698681f, 0.1340581810192960f, 0.1341056850606654f, 0.1341531887938671f, + 0.1342006922187920f, 0.1342481953353309f, 0.1342956981433747f, 0.1343432006428141f, + 0.1343907028335401f, 0.1344382047154434f, 0.1344857062884150f, 0.1345332075523457f, + 0.1345807085071262f, 0.1346282091526475f, 0.1346757094888004f, 0.1347232095154757f, + 0.1347707092325643f, 0.1348182086399571f, 0.1348657077375449f, 0.1349132065252185f, + 0.1349607050028687f, 0.1350082031703866f, 0.1350557010276628f, 0.1351031985745883f, + 0.1351506958110539f, 0.1351981927369504f, 0.1352456893521687f, 0.1352931856565997f, + 0.1353406816501342f, 0.1353881773326631f, 0.1354356727040772f, 0.1354831677642674f, + 0.1355306625131246f, 0.1355781569505396f, 0.1356256510764032f, 0.1356731448906064f, + 0.1357206383930399f, 0.1357681315835947f, 0.1358156244621617f, 0.1358631170286316f, + 0.1359106092828954f, 0.1359581012248438f, 0.1360055928543679f, 0.1360530841713584f, + 0.1361005751757062f, 0.1361480658673022f, 0.1361955562460372f, 0.1362430463118022f, + 0.1362905360644880f, 0.1363380255039854f, 0.1363855146301853f, 0.1364330034429787f, + 0.1364804919422563f, 0.1365279801279091f, 0.1365754679998279f, 0.1366229555579036f, + 0.1366704428020271f, 0.1367179297320892f, 0.1367654163479809f, 0.1368129026495930f, + 0.1368603886368164f, 0.1369078743095419f, 0.1369553596676605f, 0.1370028447110631f, + 0.1370503294396404f, 0.1370978138532835f, 0.1371452979518831f, 0.1371927817353302f, + 0.1372402652035156f, 0.1372877483563303f, 0.1373352311936651f, 0.1373827137154109f, + 0.1374301959214586f, 0.1374776778116990f, 0.1375251593860232f, 0.1375726406443219f, + 0.1376201215864860f, 0.1376676022124066f, 0.1377150825219743f, 0.1377625625150802f, + 0.1378100421916151f, 0.1378575215514699f, 0.1379050005945355f, 0.1379524793207029f, + 0.1379999577298628f, 0.1380474358219062f, 0.1380949135967241f, 0.1381423910542072f, + 0.1381898681942466f, 0.1382373450167330f, 0.1382848215215574f, 0.1383322977086107f, + 0.1383797735777839f, 0.1384272491289677f, 0.1384747243620532f, 0.1385221992769312f, + 0.1385696738734925f, 0.1386171481516282f, 0.1386646221112292f, 0.1387120957521862f, + 0.1387595690743904f, 0.1388070420777324f, 0.1388545147621034f, 0.1389019871273941f, + 0.1389494591734955f, 0.1389969309002985f, 0.1390444023076940f, 0.1390918733955729f, + 0.1391393441638262f, 0.1391868146123447f, 0.1392342847410194f, 0.1392817545497412f, + 0.1393292240384010f, 0.1393766932068897f, 0.1394241620550982f, 0.1394716305829175f, + 0.1395190987902385f, 0.1395665666769521f, 0.1396140342429491f, 0.1396615014881206f, + 0.1397089684123576f, 0.1397564350155507f, 0.1398039012975911f, 0.1398513672583696f, + 0.1398988328977772f, 0.1399462982157048f, 0.1399937632120433f, 0.1400412278866836f, + 0.1400886922395167f, 0.1401361562704335f, 0.1401836199793249f, 0.1402310833660819f, + 0.1402785464305954f, 0.1403260091727564f, 0.1403734715924556f, 0.1404209336895842f, + 0.1404683954640330f, 0.1405158569156930f, 0.1405633180444550f, 0.1406107788502102f, + 0.1406582393328492f, 0.1407056994922632f, 0.1407531593283431f, 0.1408006188409797f, + 0.1408480780300641f, 0.1408955368954871f, 0.1409429954371398f, 0.1409904536549130f, + 0.1410379115486977f, 0.1410853691183849f, 0.1411328263638655f, 0.1411802832850303f, + 0.1412277398817705f, 0.1412751961539769f, 0.1413226521015405f, 0.1413701077243522f, + 0.1414175630223030f, 0.1414650179952839f, 0.1415124726431856f, 0.1415599269658994f, + 0.1416073809633160f, 0.1416548346353265f, 0.1417022879818217f, 0.1417497410026927f, + 0.1417971936978304f, 0.1418446460671257f, 0.1418920981104697f, 0.1419395498277532f, + 0.1419870012188673f, 0.1420344522837028f, 0.1420819030221508f, 0.1421293534341023f, + 0.1421768035194481f, 0.1422242532780792f, 0.1422717027098866f, 0.1423191518147613f, + 0.1423666005925942f, 0.1424140490432763f, 0.1424614971666985f, 0.1425089449627519f, + 0.1425563924313273f, 0.1426038395723159f, 0.1426512863856084f, 0.1426987328710960f, + 0.1427461790286695f, 0.1427936248582199f, 0.1428410703596383f, 0.1428885155328156f, + 0.1429359603776427f, 0.1429834048940106f, 0.1430308490818104f, 0.1430782929409329f, + 0.1431257364712692f, 0.1431731796727102f, 0.1432206225451470f, 0.1432680650884704f, + 0.1433155073025715f, 0.1433629491873413f, 0.1434103907426707f, 0.1434578319684507f, + 0.1435052728645723f, 0.1435527134309265f, 0.1436001536674043f, 0.1436475935738966f, + 0.1436950331502945f, 0.1437424723964889f, 0.1437899113123707f, 0.1438373498978311f, + 0.1438847881527610f, 0.1439322260770514f, 0.1439796636705932f, 0.1440271009332774f, + 0.1440745378649952f, 0.1441219744656373f, 0.1441694107350950f, 0.1442168466732590f, + 0.1442642822800205f, 0.1443117175552703f, 0.1443591524988996f, 0.1444065871107993f, + 0.1444540213908605f, 0.1445014553389740f, 0.1445488889550309f, 0.1445963222389223f, + 0.1446437551905390f, 0.1446911878097722f, 0.1447386200965128f, 0.1447860520506518f, + 0.1448334836720802f, 0.1448809149606891f, 0.1449283459163693f, 0.1449757765390121f, + 0.1450232068285082f, 0.1450706367847488f, 0.1451180664076249f, 0.1451654956970274f, + 0.1452129246528475f, 0.1452603532749760f, 0.1453077815633040f, 0.1453552095177225f, + 0.1454026371381226f, 0.1454500644243952f, 0.1454974913764313f, 0.1455449179941221f, + 0.1455923442773583f, 0.1456397702260313f, 0.1456871958400318f, 0.1457346211192510f, + 0.1457820460635799f, 0.1458294706729094f, 0.1458768949471306f, 0.1459243188861345f, + 0.1459717424898122f, 0.1460191657580547f, 0.1460665886907529f, 0.1461140112877980f, + 0.1461614335490809f, 0.1462088554744927f, 0.1462562770639244f, 0.1463036983172669f, + 0.1463511192344115f, 0.1463985398152490f, 0.1464459600596705f, 0.1464933799675671f, + 0.1465407995388298f, 0.1465882187733495f, 0.1466356376710174f, 0.1466830562317245f, + 0.1467304744553617f, 0.1467778923418203f, 0.1468253098909911f, 0.1468727271027652f, + 0.1469201439770336f, 0.1469675605136875f, 0.1470149767126178f, 0.1470623925737155f, + 0.1471098080968718f, 0.1471572232819776f, 0.1472046381289240f, 0.1472520526376021f, + 0.1472994668079028f, 0.1473468806397173f, 0.1473942941329366f, 0.1474417072874517f, + 0.1474891201031536f, 0.1475365325799334f, 0.1475839447176823f, 0.1476313565162911f, + 0.1476787679756510f, 0.1477261790956530f, 0.1477735898761882f, 0.1478210003171476f, + 0.1478684104184222f, 0.1479158201799032f, 0.1479632296014816f, 0.1480106386830484f, + 0.1480580474244947f, 0.1481054558257116f, 0.1481528638865900f, 0.1482002716070212f, + 0.1482476789868960f, 0.1482950860261057f, 0.1483424927245412f, 0.1483898990820936f, + 0.1484373050986540f, 0.1484847107741134f, 0.1485321161083629f, 0.1485795211012936f, + 0.1486269257527965f, 0.1486743300627628f, 0.1487217340310834f, 0.1487691376576494f, + 0.1488165409423519f, 0.1488639438850820f, 0.1489113464857308f, 0.1489587487441892f, + 0.1490061506603484f, 0.1490535522340996f, 0.1491009534653336f, 0.1491483543539417f, + 0.1491957548998148f, 0.1492431551028441f, 0.1492905549629206f, 0.1493379544799355f, + 0.1493853536537797f, 0.1494327524843445f, 0.1494801509715207f, 0.1495275491151996f, + 0.1495749469152722f, 0.1496223443716297f, 0.1496697414841630f, 0.1497171382527632f, + 0.1497645346773215f, 0.1498119307577289f, 0.1498593264938766f, 0.1499067218856556f, + 0.1499541169329570f, 0.1500015116356718f, 0.1500489059936913f, 0.1500963000069064f, + 0.1501436936752082f, 0.1501910869984879f, 0.1502384799766366f, 0.1502858726095452f, + 0.1503332648971050f, 0.1503806568392070f, 0.1504280484357424f, 0.1504754396866022f, + 0.1505228305916774f, 0.1505702211508593f, 0.1506176113640389f, 0.1506650012311073f, + 0.1507123907519556f, 0.1507597799264750f, 0.1508071687545564f, 0.1508545572360910f, + 0.1509019453709700f, 0.1509493331590845f, 0.1509967206003254f, 0.1510441076945840f, + 0.1510914944417513f, 0.1511388808417185f, 0.1511862668943766f, 0.1512336525996168f, + 0.1512810379573302f, 0.1513284229674079f, 0.1513758076297410f, 0.1514231919442206f, + 0.1514705759107378f, 0.1515179595291838f, 0.1515653427994496f, 0.1516127257214264f, + 0.1516601082950053f, 0.1517074905200774f, 0.1517548723965339f, 0.1518022539242657f, + 0.1518496351031642f, 0.1518970159331203f, 0.1519443964140253f, 0.1519917765457701f, + 0.1520391563282461f, 0.1520865357613441f, 0.1521339148449555f, 0.1521812935789714f, + 0.1522286719632827f, 0.1522760499977808f, 0.1523234276823567f, 0.1523708050169015f, + 0.1524181820013063f, 0.1524655586354624f, 0.1525129349192608f, 0.1525603108525926f, + 0.1526076864353491f, 0.1526550616674212f, 0.1527024365487002f, 0.1527498110790773f, + 0.1527971852584434f, 0.1528445590866898f, 0.1528919325637077f, 0.1529393056893880f, + 0.1529866784636220f, 0.1530340508863009f, 0.1530814229573157f, 0.1531287946765577f, + 0.1531761660439178f, 0.1532235370592874f, 0.1532709077225575f, 0.1533182780336193f, + 0.1533656479923639f, 0.1534130175986824f, 0.1534603868524661f, 0.1535077557536061f, + 0.1535551243019934f, 0.1536024924975194f, 0.1536498603400750f, 0.1536972278295515f, + 0.1537445949658400f, 0.1537919617488317f, 0.1538393281784178f, 0.1538866942544893f, + 0.1539340599769374f, 0.1539814253456533f, 0.1540287903605282f, 0.1540761550214531f, + 0.1541235193283194f, 0.1541708832810180f, 0.1542182468794402f, 0.1542656101234772f, + 0.1543129730130201f, 0.1543603355479601f, 0.1544076977281882f, 0.1544550595535958f, + 0.1545024210240739f, 0.1545497821395138f, 0.1545971428998066f, 0.1546445033048434f, + 0.1546918633545155f, 0.1547392230487139f, 0.1547865823873299f, 0.1548339413702546f, + 0.1548812999973793f, 0.1549286582685951f, 0.1549760161837931f, 0.1550233737428645f, + 0.1550707309457005f, 0.1551180877921923f, 0.1551654442822311f, 0.1552128004157080f, + 0.1552601561925142f, 0.1553075116125409f, 0.1553548666756793f, 0.1554022213818206f, + 0.1554495757308559f, 0.1554969297226763f, 0.1555442833571732f, 0.1555916366342377f, + 0.1556389895537609f, 0.1556863421156341f, 0.1557336943197484f, 0.1557810461659951f, + 0.1558283976542652f, 0.1558757487844501f, 0.1559230995564409f, 0.1559704499701287f, + 0.1560178000254048f, 0.1560651497221604f, 0.1561124990602867f, 0.1561598480396748f, + 0.1562071966602159f, 0.1562545449218013f, 0.1563018928243221f, 0.1563492403676696f, + 0.1563965875517349f, 0.1564439343764092f, 0.1564912808415838f, 0.1565386269471498f, + 0.1565859726929984f, 0.1566333180790209f, 0.1566806631051084f, 0.1567280077711522f, + 0.1567753520770434f, 0.1568226960226732f, 0.1568700396079329f, 0.1569173828327137f, + 0.1569647256969068f, 0.1570120682004033f, 0.1570594103430945f, 0.1571067521248717f, + 0.1571540935456259f, 0.1572014346052485f, 0.1572487753036306f, 0.1572961156406635f, + 0.1573434556162382f, 0.1573907952302463f, 0.1574381344825787f, 0.1574854733731267f, + 0.1575328119017815f, 0.1575801500684344f, 0.1576274878729766f, 0.1576748253152992f, + 0.1577221623952936f, 0.1577694991128509f, 0.1578168354678624f, 0.1578641714602192f, + 0.1579115070898127f, 0.1579588423565339f, 0.1580061772602743f, 0.1580535118009249f, + 0.1581008459783770f, 0.1581481797925219f, 0.1581955132432507f, 0.1582428463304547f, + 0.1582901790540252f, 0.1583375114138533f, 0.1583848434098303f, 0.1584321750418475f, + 0.1584795063097960f, 0.1585268372135671f, 0.1585741677530520f, 0.1586214979281420f, + 0.1586688277387283f, 0.1587161571847022f, 0.1587634862659548f, 0.1588108149823775f, + 0.1588581433338614f, 0.1589054713202979f, 0.1589527989415781f, 0.1590001261975933f, + 0.1590474530882348f, 0.1590947796133937f, 0.1591421057729614f, 0.1591894315668290f, + 0.1592367569948878f, 0.1592840820570292f, 0.1593314067531443f, 0.1593787310831243f, + 0.1594260550468606f, 0.1594733786442444f, 0.1595207018751668f, 0.1595680247395193f, + 0.1596153472371931f, 0.1596626693680793f, 0.1597099911320692f, 0.1597573125290542f, + 0.1598046335589254f, 0.1598519542215742f, 0.1598992745168918f, 0.1599465944447694f, + 0.1599939140050983f, 0.1600412331977697f, 0.1600885520226751f, 0.1601358704797055f, + 0.1601831885687522f, 0.1602305062897066f, 0.1602778236424599f, 0.1603251406269034f, + 0.1603724572429283f, 0.1604197734904259f, 0.1604670893692874f, 0.1605144048794042f, + 0.1605617200206675f, 0.1606090347929686f, 0.1606563491961987f, 0.1607036632302492f, + 0.1607509768950112f, 0.1607982901903762f, 0.1608456031162353f, 0.1608929156724798f, + 0.1609402278590011f, 0.1609875396756903f, 0.1610348511224388f, 0.1610821621991379f, + 0.1611294729056788f, 0.1611767832419528f, 0.1612240932078512f, 0.1612714028032653f, + 0.1613187120280864f, 0.1613660208822058f, 0.1614133293655146f, 0.1614606374779043f, + 0.1615079452192661f, 0.1615552525894914f, 0.1616025595884713f, 0.1616498662160972f, + 0.1616971724722604f, 0.1617444783568522f, 0.1617917838697638f, 0.1618390890108866f, + 0.1618863937801118f, 0.1619336981773309f, 0.1619810022024349f, 0.1620283058553153f, + 0.1620756091358633f, 0.1621229120439703f, 0.1621702145795276f, 0.1622175167424264f, + 0.1622648185325580f, 0.1623121199498138f, 0.1623594209940851f, 0.1624067216652631f, + 0.1624540219632392f, 0.1625013218879046f, 0.1625486214391507f, 0.1625959206168689f, + 0.1626432194209503f, 0.1626905178512864f, 0.1627378159077683f, 0.1627851135902875f, + 0.1628324108987352f, 0.1628797078330028f, 0.1629270043929816f, 0.1629743005785628f, + 0.1630215963896378f, 0.1630688918260980f, 0.1631161868878346f, 0.1631634815747389f, + 0.1632107758867024f, 0.1632580698236162f, 0.1633053633853717f, 0.1633526565718603f, + 0.1633999493829732f, 0.1634472418186018f, 0.1634945338786375f, 0.1635418255629714f, + 0.1635891168714950f, 0.1636364078040996f, 0.1636836983606766f, 0.1637309885411171f, + 0.1637782783453127f, 0.1638255677731545f, 0.1638728568245340f, 0.1639201454993424f, + 0.1639674337974712f, 0.1640147217188115f, 0.1640620092632549f, 0.1641092964306925f, + 0.1641565832210158f, 0.1642038696341161f, 0.1642511556698847f, 0.1642984413282129f, + 0.1643457266089922f, 0.1643930115121138f, 0.1644402960374690f, 0.1644875801849493f, + 0.1645348639544460f, 0.1645821473458504f, 0.1646294303590538f, 0.1646767129939476f, + 0.1647239952504232f, 0.1647712771283718f, 0.1648185586276850f, 0.1648658397482539f, + 0.1649131204899699f, 0.1649604008527245f, 0.1650076808364089f, 0.1650549604409145f, + 0.1651022396661327f, 0.1651495185119547f, 0.1651967969782721f, 0.1652440750649760f, + 0.1652913527719580f, 0.1653386300991093f, 0.1653859070463213f, 0.1654331836134853f, + 0.1654804598004928f, 0.1655277356072350f, 0.1655750110336034f, 0.1656222860794893f, + 0.1656695607447841f, 0.1657168350293791f, 0.1657641089331658f, 0.1658113824560354f, + 0.1658586555978793f, 0.1659059283585889f, 0.1659532007380556f, 0.1660004727361708f, + 0.1660477443528258f, 0.1660950155879120f, 0.1661422864413207f, 0.1661895569129434f, + 0.1662368270026714f, 0.1662840967103961f, 0.1663313660360089f, 0.1663786349794011f, + 0.1664259035404641f, 0.1664731717190893f, 0.1665204395151682f, 0.1665677069285920f, + 0.1666149739592521f, 0.1666622406070399f, 0.1667095068718469f, 0.1667567727535644f, + 0.1668040382520837f, 0.1668513033672964f, 0.1668985680990936f, 0.1669458324473670f, + 0.1669930964120077f, 0.1670403599929073f, 0.1670876231899571f, 0.1671348860030485f, + 0.1671821484320729f, 0.1672294104769217f, 0.1672766721374863f, 0.1673239334136581f, + 0.1673711943053284f, 0.1674184548123888f, 0.1674657149347305f, 0.1675129746722449f, + 0.1675602340248236f, 0.1676074929923578f, 0.1676547515747390f, 0.1677020097718586f, + 0.1677492675836079f, 0.1677965250098784f, 0.1678437820505616f, 0.1678910387055487f, + 0.1679382949747312f, 0.1679855508580005f, 0.1680328063552480f, 0.1680800614663652f, + 0.1681273161912434f, 0.1681745705297741f, 0.1682218244818486f, 0.1682690780473584f, + 0.1683163312261948f, 0.1683635840182494f, 0.1684108364234135f, 0.1684580884415785f, + 0.1685053400726359f, 0.1685525913164770f, 0.1685998421729934f, 0.1686470926420763f, + 0.1686943427236173f, 0.1687415924175077f, 0.1687888417236390f, 0.1688360906419026f, + 0.1688833391721900f, 0.1689305873143924f, 0.1689778350684015f, 0.1690250824341085f, + 0.1690723294114050f, 0.1691195760001823f, 0.1691668222003320f, 0.1692140680117453f, + 0.1692613134343138f, 0.1693085584679289f, 0.1693558031124820f, 0.1694030473678645f, + 0.1694502912339680f, 0.1694975347106837f, 0.1695447777979033f, 0.1695920204955179f, + 0.1696392628034193f, 0.1696865047214987f, 0.1697337462496477f, 0.1697809873877576f, + 0.1698282281357198f, 0.1698754684934260f, 0.1699227084607674f, 0.1699699480376356f, + 0.1700171872239220f, 0.1700644260195179f, 0.1701116644243149f, 0.1701589024382045f, + 0.1702061400610781f, 0.1702533772928270f, 0.1703006141333429f, 0.1703478505825170f, + 0.1703950866402409f, 0.1704423223064061f, 0.1704895575809040f, 0.1705367924636260f, + 0.1705840269544636f, 0.1706312610533083f, 0.1706784947600515f, 0.1707257280745846f, + 0.1707729609967992f, 0.1708201935265867f, 0.1708674256638386f, 0.1709146574084462f, + 0.1709618887603012f, 0.1710091197192949f, 0.1710563502853189f, 0.1711035804582645f, + 0.1711508102380233f, 0.1711980396244867f, 0.1712452686175462f, 0.1712924972170932f, + 0.1713397254230193f, 0.1713869532352159f, 0.1714341806535744f, 0.1714814076779865f, + 0.1715286343083434f, 0.1715758605445368f, 0.1716230863864580f, 0.1716703118339986f, + 0.1717175368870500f, 0.1717647615455037f, 0.1718119858092512f, 0.1718592096781840f, + 0.1719064331521936f, 0.1719536562311713f, 0.1720008789150089f, 0.1720481012035976f, + 0.1720953230968290f, 0.1721425445945946f, 0.1721897656967859f, 0.1722369864032943f, + 0.1722842067140114f, 0.1723314266288286f, 0.1723786461476375f, 0.1724258652703294f, + 0.1724730839967960f, 0.1725203023269286f, 0.1725675202606189f, 0.1726147377977583f, + 0.1726619549382383f, 0.1727091716819503f, 0.1727563880287860f, 0.1728036039786368f, + 0.1728508195313941f, 0.1728980346869495f, 0.1729452494451945f, 0.1729924638060206f, + 0.1730396777693194f, 0.1730868913349822f, 0.1731341045029006f, 0.1731813172729662f, + 0.1732285296450703f, 0.1732757416191046f, 0.1733229531949606f, 0.1733701643725297f, + 0.1734173751517035f, 0.1734645855323734f, 0.1735117955144310f, 0.1735590050977679f, + 0.1736062142822754f, 0.1736534230678452f, 0.1737006314543688f, 0.1737478394417376f, + 0.1737950470298432f, 0.1738422542185770f, 0.1738894610078308f, 0.1739366673974959f, + 0.1739838733874638f, 0.1740310789776262f, 0.1740782841678744f, 0.1741254889581001f, + 0.1741726933481948f, 0.1742198973380500f, 0.1742671009275572f, 0.1743143041166079f, + 0.1743615069050937f, 0.1744087092929062f, 0.1744559112799368f, 0.1745031128660771f, + 0.1745503140512185f, 0.1745975148352527f, 0.1746447152180712f, 0.1746919151995656f, + 0.1747391147796272f, 0.1747863139581478f, 0.1748335127350187f, 0.1748807111101317f, + 0.1749279090833782f, 0.1749751066546497f, 0.1750223038238378f, 0.1750695005908340f, + 0.1751166969555299f, 0.1751638929178171f, 0.1752110884775870f, 0.1752582836347312f, + 0.1753054783891413f, 0.1753526727407088f, 0.1753998666893253f, 0.1754470602348824f, + 0.1754942533772714f, 0.1755414461163841f, 0.1755886384521120f, 0.1756358303843466f, + 0.1756830219129795f, 0.1757302130379022f, 0.1757774037590064f, 0.1758245940761834f, + 0.1758717839893250f, 0.1759189734983227f, 0.1759661626030680f, 0.1760133513034526f, + 0.1760605395993678f, 0.1761077274907054f, 0.1761549149773569f, 0.1762021020592139f, + 0.1762492887361679f, 0.1762964750081105f, 0.1763436608749332f, 0.1763908463365277f, + 0.1764380313927854f, 0.1764852160435980f, 0.1765324002888571f, 0.1765795841284542f, + 0.1766267675622809f, 0.1766739505902287f, 0.1767211332121893f, 0.1767683154280542f, + 0.1768154972377150f, 0.1768626786410633f, 0.1769098596379906f, 0.1769570402283886f, + 0.1770042204121487f, 0.1770514001891627f, 0.1770985795593221f, 0.1771457585225184f, + 0.1771929370786433f, 0.1772401152275883f, 0.1772872929692451f, 0.1773344703035051f, + 0.1773816472302600f, 0.1774288237494015f, 0.1774759998608210f, 0.1775231755644102f, + 0.1775703508600607f, 0.1776175257476641f, 0.1776647002271118f, 0.1777118742982957f, + 0.1777590479611072f, 0.1778062212154379f, 0.1778533940611795f, 0.1779005664982235f, + 0.1779477385264616f, 0.1779949101457853f, 0.1780420813560862f, 0.1780892521572560f, + 0.1781364225491863f, 0.1781835925317686f, 0.1782307621048946f, 0.1782779312684559f, + 0.1783251000223440f, 0.1783722683664506f, 0.1784194363006673f, 0.1784666038248858f, + 0.1785137709389975f, 0.1785609376428942f, 0.1786081039364674f, 0.1786552698196088f, + 0.1787024352922100f, 0.1787496003541625f, 0.1787967650053581f, 0.1788439292456883f, + 0.1788910930750447f, 0.1789382564933190f, 0.1789854195004028f, 0.1790325820961877f, + 0.1790797442805654f, 0.1791269060534274f, 0.1791740674146654f, 0.1792212283641709f, + 0.1792683889018357f, 0.1793155490275514f, 0.1793627087412096f, 0.1794098680427019f, + 0.1794570269319199f, 0.1795041854087553f, 0.1795513434730997f, 0.1795985011248448f, + 0.1796456583638822f, 0.1796928151901034f, 0.1797399716034002f, 0.1797871276036642f, + 0.1798342831907871f, 0.1798814383646604f, 0.1799285931251758f, 0.1799757474722250f, + 0.1800229014056995f, 0.1800700549254911f, 0.1801172080314914f, 0.1801643607235919f, + 0.1802115130016845f, 0.1802586648656606f, 0.1803058163154120f, 0.1803529673508303f, + 0.1804001179718072f, 0.1804472681782343f, 0.1804944179700033f, 0.1805415673470057f, + 0.1805887163091333f, 0.1806358648562778f, 0.1806830129883307f, 0.1807301607051838f, + 0.1807773080067286f, 0.1808244548928569f, 0.1808716013634603f, 0.1809187474184304f, + 0.1809658930576590f, 0.1810130382810377f, 0.1810601830884581f, 0.1811073274798119f, + 0.1811544714549908f, 0.1812016150138865f, 0.1812487581563905f, 0.1812959008823946f, + 0.1813430431917905f, 0.1813901850844699f, 0.1814373265603243f, 0.1814844676192454f, + 0.1815316082611250f, 0.1815787484858547f, 0.1816258882933261f, 0.1816730276834310f, + 0.1817201666560611f, 0.1817673052111080f, 0.1818144433484633f, 0.1818615810680188f, + 0.1819087183696662f, 0.1819558552532970f, 0.1820029917188031f, 0.1820501277660761f, + 0.1820972633950076f, 0.1821443986054894f, 0.1821915333974132f, 0.1822386677706706f, + 0.1822858017251533f, 0.1823329352607530f, 0.1823800683773614f, 0.1824272010748702f, + 0.1824743333531711f, 0.1825214652121558f, 0.1825685966517159f, 0.1826157276717431f, + 0.1826628582721293f, 0.1827099884527660f, 0.1827571182135449f, 0.1828042475543578f, + 0.1828513764750963f, 0.1828985049756522f, 0.1829456330559171f, 0.1829927607157828f, + 0.1830398879551410f, 0.1830870147738832f, 0.1831341411719014f, 0.1831812671490871f, + 0.1832283927053321f, 0.1832755178405281f, 0.1833226425545668f, 0.1833697668473399f, + 0.1834168907187391f, 0.1834640141686561f, 0.1835111371969827f, 0.1835582598036105f, + 0.1836053819884313f, 0.1836525037513368f, 0.1836996250922186f, 0.1837467460109686f, + 0.1837938665074784f, 0.1838409865816398f, 0.1838881062333445f, 0.1839352254624841f, + 0.1839823442689505f, 0.1840294626526353f, 0.1840765806134304f, 0.1841236981512272f, + 0.1841708152659177f, 0.1842179319573936f, 0.1842650482255465f, 0.1843121640702682f, + 0.1843592794914505f, 0.1844063944889850f, 0.1844535090627636f, 0.1845006232126779f, + 0.1845477369386196f, 0.1845948502404806f, 0.1846419631181524f, 0.1846890755715270f, + 0.1847361876004960f, 0.1847832992049511f, 0.1848304103847841f, 0.1848775211398868f, + 0.1849246314701508f, 0.1849717413754679f, 0.1850188508557299f, 0.1850659599108286f, + 0.1851130685406555f, 0.1851601767451026f, 0.1852072845240615f, 0.1852543918774240f, + 0.1853014988050819f, 0.1853486053069269f, 0.1853957113828507f, 0.1854428170327451f, + 0.1854899222565019f, 0.1855370270540128f, 0.1855841314251695f, 0.1856312353698639f, + 0.1856783388879876f, 0.1857254419794325f, 0.1857725446440903f, 0.1858196468818528f, + 0.1858667486926117f, 0.1859138500762587f, 0.1859609510326857f, 0.1860080515617844f, + 0.1860551516634466f, 0.1861022513375641f, 0.1861493505840285f, 0.1861964494027318f, + 0.1862435477935656f, 0.1862906457564217f, 0.1863377432911919f, 0.1863848403977679f, + 0.1864319370760416f, 0.1864790333259047f, 0.1865261291472490f, 0.1865732245399663f, + 0.1866203195039483f, 0.1866674140390868f, 0.1867145081452736f, 0.1867616018224005f, + 0.1868086950703593f, 0.1868557878890417f, 0.1869028802783395f, 0.1869499722381445f, + 0.1869970637683485f, 0.1870441548688433f, 0.1870912455395207f, 0.1871383357802724f, + 0.1871854255909903f, 0.1872325149715661f, 0.1872796039218917f, 0.1873266924418587f, + 0.1873737805313591f, 0.1874208681902846f, 0.1874679554185270f, 0.1875150422159780f, + 0.1875621285825296f, 0.1876092145180734f, 0.1876563000225014f, 0.1877033850957052f, + 0.1877504697375768f, 0.1877975539480078f, 0.1878446377268901f, 0.1878917210741156f, + 0.1879388039895759f, 0.1879858864731629f, 0.1880329685247685f, 0.1880800501442844f, + 0.1881271313316024f, 0.1881742120866144f, 0.1882212924092121f, 0.1882683722992874f, + 0.1883154517567321f, 0.1883625307814380f, 0.1884096093732969f, 0.1884566875322006f, + 0.1885037652580410f, 0.1885508425507098f, 0.1885979194100989f, 0.1886449958361001f, + 0.1886920718286052f, 0.1887391473875061f, 0.1887862225126945f, 0.1888332972040623f, + 0.1888803714615014f, 0.1889274452849035f, 0.1889745186741604f, 0.1890215916291640f, + 0.1890686641498062f, 0.1891157362359787f, 0.1891628078875734f, 0.1892098791044822f, + 0.1892569498865967f, 0.1893040202338090f, 0.1893510901460108f, 0.1893981596230939f, + 0.1894452286649502f, 0.1894922972714716f, 0.1895393654425498f, 0.1895864331780767f, + 0.1896335004779442f, 0.1896805673420441f, 0.1897276337702682f, 0.1897746997625084f, + 0.1898217653186564f, 0.1898688304386043f, 0.1899158951222438f, 0.1899629593694667f, + 0.1900100231801650f, 0.1900570865542304f, 0.1901041494915548f, 0.1901512119920301f, + 0.1901982740555481f, 0.1902453356820007f, 0.1902923968712797f, 0.1903394576232770f, + 0.1903865179378845f, 0.1904335778149939f, 0.1904806372544972f, 0.1905276962562862f, + 0.1905747548202528f, 0.1906218129462888f, 0.1906688706342861f, 0.1907159278841366f, + 0.1907629846957321f, 0.1908100410689645f, 0.1908570970037257f, 0.1909041524999075f, + 0.1909512075574018f, 0.1909982621761005f, 0.1910453163558954f, 0.1910923700966785f, + 0.1911394233983414f, 0.1911864762607763f, 0.1912335286838749f, 0.1912805806675292f, + 0.1913276322116309f, 0.1913746833160720f, 0.1914217339807443f, 0.1914687842055398f, + 0.1915158339903502f, 0.1915628833350676f, 0.1916099322395837f, 0.1916569807037905f, + 0.1917040287275798f, 0.1917510763108436f, 0.1917981234534736f, 0.1918451701553619f, + 0.1918922164164003f, 0.1919392622364806f, 0.1919863076154948f, 0.1920333525533348f, + 0.1920803970498924f, 0.1921274411050596f, 0.1921744847187283f, 0.1922215278907903f, + 0.1922685706211375f, 0.1923156129096619f, 0.1923626547562553f, 0.1924096961608097f, + 0.1924567371232168f, 0.1925037776433688f, 0.1925508177211574f, 0.1925978573564745f, + 0.1926448965492121f, 0.1926919352992621f, 0.1927389736065163f, 0.1927860114708667f, + 0.1928330488922052f, 0.1928800858704238f, 0.1929271224054142f, 0.1929741584970684f, + 0.1930211941452784f, 0.1930682293499360f, 0.1931152641109332f, 0.1931622984281619f, + 0.1932093323015140f, 0.1932563657308814f, 0.1933033987161560f, 0.1933504312572299f, + 0.1933974633539947f, 0.1934444950063427f, 0.1934915262141655f, 0.1935385569773551f, + 0.1935855872958036f, 0.1936326171694028f, 0.1936796465980446f, 0.1937266755816210f, + 0.1937737041200238f, 0.1938207322131451f, 0.1938677598608768f, 0.1939147870631107f, + 0.1939618138197389f, 0.1940088401306532f, 0.1940558659957456f, 0.1941028914149080f, + 0.1941499163880324f, 0.1941969409150108f, 0.1942439649957349f, 0.1942909886300969f, + 0.1943380118179886f, 0.1943850345593020f, 0.1944320568539290f, 0.1944790787017616f, + 0.1945261001026916f, 0.1945731210566111f, 0.1946201415634121f, 0.1946671616229864f, + 0.1947141812352260f, 0.1947612004000228f, 0.1948082191172689f, 0.1948552373868561f, + 0.1949022552086765f, 0.1949492725826220f, 0.1949962895085844f, 0.1950433059864559f, + 0.1950903220161282f, 0.1951373375974936f, 0.1951843527304438f, 0.1952313674148708f, + 0.1952783816506665f, 0.1953253954377231f, 0.1953724087759324f, 0.1954194216651864f, + 0.1954664341053770f, 0.1955134460963962f, 0.1955604576381360f, 0.1956074687304885f, + 0.1956544793733454f, 0.1957014895665988f, 0.1957484993101407f, 0.1957955086038631f, + 0.1958425174476578f, 0.1958895258414171f, 0.1959365337850326f, 0.1959835412783966f, + 0.1960305483214008f, 0.1960775549139374f, 0.1961245610558983f, 0.1961715667471755f, + 0.1962185719876609f, 0.1962655767772466f, 0.1963125811158245f, 0.1963595850032866f, + 0.1964065884395250f, 0.1964535914244315f, 0.1965005939578982f, 0.1965475960398172f, + 0.1965945976700802f, 0.1966415988485795f, 0.1966885995752069f, 0.1967355998498544f, + 0.1967825996724141f, 0.1968295990427779f, 0.1968765979608380f, 0.1969235964264861f, + 0.1969705944396143f, 0.1970175920001148f, 0.1970645891078793f, 0.1971115857628000f, + 0.1971585819647689f, 0.1972055777136779f, 0.1972525730094191f, 0.1972995678518844f, + 0.1973465622409659f, 0.1973935561765556f, 0.1974405496585455f, 0.1974875426868277f, + 0.1975345352612940f, 0.1975815273818366f, 0.1976285190483474f, 0.1976755102607185f, + 0.1977225010188419f, 0.1977694913226096f, 0.1978164811719136f, 0.1978634705666460f, + 0.1979104595066987f, 0.1979574479919638f, 0.1980044360223333f, 0.1980514235976992f, + 0.1980984107179536f, 0.1981453973829884f, 0.1981923835926958f, 0.1982393693469677f, + 0.1982863546456962f, 0.1983333394887733f, 0.1983803238760909f, 0.1984273078075413f, + 0.1984742912830164f, 0.1985212743024082f, 0.1985682568656087f, 0.1986152389725100f, + 0.1986622206230042f, 0.1987092018169833f, 0.1987561825543392f, 0.1988031628349642f, + 0.1988501426587501f, 0.1988971220255891f, 0.1989441009353731f, 0.1989910793879943f, + 0.1990380573833447f, 0.1990850349213163f, 0.1991320120018011f, 0.1991789886246913f, + 0.1992259647898788f, 0.1992729404972558f, 0.1993199157467143f, 0.1993668905381462f, + 0.1994138648714438f, 0.1994608387464990f, 0.1995078121632039f, 0.1995547851214505f, + 0.1996017576211310f, 0.1996487296621373f, 0.1996957012443615f, 0.1997426723676958f, + 0.1997896430320321f, 0.1998366132372625f, 0.1998835829832791f, 0.1999305522699740f, + 0.1999775210972392f, 0.2000244894649667f, 0.2000714573730488f, 0.2001184248213773f, + 0.2001653918098445f, 0.2002123583383423f, 0.2002593244067628f, 0.2003062900149982f, + 0.2003532551629404f, 0.2004002198504817f, 0.2004471840775140f, 0.2004941478439294f, + 0.2005411111496200f, 0.2005880739944779f, 0.2006350363783952f, 0.2006819983012639f, + 0.2007289597629761f, 0.2007759207634240f, 0.2008228813024996f, 0.2008698413800950f, + 0.2009168009961023f, 0.2009637601504135f, 0.2010107188429208f, 0.2010576770735162f, + 0.2011046348420919f, 0.2011515921485399f, 0.2011985489927524f, 0.2012455053746214f, + 0.2012924612940390f, 0.2013394167508974f, 0.2013863717450886f, 0.2014333262765046f, + 0.2014802803450377f, 0.2015272339505800f, 0.2015741870930235f, 0.2016211397722603f, + 0.2016680919881825f, 0.2017150437406823f, 0.2017619950296518f, 0.2018089458549830f, + 0.2018558962165680f, 0.2019028461142991f, 0.2019497955480682f, 0.2019967445177676f, + 0.2020436930232893f, 0.2020906410645254f, 0.2021375886413680f, 0.2021845357537094f, + 0.2022314824014415f, 0.2022784285844565f, 0.2023253743026465f, 0.2023723195559037f, + 0.2024192643441202f, 0.2024662086671880f, 0.2025131525249994f, 0.2025600959174463f, + 0.2026070388444211f, 0.2026539813058158f, 0.2027009233015225f, 0.2027478648314333f, + 0.2027948058954404f, 0.2028417464934360f, 0.2028886866253121f, 0.2029356262909609f, + 0.2029825654902745f, 0.2030295042231450f, 0.2030764424894647f, 0.2031233802891255f, + 0.2031703176220198f, 0.2032172544880396f, 0.2032641908870770f, 0.2033111268190242f, + 0.2033580622837733f, 0.2034049972812166f, 0.2034519318112460f, 0.2034988658737538f, + 0.2035457994686322f, 0.2035927325957732f, 0.2036396652550691f, 0.2036865974464120f, + 0.2037335291696939f, 0.2037804604248072f, 0.2038273912116438f, 0.2038743215300961f, + 0.2039212513800561f, 0.2039681807614161f, 0.2040151096740681f, 0.2040620381179042f, + 0.2041089660928169f, 0.2041558935986980f, 0.2042028206354399f, 0.2042497472029346f, + 0.2042966733010744f, 0.2043435989297513f, 0.2043905240888577f, 0.2044374487782856f, + 0.2044843729979272f, 0.2045312967476747f, 0.2045782200274202f, 0.2046251428370560f, + 0.2046720651764742f, 0.2047189870455670f, 0.2047659084442265f, 0.2048128293723449f, + 0.2048597498298144f, 0.2049066698165272f, 0.2049535893323755f, 0.2050005083772515f, + 0.2050474269510473f, 0.2050943450536550f, 0.2051412626849670f, 0.2051881798448754f, + 0.2052350965332723f, 0.2052820127500500f, 0.2053289284951007f, 0.2053758437683165f, + 0.2054227585695896f, 0.2054696728988122f, 0.2055165867558766f, 0.2055635001406749f, + 0.2056104130530992f, 0.2056573254930419f, 0.2057042374603951f, 0.2057511489550510f, + 0.2057980599769018f, 0.2058449705258397f, 0.2058918806017568f, 0.2059387902045455f, + 0.2059856993340979f, 0.2060326079903062f, 0.2060795161730627f, 0.2061264238822594f, + 0.2061733311177887f, 0.2062202378795428f, 0.2062671441674138f, 0.2063140499812940f, + 0.2063609553210755f, 0.2064078601866507f, 0.2064547645779116f, 0.2065016684947506f, + 0.2065485719370599f, 0.2065954749047316f, 0.2066423773976580f, 0.2066892794157313f, + 0.2067361809588437f, 0.2067830820268875f, 0.2068299826197548f, 0.2068768827373380f, + 0.2069237823795291f, 0.2069706815462205f, 0.2070175802373044f, 0.2070644784526730f, + 0.2071113761922186f, 0.2071582734558332f, 0.2072051702434094f, 0.2072520665548391f, + 0.2072989623900147f, 0.2073458577488285f, 0.2073927526311725f, 0.2074396470369392f, + 0.2074865409660206f, 0.2075334344183092f, 0.2075803273936970f, 0.2076272198920764f, + 0.2076741119133396f, 0.2077210034573788f, 0.2077678945240863f, 0.2078147851133543f, + 0.2078616752250751f, 0.2079085648591409f, 0.2079554540154439f, 0.2080023426938765f, + 0.2080492308943309f, 0.2080961186166994f, 0.2081430058608741f, 0.2081898926267473f, + 0.2082367789142113f, 0.2082836647231584f, 0.2083305500534808f, 0.2083774349050708f, + 0.2084243192778206f, 0.2084712031716225f, 0.2085180865863688f, 0.2085649695219517f, + 0.2086118519782635f, 0.2086587339551964f, 0.2087056154526428f, 0.2087524964704948f, + 0.2087993770086449f, 0.2088462570669851f, 0.2088931366454079f, 0.2089400157438055f, + 0.2089868943620701f, 0.2090337725000940f, 0.2090806501577696f, 0.2091275273349890f, + 0.2091744040316446f, 0.2092212802476286f, 0.2092681559828334f, 0.2093150312371511f, + 0.2093619060104742f, 0.2094087803026948f, 0.2094556541137053f, 0.2095025274433979f, + 0.2095494002916649f, 0.2095962726583987f, 0.2096431445434915f, 0.2096900159468356f, + 0.2097368868683233f, 0.2097837573078469f, 0.2098306272652986f, 0.2098774967405709f, + 0.2099243657335559f, 0.2099712342441460f, 0.2100181022722334f, 0.2100649698177105f, + 0.2101118368804696f, 0.2101587034604030f, 0.2102055695574029f, 0.2102524351713617f, + 0.2102993003021717f, 0.2103461649497252f, 0.2103930291139145f, 0.2104398927946319f, + 0.2104867559917697f, 0.2105336187052203f, 0.2105804809348759f, 0.2106273426806288f, + 0.2106742039423714f, 0.2107210647199960f, 0.2107679250133949f, 0.2108147848224604f, + 0.2108616441470849f, 0.2109085029871605f, 0.2109553613425798f, 0.2110022192132350f, + 0.2110490765990184f, 0.2110959334998223f, 0.2111427899155391f, 0.2111896458460612f, + 0.2112365012912807f, 0.2112833562510901f, 0.2113302107253817f, 0.2113770647140477f, + 0.2114239182169807f, 0.2114707712340728f, 0.2115176237652164f, 0.2115644758103039f, + 0.2116113273692276f, 0.2116581784418798f, 0.2117050290281528f, 0.2117518791279391f, + 0.2117987287411309f, 0.2118455778676205f, 0.2118924265073004f, 0.2119392746600629f, + 0.2119861223258003f, 0.2120329695044050f, 0.2120798161957693f, 0.2121266623997855f, + 0.2121735081163461f, 0.2122203533453433f, 0.2122671980866695f, 0.2123140423402171f, + 0.2123608861058784f, 0.2124077293835458f, 0.2124545721731117f, 0.2125014144744683f, + 0.2125482562875081f, 0.2125950976121233f, 0.2126419384482065f, 0.2126887787956499f, + 0.2127356186543459f, 0.2127824580241869f, 0.2128292969050652f, 0.2128761352968731f, + 0.2129229731995032f, 0.2129698106128476f, 0.2130166475367989f, 0.2130634839712494f, + 0.2131103199160914f, 0.2131571553712173f, 0.2132039903365195f, 0.2132508248118904f, + 0.2132976587972223f, 0.2133444922924077f, 0.2133913252973388f, 0.2134381578119081f, + 0.2134849898360081f, 0.2135318213695309f, 0.2135786524123691f, 0.2136254829644150f, + 0.2136723130255610f, 0.2137191425956995f, 0.2137659716747228f, 0.2138128002625235f, + 0.2138596283589938f, 0.2139064559640261f, 0.2139532830775129f, 0.2140001096993465f, + 0.2140469358294194f, 0.2140937614676238f, 0.2141405866138523f, 0.2141874112679972f, + 0.2142342354299510f, 0.2142810590996060f, 0.2143278822768545f, 0.2143747049615891f, + 0.2144215271537022f, 0.2144683488530860f, 0.2145151700596332f, 0.2145619907732360f, + 0.2146088109937868f, 0.2146556307211780f, 0.2147024499553022f, 0.2147492686960517f, + 0.2147960869433189f, 0.2148429046969962f, 0.2148897219569759f, 0.2149365387231507f, + 0.2149833549954128f, 0.2150301707736547f, 0.2150769860577689f, 0.2151238008476476f, + 0.2151706151431834f, 0.2152174289442687f, 0.2152642422507958f, 0.2153110550626573f, + 0.2153578673797455f, 0.2154046792019530f, 0.2154514905291720f, 0.2154983013612950f, + 0.2155451116982145f, 0.2155919215398229f, 0.2156387308860127f, 0.2156855397366761f, + 0.2157323480917059f, 0.2157791559509942f, 0.2158259633144337f, 0.2158727701819166f, + 0.2159195765533355f, 0.2159663824285828f, 0.2160131878075509f, 0.2160599926901323f, + 0.2161067970762195f, 0.2161536009657049f, 0.2162004043584808f, 0.2162472072544398f, + 0.2162940096534743f, 0.2163408115554769f, 0.2163876129603398f, 0.2164344138679556f, + 0.2164812142782167f, 0.2165280141910157f, 0.2165748136062449f, 0.2166216125237967f, + 0.2166684109435638f, 0.2167152088654384f, 0.2167620062893131f, 0.2168088032150804f, + 0.2168555996426326f, 0.2169023955718624f, 0.2169491910026620f, 0.2169959859349241f, + 0.2170427803685410f, 0.2170895743034053f, 0.2171363677394093f, 0.2171831606764457f, + 0.2172299531144068f, 0.2172767450531851f, 0.2173235364926731f, 0.2173703274327633f, + 0.2174171178733482f, 0.2174639078143202f, 0.2175106972555717f, 0.2175574861969954f, + 0.2176042746384836f, 0.2176510625799289f, 0.2176978500212238f, 0.2177446369622606f, + 0.2177914234029319f, 0.2178382093431303f, 0.2178849947827481f, 0.2179317797216780f, + 0.2179785641598122f, 0.2180253480970434f, 0.2180721315332641f, 0.2181189144683667f, + 0.2181656969022438f, 0.2182124788347878f, 0.2182592602658912f, 0.2183060411954465f, + 0.2183528216233463f, 0.2183996015494830f, 0.2184463809737492f, 0.2184931598960373f, + 0.2185399383162398f, 0.2185867162342493f, 0.2186334936499582f, 0.2186802705632591f, + 0.2187270469740445f, 0.2187738228822068f, 0.2188205982876386f, 0.2188673731902325f, + 0.2189141475898808f, 0.2189609214864762f, 0.2190076948799112f, 0.2190544677700782f, + 0.2191012401568698f, 0.2191480120401785f, 0.2191947834198968f, 0.2192415542959173f, + 0.2192883246681325f, 0.2193350945364348f, 0.2193818639007169f, 0.2194286327608712f, + 0.2194754011167903f, 0.2195221689683667f, 0.2195689363154929f, 0.2196157031580615f, + 0.2196624694959650f, 0.2197092353290960f, 0.2197560006573469f, 0.2198027654806103f, + 0.2198495297987787f, 0.2198962936117447f, 0.2199430569194008f, 0.2199898197216396f, + 0.2200365820183536f, 0.2200833438094353f, 0.2201301050947773f, 0.2201768658742722f, + 0.2202236261478124f, 0.2202703859152905f, 0.2203171451765991f, 0.2203639039316307f, + 0.2204106621802779f, 0.2204574199224333f, 0.2205041771579893f, 0.2205509338868385f, + 0.2205976901088735f, 0.2206444458239869f, 0.2206912010320712f, 0.2207379557330189f, + 0.2207847099267226f, 0.2208314636130750f, 0.2208782167919685f, 0.2209249694632957f, + 0.2209717216269491f, 0.2210184732828214f, 0.2210652244308051f, 0.2211119750707928f, + 0.2211587252026770f, 0.2212054748263504f, 0.2212522239417054f, 0.2212989725486347f, + 0.2213457206470308f, 0.2213924682367863f, 0.2214392153177939f, 0.2214859618899460f, + 0.2215327079531352f, 0.2215794535072542f, 0.2216261985521954f, 0.2216729430878516f, + 0.2217196871141152f, 0.2217664306308789f, 0.2218131736380352f, 0.2218599161354767f, + 0.2219066581230961f, 0.2219533996007859f, 0.2220001405684386f, 0.2220468810259470f, + 0.2220936209732035f, 0.2221403604101008f, 0.2221870993365315f, 0.2222338377523882f, + 0.2222805756575634f, 0.2223273130519498f, 0.2223740499354399f, 0.2224207863079264f, + 0.2224675221693019f, 0.2225142575194589f, 0.2225609923582901f, 0.2226077266856882f, + 0.2226544605015455f, 0.2227011938057549f, 0.2227479265982089f, 0.2227946588788001f, + 0.2228413906474211f, 0.2228881219039646f, 0.2229348526483231f, 0.2229815828803893f, + 0.2230283126000558f, 0.2230750418072152f, 0.2231217705017601f, 0.2231684986835832f, + 0.2232152263525770f, 0.2232619535086342f, 0.2233086801516474f, 0.2233554062815093f, + 0.2234021318981124f, 0.2234488570013494f, 0.2234955815911129f, 0.2235423056672955f, + 0.2235890292297900f, 0.2236357522784888f, 0.2236824748132847f, 0.2237291968340703f, + 0.2237759183407382f, 0.2238226393331810f, 0.2238693598112914f, 0.2239160797749620f, + 0.2239627992240855f, 0.2240095181585545f, 0.2240562365782616f, 0.2241029544830995f, + 0.2241496718729609f, 0.2241963887477383f, 0.2242431051073245f, 0.2242898209516120f, + 0.2243365362804936f, 0.2243832510938619f, 0.2244299653916094f, 0.2244766791736290f, + 0.2245233924398132f, 0.2245701051900547f, 0.2246168174242461f, 0.2246635291422801f, + 0.2247102403440494f, 0.2247569510294466f, 0.2248036611983645f, 0.2248503708506955f, + 0.2248970799863325f, 0.2249437886051680f, 0.2249904967070948f, 0.2250372042920055f, + 0.2250839113597928f, 0.2251306179103494f, 0.2251773239435678f, 0.2252240294593408f, + 0.2252707344575612f, 0.2253174389381214f, 0.2253641429009143f, 0.2254108463458324f, + 0.2254575492727685f, 0.2255042516816153f, 0.2255509535722654f, 0.2255976549446115f, + 0.2256443557985463f, 0.2256910561339625f, 0.2257377559507527f, 0.2257844552488097f, + 0.2258311540280262f, 0.2258778522882947f, 0.2259245500295081f, 0.2259712472515590f, + 0.2260179439543400f, 0.2260646401377440f, 0.2261113358016635f, 0.2261580309459914f, + 0.2262047255706202f, 0.2262514196754427f, 0.2262981132603515f, 0.2263448063252395f, + 0.2263914988699992f, 0.2264381908945234f, 0.2264848823987048f, 0.2265315733824361f, + 0.2265782638456100f, 0.2266249537881192f, 0.2266716432098564f, 0.2267183321107143f, + 0.2267650204905857f, 0.2268117083493632f, 0.2268583956869396f, 0.2269050825032076f, + 0.2269517687980598f, 0.2269984545713891f, 0.2270451398230881f, 0.2270918245530495f, + 0.2271385087611662f, 0.2271851924473307f, 0.2272318756114358f, 0.2272785582533743f, + 0.2273252403730389f, 0.2273719219703222f, 0.2274186030451171f, 0.2274652835973162f, + 0.2275119636268123f, 0.2275586431334981f, 0.2276053221172664f, 0.2276520005780098f, + 0.2276986785156212f, 0.2277453559299932f, 0.2277920328210186f, 0.2278387091885901f, + 0.2278853850326005f, 0.2279320603529426f, 0.2279787351495089f, 0.2280254094221924f, + 0.2280720831708857f, 0.2281187563954817f, 0.2281654290958729f, 0.2282121012719522f, + 0.2282587729236124f, 0.2283054440507462f, 0.2283521146532462f, 0.2283987847310054f, + 0.2284454542839165f, 0.2284921233118721f, 0.2285387918147651f, 0.2285854597924882f, + 0.2286321272449342f, 0.2286787941719959f, 0.2287254605735659f, 0.2287721264495371f, + 0.2288187917998022f, 0.2288654566242540f, 0.2289121209227853f, 0.2289587846952889f, + 0.2290054479416574f, 0.2290521106617836f, 0.2290987728555604f, 0.2291454345228806f, + 0.2291920956636368f, 0.2292387562777219f, 0.2292854163650286f, 0.2293320759254497f, + 0.2293787349588780f, 0.2294253934652063f, 0.2294720514443274f, 0.2295187088961340f, + 0.2295653658205189f, 0.2296120222173749f, 0.2296586780865948f, 0.2297053334280714f, + 0.2297519882416975f, 0.2297986425273658f, 0.2298452962849692f, 0.2298919495144004f, + 0.2299386022155522f, 0.2299852543883175f, 0.2300319060325890f, 0.2300785571482595f, + 0.2301252077352219f, 0.2301718577933688f, 0.2302185073225932f, 0.2302651563227878f, + 0.2303118047938455f, 0.2303584527356589f, 0.2304051001481210f, 0.2304517470311246f, + 0.2304983933845624f, 0.2305450392083272f, 0.2305916845023119f, 0.2306383292664093f, + 0.2306849735005122f, 0.2307316172045134f, 0.2307782603783058f, 0.2308249030217820f, + 0.2308715451348350f, 0.2309181867173576f, 0.2309648277692426f, 0.2310114682903829f, + 0.2310581082806711f, 0.2311047477400003f, 0.2311513866682630f, 0.2311980250653524f, + 0.2312446629311611f, 0.2312913002655819f, 0.2313379370685077f, 0.2313845733398314f, + 0.2314312090794458f, 0.2314778442872436f, 0.2315244789631178f, 0.2315711131069611f, + 0.2316177467186665f, 0.2316643797981267f, 0.2317110123452346f, 0.2317576443598830f, + 0.2318042758419648f, 0.2318509067913728f, 0.2318975372079998f, 0.2319441670917387f, + 0.2319907964424824f, 0.2320374252601237f, 0.2320840535445555f, 0.2321306812956705f, + 0.2321773085133617f, 0.2322239351975219f, 0.2322705613480439f, 0.2323171869648207f, + 0.2323638120477451f, 0.2324104365967098f, 0.2324570606116078f, 0.2325036840923320f, + 0.2325503070387752f, 0.2325969294508303f, 0.2326435513283901f, 0.2326901726713475f, + 0.2327367934795954f, 0.2327834137530266f, 0.2328300334915341f, 0.2328766526950105f, + 0.2329232713633490f, 0.2329698894964422f, 0.2330165070941832f, 0.2330631241564647f, + 0.2331097406831797f, 0.2331563566742210f, 0.2332029721294815f, 0.2332495870488541f, + 0.2332962014322316f, 0.2333428152795070f, 0.2333894285905731f, 0.2334360413653228f, + 0.2334826536036491f, 0.2335292653054447f, 0.2335758764706026f, 0.2336224870990157f, + 0.2336690971905769f, 0.2337157067451789f, 0.2337623157627149f, 0.2338089242430775f, + 0.2338555321861598f, 0.2339021395918547f, 0.2339487464600550f, 0.2339953527906536f, + 0.2340419585835434f, 0.2340885638386174f, 0.2341351685557684f, 0.2341817727348894f, + 0.2342283763758732f, 0.2342749794786128f, 0.2343215820430010f, 0.2343681840689309f, + 0.2344147855562952f, 0.2344613865049869f, 0.2345079869148989f, 0.2345545867859242f, + 0.2346011861179556f, 0.2346477849108860f, 0.2346943831646085f, 0.2347409808790158f, + 0.2347875780540010f, 0.2348341746894569f, 0.2348807707852764f, 0.2349273663413526f, + 0.2349739613575783f, 0.2350205558338464f, 0.2350671497700499f, 0.2351137431660817f, + 0.2351603360218347f, 0.2352069283372019f, 0.2352535201120762f, 0.2353001113463505f, + 0.2353467020399178f, 0.2353932921926710f, 0.2354398818045031f, 0.2354864708753069f, + 0.2355330594049755f, 0.2355796473934017f, 0.2356262348404786f, 0.2356728217460990f, + 0.2357194081101558f, 0.2357659939325422f, 0.2358125792131509f, 0.2358591639518750f, + 0.2359057481486074f, 0.2359523318032410f, 0.2359989149156688f, 0.2360454974857838f, + 0.2360920795134789f, 0.2361386609986471f, 0.2361852419411813f, 0.2362318223409745f, + 0.2362784021979196f, 0.2363249815119096f, 0.2363715602828375f, 0.2364181385105963f, + 0.2364647161950788f, 0.2365112933361781f, 0.2365578699337872f, 0.2366044459877989f, + 0.2366510214981064f, 0.2366975964646025f, 0.2367441708871802f, 0.2367907447657325f, + 0.2368373181001524f, 0.2368838908903328f, 0.2369304631361668f, 0.2369770348375473f, + 0.2370236059943672f, 0.2370701766065196f, 0.2371167466738975f, 0.2371633161963939f, + 0.2372098851739016f, 0.2372564536063138f, 0.2373030214935233f, 0.2373495888354233f, + 0.2373961556319066f, 0.2374427218828663f, 0.2374892875881954f, 0.2375358527477868f, + 0.2375824173615336f, 0.2376289814293287f, 0.2376755449510652f, 0.2377221079266360f, + 0.2377686703559342f, 0.2378152322388527f, 0.2378617935752846f, 0.2379083543651229f, + 0.2379549146082605f, 0.2380014743045905f, 0.2380480334540059f, 0.2380945920563997f, + 0.2381411501116648f, 0.2381877076196944f, 0.2382342645803815f, 0.2382808209936189f, + 0.2383273768592998f, 0.2383739321773172f, 0.2384204869475641f, 0.2384670411699335f, + 0.2385135948443184f, 0.2385601479706119f, 0.2386067005487070f, 0.2386532525784966f, + 0.2386998040598740f, 0.2387463549927319f, 0.2387929053769636f, 0.2388394552124619f, + 0.2388860044991200f, 0.2389325532368309f, 0.2389791014254876f, 0.2390256490649832f, + 0.2390721961552106f, 0.2391187426960630f, 0.2391652886874333f, 0.2392118341292146f, + 0.2392583790213000f, 0.2393049233635824f, 0.2393514671559550f, 0.2393980103983107f, + 0.2394445530905426f, 0.2394910952325439f, 0.2395376368242074f, 0.2395841778654263f, + 0.2396307183560936f, 0.2396772582961023f, 0.2397237976853456f, 0.2397703365237165f, + 0.2398168748111080f, 0.2398634125474132f, 0.2399099497325251f, 0.2399564863663369f, + 0.2400030224487415f, 0.2400495579796320f, 0.2400960929589016f, 0.2401426273864432f, + 0.2401891612621499f, 0.2402356945859148f, 0.2402822273576310f, 0.2403287595771915f, + 0.2403752912444894f, 0.2404218223594178f, 0.2404683529218698f, 0.2405148829317384f, + 0.2405614123889167f, 0.2406079412932977f, 0.2406544696447747f, 0.2407009974432405f, + 0.2407475246885884f, 0.2407940513807114f, 0.2408405775195026f, 0.2408871031048551f, + 0.2409336281366619f, 0.2409801526148162f, 0.2410266765392110f, 0.2410731999097395f, + 0.2411197227262946f, 0.2411662449887696f, 0.2412127666970575f, 0.2412592878510514f, + 0.2413058084506444f, 0.2413523284957296f, 0.2413988479862000f, 0.2414453669219489f, + 0.2414918853028693f, 0.2415384031288544f, 0.2415849203997971f, 0.2416314371155906f, + 0.2416779532761280f, 0.2417244688813025f, 0.2417709839310071f, 0.2418174984251350f, + 0.2418640123635792f, 0.2419105257462329f, 0.2419570385729892f, 0.2420035508437412f, + 0.2420500625583821f, 0.2420965737168048f, 0.2421430843189027f, 0.2421895943645687f, + 0.2422361038536960f, 0.2422826127861778f, 0.2423291211619071f, 0.2423756289807771f, + 0.2424221362426809f, 0.2424686429475116f, 0.2425151490951625f, 0.2425616546855265f, + 0.2426081597184968f, 0.2426546641939666f, 0.2427011681118290f, 0.2427476714719772f, + 0.2427941742743042f, 0.2428406765187033f, 0.2428871782050675f, 0.2429336793332899f, + 0.2429801799032639f, 0.2430266799148824f, 0.2430731793680387f, 0.2431196782626258f, + 0.2431661765985369f, 0.2432126743756652f, 0.2432591715939039f, 0.2433056682531460f, + 0.2433521643532847f, 0.2433986598942133f, 0.2434451548758247f, 0.2434916492980123f, + 0.2435381431606691f, 0.2435846364636884f, 0.2436311292069632f, 0.2436776213903867f, + 0.2437241130138522f, 0.2437706040772527f, 0.2438170945804814f, 0.2438635845234316f, + 0.2439100739059963f, 0.2439565627280687f, 0.2440030509895421f, 0.2440495386903095f, + 0.2440960258302642f, 0.2441425124092993f, 0.2441889984273080f, 0.2442354838841835f, + 0.2442819687798190f, 0.2443284531141076f, 0.2443749368869426f, 0.2444214200982170f, + 0.2444679027478242f, 0.2445143848356572f, 0.2445608663616093f, 0.2446073473255736f, + 0.2446538277274433f, 0.2447003075671117f, 0.2447467868444720f, 0.2447932655594172f, + 0.2448397437118407f, 0.2448862213016355f, 0.2449326983286950f, 0.2449791747929122f, + 0.2450256506941805f, 0.2450721260323930f, 0.2451186008074428f, 0.2451650750192233f, + 0.2452115486676275f, 0.2452580217525488f, 0.2453044942738804f, 0.2453509662315153f, + 0.2453974376253470f, 0.2454439084552684f, 0.2454903787211729f, 0.2455368484229537f, + 0.2455833175605041f, 0.2456297861337171f, 0.2456762541424860f, 0.2457227215867041f, + 0.2457691884662646f, 0.2458156547810606f, 0.2458621205309855f, 0.2459085857159324f, + 0.2459550503357946f, 0.2460015143904653f, 0.2460479778798376f, 0.2460944408038050f, + 0.2461409031622605f, 0.2461873649550975f, 0.2462338261822090f, 0.2462802868434885f, + 0.2463267469388290f, 0.2463732064681239f, 0.2464196654312665f, 0.2464661238281498f, + 0.2465125816586672f, 0.2465590389227119f, 0.2466054956201772f, 0.2466519517509563f, + 0.2466984073149424f, 0.2467448623120289f, 0.2467913167421088f, 0.2468377706050756f, + 0.2468842239008224f, 0.2469306766292426f, 0.2469771287902292f, 0.2470235803836757f, + 0.2470700314094753f, 0.2471164818675211f, 0.2471629317577066f, 0.2472093810799249f, + 0.2472558298340693f, 0.2473022780200331f, 0.2473487256377095f, 0.2473951726869918f, + 0.2474416191677733f, 0.2474880650799472f, 0.2475345104234068f, 0.2475809551980455f, + 0.2476273994037563f, 0.2476738430404326f, 0.2477202861079678f, 0.2477667286062550f, + 0.2478131705351877f, 0.2478596118946589f, 0.2479060526845620f, 0.2479524929047903f, + 0.2479989325552371f, 0.2480453716357957f, 0.2480918101463593f, 0.2481382480868213f, + 0.2481846854570748f, 0.2482311222570132f, 0.2482775584865299f, 0.2483239941455181f, + 0.2483704292338710f, 0.2484168637514821f, 0.2484632976982444f, 0.2485097310740515f, + 0.2485561638787966f, 0.2486025961123729f, 0.2486490277746738f, 0.2486954588655925f, + 0.2487418893850225f, 0.2487883193328569f, 0.2488347487089891f, 0.2488811775133124f, + 0.2489276057457201f, 0.2489740334061056f, 0.2490204604943621f, 0.2490668870103829f, + 0.2491133129540614f, 0.2491597383252908f, 0.2492061631239646f, 0.2492525873499759f, + 0.2492990110032182f, 0.2493454340835847f, 0.2493918565909688f, 0.2494382785252638f, + 0.2494846998863630f, 0.2495311206741598f, 0.2495775408885474f, 0.2496239605294192f, + 0.2496703795966685f, 0.2497167980901888f, 0.2497632160098732f, 0.2498096333556152f, + 0.2498560501273080f, 0.2499024663248450f, 0.2499488819481195f, 0.2499952969970250f, + 0.2500417114714547f, 0.2500881253713019f, 0.2501345386964600f, 0.2501809514468225f, + 0.2502273636222824f, 0.2502737752227333f, 0.2503201862480686f, 0.2503665966981814f, + 0.2504130065729653f, 0.2504594158723135f, 0.2505058245961194f, 0.2505522327442763f, + 0.2505986403166777f, 0.2506450473132169f, 0.2506914537337871f, 0.2507378595782819f, + 0.2507842648465945f, 0.2508306695386183f, 0.2508770736542467f, 0.2509234771933731f, + 0.2509698801558907f, 0.2510162825416931f, 0.2510626843506735f, 0.2511090855827253f, + 0.2511554862377419f, 0.2512018863156167f, 0.2512482858162430f, 0.2512946847395143f, + 0.2513410830853239f, 0.2513874808535650f, 0.2514338780441314f, 0.2514802746569161f, + 0.2515266706918126f, 0.2515730661487144f, 0.2516194610275147f, 0.2516658553281070f, + 0.2517122490503847f, 0.2517586421942412f, 0.2518050347595698f, 0.2518514267462639f, + 0.2518978181542170f, 0.2519442089833223f, 0.2519905992334734f, 0.2520369889045637f, + 0.2520833779964864f, 0.2521297665091352f, 0.2521761544424032f, 0.2522225417961840f, + 0.2522689285703708f, 0.2523153147648572f, 0.2523617003795366f, 0.2524080854143023f, + 0.2524544698690478f, 0.2525008537436664f, 0.2525472370380517f, 0.2525936197520969f, + 0.2526400018856955f, 0.2526863834387411f, 0.2527327644111267f, 0.2527791448027461f, + 0.2528255246134926f, 0.2528719038432596f, 0.2529182824919406f, 0.2529646605594288f, + 0.2530110380456179f, 0.2530574149504012f, 0.2531037912736721f, 0.2531501670153241f, + 0.2531965421752506f, 0.2532429167533450f, 0.2532892907495007f, 0.2533356641636113f, + 0.2533820369955702f, 0.2534284092452707f, 0.2534747809126063f, 0.2535211519974704f, + 0.2535675224997566f, 0.2536138924193582f, 0.2536602617561686f, 0.2537066305100815f, + 0.2537529986809900f, 0.2537993662687878f, 0.2538457332733683f, 0.2538920996946248f, + 0.2539384655324511f, 0.2539848307867403f, 0.2540311954573859f, 0.2540775595442816f, + 0.2541239230473206f, 0.2541702859663966f, 0.2542166483014028f, 0.2542630100522328f, + 0.2543093712187800f, 0.2543557318009380f, 0.2544020917986001f, 0.2544484512116599f, + 0.2544948100400108f, 0.2545411682835462f, 0.2545875259421597f, 0.2546338830157448f, + 0.2546802395041948f, 0.2547265954074034f, 0.2547729507252638f, 0.2548193054576697f, + 0.2548656596045146f, 0.2549120131656917f, 0.2549583661410948f, 0.2550047185306172f, + 0.2550510703341525f, 0.2550974215515941f, 0.2551437721828355f, 0.2551901222277702f, + 0.2552364716862917f, 0.2552828205582935f, 0.2553291688436691f, 0.2553755165423118f, + 0.2554218636541155f, 0.2554682101789733f, 0.2555145561167789f, 0.2555609014674258f, + 0.2556072462308074f, 0.2556535904068173f, 0.2556999339953490f, 0.2557462769962959f, + 0.2557926194095516f, 0.2558389612350096f, 0.2558853024725634f, 0.2559316431221065f, + 0.2559779831835324f, 0.2560243226567346f, 0.2560706615416067f, 0.2561169998380421f, + 0.2561633375459345f, 0.2562096746651772f, 0.2562560111956638f, 0.2563023471372879f, + 0.2563486824899429f, 0.2563950172535224f, 0.2564413514279199f, 0.2564876850130289f, + 0.2565340180087431f, 0.2565803504149557f, 0.2566266822315605f, 0.2566730134584511f, + 0.2567193440955207f, 0.2567656741426631f, 0.2568120035997717f, 0.2568583324667401f, + 0.2569046607434619f, 0.2569509884298306f, 0.2569973155257396f, 0.2570436420310826f, + 0.2570899679457531f, 0.2571362932696447f, 0.2571826180026509f, 0.2572289421446652f, + 0.2572752656955811f, 0.2573215886552924f, 0.2573679110236924f, 0.2574142328006748f, + 0.2574605539861331f, 0.2575068745799608f, 0.2575531945820516f, 0.2575995139922990f, + 0.2576458328105964f, 0.2576921510368376f, 0.2577384686709160f, 0.2577847857127253f, + 0.2578311021621590f, 0.2578774180191106f, 0.2579237332834738f, 0.2579700479551421f, + 0.2580163620340090f, 0.2580626755199681f, 0.2581089884129131f, 0.2581553007127376f, + 0.2582016124193349f, 0.2582479235325988f, 0.2582942340524228f, 0.2583405439787006f, + 0.2583868533113256f, 0.2584331620501915f, 0.2584794701951919f, 0.2585257777462203f, + 0.2585720847031704f, 0.2586183910659356f, 0.2586646968344097f, 0.2587110020084862f, + 0.2587573065880587f, 0.2588036105730208f, 0.2588499139632660f, 0.2588962167586881f, + 0.2589425189591805f, 0.2589888205646370f, 0.2590351215749510f, 0.2590814219900162f, + 0.2591277218097262f, 0.2591740210339746f, 0.2592203196626550f, 0.2592666176956610f, + 0.2593129151328862f, 0.2593592119742243f, 0.2594055082195688f, 0.2594518038688134f, + 0.2594980989218517f, 0.2595443933785772f, 0.2595906872388837f, 0.2596369805026646f, + 0.2596832731698138f, 0.2597295652402247f, 0.2597758567137910f, 0.2598221475904063f, + 0.2598684378699643f, 0.2599147275523585f, 0.2599610166374827f, 0.2600073051252303f, + 0.2600535930154952f, 0.2600998803081708f, 0.2601461670031509f, 0.2601924531003290f, + 0.2602387385995988f, 0.2602850235008540f, 0.2603313078039882f, 0.2603775915088950f, + 0.2604238746154680f, 0.2604701571236009f, 0.2605164390331875f, 0.2605627203441212f, + 0.2606090010562958f, 0.2606552811696048f, 0.2607015606839420f, 0.2607478395992011f, + 0.2607941179152755f, 0.2608403956320591f, 0.2608866727494454f, 0.2609329492673282f, + 0.2609792251856011f, 0.2610255005041576f, 0.2610717752228917f, 0.2611180493416967f, + 0.2611643228604665f, 0.2612105957790947f, 0.2612568680974749f, 0.2613031398155010f, + 0.2613494109330664f, 0.2613956814500649f, 0.2614419513663901f, 0.2614882206819357f, + 0.2615344893965955f, 0.2615807575102630f, 0.2616270250228320f, 0.2616732919341961f, + 0.2617195582442490f, 0.2617658239528845f, 0.2618120890599961f, 0.2618583535654776f, + 0.2619046174692226f, 0.2619508807711248f, 0.2619971434710781f, 0.2620434055689759f, + 0.2620896670647120f, 0.2621359279581802f, 0.2621821882492741f, 0.2622284479378873f, + 0.2622747070239136f, 0.2623209655072468f, 0.2623672233877804f, 0.2624134806654083f, + 0.2624597373400240f, 0.2625059934115213f, 0.2625522488797940f, 0.2625985037447356f, + 0.2626447580062401f, 0.2626910116642009f, 0.2627372647185118f, 0.2627835171690667f, + 0.2628297690157592f, 0.2628760202584829f, 0.2629222708971316f, 0.2629685209315991f, + 0.2630147703617790f, 0.2630610191875651f, 0.2631072674088510f, 0.2631535150255306f, + 0.2631997620374976f, 0.2632460084446456f, 0.2632922542468684f, 0.2633384994440597f, + 0.2633847440361133f, 0.2634309880229229f, 0.2634772314043821f, 0.2635234741803849f, + 0.2635697163508249f, 0.2636159579155957f, 0.2636621988745913f, 0.2637084392277053f, + 0.2637546789748313f, 0.2638009181158634f, 0.2638471566506951f, 0.2638933945792202f, + 0.2639396319013323f, 0.2639858686169254f, 0.2640321047258932f, 0.2640783402281293f, + 0.2641245751235275f, 0.2641708094119817f, 0.2642170430933855f, 0.2642632761676327f, + 0.2643095086346171f, 0.2643557404942324f, 0.2644019717463724f, 0.2644482023909310f, + 0.2644944324278016f, 0.2645406618568783f, 0.2645868906780547f, 0.2646331188912247f, + 0.2646793464962819f, 0.2647255734931202f, 0.2647717998816334f, 0.2648180256617151f, + 0.2648642508332593f, 0.2649104753961596f, 0.2649566993503098f, 0.2650029226956038f, + 0.2650491454319353f, 0.2650953675591980f, 0.2651415890772859f, 0.2651878099860925f, + 0.2652340302855118f, 0.2652802499754375f, 0.2653264690557635f, 0.2653726875263835f, + 0.2654189053871913f, 0.2654651226380807f, 0.2655113392789454f, 0.2655575553096793f, + 0.2656037707301763f, 0.2656499855403300f, 0.2656961997400344f, 0.2657424133291831f, + 0.2657886263076699f, 0.2658348386753889f, 0.2658810504322335f, 0.2659272615780979f, + 0.2659734721128756f, 0.2660196820364605f, 0.2660658913487466f, 0.2661121000496274f, + 0.2661583081389970f, 0.2662045156167490f, 0.2662507224827774f, 0.2662969287369758f, + 0.2663431343792382f, 0.2663893394094584f, 0.2664355438275301f, 0.2664817476333473f, + 0.2665279508268037f, 0.2665741534077932f, 0.2666203553762096f, 0.2666665567319467f, + 0.2667127574748984f, 0.2667589576049584f, 0.2668051571220207f, 0.2668513560259791f, + 0.2668975543167273f, 0.2669437519941594f, 0.2669899490581690f, 0.2670361455086500f, + 0.2670823413454962f, 0.2671285365686016f, 0.2671747311778600f, 0.2672209251731651f, + 0.2672671185544109f, 0.2673133113214912f, 0.2673595034742999f, 0.2674056950127308f, + 0.2674518859366776f, 0.2674980762460345f, 0.2675442659406951f, 0.2675904550205533f, + 0.2676366434855031f, 0.2676828313354381f, 0.2677290185702525f, 0.2677752051898398f, + 0.2678213911940941f, 0.2678675765829093f, 0.2679137613561791f, 0.2679599455137975f, + 0.2680061290556583f, 0.2680523119816554f, 0.2680984942916826f, 0.2681446759856340f, + 0.2681908570634032f, 0.2682370375248842f, 0.2682832173699710f, 0.2683293965985572f, + 0.2683755752105369f, 0.2684217532058040f, 0.2684679305842522f, 0.2685141073457756f, + 0.2685602834902679f, 0.2686064590176231f, 0.2686526339277351f, 0.2686988082204977f, + 0.2687449818958050f, 0.2687911549535506f, 0.2688373273936286f, 0.2688834992159329f, + 0.2689296704203573f, 0.2689758410067957f, 0.2690220109751421f, 0.2690681803252903f, + 0.2691143490571344f, 0.2691605171705680f, 0.2692066846654853f, 0.2692528515417800f, + 0.2692990177993462f, 0.2693451834380776f, 0.2693913484578682f, 0.2694375128586120f, + 0.2694836766402028f, 0.2695298398025347f, 0.2695760023455013f, 0.2696221642689968f, + 0.2696683255729151f, 0.2697144862571500f, 0.2697606463215955f, 0.2698068057661455f, + 0.2698529645906939f, 0.2698991227951347f, 0.2699452803793618f, 0.2699914373432691f, + 0.2700375936867506f, 0.2700837494097001f, 0.2701299045120118f, 0.2701760589935793f, + 0.2702222128542969f, 0.2702683660940582f, 0.2703145187127574f, 0.2703606707102882f, + 0.2704068220865448f, 0.2704529728414211f, 0.2704991229748108f, 0.2705452724866081f, + 0.2705914213767069f, 0.2706375696450011f, 0.2706837172913848f, 0.2707298643157517f, + 0.2707760107179960f, 0.2708221564980115f, 0.2708683016556922f, 0.2709144461909321f, + 0.2709605901036252f, 0.2710067333936653f, 0.2710528760609465f, 0.2710990181053627f, + 0.2711451595268080f, 0.2711913003251762f, 0.2712374405003614f, 0.2712835800522574f, + 0.2713297189807585f, 0.2713758572857582f, 0.2714219949671509f, 0.2714681320248304f, + 0.2715142684586907f, 0.2715604042686258f, 0.2716065394545296f, 0.2716526740162962f, + 0.2716988079538195f, 0.2717449412669935f, 0.2717910739557122f, 0.2718372060198697f, + 0.2718833374593597f, 0.2719294682740765f, 0.2719755984639140f, 0.2720217280287661f, + 0.2720678569685269f, 0.2721139852830903f, 0.2721601129723505f, 0.2722062400362013f, + 0.2722523664745367f, 0.2722984922872508f, 0.2723446174742376f, 0.2723907420353911f, + 0.2724368659706052f, 0.2724829892797741f, 0.2725291119627917f, 0.2725752340195520f, + 0.2726213554499490f, 0.2726674762538767f, 0.2727135964312293f, 0.2727597159819006f, + 0.2728058349057848f, 0.2728519532027758f, 0.2728980708727676f, 0.2729441879156543f, + 0.2729903043313299f, 0.2730364201196885f, 0.2730825352806239f, 0.2731286498140304f, + 0.2731747637198019f, 0.2732208769978324f, 0.2732669896480161f, 0.2733131016702468f, + 0.2733592130644187f, 0.2734053238304258f, 0.2734514339681621f, 0.2734975434775218f, + 0.2735436523583987f, 0.2735897606106870f, 0.2736358682342807f, 0.2736819752290738f, + 0.2737280815949605f, 0.2737741873318347f, 0.2738202924395906f, 0.2738663969181221f, + 0.2739125007673233f, 0.2739586039870883f, 0.2740047065773111f, 0.2740508085378858f, + 0.2740969098687064f, 0.2741430105696670f, 0.2741891106406618f, 0.2742352100815846f, + 0.2742813088923297f, 0.2743274070727910f, 0.2743735046228626f, 0.2744196015424387f, + 0.2744656978314132f, 0.2745117934896803f, 0.2745578885171340f, 0.2746039829136685f, + 0.2746500766791777f, 0.2746961698135557f, 0.2747422623166967f, 0.2747883541884948f, + 0.2748344454288439f, 0.2748805360376382f, 0.2749266260147718f, 0.2749727153601388f, + 0.2750188040736332f, 0.2750648921551492f, 0.2751109796045808f, 0.2751570664218221f, + 0.2752031526067673f, 0.2752492381593103f, 0.2752953230793455f, 0.2753414073667667f, + 0.2753874910214681f, 0.2754335740433439f, 0.2754796564322881f, 0.2755257381881948f, + 0.2755718193109581f, 0.2756178998004723f, 0.2756639796566312f, 0.2757100588793291f, + 0.2757561374684601f, 0.2758022154239183f, 0.2758482927455978f, 0.2758943694333927f, + 0.2759404454871972f, 0.2759865209069053f, 0.2760325956924112f, 0.2760786698436090f, + 0.2761247433603928f, 0.2761708162426568f, 0.2762168884902951f, 0.2762629601032018f, + 0.2763090310812711f, 0.2763551014243970f, 0.2764011711324737f, 0.2764472402053953f, + 0.2764933086430560f, 0.2765393764453500f, 0.2765854436121712f, 0.2766315101434140f, + 0.2766775760389724f, 0.2767236412987406f, 0.2767697059226127f, 0.2768157699104828f, + 0.2768618332622453f, 0.2769078959777940f, 0.2769539580570232f, 0.2770000194998272f, + 0.2770460803060999f, 0.2770921404757357f, 0.2771382000086284f, 0.2771842589046726f, + 0.2772303171637622f, 0.2772763747857913f, 0.2773224317706543f, 0.2773684881182452f, + 0.2774145438284581f, 0.2774605989011873f, 0.2775066533363270f, 0.2775527071337713f, + 0.2775987602934143f, 0.2776448128151503f, 0.2776908646988734f, 0.2777369159444777f, + 0.2777829665518577f, 0.2778290165209071f, 0.2778750658515205f, 0.2779211145435919f, + 0.2779671625970154f, 0.2780132100116853f, 0.2780592567874957f, 0.2781053029243410f, + 0.2781513484221151f, 0.2781973932807124f, 0.2782434375000270f, 0.2782894810799530f, + 0.2783355240203849f, 0.2783815663212166f, 0.2784276079823425f, 0.2784736490036565f, + 0.2785196893850531f, 0.2785657291264264f, 0.2786117682276706f, 0.2786578066886799f, + 0.2787038445093485f, 0.2787498816895706f, 0.2787959182292405f, 0.2788419541282523f, + 0.2788879893865003f, 0.2789340240038786f, 0.2789800579802814f, 0.2790260913156031f, + 0.2790721240097378f, 0.2791181560625798f, 0.2791641874740232f, 0.2792102182439622f, + 0.2792562483722912f, 0.2793022778589043f, 0.2793483067036957f, 0.2793943349065597f, + 0.2794403624673906f, 0.2794863893860824f, 0.2795324156625296f, 0.2795784412966262f, + 0.2796244662882666f, 0.2796704906373450f, 0.2797165143437556f, 0.2797625374073926f, + 0.2798085598281504f, 0.2798545816059230f, 0.2799006027406050f, 0.2799466232320902f, + 0.2799926430802732f, 0.2800386622850481f, 0.2800846808463092f, 0.2801306987639508f, + 0.2801767160378670f, 0.2802227326679522f, 0.2802687486541005f, 0.2803147639962063f, + 0.2803607786941638f, 0.2804067927478673f, 0.2804528061572111f, 0.2804988189220893f, + 0.2805448310423962f, 0.2805908425180263f, 0.2806368533488736f, 0.2806828635348325f, + 0.2807288730757972f, 0.2807748819716620f, 0.2808208902223213f, 0.2808668978276692f, + 0.2809129047876000f, 0.2809589111020080f, 0.2810049167707875f, 0.2810509217938329f, + 0.2810969261710383f, 0.2811429299022980f, 0.2811889329875064f, 0.2812349354265576f, + 0.2812809372193461f, 0.2813269383657661f, 0.2813729388657119f, 0.2814189387190777f, + 0.2814649379257580f, 0.2815109364856469f, 0.2815569343986388f, 0.2816029316646280f, + 0.2816489282835086f, 0.2816949242551753f, 0.2817409195795220f, 0.2817869142564433f, + 0.2818329082858334f, 0.2818789016675865f, 0.2819248944015971f, 0.2819708864877594f, + 0.2820168779259676f, 0.2820628687161164f, 0.2821088588580997f, 0.2821548483518120f, + 0.2822008371971476f, 0.2822468253940008f, 0.2822928129422659f, 0.2823387998418373f, + 0.2823847860926094f, 0.2824307716944763f, 0.2824767566473325f, 0.2825227409510722f, + 0.2825687246055897f, 0.2826147076107797f, 0.2826606899665360f, 0.2827066716727534f, + 0.2827526527293259f, 0.2827986331361481f, 0.2828446128931141f, 0.2828905920001185f, + 0.2829365704570554f, 0.2829825482638192f, 0.2830285254203043f, 0.2830745019264051f, + 0.2831204777820158f, 0.2831664529870310f, 0.2832124275413447f, 0.2832584014448515f, + 0.2833043746974457f, 0.2833503472990216f, 0.2833963192494737f, 0.2834422905486962f, + 0.2834882611965836f, 0.2835342311930301f, 0.2835802005379301f, 0.2836261692311782f, + 0.2836721372726684f, 0.2837181046622954f, 0.2837640713999533f, 0.2838100374855366f, + 0.2838560029189398f, 0.2839019677000569f, 0.2839479318287827f, 0.2839938953050113f, + 0.2840398581286372f, 0.2840858202995548f, 0.2841317818176583f, 0.2841777426828423f, + 0.2842237028950010f, 0.2842696624540290f, 0.2843156213598205f, 0.2843615796122700f, + 0.2844075372112719f, 0.2844534941567204f, 0.2844994504485101f, 0.2845454060865353f, + 0.2845913610706904f, 0.2846373154008700f, 0.2846832690769681f, 0.2847292220988795f, + 0.2847751744664983f, 0.2848211261797191f, 0.2848670772384362f, 0.2849130276425440f, + 0.2849589773919370f, 0.2850049264865095f, 0.2850508749261561f, 0.2850968227107710f, + 0.2851427698402487f, 0.2851887163144836f, 0.2852346621333702f, 0.2852806072968028f, + 0.2853265518046759f, 0.2853724956568838f, 0.2854184388533211f, 0.2854643813938821f, + 0.2855103232784613f, 0.2855562645069531f, 0.2856022050792519f, 0.2856481449952522f, + 0.2856940842548483f, 0.2857400228579349f, 0.2857859608044061f, 0.2858318980941565f, + 0.2858778347270806f, 0.2859237707030727f, 0.2859697060220274f, 0.2860156406838390f, + 0.2860615746884020f, 0.2861075080356109f, 0.2861534407253601f, 0.2861993727575440f, + 0.2862453041320571f, 0.2862912348487939f, 0.2863371649076488f, 0.2863830943085162f, + 0.2864290230512907f, 0.2864749511358666f, 0.2865208785621385f, 0.2865668053300007f, + 0.2866127314393478f, 0.2866586568900742f, 0.2867045816820744f, 0.2867505058152429f, + 0.2867964292894741f, 0.2868423521046625f, 0.2868882742607026f, 0.2869341957574887f, + 0.2869801165949156f, 0.2870260367728774f, 0.2870719562912689f, 0.2871178751499844f, + 0.2871637933489184f, 0.2872097108879655f, 0.2872556277670200f, 0.2873015439859766f, + 0.2873474595447295f, 0.2873933744431734f, 0.2874392886812029f, 0.2874852022587122f, + 0.2875311151755960f, 0.2875770274317486f, 0.2876229390270647f, 0.2876688499614388f, + 0.2877147602347652f, 0.2877606698469385f, 0.2878065787978533f, 0.2878524870874040f, + 0.2878983947154852f, 0.2879443016819912f, 0.2879902079868167f, 0.2880361136298562f, + 0.2880820186110041f, 0.2881279229301550f, 0.2881738265872034f, 0.2882197295820439f, + 0.2882656319145708f, 0.2883115335846788f, 0.2883574345922623f, 0.2884033349372159f, + 0.2884492346194342f, 0.2884951336388116f, 0.2885410319952427f, 0.2885869296886219f, + 0.2886328267188438f, 0.2886787230858031f, 0.2887246187893940f, 0.2887705138295114f, + 0.2888164082060495f, 0.2888623019189030f, 0.2889081949679665f, 0.2889540873531344f, + 0.2889999790743014f, 0.2890458701313619f, 0.2890917605242105f, 0.2891376502527418f, + 0.2891835393168502f, 0.2892294277164305f, 0.2892753154513769f, 0.2893212025215843f, + 0.2893670889269470f, 0.2894129746673597f, 0.2894588597427169f, 0.2895047441529132f, + 0.2895506278978431f, 0.2895965109774011f, 0.2896423933914820f, 0.2896882751399802f, + 0.2897341562227903f, 0.2897800366398068f, 0.2898259163909243f, 0.2898717954760374f, + 0.2899176738950408f, 0.2899635516478288f, 0.2900094287342961f, 0.2900553051543374f, + 0.2901011809078471f, 0.2901470559947199f, 0.2901929304148503f, 0.2902388041681330f, + 0.2902846772544623f, 0.2903305496737332f, 0.2903764214258400f, 0.2904222925106773f, + 0.2904681629281398f, 0.2905140326781221f, 0.2905599017605187f, 0.2906057701752242f, + 0.2906516379221332f, 0.2906975050011404f, 0.2907433714121404f, 0.2907892371550276f, + 0.2908351022296968f, 0.2908809666360425f, 0.2909268303739594f, 0.2909726934433420f, + 0.2910185558440851f, 0.2910644175760830f, 0.2911102786392306f, 0.2911561390334224f, + 0.2912019987585529f, 0.2912478578145169f, 0.2912937162012089f, 0.2913395739185237f, + 0.2913854309663557f, 0.2914312873445996f, 0.2914771430531500f, 0.2915229980919017f, + 0.2915688524607491f, 0.2916147061595869f, 0.2916605591883098f, 0.2917064115468124f, + 0.2917522632349893f, 0.2917981142527352f, 0.2918439645999445f, 0.2918898142765122f, + 0.2919356632823328f, 0.2919815116173008f, 0.2920273592813110f, 0.2920732062742580f, + 0.2921190525960364f, 0.2921648982465410f, 0.2922107432256662f, 0.2922565875333069f, + 0.2923024311693576f, 0.2923482741337129f, 0.2923941164262677f, 0.2924399580469164f, + 0.2924857989955539f, 0.2925316392720746f, 0.2925774788763734f, 0.2926233178083448f, + 0.2926691560678835f, 0.2927149936548842f, 0.2927608305692415f, 0.2928066668108502f, + 0.2928525023796048f, 0.2928983372754001f, 0.2929441714981308f, 0.2929900050476914f, + 0.2930358379239768f, 0.2930816701268815f, 0.2931275016563002f, 0.2931733325121277f, + 0.2932191626942586f, 0.2932649922025877f, 0.2933108210370095f, 0.2933566491974187f, + 0.2934024766837101f, 0.2934483034957783f, 0.2934941296335182f, 0.2935399550968242f, + 0.2935857798855913f, 0.2936316039997138f, 0.2936774274390868f, 0.2937232502036047f, + 0.2937690722931624f, 0.2938148937076546f, 0.2938607144469759f, 0.2939065345110209f, + 0.2939523538996847f, 0.2939981726128615f, 0.2940439906504465f, 0.2940898080123341f, + 0.2941356246984190f, 0.2941814407085962f, 0.2942272560427601f, 0.2942730707008057f, + 0.2943188846826274f, 0.2943646979881202f, 0.2944105106171787f, 0.2944563225696976f, + 0.2945021338455717f, 0.2945479444446957f, 0.2945937543669643f, 0.2946395636122723f, + 0.2946853721805143f, 0.2947311800715853f, 0.2947769872853797f, 0.2948227938217925f, + 0.2948685996807183f, 0.2949144048620518f, 0.2949602093656880f, 0.2950060131915213f, + 0.2950518163394467f, 0.2950976188093588f, 0.2951434206011525f, 0.2951892217147223f, + 0.2952350221499632f, 0.2952808219067699f, 0.2953266209850371f, 0.2953724193846595f, + 0.2954182171055320f, 0.2954640141475492f, 0.2955098105106061f, 0.2955556061945972f, + 0.2956014011994174f, 0.2956471955249614f, 0.2956929891711241f, 0.2957387821378001f, + 0.2957845744248843f, 0.2958303660322714f, 0.2958761569598561f, 0.2959219472075333f, + 0.2959677367751979f, 0.2960135256627444f, 0.2960593138700677f, 0.2961051013970626f, + 0.2961508882436238f, 0.2961966744096463f, 0.2962424598950246f, 0.2962882446996536f, + 0.2963340288234282f, 0.2963798122662431f, 0.2964255950279930f, 0.2964713771085729f, + 0.2965171585078775f, 0.2965629392258015f, 0.2966087192622398f, 0.2966544986170871f, + 0.2967002772902383f, 0.2967460552815883f, 0.2967918325910317f, 0.2968376092184635f, + 0.2968833851637783f, 0.2969291604268710f, 0.2969749350076364f, 0.2970207089059694f, + 0.2970664821217647f, 0.2971122546549172f, 0.2971580265053216f, 0.2972037976728730f, + 0.2972495681574658f, 0.2972953379589952f, 0.2973411070773558f, 0.2973868755124425f, + 0.2974326432641500f, 0.2974784103323734f, 0.2975241767170073f, 0.2975699424179467f, + 0.2976157074350863f, 0.2976614717683209f, 0.2977072354175454f, 0.2977529983826547f, + 0.2977987606635435f, 0.2978445222601069f, 0.2978902831722394f, 0.2979360433998361f, + 0.2979818029427918f, 0.2980275618010012f, 0.2980733199743594f, 0.2981190774627610f, + 0.2981648342661009f, 0.2982105903842741f, 0.2982563458171753f, 0.2983021005646995f, + 0.2983478546267414f, 0.2983936080031960f, 0.2984393606939580f, 0.2984851126989225f, + 0.2985308640179841f, 0.2985766146510379f, 0.2986223645979786f, 0.2986681138587011f, + 0.2987138624331003f, 0.2987596103210712f, 0.2988053575225084f, 0.2988511040373070f, + 0.2988968498653618f, 0.2989425950065676f, 0.2989883394608195f, 0.2990340832280121f, + 0.2990798263080405f, 0.2991255687007994f, 0.2991713104061839f, 0.2992170514240888f, + 0.2992627917544088f, 0.2993085313970392f, 0.2993542703518745f, 0.2994000086188098f, + 0.2994457461977399f, 0.2994914830885598f, 0.2995372192911643f, 0.2995829548054483f, + 0.2996286896313068f, 0.2996744237686347f, 0.2997201572173268f, 0.2997658899772780f, + 0.2998116220483834f, 0.2998573534305377f, 0.2999030841236359f, 0.2999488141275728f, + 0.2999945434422436f, 0.3000402720675429f, 0.3000860000033658f, 0.3001317272496072f, + 0.3001774538061620f, 0.3002231796729251f, 0.3002689048497914f, 0.3003146293366559f, + 0.3003603531334135f, 0.3004060762399591f, 0.3004517986561877f, 0.3004975203819942f, + 0.3005432414172735f, 0.3005889617619205f, 0.3006346814158303f, 0.3006804003788976f, + 0.3007261186510175f, 0.3007718362320850f, 0.3008175531219949f, 0.3008632693206423f, + 0.3009089848279219f, 0.3009546996437288f, 0.3010004137679581f, 0.3010461272005045f, + 0.3010918399412631f, 0.3011375519901288f, 0.3011832633469965f, 0.3012289740117612f, + 0.3012746839843179f, 0.3013203932645617f, 0.3013661018523872f, 0.3014118097476897f, + 0.3014575169503639f, 0.3015032234603050f, 0.3015489292774079f, 0.3015946344015675f, + 0.3016403388326788f, 0.3016860425706368f, 0.3017317456153364f, 0.3017774479666727f, + 0.3018231496245407f, 0.3018688505888352f, 0.3019145508594512f, 0.3019602504362838f, + 0.3020059493192281f, 0.3020516475081788f, 0.3020973450030310f, 0.3021430418036798f, + 0.3021887379100200f, 0.3022344333219468f, 0.3022801280393550f, 0.3023258220621398f, + 0.3023715153901960f, 0.3024172080234186f, 0.3024628999617028f, 0.3025085912049434f, + 0.3025542817530356f, 0.3025999716058742f, 0.3026456607633544f, 0.3026913492253710f, + 0.3027370369918191f, 0.3027827240625939f, 0.3028284104375901f, 0.3028740961167030f, + 0.3029197810998273f, 0.3029654653868583f, 0.3030111489776909f, 0.3030568318722201f, + 0.3031025140703411f, 0.3031481955719486f, 0.3031938763769380f, 0.3032395564852040f, + 0.3032852358966417f, 0.3033309146111464f, 0.3033765926286128f, 0.3034222699489361f, + 0.3034679465720113f, 0.3035136224977334f, 0.3035592977259976f, 0.3036049722566987f, + 0.3036506460897320f, 0.3036963192249923f, 0.3037419916623747f, 0.3037876634017744f, + 0.3038333344430864f, 0.3038790047862056f, 0.3039246744310272f, 0.3039703433774461f, + 0.3040160116253576f, 0.3040616791746565f, 0.3041073460252381f, 0.3041530121769973f, + 0.3041986776298292f, 0.3042443423836287f, 0.3042900064382912f, 0.3043356697937116f, + 0.3043813324497849f, 0.3044269944064062f, 0.3044726556634706f, 0.3045183162208732f, + 0.3045639760785091f, 0.3046096352362733f, 0.3046552936940609f, 0.3047009514517670f, + 0.3047466085092865f, 0.3047922648665148f, 0.3048379205233469f, 0.3048835754796777f, + 0.3049292297354024f, 0.3049748832904161f, 0.3050205361446139f, 0.3050661882978908f, + 0.3051118397501421f, 0.3051574905012627f, 0.3052031405511478f, 0.3052487898996924f, + 0.3052944385467917f, 0.3053400864923407f, 0.3053857337362346f, 0.3054313802783685f, + 0.3054770261186374f, 0.3055226712569366f, 0.3055683156931610f, 0.3056139594272058f, + 0.3056596024589662f, 0.3057052447883372f, 0.3057508864152139f, 0.3057965273394915f, + 0.3058421675610651f, 0.3058878070798298f, 0.3059334458956807f, 0.3059790840085130f, + 0.3060247214182218f, 0.3060703581247021f, 0.3061159941278493f, 0.3061616294275583f, + 0.3062072640237243f, 0.3062528979162424f, 0.3062985311050078f, 0.3063441635899156f, + 0.3063897953708609f, 0.3064354264477390f, 0.3064810568204449f, 0.3065266864888737f, + 0.3065723154529207f, 0.3066179437124810f, 0.3066635712674496f, 0.3067091981177218f, + 0.3067548242631928f, 0.3068004497037576f, 0.3068460744393114f, 0.3068916984697495f, + 0.3069373217949669f, 0.3069829444148587f, 0.3070285663293204f, 0.3070741875382467f, + 0.3071198080415331f, 0.3071654278390746f, 0.3072110469307665f, 0.3072566653165038f, + 0.3073022829961818f, 0.3073478999696957f, 0.3073935162369406f, 0.3074391317978117f, + 0.3074847466522041f, 0.3075303608000131f, 0.3075759742411338f, 0.3076215869754614f, + 0.3076671990028912f, 0.3077128103233182f, 0.3077584209366377f, 0.3078040308427449f, + 0.3078496400415349f, 0.3078952485329030f, 0.3079408563167442f, 0.3079864633929539f, + 0.3080320697614273f, 0.3080776754220595f, 0.3081232803747458f, 0.3081688846193812f, + 0.3082144881558611f, 0.3082600909840806f, 0.3083056931039350f, 0.3083512945153195f, + 0.3083968952181292f, 0.3084424952122594f, 0.3084880944976053f, 0.3085336930740621f, + 0.3085792909415251f, 0.3086248880998893f, 0.3086704845490502f, 0.3087160802889028f, + 0.3087616753193425f, 0.3088072696402643f, 0.3088528632515637f, 0.3088984561531358f, + 0.3089440483448757f, 0.3089896398266788f, 0.3090352305984403f, 0.3090808206600554f, + 0.3091264100114194f, 0.3091719986524275f, 0.3092175865829749f, 0.3092631738029569f, + 0.3093087603122687f, 0.3093543461108056f, 0.3093999311984628f, 0.3094455155751356f, + 0.3094910992407191f, 0.3095366821951087f, 0.3095822644381996f, 0.3096278459698871f, + 0.3096734267900664f, 0.3097190068986329f, 0.3097645862954815f, 0.3098101649805079f, + 0.3098557429536071f, 0.3099013202146745f, 0.3099468967636052f, 0.3099924726002945f, + 0.3100380477246379f, 0.3100836221365303f, 0.3101291958358674f, 0.3101747688225441f, + 0.3102203410964559f, 0.3102659126574979f, 0.3103114835055656f, 0.3103570536405541f, + 0.3104026230623587f, 0.3104481917708748f, 0.3104937597659976f, 0.3105393270476224f, + 0.3105848936156445f, 0.3106304594699591f, 0.3106760246104617f, 0.3107215890370473f, + 0.3107671527496115f, 0.3108127157480494f, 0.3108582780322564f, 0.3109038396021277f, + 0.3109494004575586f, 0.3109949605984446f, 0.3110405200246808f, 0.3110860787361626f, + 0.3111316367327853f, 0.3111771940144441f, 0.3112227505810345f, 0.3112683064324516f, + 0.3113138615685909f, 0.3113594159893477f, 0.3114049696946172f, 0.3114505226842949f, + 0.3114960749582759f, 0.3115416265164556f, 0.3115871773587295f, 0.3116327274849927f, + 0.3116782768951406f, 0.3117238255890685f, 0.3117693735666718f, 0.3118149208278460f, + 0.3118604673724860f, 0.3119060132004875f, 0.3119515583117456f, 0.3119971027061559f, + 0.3120426463836135f, 0.3120881893440139f, 0.3121337315872524f, 0.3121792731132242f, + 0.3122248139218249f, 0.3122703540129497f, 0.3123158933864940f, 0.3123614320423532f, + 0.3124069699804224f, 0.3124525072005973f, 0.3124980437027731f, 0.3125435794868450f, + 0.3125891145527087f, 0.3126346489002593f, 0.3126801825293923f, 0.3127257154400030f, + 0.3127712476319868f, 0.3128167791052391f, 0.3128623098596551f, 0.3129078398951304f, + 0.3129533692115602f, 0.3129988978088400f, 0.3130444256868651f, 0.3130899528455309f, + 0.3131354792847328f, 0.3131810050043662f, 0.3132265300043265f, 0.3132720542845089f, + 0.3133175778448090f, 0.3133631006851221f, 0.3134086228053437f, 0.3134541442053690f, + 0.3134996648850935f, 0.3135451848444126f, 0.3135907040832217f, 0.3136362226014162f, + 0.3136817403988915f, 0.3137272574755429f, 0.3137727738312659f, 0.3138182894659561f, + 0.3138638043795085f, 0.3139093185718189f, 0.3139548320427824f, 0.3140003447922945f, + 0.3140458568202507f, 0.3140913681265464f, 0.3141368787110770f, 0.3141823885737379f, + 0.3142278977144245f, 0.3142734061330322f, 0.3143189138294565f, 0.3143644208035929f, + 0.3144099270553367f, 0.3144554325845833f, 0.3145009373912282f, 0.3145464414751668f, + 0.3145919448362947f, 0.3146374474745070f, 0.3146829493896994f, 0.3147284505817673f, + 0.3147739510506061f, 0.3148194507961112f, 0.3148649498181781f, 0.3149104481167023f, + 0.3149559456915791f, 0.3150014425427041f, 0.3150469386699727f, 0.3150924340732803f, + 0.3151379287525224f, 0.3151834227075945f, 0.3152289159383919f, 0.3152744084448103f, + 0.3153199002267449f, 0.3153653912840914f, 0.3154108816167450f, 0.3154563712246014f, + 0.3155018601075560f, 0.3155473482655042f, 0.3155928356983416f, 0.3156383224059636f, + 0.3156838083882657f, 0.3157292936451432f, 0.3157747781764917f, 0.3158202619822069f, + 0.3158657450621840f, 0.3159112274163186f, 0.3159567090445061f, 0.3160021899466420f, + 0.3160476701226219f, 0.3160931495723411f, 0.3161386282956953f, 0.3161841062925799f, + 0.3162295835628904f, 0.3162750601065222f, 0.3163205359233709f, 0.3163660110133321f, + 0.3164114853763010f, 0.3164569590121734f, 0.3165024319208447f, 0.3165479041022103f, + 0.3165933755561658f, 0.3166388462826068f, 0.3166843162814287f, 0.3167297855525270f, + 0.3167752540957973f, 0.3168207219111350f, 0.3168661889984357f, 0.3169116553575950f, + 0.3169571209885081f, 0.3170025858910709f, 0.3170480500651788f, 0.3170935135107272f, + 0.3171389762276118f, 0.3171844382157279f, 0.3172298994749713f, 0.3172753600052374f, + 0.3173208198064217f, 0.3173662788784199f, 0.3174117372211273f, 0.3174571948344396f, + 0.3175026517182523f, 0.3175481078724609f, 0.3175935632969610f, 0.3176390179916482f, + 0.3176844719564180f, 0.3177299251911658f, 0.3177753776957873f, 0.3178208294701781f, + 0.3178662805142337f, 0.3179117308278496f, 0.3179571804109214f, 0.3180026292633447f, + 0.3180480773850149f, 0.3180935247758278f, 0.3181389714356788f, 0.3181844173644635f, + 0.3182298625620776f, 0.3182753070284164f, 0.3183207507633757f, 0.3183661937668510f, + 0.3184116360387378f, 0.3184570775789318f, 0.3185025183873285f, 0.3185479584638235f, + 0.3185933978083124f, 0.3186388364206907f, 0.3186842743008542f, 0.3187297114486982f, + 0.3187751478641185f, 0.3188205835470106f, 0.3188660184972701f, 0.3189114527147926f, + 0.3189568861994737f, 0.3190023189512090f, 0.3190477509698940f, 0.3190931822554244f, + 0.3191386128076959f, 0.3191840426266039f, 0.3192294717120442f, 0.3192749000639122f, + 0.3193203276821036f, 0.3193657545665141f, 0.3194111807170391f, 0.3194566061335745f, + 0.3195020308160157f, 0.3195474547642583f, 0.3195928779781981f, 0.3196383004577306f, + 0.3196837222027514f, 0.3197291432131562f, 0.3197745634888405f, 0.3198199830297001f, + 0.3198654018356305f, 0.3199108199065274f, 0.3199562372422863f, 0.3200016538428031f, + 0.3200470697079731f, 0.3200924848376922f, 0.3201378992318560f, 0.3201833128903600f, + 0.3202287258130999f, 0.3202741379999714f, 0.3203195494508701f, 0.3203649601656917f, + 0.3204103701443318f, 0.3204557793866861f, 0.3205011878926501f, 0.3205465956621197f, + 0.3205920026949903f, 0.3206374089911578f, 0.3206828145505177f, 0.3207282193729656f, + 0.3207736234583973f, 0.3208190268067085f, 0.3208644294177947f, 0.3209098312915518f, + 0.3209552324278752f, 0.3210006328266608f, 0.3210460324878041f, 0.3210914314112008f, + 0.3211368295967467f, 0.3211822270443373f, 0.3212276237538685f, 0.3212730197252358f, + 0.3213184149583349f, 0.3213638094530615f, 0.3214092032093114f, 0.3214545962269802f, + 0.3214999885059635f, 0.3215453800461571f, 0.3215907708474567f, 0.3216361609097579f, + 0.3216815502329566f, 0.3217269388169482f, 0.3217723266616286f, 0.3218177137668936f, + 0.3218631001326386f, 0.3219084857587595f, 0.3219538706451520f, 0.3219992547917118f, + 0.3220446381983345f, 0.3220900208649159f, 0.3221354027913518f, 0.3221807839775378f, + 0.3222261644233697f, 0.3222715441287430f, 0.3223169230935537f, 0.3223623013176974f, + 0.3224076788010699f, 0.3224530555435667f, 0.3224984315450838f, 0.3225438068055167f, + 0.3225891813247613f, 0.3226345551027133f, 0.3226799281392684f, 0.3227253004343222f, + 0.3227706719877707f, 0.3228160427995095f, 0.3228614128694344f, 0.3229067821974411f, + 0.3229521507834253f, 0.3229975186272828f, 0.3230428857289092f, 0.3230882520882005f, + 0.3231336177050523f, 0.3231789825793605f, 0.3232243467110206f, 0.3232697100999285f, + 0.3233150727459800f, 0.3233604346490708f, 0.3234057958090967f, 0.3234511562259534f, + 0.3234965158995367f, 0.3235418748297423f, 0.3235872330164661f, 0.3236325904596039f, + 0.3236779471590512f, 0.3237233031147040f, 0.3237686583264580f, 0.3238140127942091f, + 0.3238593665178529f, 0.3239047194972853f, 0.3239500717324019f, 0.3239954232230988f, + 0.3240407739692714f, 0.3240861239708158f, 0.3241314732276277f, 0.3241768217396028f, + 0.3242221695066370f, 0.3242675165286261f, 0.3243128628054657f, 0.3243582083370519f, + 0.3244035531232802f, 0.3244488971640467f, 0.3244942404592469f, 0.3245395830087768f, + 0.3245849248125321f, 0.3246302658704088f, 0.3246756061823025f, 0.3247209457481090f, + 0.3247662845677242f, 0.3248116226410440f, 0.3248569599679640f, 0.3249022965483803f, + 0.3249476323821884f, 0.3249929674692844f, 0.3250383018095639f, 0.3250836354029228f, + 0.3251289682492571f, 0.3251743003484623f, 0.3252196317004346f, 0.3252649623050695f, + 0.3253102921622629f, 0.3253556212719108f, 0.3254009496339089f, 0.3254462772481532f, + 0.3254916041145393f, 0.3255369302329632f, 0.3255822556033207f, 0.3256275802255076f, + 0.3256729040994198f, 0.3257182272249532f, 0.3257635496020035f, 0.3258088712304667f, + 0.3258541921102386f, 0.3258995122412151f, 0.3259448316232919f, 0.3259901502563650f, + 0.3260354681403302f, 0.3260807852750834f, 0.3261261016605206f, 0.3261714172965373f, + 0.3262167321830298f, 0.3262620463198936f, 0.3263073597070247f, 0.3263526723443191f, + 0.3263979842316725f, 0.3264432953689809f, 0.3264886057561400f, 0.3265339153930459f, + 0.3265792242795944f, 0.3266245324156813f, 0.3266698398012026f, 0.3267151464360541f, + 0.3267604523201317f, 0.3268057574533315f, 0.3268510618355490f, 0.3268963654666804f, + 0.3269416683466214f, 0.3269869704752681f, 0.3270322718525162f, 0.3270775724782617f, + 0.3271228723524005f, 0.3271681714748285f, 0.3272134698454416f, 0.3272587674641357f, + 0.3273040643308067f, 0.3273493604453505f, 0.3273946558076630f, 0.3274399504176403f, + 0.3274852442751780f, 0.3275305373801722f, 0.3275758297325189f, 0.3276211213321139f, + 0.3276664121788531f, 0.3277117022726325f, 0.3277569916133479f, 0.3278022802008954f, + 0.3278475680351708f, 0.3278928551160702f, 0.3279381414434893f, 0.3279834270173242f, + 0.3280287118374707f, 0.3280739959038249f, 0.3281192792162826f, 0.3281645617747398f, + 0.3282098435790926f, 0.3282551246292366f, 0.3283004049250680f, 0.3283456844664827f, + 0.3283909632533766f, 0.3284362412856457f, 0.3284815185631860f, 0.3285267950858933f, + 0.3285720708536637f, 0.3286173458663931f, 0.3286626201239775f, 0.3287078936263128f, + 0.3287531663732950f, 0.3287984383648201f, 0.3288437096007840f, 0.3288889800810827f, + 0.3289342498056122f, 0.3289795187742685f, 0.3290247869869473f, 0.3290700544435449f, + 0.3291153211439573f, 0.3291605870880802f, 0.3292058522758098f, 0.3292511167070420f, + 0.3292963803816727f, 0.3293416432995982f, 0.3293869054607141f, 0.3294321668649167f, + 0.3294774275121017f, 0.3295226874021653f, 0.3295679465350035f, 0.3296132049105122f, + 0.3296584625285875f, 0.3297037193891253f, 0.3297489754920216f, 0.3297942308371725f, + 0.3298394854244739f, 0.3298847392538219f, 0.3299299923251125f, 0.3299752446382417f, + 0.3300204961931054f, 0.3300657469895997f, 0.3301109970276208f, 0.3301562463070644f, + 0.3302014948278266f, 0.3302467425898036f, 0.3302919895928912f, 0.3303372358369857f, + 0.3303824813219828f, 0.3304277260477787f, 0.3304729700142695f, 0.3305182132213510f, + 0.3305634556689195f, 0.3306086973568709f, 0.3306539382851013f, 0.3306991784535065f, + 0.3307444178619829f, 0.3307896565104264f, 0.3308348943987329f, 0.3308801315267986f, + 0.3309253678945195f, 0.3309706035017917f, 0.3310158383485112f, 0.3310610724345741f, + 0.3311063057598764f, 0.3311515383243142f, 0.3311967701277835f, 0.3312420011701803f, + 0.3312872314514008f, 0.3313324609713411f, 0.3313776897298972f, 0.3314229177269651f, + 0.3314681449624409f, 0.3315133714362206f, 0.3315585971482005f, 0.3316038220982765f, + 0.3316490462863447f, 0.3316942697123011f, 0.3317394923760420f, 0.3317847142774633f, + 0.3318299354164611f, 0.3318751557929316f, 0.3319203754067707f, 0.3319655942578746f, + 0.3320108123461394f, 0.3320560296714611f, 0.3321012462337360f, 0.3321464620328600f, + 0.3321916770687292f, 0.3322368913412397f, 0.3322821048502878f, 0.3323273175957694f, + 0.3323725295775806f, 0.3324177407956176f, 0.3324629512497765f, 0.3325081609399533f, + 0.3325533698660442f, 0.3325985780279453f, 0.3326437854255528f, 0.3326889920587627f, + 0.3327341979274711f, 0.3327794030315742f, 0.3328246073709680f, 0.3328698109455488f, + 0.3329150137552127f, 0.3329602157998556f, 0.3330054170793739f, 0.3330506175936636f, + 0.3330958173426208f, 0.3331410163261417f, 0.3331862145441224f, 0.3332314119964591f, + 0.3332766086830479f, 0.3333218046037850f, 0.3333669997585663f, 0.3334121941472883f, + 0.3334573877698468f, 0.3335025806261382f, 0.3335477727160586f, 0.3335929640395041f, + 0.3336381545963709f, 0.3336833443865550f, 0.3337285334099527f, 0.3337737216664602f, + 0.3338189091559736f, 0.3338640958783891f, 0.3339092818336027f, 0.3339544670215108f, + 0.3339996514420094f, 0.3340448350949947f, 0.3340900179803630f, 0.3341352000980102f, + 0.3341803814478327f, 0.3342255620297266f, 0.3342707418435882f, 0.3343159208893135f, + 0.3343610991667987f, 0.3344062766759401f, 0.3344514534166338f, 0.3344966293887760f, + 0.3345418045922629f, 0.3345869790269907f, 0.3346321526928556f, 0.3346773255897537f, + 0.3347224977175812f, 0.3347676690762345f, 0.3348128396656096f, 0.3348580094856028f, + 0.3349031785361102f, 0.3349483468170281f, 0.3349935143282526f, 0.3350386810696800f, + 0.3350838470412066f, 0.3351290122427284f, 0.3351741766741418f, 0.3352193403353428f, + 0.3352645032262278f, 0.3353096653466930f, 0.3353548266966345f, 0.3353999872759487f, + 0.3354451470845316f, 0.3354903061222796f, 0.3355354643890889f, 0.3355806218848557f, + 0.3356257786094763f, 0.3356709345628468f, 0.3357160897448635f, 0.3357612441554226f, + 0.3358063977944205f, 0.3358515506617533f, 0.3358967027573171f, 0.3359418540810085f, + 0.3359870046327234f, 0.3360321544123582f, 0.3360773034198092f, 0.3361224516549725f, + 0.3361675991177446f, 0.3362127458080214f, 0.3362578917256995f, 0.3363030368706749f, + 0.3363481812428440f, 0.3363933248421031f, 0.3364384676683483f, 0.3364836097214760f, + 0.3365287510013824f, 0.3365738915079638f, 0.3366190312411165f, 0.3366641702007366f, + 0.3367093083867206f, 0.3367544457989647f, 0.3367995824373651f, 0.3368447183018181f, + 0.3368898533922201f, 0.3369349877084672f, 0.3369801212504558f, 0.3370252540180821f, + 0.3370703860112426f, 0.3371155172298334f, 0.3371606476737508f, 0.3372057773428911f, + 0.3372509062371506f, 0.3372960343564257f, 0.3373411617006125f, 0.3373862882696075f, + 0.3374314140633068f, 0.3374765390816069f, 0.3375216633244041f, 0.3375667867915945f, + 0.3376119094830746f, 0.3376570313987406f, 0.3377021525384889f, 0.3377472729022157f, + 0.3377923924898175f, 0.3378375113011904f, 0.3378826293362309f, 0.3379277465948353f, + 0.3379728630768997f, 0.3380179787823207f, 0.3380630937109946f, 0.3381082078628175f, + 0.3381533212376860f, 0.3381984338354962f, 0.3382435456561446f, 0.3382886566995275f, + 0.3383337669655411f, 0.3383788764540820f, 0.3384239851650463f, 0.3384690930983305f, + 0.3385142002538309f, 0.3385593066314438f, 0.3386044122310656f, 0.3386495170525926f, + 0.3386946210959212f, 0.3387397243609477f, 0.3387848268475686f, 0.3388299285556800f, + 0.3388750294851784f, 0.3389201296359603f, 0.3389652290079219f, 0.3390103276009595f, + 0.3390554254149696f, 0.3391005224498485f, 0.3391456187054926f, 0.3391907141817984f, + 0.3392358088786619f, 0.3392809027959799f, 0.3393259959336485f, 0.3393710882915643f, + 0.3394161798696234f, 0.3394612706677223f, 0.3395063606857575f, 0.3395514499236253f, + 0.3395965383812221f, 0.3396416260584442f, 0.3396867129551882f, 0.3397317990713502f, + 0.3397768844068269f, 0.3398219689615145f, 0.3398670527353094f, 0.3399121357281081f, + 0.3399572179398069f, 0.3400022993703022f, 0.3400473800194906f, 0.3400924598872683f, + 0.3401375389735318f, 0.3401826172781774f, 0.3402276948011017f, 0.3402727715422010f, + 0.3403178475013717f, 0.3403629226785103f, 0.3404079970735130f, 0.3404530706862765f, + 0.3404981435166972f, 0.3405432155646713f, 0.3405882868300955f, 0.3406333573128659f, + 0.3406784270128793f, 0.3407234959300318f, 0.3407685640642201f, 0.3408136314153405f, + 0.3408586979832894f, 0.3409037637679634f, 0.3409488287692588f, 0.3409938929870721f, + 0.3410389564212997f, 0.3410840190718381f, 0.3411290809385837f, 0.3411741420214330f, + 0.3412192023202824f, 0.3412642618350284f, 0.3413093205655674f, 0.3413543785117960f, + 0.3413994356736104f, 0.3414444920509073f, 0.3414895476435831f, 0.3415346024515342f, + 0.3415796564746572f, 0.3416247097128483f, 0.3416697621660043f, 0.3417148138340215f, + 0.3417598647167963f, 0.3418049148142254f, 0.3418499641262050f, 0.3418950126526318f, + 0.3419400603934022f, 0.3419851073484127f, 0.3420301535175598f, 0.3420751989007399f, + 0.3421202434978496f, 0.3421652873087853f, 0.3422103303334434f, 0.3422553725717208f, + 0.3423004140235135f, 0.3423454546887184f, 0.3423904945672316f, 0.3424355336589499f, + 0.3424805719637698f, 0.3425256094815876f, 0.3425706462123000f, 0.3426156821558034f, + 0.3426607173119944f, 0.3427057516807694f, 0.3427507852620250f, 0.3427958180556577f, + 0.3428408500615640f, 0.3428858812796404f, 0.3429309117097834f, 0.3429759413518896f, + 0.3430209702058555f, 0.3430659982715776f, 0.3431110255489525f, 0.3431560520378766f, + 0.3432010777382465f, 0.3432461026499589f, 0.3432911267729100f, 0.3433361501069965f, + 0.3433811726521150f, 0.3434261944081620f, 0.3434712153750341f, 0.3435162355526277f, + 0.3435612549408394f, 0.3436062735395658f, 0.3436512913487034f, 0.3436963083681488f, + 0.3437413245977985f, 0.3437863400375491f, 0.3438313546872971f, 0.3438763685469391f, + 0.3439213816163717f, 0.3439663938954914f, 0.3440114053841948f, 0.3440564160823784f, + 0.3441014259899389f, 0.3441464351067727f, 0.3441914434327764f, 0.3442364509678468f, + 0.3442814577118802f, 0.3443264636647733f, 0.3443714688264227f, 0.3444164731967249f, + 0.3444614767755765f, 0.3445064795628741f, 0.3445514815585144f, 0.3445964827623938f, + 0.3446414831744090f, 0.3446864827944565f, 0.3447314816224331f, 0.3447764796582351f, + 0.3448214769017593f, 0.3448664733529023f, 0.3449114690115606f, 0.3449564638776308f, + 0.3450014579510097f, 0.3450464512315936f, 0.3450914437192794f, 0.3451364354139635f, + 0.3451814263155425f, 0.3452264164239133f, 0.3452714057389722f, 0.3453163942606160f, + 0.3453613819887412f, 0.3454063689232445f, 0.3454513550640225f, 0.3454963404109718f, + 0.3455413249639891f, 0.3455863087229709f, 0.3456312916878140f, 0.3456762738584148f, + 0.3457212552346701f, 0.3457662358164766f, 0.3458112156037308f, 0.3458561945963294f, + 0.3459011727941690f, 0.3459461501971462f, 0.3459911268051578f, 0.3460361026181003f, + 0.3460810776358705f, 0.3461260518583648f, 0.3461710252854801f, 0.3462159979171129f, + 0.3462609697531600f, 0.3463059407935180f, 0.3463509110380834f, 0.3463958804867530f, + 0.3464408491394235f, 0.3464858169959915f, 0.3465307840563537f, 0.3465757503204068f, + 0.3466207157880474f, 0.3466656804591721f, 0.3467106443336777f, 0.3467556074114609f, + 0.3468005696924183f, 0.3468455311764466f, 0.3468904918634425f, 0.3469354517533026f, + 0.3469804108459237f, 0.3470253691412024f, 0.3470703266390354f, 0.3471152833393195f, + 0.3471602392419512f, 0.3472051943468273f, 0.3472501486538446f, 0.3472951021628996f, + 0.3473400548738891f, 0.3473850067867098f, 0.3474299579012584f, 0.3474749082174316f, + 0.3475198577351261f, 0.3475648064542387f, 0.3476097543746659f, 0.3476547014963046f, + 0.3476996478190514f, 0.3477445933428031f, 0.3477895380674563f, 0.3478344819929080f, + 0.3478794251190545f, 0.3479243674457929f, 0.3479693089730197f, 0.3480142497006317f, + 0.3480591896285257f, 0.3481041287565982f, 0.3481490670847462f, 0.3481940046128663f, + 0.3482389413408553f, 0.3482838772686099f, 0.3483288123960268f, 0.3483737467230028f, + 0.3484186802494346f, 0.3484636129752189f, 0.3485085449002526f, 0.3485534760244324f, + 0.3485984063476550f, 0.3486433358698171f, 0.3486882645908155f, 0.3487331925105471f, + 0.3487781196289084f, 0.3488230459457964f, 0.3488679714611077f, 0.3489128961747391f, + 0.3489578200865875f, 0.3490027431965494f, 0.3490476655045218f, 0.3490925870104014f, + 0.3491375077140850f, 0.3491824276154692f, 0.3492273467144510f, 0.3492722650109272f, + 0.3493171825047944f, 0.3493620991959494f, 0.3494070150842891f, 0.3494519301697102f, + 0.3494968444521095f, 0.3495417579313838f, 0.3495866706074300f, 0.3496315824801447f, + 0.3496764935494248f, 0.3497214038151670f, 0.3497663132772683f, 0.3498112219356254f, + 0.3498561297901349f, 0.3499010368406939f, 0.3499459430871991f, 0.3499908485295473f, + 0.3500357531676353f, 0.3500806570013599f, 0.3501255600306179f, 0.3501704622553062f, + 0.3502153636753216f, 0.3502602642905609f, 0.3503051641009208f, 0.3503500631062983f, + 0.3503949613065901f, 0.3504398587016931f, 0.3504847552915042f, 0.3505296510759200f, + 0.3505745460548376f, 0.3506194402281536f, 0.3506643335957649f, 0.3507092261575686f, + 0.3507541179134611f, 0.3507990088633395f, 0.3508438990071006f, 0.3508887883446413f, + 0.3509336768758584f, 0.3509785646006486f, 0.3510234515189091f, 0.3510683376305364f, + 0.3511132229354275f, 0.3511581074334793f, 0.3512029911245885f, 0.3512478740086523f, + 0.3512927560855671f, 0.3513376373552301f, 0.3513825178175380f, 0.3514273974723878f, + 0.3514722763196763f, 0.3515171543593003f, 0.3515620315911568f, 0.3516069080151426f, + 0.3516517836311546f, 0.3516966584390896f, 0.3517415324388447f, 0.3517864056303165f, + 0.3518312780134020f, 0.3518761495879982f, 0.3519210203540019f, 0.3519658903113098f, + 0.3520107594598191f, 0.3520556277994266f, 0.3521004953300291f, 0.3521453620515235f, + 0.3521902279638068f, 0.3522350930667759f, 0.3522799573603276f, 0.3523248208443589f, + 0.3523696835187666f, 0.3524145453834477f, 0.3524594064382992f, 0.3525042666832178f, + 0.3525491261181005f, 0.3525939847428442f, 0.3526388425573458f, 0.3526836995615024f, + 0.3527285557552107f, 0.3527734111383677f, 0.3528182657108704f, 0.3528631194726156f, + 0.3529079724235002f, 0.3529528245634214f, 0.3529976758922758f, 0.3530425264099605f, + 0.3530873761163725f, 0.3531322250114086f, 0.3531770730949658f, 0.3532219203669411f, + 0.3532667668272312f, 0.3533116124757333f, 0.3533564573123444f, 0.3534013013369612f, + 0.3534461445494808f, 0.3534909869498001f, 0.3535358285378161f, 0.3535806693134257f, + 0.3536255092765260f, 0.3536703484270138f, 0.3537151867647860f, 0.3537600242897398f, + 0.3538048610017721f, 0.3538496969007797f, 0.3538945319866597f, 0.3539393662593091f, + 0.3539841997186248f, 0.3540290323645038f, 0.3540738641968431f, 0.3541186952155396f, + 0.3541635254204903f, 0.3542083548115924f, 0.3542531833887426f, 0.3542980111518380f, + 0.3543428381007755f, 0.3543876642354523f, 0.3544324895557652f, 0.3544773140616113f, + 0.3545221377528875f, 0.3545669606294908f, 0.3546117826913183f, 0.3546566039382670f, + 0.3547014243702338f, 0.3547462439871159f, 0.3547910627888100f, 0.3548358807752133f, + 0.3548806979462228f, 0.3549255143017355f, 0.3549703298416484f, 0.3550151445658585f, + 0.3550599584742629f, 0.3551047715667586f, 0.3551495838432425f, 0.3551943953036117f, + 0.3552392059477633f, 0.3552840157755943f, 0.3553288247870016f, 0.3553736329818824f, + 0.3554184403601336f, 0.3554632469216524f, 0.3555080526663357f, 0.3555528575940805f, + 0.3555976617047839f, 0.3556424649983430f, 0.3556872674746547f, 0.3557320691336163f, + 0.3557768699751246f, 0.3558216699990768f, 0.3558664692053699f, 0.3559112675939008f, + 0.3559560651645669f, 0.3560008619172649f, 0.3560456578518921f, 0.3560904529683455f, + 0.3561352472665221f, 0.3561800407463191f, 0.3562248334076333f, 0.3562696252503622f, + 0.3563144162744024f, 0.3563592064796512f, 0.3564039958660058f, 0.3564487844333630f, + 0.3564935721816201f, 0.3565383591106741f, 0.3565831452204221f, 0.3566279305107611f, + 0.3566727149815883f, 0.3567174986328007f, 0.3567622814642954f, 0.3568070634759696f, + 0.3568518446677203f, 0.3568966250394445f, 0.3569414045910396f, 0.3569861833224023f, + 0.3570309612334300f, 0.3570757383240197f, 0.3571205145940685f, 0.3571652900434736f, + 0.3572100646721320f, 0.3572548384799408f, 0.3572996114667971f, 0.3573443836325981f, + 0.3573891549772409f, 0.3574339255006226f, 0.3574786952026404f, 0.3575234640831912f, + 0.3575682321421723f, 0.3576129993794808f, 0.3576577657950138f, 0.3577025313886685f, + 0.3577472961603419f, 0.3577920601099312f, 0.3578368232373336f, 0.3578815855424461f, + 0.3579263470251661f, 0.3579711076853904f, 0.3580158675230163f, 0.3580606265379410f, + 0.3581053847300616f, 0.3581501420992753f, 0.3581948986454790f, 0.3582396543685702f, + 0.3582844092684458f, 0.3583291633450031f, 0.3583739165981393f, 0.3584186690277513f, + 0.3584634206337366f, 0.3585081714159921f, 0.3585529213744150f, 0.3585976705089026f, + 0.3586424188193520f, 0.3586871663056603f, 0.3587319129677248f, 0.3587766588054426f, + 0.3588214038187109f, 0.3588661480074268f, 0.3589108913714876f, 0.3589556339107904f, + 0.3590003756252325f, 0.3590451165147109f, 0.3590898565791229f, 0.3591345958183658f, + 0.3591793342323365f, 0.3592240718209325f, 0.3592688085840507f, 0.3593135445215885f, + 0.3593582796334431f, 0.3594030139195117f, 0.3594477473796914f, 0.3594924800138795f, + 0.3595372118219731f, 0.3595819428038695f, 0.3596266729594659f, 0.3596714022886595f, + 0.3597161307913476f, 0.3597608584674272f, 0.3598055853167957f, 0.3598503113393502f, + 0.3598950365349882f, 0.3599397609036065f, 0.3599844844451026f, 0.3600292071593738f, + 0.3600739290463170f, 0.3601186501058298f, 0.3601633703378092f, 0.3602080897421525f, + 0.3602528083187569f, 0.3602975260675196f, 0.3603422429883381f, 0.3603869590811093f, + 0.3604316743457308f, 0.3604763887820995f, 0.3605211023901128f, 0.3605658151696680f, + 0.3606105271206623f, 0.3606552382429929f, 0.3606999485365572f, 0.3607446580012523f, + 0.3607893666369756f, 0.3608340744436243f, 0.3608787814210956f, 0.3609234875692868f, + 0.3609681928880952f, 0.3610128973774181f, 0.3610576010371527f, 0.3611023038671964f, + 0.3611470058674462f, 0.3611917070377997f, 0.3612364073781540f, 0.3612811068884064f, + 0.3613258055684543f, 0.3613705034181948f, 0.3614152004375253f, 0.3614598966263430f, + 0.3615045919845453f, 0.3615492865120294f, 0.3615939802086927f, 0.3616386730744324f, + 0.3616833651091458f, 0.3617280563127303f, 0.3617727466850831f, 0.3618174362261016f, + 0.3618621249356830f, 0.3619068128137246f, 0.3619514998601238f, 0.3619961860747779f, + 0.3620408714575842f, 0.3620855560084400f, 0.3621302397272426f, 0.3621749226138893f, + 0.3622196046682775f, 0.3622642858903045f, 0.3623089662798676f, 0.3623536458368641f, + 0.3623983245611914f, 0.3624430024527467f, 0.3624876795114275f, 0.3625323557371311f, + 0.3625770311297548f, 0.3626217056891959f, 0.3626663794153517f, 0.3627110523081197f, + 0.3627557243673972f, 0.3628003955930815f, 0.3628450659850699f, 0.3628897355432598f, + 0.3629344042675486f, 0.3629790721578336f, 0.3630237392140122f, 0.3630684054359817f, + 0.3631130708236395f, 0.3631577353768830f, 0.3632023990956094f, 0.3632470619797162f, + 0.3632917240291008f, 0.3633363852436604f, 0.3633810456232926f, 0.3634257051678946f, + 0.3634703638773638f, 0.3635150217515976f, 0.3635596787904934f, 0.3636043349939486f, + 0.3636489903618605f, 0.3636936448941266f, 0.3637382985906442f, 0.3637829514513107f, + 0.3638276034760235f, 0.3638722546646799f, 0.3639169050171775f, 0.3639615545334136f, + 0.3640062032132855f, 0.3640508510566907f, 0.3640954980635265f, 0.3641401442336905f, + 0.3641847895670799f, 0.3642294340635922f, 0.3642740777231249f, 0.3643187205455752f, + 0.3643633625308407f, 0.3644080036788187f, 0.3644526439894066f, 0.3644972834625020f, + 0.3645419220980021f, 0.3645865598958046f, 0.3646311968558066f, 0.3646758329779056f, + 0.3647204682619993f, 0.3647651027079848f, 0.3648097363157597f, 0.3648543690852214f, + 0.3648990010162673f, 0.3649436321087949f, 0.3649882623627017f, 0.3650328917778849f, + 0.3650775203542422f, 0.3651221480916710f, 0.3651667749900686f, 0.3652114010493325f, + 0.3652560262693603f, 0.3653006506500493f, 0.3653452741912970f, 0.3653898968930009f, + 0.3654345187550584f, 0.3654791397773670f, 0.3655237599598241f, 0.3655683793023273f, + 0.3656129978047739f, 0.3656576154670614f, 0.3657022322890874f, 0.3657468482707493f, + 0.3657914634119446f, 0.3658360777125707f, 0.3658806911725250f, 0.3659253037917053f, + 0.3659699155700087f, 0.3660145265073331f, 0.3660591366035756f, 0.3661037458586339f, + 0.3661483542724053f, 0.3661929618447876f, 0.3662375685756781f, 0.3662821744649742f, + 0.3663267795125736f, 0.3663713837183737f, 0.3664159870822720f, 0.3664605896041661f, + 0.3665051912839534f, 0.3665497921215314f, 0.3665943921167976f, 0.3666389912696496f, + 0.3666835895799849f, 0.3667281870477010f, 0.3667727836726954f, 0.3668173794548656f, + 0.3668619743941091f, 0.3669065684903235f, 0.3669511617434063f, 0.3669957541532550f, + 0.3670403457197672f, 0.3670849364428403f, 0.3671295263223720f, 0.3671741153582597f, + 0.3672187035504010f, 0.3672632908986934f, 0.3673078774030344f, 0.3673524630633217f, + 0.3673970478794527f, 0.3674416318513251f, 0.3674862149788362f, 0.3675307972618838f, + 0.3675753787003653f, 0.3676199592941783f, 0.3676645390432204f, 0.3677091179473891f, + 0.3677536960065820f, 0.3677982732206965f, 0.3678428495896304f, 0.3678874251132813f, + 0.3679319997915464f, 0.3679765736243237f, 0.3680211466115104f, 0.3680657187530044f, + 0.3681102900487030f, 0.3681548604985040f, 0.3681994301023049f, 0.3682439988600032f, + 0.3682885667714966f, 0.3683331338366826f, 0.3683777000554588f, 0.3684222654277229f, + 0.3684668299533723f, 0.3685113936323048f, 0.3685559564644178f, 0.3686005184496090f, + 0.3686450795877760f, 0.3686896398788164f, 0.3687341993226278f, 0.3687787579191077f, + 0.3688233156681539f, 0.3688678725696639f, 0.3689124286235353f, 0.3689569838296657f, + 0.3690015381879528f, 0.3690460916982942f, 0.3690906443605874f, 0.3691351961747301f, + 0.3691797471406200f, 0.3692242972581546f, 0.3692688465272316f, 0.3693133949477486f, + 0.3693579425196031f, 0.3694024892426931f, 0.3694470351169158f, 0.3694915801421692f, + 0.3695361243183506f, 0.3695806676453580f, 0.3696252101230887f, 0.3696697517514406f, + 0.3697142925303112f, 0.3697588324595982f, 0.3698033715391992f, 0.3698479097690120f, + 0.3698924471489341f, 0.3699369836788632f, 0.3699815193586969f, 0.3700260541883331f, + 0.3700705881676691f, 0.3701151212966027f, 0.3701596535750318f, 0.3702041850028537f, + 0.3702487155799664f, 0.3702932453062673f, 0.3703377741816543f, 0.3703823022060249f, + 0.3704268293792768f, 0.3704713557013078f, 0.3705158811720154f, 0.3705604057912975f, + 0.3706049295590517f, 0.3706494524751755f, 0.3706939745395669f, 0.3707384957521233f, + 0.3707830161127426f, 0.3708275356213224f, 0.3708720542777604f, 0.3709165720819544f, + 0.3709610890338020f, 0.3710056051332009f, 0.3710501203800488f, 0.3710946347742434f, + 0.3711391483156826f, 0.3711836610042638f, 0.3712281728398849f, 0.3712726838224435f, + 0.3713171939518375f, 0.3713617032279645f, 0.3714062116507222f, 0.3714507192200084f, + 0.3714952259357208f, 0.3715397317977570f, 0.3715842368060149f, 0.3716287409603921f, + 0.3716732442607865f, 0.3717177467070957f, 0.3717622482992173f, 0.3718067490370494f, + 0.3718512489204895f, 0.3718957479494354f, 0.3719402461237847f, 0.3719847434434354f, + 0.3720292399082850f, 0.3720737355182314f, 0.3721182302731724f, 0.3721627241730056f, + 0.3722072172176289f, 0.3722517094069399f, 0.3722962007408365f, 0.3723406912192164f, + 0.3723851808419774f, 0.3724296696090172f, 0.3724741575202336f, 0.3725186445755243f, + 0.3725631307747873f, 0.3726076161179200f, 0.3726521006048206f, 0.3726965842353865f, + 0.3727410670095158f, 0.3727855489271060f, 0.3728300299880551f, 0.3728745101922608f, + 0.3729189895396208f, 0.3729634680300331f, 0.3730079456633952f, 0.3730524224396051f, + 0.3730968983585606f, 0.3731413734201595f, 0.3731858476242995f, 0.3732303209708783f, + 0.3732747934597940f, 0.3733192650909443f, 0.3733637358642268f, 0.3734082057795396f, + 0.3734526748367803f, 0.3734971430358468f, 0.3735416103766369f, 0.3735860768590484f, + 0.3736305424829793f, 0.3736750072483271f, 0.3737194711549898f, 0.3737639342028652f, + 0.3738083963918512f, 0.3738528577218456f, 0.3738973181927461f, 0.3739417778044506f, + 0.3739862365568570f, 0.3740306944498631f, 0.3740751514833668f, 0.3741196076572658f, + 0.3741640629714580f, 0.3742085174258413f, 0.3742529710203134f, 0.3742974237547724f, + 0.3743418756291159f, 0.3743863266432420f, 0.3744307767970482f, 0.3744752260904327f, + 0.3745196745232932f, 0.3745641220955276f, 0.3746085688070337f, 0.3746530146577094f, + 0.3746974596474527f, 0.3747419037761612f, 0.3747863470437329f, 0.3748307894500658f, + 0.3748752309950575f, 0.3749196716786062f, 0.3749641115006095f, 0.3750085504609655f, + 0.3750529885595719f, 0.3750974257963267f, 0.3751418621711277f, 0.3751862976838728f, + 0.3752307323344599f, 0.3752751661227870f, 0.3753195990487518f, 0.3753640311122524f, + 0.3754084623131866f, 0.3754528926514522f, 0.3754973221269473f, 0.3755417507395696f, + 0.3755861784892172f, 0.3756306053757879f, 0.3756750313991796f, 0.3757194565592902f, + 0.3757638808560177f, 0.3758083042892599f, 0.3758527268589149f, 0.3758971485648804f, + 0.3759415694070544f, 0.3759859893853349f, 0.3760304084996198f, 0.3760748267498070f, + 0.3761192441357943f, 0.3761636606574799f, 0.3762080763147615f, 0.3762524911075372f, + 0.3762969050357048f, 0.3763413180991623f, 0.3763857302978077f, 0.3764301416315388f, + 0.3764745521002538f, 0.3765189617038503f, 0.3765633704422265f, 0.3766077783152803f, + 0.3766521853229096f, 0.3766965914650124f, 0.3767409967414866f, 0.3767854011522303f, + 0.3768298046971413f, 0.3768742073761177f, 0.3769186091890572f, 0.3769630101358581f, + 0.3770074102164183f, 0.3770518094306355f, 0.3770962077784081f, 0.3771406052596337f, + 0.3771850018742104f, 0.3772293976220363f, 0.3772737925030092f, 0.3773181865170273f, + 0.3773625796639883f, 0.3774069719437904f, 0.3774513633563316f, 0.3774957539015097f, + 0.3775401435792229f, 0.3775845323893691f, 0.3776289203318463f, 0.3776733074065525f, + 0.3777176936133856f, 0.3777620789522438f, 0.3778064634230250f, 0.3778508470256273f, + 0.3778952297599485f, 0.3779396116258868f, 0.3779839926233401f, 0.3780283727522065f, + 0.3780727520123841f, 0.3781171304037706f, 0.3781615079262643f, 0.3782058845797632f, + 0.3782502603641652f, 0.3782946352793685f, 0.3783390093252709f, 0.3783833825017706f, + 0.3784277548087656f, 0.3784721262461539f, 0.3785164968138336f, 0.3785608665117026f, + 0.3786052353396592f, 0.3786496032976012f, 0.3786939703854267f, 0.3787383366030338f, + 0.3787827019503205f, 0.3788270664271849f, 0.3788714300335251f, 0.3789157927692390f, + 0.3789601546342247f, 0.3790045156283804f, 0.3790488757516040f, 0.3790932350037936f, + 0.3791375933848473f, 0.3791819508946632f, 0.3792263075331393f, 0.3792706633001737f, + 0.3793150181956644f, 0.3793593722195096f, 0.3794037253716073f, 0.3794480776518556f, + 0.3794924290601526f, 0.3795367795963963f, 0.3795811292604849f, 0.3796254780523164f, + 0.3796698259717889f, 0.3797141730188006f, 0.3797585191932495f, 0.3798028644950336f, + 0.3798472089240512f, 0.3798915524802002f, 0.3799358951633788f, 0.3799802369734852f, + 0.3800245779104173f, 0.3800689179740734f, 0.3801132571643514f, 0.3801575954811496f, + 0.3802019329243660f, 0.3802462694938989f, 0.3802906051896461f, 0.3803349400115060f, + 0.3803792739593766f, 0.3804236070331560f, 0.3804679392327424f, 0.3805122705580338f, + 0.3805566010089286f, 0.3806009305853246f, 0.3806452592871201f, 0.3806895871142132f, + 0.3807339140665021f, 0.3807782401438849f, 0.3808225653462597f, 0.3808668896735247f, + 0.3809112131255781f, 0.3809555357023178f, 0.3809998574036423f, 0.3810441782294495f, + 0.3810884981796375f, 0.3811328172541047f, 0.3811771354527492f, 0.3812214527754690f, + 0.3812657692221624f, 0.3813100847927274f, 0.3813543994870625f, 0.3813987133050654f, + 0.3814430262466347f, 0.3814873383116684f, 0.3815316495000646f, 0.3815759598117215f, + 0.3816202692465374f, 0.3816645778044103f, 0.3817088854852386f, 0.3817531922889203f, + 0.3817974982153536f, 0.3818418032644368f, 0.3818861074360680f, 0.3819304107301454f, + 0.3819747131465673f, 0.3820190146852317f, 0.3820633153460369f, 0.3821076151288812f, + 0.3821519140336626f, 0.3821962120602795f, 0.3822405092086299f, 0.3822848054786122f, + 0.3823291008701245f, 0.3823733953830650f, 0.3824176890173320f, 0.3824619817728237f, + 0.3825062736494383f, 0.3825505646470739f, 0.3825948547656289f, 0.3826391440050015f, + 0.3826834323650898f, 0.3827277198457921f, 0.3827720064470067f, 0.3828162921686317f, + 0.3828605770105654f, 0.3829048609727060f, 0.3829491440549520f, 0.3829934262572012f, + 0.3830377075793521f, 0.3830819880213029f, 0.3831262675829518f, 0.3831705462641972f, + 0.3832148240649372f, 0.3832591009850700f, 0.3833033770244941f, 0.3833476521831075f, + 0.3833919264608087f, 0.3834361998574957f, 0.3834804723730669f, 0.3835247440074205f, + 0.3835690147604549f, 0.3836132846320683f, 0.3836575536221589f, 0.3837018217306251f, + 0.3837460889573650f, 0.3837903553022770f, 0.3838346207652594f, 0.3838788853462105f, + 0.3839231490450284f, 0.3839674118616115f, 0.3840116737958582f, 0.3840559348476666f, + 0.3841001950169350f, 0.3841444543035619f, 0.3841887127074454f, 0.3842329702284838f, + 0.3842772268665755f, 0.3843214826216187f, 0.3843657374935119f, 0.3844099914821531f, + 0.3844542445874409f, 0.3844984968092733f, 0.3845427481475489f, 0.3845869986021659f, + 0.3846312481730226f, 0.3846754968600173f, 0.3847197446630484f, 0.3847639915820141f, + 0.3848082376168129f, 0.3848524827673429f, 0.3848967270335026f, 0.3849409704151903f, + 0.3849852129123042f, 0.3850294545247429f, 0.3850736952524044f, 0.3851179350951873f, + 0.3851621740529899f, 0.3852064121257103f, 0.3852506493132472f, 0.3852948856154987f, + 0.3853391210323633f, 0.3853833555637393f, 0.3854275892095250f, 0.3854718219696187f, + 0.3855160538439188f, 0.3855602848323239f, 0.3856045149347320f, 0.3856487441510416f, + 0.3856929724811511f, 0.3857371999249589f, 0.3857814264823632f, 0.3858256521532626f, + 0.3858698769375554f, 0.3859141008351398f, 0.3859583238459143f, 0.3860025459697773f, + 0.3860467672066272f, 0.3860909875563623f, 0.3861352070188810f, 0.3861794255940818f, + 0.3862236432818630f, 0.3862678600821229f, 0.3863120759947601f, 0.3863562910196728f, + 0.3864005051567595f, 0.3864447184059185f, 0.3864889307670483f, 0.3865331422400474f, + 0.3865773528248139f, 0.3866215625212465f, 0.3866657713292435f, 0.3867099792487032f, + 0.3867541862795242f, 0.3867983924216048f, 0.3868425976748435f, 0.3868868020391386f, + 0.3869310055143886f, 0.3869752081004919f, 0.3870194097973469f, 0.3870636106048522f, + 0.3871078105229060f, 0.3871520095514068f, 0.3871962076902531f, 0.3872404049393433f, + 0.3872846012985758f, 0.3873287967678490f, 0.3873729913470615f, 0.3874171850361117f, + 0.3874613778348979f, 0.3875055697433187f, 0.3875497607612724f, 0.3875939508886576f, + 0.3876381401253727f, 0.3876823284713162f, 0.3877265159263865f, 0.3877707024904820f, + 0.3878148881635012f, 0.3878590729453427f, 0.3879032568359048f, 0.3879474398350861f, + 0.3879916219427849f, 0.3880358031588999f, 0.3880799834833293f, 0.3881241629159717f, + 0.3881683414567257f, 0.3882125191054897f, 0.3882566958621622f, 0.3883008717266415f, + 0.3883450466988263f, 0.3883892207786150f, 0.3884333939659061f, 0.3884775662605982f, + 0.3885217376625896f, 0.3885659081717789f, 0.3886100777880646f, 0.3886542465113452f, + 0.3886984143415192f, 0.3887425812784851f, 0.3887867473221414f, 0.3888309124723866f, + 0.3888750767291193f, 0.3889192400922378f, 0.3889634025616409f, 0.3890075641372269f, + 0.3890517248188944f, 0.3890958846065419f, 0.3891400435000679f, 0.3891842014993710f, + 0.3892283586043497f, 0.3892725148149025f, 0.3893166701309280f, 0.3893608245523246f, + 0.3894049780789909f, 0.3894491307108255f, 0.3894932824477269f, 0.3895374332895937f, + 0.3895815832363243f, 0.3896257322878173f, 0.3896698804439713f, 0.3897140277046848f, + 0.3897581740698565f, 0.3898023195393847f, 0.3898464641131681f, 0.3898906077911053f, + 0.3899347505730947f, 0.3899788924590351f, 0.3900230334488248f, 0.3900671735423625f, + 0.3901113127395469f, 0.3901554510402763f, 0.3901995884444495f, 0.3902437249519649f, + 0.3902878605627212f, 0.3903319952766170f, 0.3903761290935507f, 0.3904202620134211f, + 0.3904643940361266f, 0.3905085251615660f, 0.3905526553896376f, 0.3905967847202402f, + 0.3906409131532724f, 0.3906850406886327f, 0.3907291673262198f, 0.3907732930659322f, + 0.3908174179076685f, 0.3908615418513274f, 0.3909056648968074f, 0.3909497870440072f, + 0.3909939082928254f, 0.3910380286431605f, 0.3910821480949112f, 0.3911262666479761f, + 0.3911703843022539f, 0.3912145010576430f, 0.3912586169140423f, 0.3913027318713503f, + 0.3913468459294656f, 0.3913909590882868f, 0.3914350713477125f, 0.3914791827076416f, + 0.3915232931679724f, 0.3915674027286037f, 0.3916115113894342f, 0.3916556191503624f, + 0.3916997260112870f, 0.3917438319721067f, 0.3917879370327200f, 0.3918320411930257f, + 0.3918761444529223f, 0.3919202468123087f, 0.3919643482710833f, 0.3920084488291449f, + 0.3920525484863921f, 0.3920966472427235f, 0.3921407450980380f, 0.3921848420522340f, + 0.3922289381052103f, 0.3922730332568656f, 0.3923171275070984f, 0.3923612208558076f, + 0.3924053133028917f, 0.3924494048482495f, 0.3924934954917796f, 0.3925375852333807f, + 0.3925816740729515f, 0.3926257620103906f, 0.3926698490455969f, 0.3927139351784689f, + 0.3927580204089053f, 0.3928021047368049f, 0.3928461881620663f, 0.3928902706845883f, + 0.3929343523042695f, 0.3929784330210086f, 0.3930225128347044f, 0.3930665917452555f, + 0.3931106697525608f, 0.3931547468565187f, 0.3931988230570282f, 0.3932428983539878f, + 0.3932869727472964f, 0.3933310462368527f, 0.3933751188225552f, 0.3934191905043029f, + 0.3934632612819943f, 0.3935073311555283f, 0.3935514001248037f, 0.3935954681897189f, + 0.3936395353501729f, 0.3936836016060644f, 0.3937276669572921f, 0.3937717314037547f, + 0.3938157949453510f, 0.3938598575819798f, 0.3939039193135397f, 0.3939479801399296f, + 0.3939920400610481f, 0.3940360990767940f, 0.3940801571870662f, 0.3941242143917633f, + 0.3941682706907841f, 0.3942123260840274f, 0.3942563805713919f, 0.3943004341527764f, + 0.3943444868280796f, 0.3943885385972004f, 0.3944325894600375f, 0.3944766394164896f, + 0.3945206884664556f, 0.3945647366098342f, 0.3946087838465243f, 0.3946528301764244f, + 0.3946968755994336f, 0.3947409201154505f, 0.3947849637243740f, 0.3948290064261029f, + 0.3948730482205358f, 0.3949170891075717f, 0.3949611290871092f, 0.3950051681590473f, + 0.3950492063232848f, 0.3950932435797203f, 0.3951372799282528f, 0.3951813153687810f, + 0.3952253499012037f, 0.3952693835254198f, 0.3953134162413280f, 0.3953574480488273f, + 0.3954014789478164f, 0.3954455089381940f, 0.3954895380198591f, 0.3955335661927104f, + 0.3955775934566469f, 0.3956216198115672f, 0.3956656452573703f, 0.3957096697939550f, + 0.3957536934212201f, 0.3957977161390644f, 0.3958417379473868f, 0.3958857588460862f, + 0.3959297788350613f, 0.3959737979142109f, 0.3960178160834342f, 0.3960618333426296f, + 0.3961058496916963f, 0.3961498651305330f, 0.3961938796590385f, 0.3962378932771117f, + 0.3962819059846515f, 0.3963259177815568f, 0.3963699286677264f, 0.3964139386430591f, + 0.3964579477074539f, 0.3965019558608096f, 0.3965459631030251f, 0.3965899694339992f, + 0.3966339748536308f, 0.3966779793618189f, 0.3967219829584622f, 0.3967659856434598f, + 0.3968099874167103f, 0.3968539882781129f, 0.3968979882275662f, 0.3969419872649692f, + 0.3969859853902209f, 0.3970299826032201f, 0.3970739789038656f, 0.3971179742920565f, + 0.3971619687676916f, 0.3972059623306698f, 0.3972499549808900f, 0.3972939467182511f, + 0.3973379375426521f, 0.3973819274539917f, 0.3974259164521691f, 0.3974699045370829f, + 0.3975138917086324f, 0.3975578779667162f, 0.3976018633112332f, 0.3976458477420826f, + 0.3976898312591632f, 0.3977338138623738f, 0.3977777955516135f, 0.3978217763267812f, + 0.3978657561877758f, 0.3979097351344961f, 0.3979537131668414f, 0.3979976902847102f, + 0.3980416664880018f, 0.3980856417766150f, 0.3981296161504487f, 0.3981735896094019f, + 0.3982175621533736f, 0.3982615337822627f, 0.3983055044959681f, 0.3983494742943889f, + 0.3983934431774240f, 0.3984374111449723f, 0.3984813781969328f, 0.3985253443332045f, + 0.3985693095536863f, 0.3986132738582773f, 0.3986572372468762f, 0.3987011997193823f, + 0.3987451612756944f, 0.3987891219157116f, 0.3988330816393327f, 0.3988770404464568f, + 0.3989209983369829f, 0.3989649553108099f, 0.3990089113678369f, 0.3990528665079627f, + 0.3990968207310865f, 0.3991407740371073f, 0.3991847264259239f, 0.3992286778974355f, + 0.3992726284515410f, 0.3993165780881394f, 0.3993605268071297f, 0.3994044746084109f, + 0.3994484214918822f, 0.3994923674574424f, 0.3995363125049905f, 0.3995802566344257f, + 0.3996241998456468f, 0.3996681421385530f, 0.3997120835130432f, 0.3997560239690166f, + 0.3997999635063720f, 0.3998439021250085f, 0.3998878398248253f, 0.3999317766057212f, + 0.3999757124675954f, 0.4000196474103468f, 0.4000635814338745f, 0.4001075145380776f, + 0.4001514467228551f, 0.4001953779881061f, 0.4002393083337295f, 0.4002832377596245f, + 0.4003271662656901f, 0.4003710938518253f, 0.4004150205179293f, 0.4004589462639010f, + 0.4005028710896395f, 0.4005467949950439f, 0.4005907179800133f, 0.4006346400444468f, + 0.4006785611882432f, 0.4007224814113019f, 0.4007664007135218f, 0.4008103190948020f, + 0.4008542365550417f, 0.4008981530941397f, 0.4009420687119954f, 0.4009859834085077f, + 0.4010298971835756f, 0.4010738100370985f, 0.4011177219689752f, 0.4011616329791049f, + 0.4012055430673867f, 0.4012494522337197f, 0.4012933604780030f, 0.4013372678001357f, + 0.4013811742000168f, 0.4014250796775456f, 0.4014689842326211f, 0.4015128878651423f, + 0.4015567905750085f, 0.4016006923621188f, 0.4016445932263722f, 0.4016884931676679f, + 0.4017323921859050f, 0.4017762902809826f, 0.4018201874527998f, 0.4018640837012558f, + 0.4019079790262498f, 0.4019518734276807f, 0.4019957669054477f, 0.4020396594594502f, + 0.4020835510895870f, 0.4021274417957574f, 0.4021713315778605f, 0.4022152204357955f, + 0.4022591083694615f, 0.4023029953787576f, 0.4023468814635831f, 0.4023907666238369f, + 0.4024346508594184f, 0.4024785341702267f, 0.4025224165561609f, 0.4025662980171202f, + 0.4026101785530037f, 0.4026540581637106f, 0.4026979368491401f, 0.4027418146091913f, + 0.4027856914437635f, 0.4028295673527558f, 0.4028734423360674f, 0.4029173163935973f, + 0.4029611895252449f, 0.4030050617309093f, 0.4030489330104897f, 0.4030928033638854f, + 0.4031366727909953f, 0.4031805412917188f, 0.4032244088659551f, 0.4032682755136032f, + 0.4033121412345626f, 0.4033560060287322f, 0.4033998698960115f, 0.4034437328362994f, + 0.4034875948494953f, 0.4035314559354984f, 0.4035753160942078f, 0.4036191753255229f, + 0.4036630336293426f, 0.4037068910055664f, 0.4037507474540935f, 0.4037946029748229f, + 0.4038384575676541f, 0.4038823112324861f, 0.4039261639692183f, 0.4039700157777498f, + 0.4040138666579799f, 0.4040577166098078f, 0.4041015656331327f, 0.4041454137278540f, + 0.4041892608938707f, 0.4042331071310822f, 0.4042769524393878f, 0.4043207968186865f, + 0.4043646402688778f, 0.4044084827898609f, 0.4044523243815349f, 0.4044961650437992f, + 0.4045400047765530f, 0.4045838435796956f, 0.4046276814531262f, 0.4046715183967441f, + 0.4047153544104486f, 0.4047591894941390f, 0.4048030236477144f, 0.4048468568710742f, + 0.4048906891641176f, 0.4049345205267440f, 0.4049783509588525f, 0.4050221804603426f, + 0.4050660090311133f, 0.4051098366710641f, 0.4051536633800944f, 0.4051974891581032f, + 0.4052413140049899f, 0.4052851379206538f, 0.4053289609049942f, 0.4053727829579104f, + 0.4054166040793016f, 0.4054604242690674f, 0.4055042435271067f, 0.4055480618533192f, + 0.4055918792476039f, 0.4056356957098602f, 0.4056795112399875f, 0.4057233258378850f, + 0.4057671395034521f, 0.4058109522365880f, 0.4058547640371922f, 0.4058985749051640f, + 0.4059423848404025f, 0.4059861938428073f, 0.4060300019122775f, 0.4060738090487125f, + 0.4061176152520118f, 0.4061614205220746f, 0.4062052248588003f, 0.4062490282620880f, + 0.4062928307318374f, 0.4063366322679476f, 0.4063804328703181f, 0.4064242325388481f, + 0.4064680312734370f, 0.4065118290739842f, 0.4065556259403890f, 0.4065994218725508f, + 0.4066432168703690f, 0.4066870109337429f, 0.4067308040625718f, 0.4067745962567552f, + 0.4068183875161923f, 0.4068621778407827f, 0.4069059672304256f, 0.4069497556850205f, + 0.4069935432044665f, 0.4070373297886633f, 0.4070811154375102f, 0.4071249001509064f, + 0.4071686839287516f, 0.4072124667709449f, 0.4072562486773857f, 0.4073000296479737f, + 0.4073438096826080f, 0.4073875887811881f, 0.4074313669436133f, 0.4074751441697831f, + 0.4075189204595969f, 0.4075626958129541f, 0.4076064702297542f, 0.4076502437098963f, + 0.4076940162532802f, 0.4077377878598050f, 0.4077815585293702f, 0.4078253282618754f, + 0.4078690970572198f, 0.4079128649153029f, 0.4079566318360242f, 0.4080003978192829f, + 0.4080441628649787f, 0.4080879269730108f, 0.4081316901432789f, 0.4081754523756821f, + 0.4082192136701201f, 0.4082629740264923f, 0.4083067334446980f, 0.4083504919246368f, + 0.4083942494662080f, 0.4084380060693112f, 0.4084817617338457f, 0.4085255164597111f, + 0.4085692702468068f, 0.4086130230950322f, 0.4086567750042868f, 0.4087005259744700f, + 0.4087442760054814f, 0.4087880250972203f, 0.4088317732495864f, 0.4088755204624789f, + 0.4089192667357974f, 0.4089630120694414f, 0.4090067564633104f, 0.4090504999173037f, + 0.4090942424313210f, 0.4091379840052616f, 0.4091817246390251f, 0.4092254643325109f, + 0.4092692030856186f, 0.4093129408982477f, 0.4093566777702975f, 0.4094004137016676f, + 0.4094441486922576f, 0.4094878827419669f, 0.4095316158506950f, 0.4095753480183414f, + 0.4096190792448057f, 0.4096628095299873f, 0.4097065388737857f, 0.4097502672761005f, + 0.4097939947368311f, 0.4098377212558773f, 0.4098814468331382f, 0.4099251714685135f, + 0.4099688951619029f, 0.4100126179132056f, 0.4100563397223215f, 0.4101000605891498f, + 0.4101437805135902f, 0.4101874994955423f, 0.4102312175349054f, 0.4102749346315792f, + 0.4103186507854633f, 0.4103623659964570f, 0.4104060802644601f, 0.4104497935893721f, + 0.4104935059710924f, 0.4105372174095206f, 0.4105809279045565f, 0.4106246374560993f, + 0.4106683460640487f, 0.4107120537283044f, 0.4107557604487657f, 0.4107994662253324f, + 0.4108431710579039f, 0.4108868749463799f, 0.4109305778906599f, 0.4109742798906434f, + 0.4110179809462302f, 0.4110616810573196f, 0.4111053802238114f, 0.4111490784456051f, + 0.4111927757226002f, 0.4112364720546964f, 0.4112801674417932f, 0.4113238618837903f, + 0.4113675553805872f, 0.4114112479320836f, 0.4114549395381790f, 0.4114986301987730f, + 0.4115423199137653f, 0.4115860086830553f, 0.4116296965065428f, 0.4116733833841273f, + 0.4117170693157086f, 0.4117607543011860f, 0.4118044383404594f, 0.4118481214334282f, + 0.4118918035799922f, 0.4119354847800508f, 0.4119791650335039f, 0.4120228443402509f, + 0.4120665227001916f, 0.4121102001132255f, 0.4121538765792522f, 0.4121975520981715f, + 0.4122412266698829f, 0.4122849002942861f, 0.4123285729712807f, 0.4123722447007663f, + 0.4124159154826427f, 0.4124595853168094f, 0.4125032542031662f, 0.4125469221416125f, + 0.4125905891320482f, 0.4126342551743729f, 0.4126779202684862f, 0.4127215844142878f, + 0.4127652476116773f, 0.4128089098605544f, 0.4128525711608187f, 0.4128962315123701f, + 0.4129398909151081f, 0.4129835493689323f, 0.4130272068737425f, 0.4130708634294383f, + 0.4131145190359194f, 0.4131581736930856f, 0.4132018274008364f, 0.4132454801590717f, + 0.4132891319676910f, 0.4133327828265939f, 0.4133764327356804f, 0.4134200816948500f, + 0.4134637297040025f, 0.4135073767630374f, 0.4135510228718546f, 0.4135946680303538f, + 0.4136383122384345f, 0.4136819554959967f, 0.4137255978029399f, 0.4137692391591638f, + 0.4138128795645683f, 0.4138565190190530f, 0.4139001575225176f, 0.4139437950748618f, + 0.4139874316759855f, 0.4140310673257881f, 0.4140747020241696f, 0.4141183357710297f, + 0.4141619685662681f, 0.4142056004097845f, 0.4142492313014786f, 0.4142928612412503f, + 0.4143364902289991f, 0.4143801182646250f, 0.4144237453480275f, 0.4144673714791066f, + 0.4145109966577618f, 0.4145546208838930f, 0.4145982441573999f, 0.4146418664781824f, + 0.4146854878461400f, 0.4147291082611727f, 0.4147727277231801f, 0.4148163462320620f, + 0.4148599637877183f, 0.4149035803900486f, 0.4149471960389527f, 0.4149908107343305f, + 0.4150344244760816f, 0.4150780372641059f, 0.4151216490983031f, 0.4151652599785731f, + 0.4152088699048156f, 0.4152524788769303f, 0.4152960868948172f, 0.4153396939583759f, + 0.4153833000675063f, 0.4154269052221081f, 0.4154705094220812f, 0.4155141126673254f, + 0.4155577149577404f, 0.4156013162932262f, 0.4156449166736823f, 0.4156885160990088f, + 0.4157321145691054f, 0.4157757120838718f, 0.4158193086432080f, 0.4158629042470137f, + 0.4159064988951888f, 0.4159500925876330f, 0.4159936853242463f, 0.4160372771049284f, + 0.4160808679295792f, 0.4161244577980985f, 0.4161680467103860f, 0.4162116346663418f, + 0.4162552216658655f, 0.4162988077088570f, 0.4163423927952163f, 0.4163859769248430f, + 0.4164295600976372f, 0.4164731423134985f, 0.4165167235723269f, 0.4165603038740223f, + 0.4166038832184843f, 0.4166474616056131f, 0.4166910390353083f, 0.4167346155074698f, + 0.4167781910219976f, 0.4168217655787915f, 0.4168653391777513f, 0.4169089118187769f, + 0.4169524835017682f, 0.4169960542266251f, 0.4170396239932474f, 0.4170831928015351f, + 0.4171267606513879f, 0.4171703275427058f, 0.4172138934753887f, 0.4172574584493364f, + 0.4173010224644489f, 0.4173445855206261f, 0.4173881476177677f, 0.4174317087557739f, + 0.4174752689345443f, 0.4175188281539790f, 0.4175623864139778f, 0.4176059437144406f, + 0.4176495000552674f, 0.4176930554363580f, 0.4177366098576125f, 0.4177801633189306f, + 0.4178237158202123f, 0.4178672673613575f, 0.4179108179422662f, 0.4179543675628383f, + 0.4179979162229736f, 0.4180414639225721f, 0.4180850106615338f, 0.4181285564397585f, + 0.4181721012571463f, 0.4182156451135970f, 0.4182591880090106f, 0.4183027299432870f, + 0.4183462709163263f, 0.4183898109280282f, 0.4184333499782927f, 0.4184768880670200f, + 0.4185204251941097f, 0.4185639613594620f, 0.4186074965629767f, 0.4186510308045540f, + 0.4186945640840936f, 0.4187380964014955f, 0.4187816277566598f, 0.4188251581494863f, + 0.4188686875798751f, 0.4189122160477262f, 0.4189557435529394f, 0.4189992700954148f, + 0.4190427956750524f, 0.4190863202917521f, 0.4191298439454140f, 0.4191733666359379f, + 0.4192168883632240f, 0.4192604091271721f, 0.4193039289276823f, 0.4193474477646545f, + 0.4193909656379889f, 0.4194344825475853f, 0.4194779984933438f, 0.4195215134751643f, + 0.4195650274929469f, 0.4196085405465916f, 0.4196520526359984f, 0.4196955637610672f, + 0.4197390739216982f, 0.4197825831177913f, 0.4198260913492466f, 0.4198695986159640f, + 0.4199131049178436f, 0.4199566102547855f, 0.4200001146266896f, 0.4200436180334559f, + 0.4200871204749845f, 0.4201306219511755f, 0.4201741224619289f, 0.4202176220071447f, + 0.4202611205867229f, 0.4203046182005636f, 0.4203481148485669f, 0.4203916105306327f, + 0.4204351052466612f, 0.4204785989965523f, 0.4205220917802063f, 0.4205655835975229f, + 0.4206090744484025f, 0.4206525643327450f, 0.4206960532504505f, 0.4207395412014189f, + 0.4207830281855505f, 0.4208265142027453f, 0.4208699992529033f, 0.4209134833359247f, + 0.4209569664517094f, 0.4210004486001576f, 0.4210439297811694f, 0.4210874099946449f, + 0.4211308892404840f, 0.4211743675185870f, 0.4212178448288538f, 0.4212613211711847f, + 0.4213047965454796f, 0.4213482709516388f, 0.4213917443895622f, 0.4214352168591500f, + 0.4214786883603023f, 0.4215221588929191f, 0.4215656284569007f, 0.4216090970521471f, + 0.4216525646785583f, 0.4216960313360347f, 0.4217394970244761f, 0.4217829617437828f, + 0.4218264254938549f, 0.4218698882745925f, 0.4219133500858958f, 0.4219568109276648f, + 0.4220002707997997f, 0.4220437297022006f, 0.4220871876347677f, 0.4221306445974010f, + 0.4221741005900008f, 0.4222175556124672f, 0.4222610096647002f, 0.4223044627466002f, + 0.4223479148580671f, 0.4223913659990011f, 0.4224348161693025f, 0.4224782653688713f, + 0.4225217135976078f, 0.4225651608554121f, 0.4226086071421842f, 0.4226520524578244f, + 0.4226954968022330f, 0.4227389401753099f, 0.4227823825769554f, 0.4228258240070698f, + 0.4228692644655531f, 0.4229127039523054f, 0.4229561424672271f, 0.4229995800102183f, + 0.4230430165811791f, 0.4230864521800097f, 0.4231298868066104f, 0.4231733204608814f, + 0.4232167531427226f, 0.4232601848520346f, 0.4233036155887173f, 0.4233470453526710f, + 0.4233904741437960f, 0.4234339019619924f, 0.4234773288071604f, 0.4235207546792001f, + 0.4235641795780120f, 0.4236076035034961f, 0.4236510264555525f, 0.4236944484340818f, + 0.4237378694389838f, 0.4237812894701591f, 0.4238247085275076f, 0.4238681266109297f, + 0.4239115437203256f, 0.4239549598555954f, 0.4239983750166396f, 0.4240417892033582f, + 0.4240852024156516f, 0.4241286146534199f, 0.4241720259165634f, 0.4242154362049824f, + 0.4242588455185770f, 0.4243022538572475f, 0.4243456612208943f, 0.4243890676094175f, + 0.4244324730227174f, 0.4244758774606943f, 0.4245192809232484f, 0.4245626834102799f, + 0.4246060849216891f, 0.4246494854573764f, 0.4246928850172419f, 0.4247362836011860f, + 0.4247796812091088f, 0.4248230778409108f, 0.4248664734964921f, 0.4249098681757530f, + 0.4249532618785939f, 0.4249966546049150f, 0.4250400463546166f, 0.4250834371275989f, + 0.4251268269237624f, 0.4251702157430072f, 0.4252136035852336f, 0.4252569904503420f, + 0.4253003763382326f, 0.4253437612488059f, 0.4253871451819619f, 0.4254305281376011f, + 0.4254739101156239f, 0.4255172911159303f, 0.4255606711384209f, 0.4256040501829959f, + 0.4256474282495556f, 0.4256908053380004f, 0.4257341814482305f, 0.4257775565801463f, + 0.4258209307336482f, 0.4258643039086364f, 0.4259076761050113f, 0.4259510473226732f, + 0.4259944175615224f, 0.4260377868214594f, 0.4260811551023843f, 0.4261245224041976f, + 0.4261678887267996f, 0.4262112540700907f, 0.4262546184339712f, 0.4262979818183414f, + 0.4263413442231018f, 0.4263847056481527f, 0.4264280660933943f, 0.4264714255587271f, + 0.4265147840440515f, 0.4265581415492679f, 0.4266014980742764f, 0.4266448536189776f, + 0.4266882081832719f, 0.4267315617670595f, 0.4267749143702409f, 0.4268182659927164f, + 0.4268616166343865f, 0.4269049662951515f, 0.4269483149749117f, 0.4269916626735677f, + 0.4270350093910197f, 0.4270783551271682f, 0.4271216998819135f, 0.4271650436551561f, + 0.4272083864467963f, 0.4272517282567346f, 0.4272950690848714f, 0.4273384089311069f, + 0.4273817477953418f, 0.4274250856774763f, 0.4274684225774109f, 0.4275117584950461f, + 0.4275550934302821f, 0.4275984273830195f, 0.4276417603531586f, 0.4276850923405999f, + 0.4277284233452438f, 0.4277717533669907f, 0.4278150824057412f, 0.4278584104613955f, + 0.4279017375338541f, 0.4279450636230175f, 0.4279883887287861f, 0.4280317128510604f, + 0.4280750359897407f, 0.4281183581447276f, 0.4281616793159215f, 0.4282049995032228f, + 0.4282483187065320f, 0.4282916369257495f, 0.4283349541607758f, 0.4283782704115114f, + 0.4284215856778567f, 0.4284648999597122f, 0.4285082132569783f, 0.4285515255695556f, + 0.4285948368973444f, 0.4286381472402453f, 0.4286814565981588f, 0.4287247649709852f, + 0.4287680723586251f, 0.4288113787609790f, 0.4288546841779474f, 0.4288979886094307f, + 0.4289412920553295f, 0.4289845945155442f, 0.4290278959899753f, 0.4290711964785233f, + 0.4291144959810888f, 0.4291577944975721f, 0.4292010920278739f, 0.4292443885718945f, + 0.4292876841295347f, 0.4293309787006946f, 0.4293742722852751f, 0.4294175648831766f, + 0.4294608564942995f, 0.4295041471185445f, 0.4295474367558119f, 0.4295907254060023f, + 0.4296340130690164f, 0.4296772997447545f, 0.4297205854331173f, 0.4297638701340051f, + 0.4298071538473187f, 0.4298504365729585f, 0.4298937183108251f, 0.4299369990608189f, + 0.4299802788228406f, 0.4300235575967908f, 0.4300668353825698f, 0.4301101121800783f, + 0.4301533879892169f, 0.4301966628098860f, 0.4302399366419863f, 0.4302832094854183f, + 0.4303264813400826f, 0.4303697522058798f, 0.4304130220827103f, 0.4304562909704748f, + 0.4304995588690738f, 0.4305428257784079f, 0.4305860916983778f, 0.4306293566288839f, + 0.4306726205698269f, 0.4307158835211072f, 0.4307591454826256f, 0.4308024064542825f, + 0.4308456664359787f, 0.4308889254276146f, 0.4309321834290910f, 0.4309754404403082f, + 0.4310186964611670f, 0.4310619514915680f, 0.4311052055314118f, 0.4311484585805989f, + 0.4311917106390300f, 0.4312349617066057f, 0.4312782117832266f, 0.4313214608687932f, + 0.4313647089632063f, 0.4314079560663666f, 0.4314512021781743f, 0.4314944472985304f, + 0.4315376914273355f, 0.4315809345644900f, 0.4316241767098948f, 0.4316674178634503f, + 0.4317106580250573f, 0.4317538971946163f, 0.4317971353720280f, 0.4318403725571932f, + 0.4318836087500122f, 0.4319268439503860f, 0.4319700781582150f, 0.4320133113733999f, + 0.4320565435958415f, 0.4320997748254403f, 0.4321430050620970f, 0.4321862343057122f, + 0.4322294625561867f, 0.4322726898134211f, 0.4323159160773160f, 0.4323591413477721f, + 0.4324023656246901f, 0.4324455889079707f, 0.4324888111975146f, 0.4325320324932223f, + 0.4325752527949947f, 0.4326184721027323f, 0.4326616904163359f, 0.4327049077357061f, + 0.4327481240607437f, 0.4327913393913493f, 0.4328345537274236f, 0.4328777670688674f, + 0.4329209794155813f, 0.4329641907674660f, 0.4330074011244222f, 0.4330506104863506f, + 0.4330938188531520f, 0.4331370262247270f, 0.4331802326009763f, 0.4332234379818007f, + 0.4332666423671009f, 0.4333098457567777f, 0.4333530481507316f, 0.4333962495488635f, + 0.4334394499510741f, 0.4334826493572640f, 0.4335258477673341f, 0.4335690451811851f, + 0.4336122415987176f, 0.4336554370198325f, 0.4336986314444304f, 0.4337418248724123f, + 0.4337850173036785f, 0.4338282087381302f, 0.4338713991756679f, 0.4339145886161924f, + 0.4339577770596044f, 0.4340009645058048f, 0.4340441509546942f, 0.4340873364061735f, + 0.4341305208601433f, 0.4341737043165045f, 0.4342168867751579f, 0.4342600682360041f, + 0.4343032486989440f, 0.4343464281638783f, 0.4343896066307079f, 0.4344327840993334f, + 0.4344759605696557f, 0.4345191360415755f, 0.4345623105149937f, 0.4346054839898111f, + 0.4346486564659283f, 0.4346918279432463f, 0.4347349984216657f, 0.4347781679010875f, + 0.4348213363814123f, 0.4348645038625411f, 0.4349076703443745f, 0.4349508358268135f, + 0.4349940003097588f, 0.4350371637931111f, 0.4350803262767715f, 0.4351234877606406f, + 0.4351666482446193f, 0.4352098077286083f, 0.4352529662125086f, 0.4352961236962209f, + 0.4353392801796461f, 0.4353824356626849f, 0.4354255901452384f, 0.4354687436272071f, + 0.4355118961084920f, 0.4355550475889940f, 0.4355981980686138f, 0.4356413475472524f, + 0.4356844960248105f, 0.4357276435011890f, 0.4357707899762888f, 0.4358139354500106f, + 0.4358570799222555f, 0.4359002233929241f, 0.4359433658619175f, 0.4359865073291364f, + 0.4360296477944816f, 0.4360727872578541f, 0.4361159257191548f, 0.4361590631782845f, + 0.4362021996351440f, 0.4362453350896343f, 0.4362884695416562f, 0.4363316029911106f, + 0.4363747354378984f, 0.4364178668819205f, 0.4364609973230777f, 0.4365041267612710f, + 0.4365472551964012f, 0.4365903826283692f, 0.4366335090570760f, 0.4366766344824224f, + 0.4367197589043094f, 0.4367628823226377f, 0.4368060047373084f, 0.4368491261482223f, + 0.4368922465552804f, 0.4369353659583835f, 0.4369784843574326f, 0.4370216017523286f, + 0.4370647181429724f, 0.4371078335292649f, 0.4371509479111071f, 0.4371940612883998f, + 0.4372371736610441f, 0.4372802850289408f, 0.4373233953919908f, 0.4373665047500952f, + 0.4374096131031548f, 0.4374527204510706f, 0.4374958267937435f, 0.4375389321310745f, + 0.4375820364629644f, 0.4376251397893144f, 0.4376682421100252f, 0.4377113434249979f, + 0.4377544437341334f, 0.4377975430373327f, 0.4378406413344968f, 0.4378837386255265f, + 0.4379268349103229f, 0.4379699301887869f, 0.4380130244608195f, 0.4380561177263217f, + 0.4380992099851945f, 0.4381423012373387f, 0.4381853914826555f, 0.4382284807210458f, + 0.4382715689524105f, 0.4383146561766506f, 0.4383577423936672f, 0.4384008276033612f, + 0.4384439118056337f, 0.4384869950003856f, 0.4385300771875179f, 0.4385731583669316f, + 0.4386162385385277f, 0.4386593177022071f, 0.4387023958578711f, 0.4387454730054204f, + 0.4387885491447563f, 0.4388316242757796f, 0.4388746983983913f, 0.4389177715124926f, + 0.4389608436179843f, 0.4390039147147676f, 0.4390469848027435f, 0.4390900538818129f, + 0.4391331219518769f, 0.4391761890128366f, 0.4392192550645930f, 0.4392623201070471f, + 0.4393053841401000f, 0.4393484471636526f, 0.4393915091776061f, 0.4394345701818615f, + 0.4394776301763198f, 0.4395206891608821f, 0.4395637471354494f, 0.4396068040999229f, + 0.4396498600542035f, 0.4396929149981922f, 0.4397359689317903f, 0.4397790218548987f, + 0.4398220737674185f, 0.4398651246692508f, 0.4399081745602966f, 0.4399512234404571f, + 0.4399942713096333f, 0.4400373181677261f, 0.4400803640146369f, 0.4401234088502666f, + 0.4401664526745164f, 0.4402094954872872f, 0.4402525372884802f, 0.4402955780779965f, + 0.4403386178557372f, 0.4403816566216034f, 0.4404246943754962f, 0.4404677311173167f, + 0.4405107668469659f, 0.4405538015643450f, 0.4405968352693552f, 0.4406398679618974f, + 0.4406828996418730f, 0.4407259303091827f, 0.4407689599637280f, 0.4408119886054099f, + 0.4408550162341294f, 0.4408980428497878f, 0.4409410684522861f, 0.4409840930415256f, + 0.4410271166174072f, 0.4410701391798322f, 0.4411131607287017f, 0.4411561812639168f, + 0.4411992007853787f, 0.4412422192929885f, 0.4412852367866473f, 0.4413282532662563f, + 0.4413712687317167f, 0.4414142831829296f, 0.4414572966197962f, 0.4415003090422175f, + 0.4415433204500949f, 0.4415863308433293f, 0.4416293402218222f, 0.4416723485854744f, + 0.4417153559341873f, 0.4417583622678621f, 0.4418013675863998f, 0.4418443718897017f, + 0.4418873751776689f, 0.4419303774502025f, 0.4419733787072040f, 0.4420163789485743f, + 0.4420593781742148f, 0.4421023763840264f, 0.4421453735779105f, 0.4421883697557684f, + 0.4422313649175010f, 0.4422743590630097f, 0.4423173521921956f, 0.4423603443049600f, + 0.4424033354012041f, 0.4424463254808290f, 0.4424893145437360f, 0.4425323025898263f, + 0.4425752896190012f, 0.4426182756311617f, 0.4426612606262093f, 0.4427042446040449f, + 0.4427472275645700f, 0.4427902095076858f, 0.4428331904332933f, 0.4428761703412940f, + 0.4429191492315890f, 0.4429621271040795f, 0.4430051039586668f, 0.4430480797952522f, + 0.4430910546137369f, 0.4431340284140221f, 0.4431770011960091f, 0.4432199729595991f, + 0.4432629437046933f, 0.4433059134311932f, 0.4433488821389998f, 0.4433918498280144f, + 0.4434348164981385f, 0.4434777821492730f, 0.4435207467813195f, 0.4435637103941791f, + 0.4436066729877530f, 0.4436496345619426f, 0.4436925951166492f, 0.4437355546517740f, + 0.4437785131672182f, 0.4438214706628833f, 0.4438644271386705f, 0.4439073825944810f, + 0.4439503370302162f, 0.4439932904457772f, 0.4440362428410656f, 0.4440791942159825f, + 0.4441221445704292f, 0.4441650939043071f, 0.4442080422175174f, 0.4442509895099615f, + 0.4442939357815406f, 0.4443368810321561f, 0.4443798252617093f, 0.4444227684701015f, + 0.4444657106572341f, 0.4445086518230082f, 0.4445515919673253f, 0.4445945310900868f, + 0.4446374691911938f, 0.4446804062705478f, 0.4447233423280501f, 0.4447662773636020f, + 0.4448092113771049f, 0.4448521443684600f, 0.4448950763375689f, 0.4449380072843326f, + 0.4449809372086527f, 0.4450238661104306f, 0.4450667939895674f, 0.4451097208459647f, + 0.4451526466795236f, 0.4451955714901457f, 0.4452384952777322f, 0.4452814180421846f, + 0.4453243397834042f, 0.4453672605012923f, 0.4454101801957503f, 0.4454530988666797f, + 0.4454960165139817f, 0.4455389331375578f, 0.4455818487373094f, 0.4456247633131377f, + 0.4456676768649443f, 0.4457105893926304f, 0.4457535008960976f, 0.4457964113752470f, + 0.4458393208299803f, 0.4458822292601987f, 0.4459251366658037f, 0.4459680430466967f, + 0.4460109484027789f, 0.4460538527339521f, 0.4460967560401173f, 0.4461396583211762f, + 0.4461825595770301f, 0.4462254598075803f, 0.4462683590127284f, 0.4463112571923758f, + 0.4463541543464238f, 0.4463970504747740f, 0.4464399455773276f, 0.4464828396539863f, + 0.4465257327046513f, 0.4465686247292242f, 0.4466115157276063f, 0.4466544056996991f, + 0.4466972946454041f, 0.4467401825646226f, 0.4467830694572562f, 0.4468259553232062f, + 0.4468688401623742f, 0.4469117239746616f, 0.4469546067599697f, 0.4469974885182003f, + 0.4470403692492545f, 0.4470832489530340f, 0.4471261276294401f, 0.4471690052783744f, + 0.4472118818997383f, 0.4472547574934333f, 0.4472976320593609f, 0.4473405055974225f, + 0.4473833781075196f, 0.4474262495895537f, 0.4474691200434263f, 0.4475119894690390f, + 0.4475548578662930f, 0.4475977252350899f, 0.4476405915753314f, 0.4476834568869188f, + 0.4477263211697536f, 0.4477691844237374f, 0.4478120466487716f, 0.4478549078447577f, + 0.4478977680115973f, 0.4479406271491919f, 0.4479834852574429f, 0.4480263423362519f, + 0.4480691983855204f, 0.4481120534051499f, 0.4481549073950420f, 0.4481977603550982f, + 0.4482406122852199f, 0.4482834631853088f, 0.4483263130552663f, 0.4483691618949940f, + 0.4484120097043934f, 0.4484548564833661f, 0.4484977022318136f, 0.4485405469496375f, + 0.4485833906367392f, 0.4486262332930204f, 0.4486690749183825f, 0.4487119155127272f, + 0.4487547550759560f, 0.4487975936079704f, 0.4488404311086721f, 0.4488832675779625f, + 0.4489261030157433f, 0.4489689374219160f, 0.4490117707963821f, 0.4490546031390432f, + 0.4490974344498010f, 0.4491402647285570f, 0.4491830939752128f, 0.4492259221896699f, + 0.4492687493718299f, 0.4493115755215945f, 0.4493544006388651f, 0.4493972247235435f, + 0.4494400477755311f, 0.4494828697947297f, 0.4495256907810407f, 0.4495685107343658f, + 0.4496113296546066f, 0.4496541475416647f, 0.4496969643954417f, 0.4497397802158391f, + 0.4497825950027587f, 0.4498254087561021f, 0.4498682214757707f, 0.4499110331616663f, + 0.4499538438136905f, 0.4499966534317449f, 0.4500394620157312f, 0.4500822695655509f, + 0.4501250760811057f, 0.4501678815622973f, 0.4502106860090272f, 0.4502534894211971f, + 0.4502962917987086f, 0.4503390931414635f, 0.4503818934493632f, 0.4504246927223095f, + 0.4504674909602041f, 0.4505102881629485f, 0.4505530843304445f, 0.4505958794625936f, + 0.4506386735592977f, 0.4506814666204581f, 0.4507242586459768f, 0.4507670496357553f, + 0.4508098395896953f, 0.4508526285076985f, 0.4508954163896665f, 0.4509382032355011f, + 0.4509809890451039f, 0.4510237738183765f, 0.4510665575552207f, 0.4511093402555382f, + 0.4511521219192306f, 0.4511949025461996f, 0.4512376821363470f, 0.4512804606895744f, + 0.4513232382057835f, 0.4513660146848760f, 0.4514087901267537f, 0.4514515645313181f, + 0.4514943378984711f, 0.4515371102281143f, 0.4515798815201495f, 0.4516226517744783f, + 0.4516654209910025f, 0.4517081891696238f, 0.4517509563102439f, 0.4517937224127646f, + 0.4518364874770875f, 0.4518792515031144f, 0.4519220144907471f, 0.4519647764398871f, + 0.4520075373504365f, 0.4520502972222967f, 0.4520930560553696f, 0.4521358138495569f, + 0.4521785706047604f, 0.4522213263208818f, 0.4522640809978228f, 0.4523068346354852f, + 0.4523495872337709f, 0.4523923387925814f, 0.4524350893118186f, 0.4524778387913843f, + 0.4525205872311801f, 0.4525633346311079f, 0.4526060809910695f, 0.4526488263109666f, + 0.4526915705907009f, 0.4527343138301744f, 0.4527770560292886f, 0.4528197971879455f, + 0.4528625373060468f, 0.4529052763834942f, 0.4529480144201897f, 0.4529907514160348f, + 0.4530334873709316f, 0.4530762222847817f, 0.4531189561574870f, 0.4531616889889492f, + 0.4532044207790702f, 0.4532471515277517f, 0.4532898812348956f, 0.4533326099004036f, + 0.4533753375241777f, 0.4534180641061196f, 0.4534607896461311f, 0.4535035141441139f, + 0.4535462375999701f, 0.4535889600136014f, 0.4536316813849095f, 0.4536744017137964f, + 0.4537171210001639f, 0.4537598392439137f, 0.4538025564449478f, 0.4538452726031680f, + 0.4538879877184761f, 0.4539307017907739f, 0.4539734148199633f, 0.4540161268059462f, + 0.4540588377486244f, 0.4541015476478998f, 0.4541442565036741f, 0.4541869643158493f, + 0.4542296710843273f, 0.4542723768090098f, 0.4543150814897988f, 0.4543577851265961f, + 0.4544004877193036f, 0.4544431892678232f, 0.4544858897720566f, 0.4545285892319060f, + 0.4545712876472729f, 0.4546139850180596f, 0.4546566813441675f, 0.4546993766254989f, + 0.4547420708619554f, 0.4547847640534392f, 0.4548274561998519f, 0.4548701473010955f, + 0.4549128373570719f, 0.4549555263676831f, 0.4549982143328308f, 0.4550409012524171f, + 0.4550835871263438f, 0.4551262719545128f, 0.4551689557368261f, 0.4552116384731856f, + 0.4552543201634931f, 0.4552970008076506f, 0.4553396804055601f, 0.4553823589571233f, + 0.4554250364622424f, 0.4554677129208192f, 0.4555103883327555f, 0.4555530626979535f, + 0.4555957360163150f, 0.4556384082877418f, 0.4556810795121362f, 0.4557237496893998f, + 0.4557664188194347f, 0.4558090869021428f, 0.4558517539374261f, 0.4558944199251865f, + 0.4559370848653260f, 0.4559797487577466f, 0.4560224116023501f, 0.4560650733990386f, + 0.4561077341477141f, 0.4561503938482784f, 0.4561930525006337f, 0.4562357101046817f, + 0.4562783666603247f, 0.4563210221674643f, 0.4563636766260027f, 0.4564063300358420f, + 0.4564489823968839f, 0.4564916337090306f, 0.4565342839721840f, 0.4565769331862461f, + 0.4566195813511189f, 0.4566622284667045f, 0.4567048745329047f, 0.4567475195496216f, + 0.4567901635167572f, 0.4568328064342135f, 0.4568754483018926f, 0.4569180891196964f, + 0.4569607288875270f, 0.4570033676052863f, 0.4570460052728764f, 0.4570886418901992f, + 0.4571312774571570f, 0.4571739119736515f, 0.4572165454395850f, 0.4572591778548594f, + 0.4573018092193766f, 0.4573444395330389f, 0.4573870687957483f, 0.4574296970074066f, + 0.4574723241679161f, 0.4575149502771786f, 0.4575575753350964f, 0.4576001993415715f, + 0.4576428222965058f, 0.4576854441998015f, 0.4577280650513605f, 0.4577706848510851f, + 0.4578133035988772f, 0.4578559212946389f, 0.4578985379382722f, 0.4579411535296792f, + 0.4579837680687621f, 0.4580263815554229f, 0.4580689939895636f, 0.4581116053710863f, + 0.4581542156998931f, 0.4581968249758862f, 0.4582394331989674f, 0.4582820403690391f, + 0.4583246464860032f, 0.4583672515497619f, 0.4584098555602172f, 0.4584524585172713f, + 0.4584950604208263f, 0.4585376612707842f, 0.4585802610670471f, 0.4586228598095172f, + 0.4586654574980966f, 0.4587080541326873f, 0.4587506497131916f, 0.4587932442395115f, + 0.4588358377115491f, 0.4588784301292066f, 0.4589210214923861f, 0.4589636118009897f, + 0.4590062010549196f, 0.4590487892540778f, 0.4590913763983666f, 0.4591339624876880f, + 0.4591765475219441f, 0.4592191315010373f, 0.4592617144248694f, 0.4593042962933429f, + 0.4593468771063596f, 0.4593894568638219f, 0.4594320355656319f, 0.4594746132116917f, + 0.4595171898019035f, 0.4595597653361694f, 0.4596023398143917f, 0.4596449132364725f, + 0.4596874856023139f, 0.4597300569118182f, 0.4597726271648874f, 0.4598151963614238f, + 0.4598577645013295f, 0.4599003315845068f, 0.4599428976108578f, 0.4599854625802847f, + 0.4600280264926897f, 0.4600705893479749f, 0.4601131511460426f, 0.4601557118867950f, + 0.4601982715701343f, 0.4602408301959627f, 0.4602833877641822f, 0.4603259442746953f, + 0.4603684997274040f, 0.4604110541222107f, 0.4604536074590174f, 0.4604961597377265f, + 0.4605387109582400f, 0.4605812611204604f, 0.4606238102242897f, 0.4606663582696302f, + 0.4607089052563841f, 0.4607514511844537f, 0.4607939960537412f, 0.4608365398641487f, + 0.4608790826155787f, 0.4609216243079333f, 0.4609641649411146f, 0.4610067045150251f, + 0.4610492430295669f, 0.4610917804846423f, 0.4611343168801535f, 0.4611768522160028f, + 0.4612193864920924f, 0.4612619197083246f, 0.4613044518646017f, 0.4613469829608259f, + 0.4613895129968995f, 0.4614320419727247f, 0.4614745698882038f, 0.4615170967432393f, + 0.4615596225377331f, 0.4616021472715877f, 0.4616446709447053f, 0.4616871935569882f, + 0.4617297151083388f, 0.4617722355986592f, 0.4618147550278519f, 0.4618572733958189f, + 0.4618997907024628f, 0.4619423069476857f, 0.4619848221313899f, 0.4620273362534779f, + 0.4620698493138518f, 0.4621123613124140f, 0.4621548722490668f, 0.4621973821237124f, + 0.4622398909362533f, 0.4622823986865918f, 0.4623249053746301f, 0.4623674110002705f, + 0.4624099155634154f, 0.4624524190639672f, 0.4624949215018281f, 0.4625374228769006f, + 0.4625799231890868f, 0.4626224224382892f, 0.4626649206244101f, 0.4627074177473518f, + 0.4627499138070167f, 0.4627924088033071f, 0.4628349027361255f, 0.4628773956053740f, + 0.4629198874109551f, 0.4629623781527712f, 0.4630048678307245f, 0.4630473564447176f, + 0.4630898439946525f, 0.4631323304804320f, 0.4631748159019581f, 0.4632173002591334f, + 0.4632597835518602f, 0.4633022657800409f, 0.4633447469435777f, 0.4633872270423733f, + 0.4634297060763298f, 0.4634721840453498f, 0.4635146609493356f, 0.4635571367881895f, + 0.4635996115618140f, 0.4636420852701115f, 0.4636845579129843f, 0.4637270294903349f, + 0.4637695000020657f, 0.4638119694480790f, 0.4638544378282773f, 0.4638969051425630f, + 0.4639393713908385f, 0.4639818365730063f, 0.4640243006889686f, 0.4640667637386280f, + 0.4641092257218870f, 0.4641516866386477f, 0.4641941464888129f, 0.4642366052722847f, + 0.4642790629889658f, 0.4643215196387585f, 0.4643639752215652f, 0.4644064297372885f, + 0.4644488831858307f, 0.4644913355670943f, 0.4645337868809817f, 0.4645762371273954f, + 0.4646186863062378f, 0.4646611344174114f, 0.4647035814608187f, 0.4647460274363621f, + 0.4647884723439440f, 0.4648309161834670f, 0.4648733589548334f, 0.4649158006579459f, + 0.4649582412927067f, 0.4650006808590185f, 0.4650431193567836f, 0.4650855567859046f, + 0.4651279931462840f, 0.4651704284378242f, 0.4652128626604277f, 0.4652552958139970f, + 0.4652977278984346f, 0.4653401589136430f, 0.4653825888595247f, 0.4654250177359820f, + 0.4654674455429178f, 0.4655098722802343f, 0.4655522979478341f, 0.4655947225456197f, + 0.4656371460734937f, 0.4656795685313584f, 0.4657219899191165f, 0.4657644102366704f, + 0.4658068294839227f, 0.4658492476607759f, 0.4658916647671325f, 0.4659340808028951f, + 0.4659764957679662f, 0.4660189096622482f, 0.4660613224856439f, 0.4661037342380556f, + 0.4661461449193859f, 0.4661885545295374f, 0.4662309630684127f, 0.4662733705359142f, + 0.4663157769319444f, 0.4663581822564061f, 0.4664005865092017f, 0.4664429896902337f, + 0.4664853917994049f, 0.4665277928366175f, 0.4665701928017745f, 0.4666125916947780f, + 0.4666549895155309f, 0.4666973862639357f, 0.4667397819398949f, 0.4667821765433112f, + 0.4668245700740870f, 0.4668669625321250f, 0.4669093539173278f, 0.4669517442295980f, + 0.4669941334688381f, 0.4670365216349507f, 0.4670789087278384f, 0.4671212947474039f, + 0.4671636796935498f, 0.4672060635661786f, 0.4672484463651928f, 0.4672908280904953f, + 0.4673332087419884f, 0.4673755883195750f, 0.4674179668231575f, 0.4674603442526386f, + 0.4675027206079209f, 0.4675450958889071f, 0.4675874700954997f, 0.4676298432276014f, + 0.4676722152851148f, 0.4677145862679425f, 0.4677569561759872f, 0.4677993250091516f, + 0.4678416927673382f, 0.4678840594504496f, 0.4679264250583886f, 0.4679687895910578f, + 0.4680111530483598f, 0.4680535154301974f, 0.4680958767364730f, 0.4681382369670894f, + 0.4681805961219493f, 0.4682229542009553f, 0.4682653112040100f, 0.4683076671310162f, + 0.4683500219818765f, 0.4683923757564936f, 0.4684347284547702f, 0.4684770800766088f, + 0.4685194306219123f, 0.4685617800905833f, 0.4686041284825244f, 0.4686464757976384f, + 0.4686888220358279f, 0.4687311671969956f, 0.4687735112810444f, 0.4688158542878767f, + 0.4688581962173954f, 0.4689005370695030f, 0.4689428768441024f, 0.4689852155410962f, + 0.4690275531603871f, 0.4690698897018780f, 0.4691122251654713f, 0.4691545595510700f, + 0.4691968928585766f, 0.4692392250878940f, 0.4692815562389248f, 0.4693238863115717f, + 0.4693662153057375f, 0.4694085432213250f, 0.4694508700582368f, 0.4694931958163757f, + 0.4695355204956445f, 0.4695778440959458f, 0.4696201666171824f, 0.4696624880592570f, + 0.4697048084220725f, 0.4697471277055315f, 0.4697894459095369f, 0.4698317630339912f, + 0.4698740790787974f, 0.4699163940438582f, 0.4699587079290763f, 0.4700010207343545f, + 0.4700433324595956f, 0.4700856431047024f, 0.4701279526695775f, 0.4701702611541239f, + 0.4702125685582442f, 0.4702548748818412f, 0.4702971801248178f, 0.4703394842870767f, + 0.4703817873685207f, 0.4704240893690526f, 0.4704663902885751f, 0.4705086901269912f, + 0.4705509888842035f, 0.4705932865601149f, 0.4706355831546282f, 0.4706778786676462f, + 0.4707201730990717f, 0.4707624664488074f, 0.4708047587167562f, 0.4708470499028210f, + 0.4708893400069045f, 0.4709316290289097f, 0.4709739169687391f, 0.4710162038262958f, + 0.4710584896014825f, 0.4711007742942021f, 0.4711430579043574f, 0.4711853404318512f, + 0.4712276218765864f, 0.4712699022384658f, 0.4713121815173922f, 0.4713544597132686f, + 0.4713967368259976f, 0.4714390128554823f, 0.4714812878016254f, 0.4715235616643298f, + 0.4715658344434984f, 0.4716081061390340f, 0.4716503767508395f, 0.4716926462788176f, + 0.4717349147228714f, 0.4717771820829038f, 0.4718194483588174f, 0.4718617135505153f, + 0.4719039776579002f, 0.4719462406808752f, 0.4719885026193429f, 0.4720307634732064f, + 0.4720730232423687f, 0.4721152819267324f, 0.4721575395262005f, 0.4721997960406759f, + 0.4722420514700615f, 0.4722843058142602f, 0.4723265590731749f, 0.4723688112467087f, + 0.4724110623347640f, 0.4724533123372442f, 0.4724955612540521f, 0.4725378090850905f, + 0.4725800558302623f, 0.4726223014894705f, 0.4726645460626180f, 0.4727067895496079f, + 0.4727490319503428f, 0.4727912732647258f, 0.4728335134926598f, 0.4728757526340479f, + 0.4729179906887928f, 0.4729602276567975f, 0.4730024635379650f, 0.4730446983321982f, + 0.4730869320394001f, 0.4731291646594736f, 0.4731713961923216f, 0.4732136266378473f, + 0.4732558559959533f, 0.4732980842665429f, 0.4733403114495187f, 0.4733825375447839f, + 0.4734247625522415f, 0.4734669864717944f, 0.4735092093033456f, 0.4735514310467980f, + 0.4735936517020545f, 0.4736358712690184f, 0.4736780897475923f, 0.4737203071376795f, + 0.4737625234391828f, 0.4738047386520053f, 0.4738469527760499f, 0.4738891658112196f, + 0.4739313777574174f, 0.4739735886145464f, 0.4740157983825095f, 0.4740580070612097f, + 0.4741002146505500f, 0.4741424211504335f, 0.4741846265607632f, 0.4742268308814420f, + 0.4742690341123730f, 0.4743112362534592f, 0.4743534373046036f, 0.4743956372657093f, + 0.4744378361366793f, 0.4744800339174166f, 0.4745222306078242f, 0.4745644262078051f, + 0.4746066207172626f, 0.4746488141360994f, 0.4746910064642187f, 0.4747331977015237f, + 0.4747753878479171f, 0.4748175769033022f, 0.4748597648675820f, 0.4749019517406595f, + 0.4749441375224379f, 0.4749863222128201f, 0.4750285058117091f, 0.4750706883190082f, + 0.4751128697346203f, 0.4751550500584486f, 0.4751972292903960f, 0.4752394074303656f, + 0.4752815844782607f, 0.4753237604339842f, 0.4753659352974391f, 0.4754081090685287f, + 0.4754502817471559f, 0.4754924533332239f, 0.4755346238266357f, 0.4755767932272945f, + 0.4756189615351033f, 0.4756611287499653f, 0.4757032948717835f, 0.4757454599004611f, + 0.4757876238359011f, 0.4758297866780067f, 0.4758719484266810f, 0.4759141090818271f, + 0.4759562686433481f, 0.4759984271111471f, 0.4760405844851273f, 0.4760827407651917f, + 0.4761248959512436f, 0.4761670500431860f, 0.4762092030409221f, 0.4762513549443549f, + 0.4762935057533877f, 0.4763356554679236f, 0.4763778040878657f, 0.4764199516131172f, + 0.4764620980435812f, 0.4765042433791609f, 0.4765463876197593f, 0.4765885307652798f, + 0.4766306728156253f, 0.4766728137706992f, 0.4767149536304045f, 0.4767570923946444f, + 0.4767992300633221f, 0.4768413666363408f, 0.4768835021136035f, 0.4769256364950136f, + 0.4769677697804742f, 0.4770099019698884f, 0.4770520330631595f, 0.4770941630601905f, + 0.4771362919608848f, 0.4771784197651455f, 0.4772205464728758f, 0.4772626720839789f, + 0.4773047965983579f, 0.4773469200159162f, 0.4773890423365568f, 0.4774311635601831f, + 0.4774732836866981f, 0.4775154027160051f, 0.4775575206480074f, 0.4775996374826081f, + 0.4776417532197105f, 0.4776838678592177f, 0.4777259814010331f, 0.4777680938450597f, + 0.4778102051912010f, 0.4778523154393600f, 0.4778944245894400f, 0.4779365326413444f, + 0.4779786395949762f, 0.4780207454502386f, 0.4780628502070352f, 0.4781049538652689f, + 0.4781470564248431f, 0.4781891578856610f, 0.4782312582476258f, 0.4782733575106409f, + 0.4783154556746095f, 0.4783575527394349f, 0.4783996487050202f, 0.4784417435712688f, + 0.4784838373380840f, 0.4785259300053690f, 0.4785680215730270f, 0.4786101120409614f, + 0.4786522014090756f, 0.4786942896772726f, 0.4787363768454557f, 0.4787784629135284f, + 0.4788205478813939f, 0.4788626317489555f, 0.4789047145161164f, 0.4789467961827800f, + 0.4789888767488495f, 0.4790309562142283f, 0.4790730345788197f, 0.4791151118425269f, + 0.4791571880052533f, 0.4791992630669022f, 0.4792413370273769f, 0.4792834098865808f, + 0.4793254816444171f, 0.4793675523007891f, 0.4794096218556002f, 0.4794516903087538f, + 0.4794937576601530f, 0.4795358239097013f, 0.4795778890573021f, 0.4796199531028585f, + 0.4796620160462742f, 0.4797040778874522f, 0.4797461386262960f, 0.4797881982627088f, + 0.4798302567965942f, 0.4798723142278554f, 0.4799143705563956f, 0.4799564257821185f, + 0.4799984799049273f, 0.4800405329247253f, 0.4800825848414159f, 0.4801246356549024f, + 0.4801666853650884f, 0.4802087339718770f, 0.4802507814751718f, 0.4802928278748760f, + 0.4803348731708930f, 0.4803769173631263f, 0.4804189604514793f, 0.4804610024358553f, + 0.4805030433161575f, 0.4805450830922897f, 0.4805871217641550f, 0.4806291593316568f, + 0.4806711957946986f, 0.4807132311531839f, 0.4807552654070160f, 0.4807972985560981f, + 0.4808393306003340f, 0.4808813615396269f, 0.4809233913738800f, 0.4809654201029972f, + 0.4810074477268816f, 0.4810494742454366f, 0.4810914996585658f, 0.4811335239661726f, + 0.4811755471681604f, 0.4812175692644325f, 0.4812595902548925f, 0.4813016101394438f, + 0.4813436289179897f, 0.4813856465904339f, 0.4814276631566797f, 0.4814696786166305f, + 0.4815116929701899f, 0.4815537062172612f, 0.4815957183577480f, 0.4816377293915535f, + 0.4816797393185815f, 0.4817217481387353f, 0.4817637558519183f, 0.4818057624580340f, + 0.4818477679569860f, 0.4818897723486777f, 0.4819317756330125f, 0.4819737778098940f, + 0.4820157788792256f, 0.4820577788409107f, 0.4820997776948530f, 0.4821417754409559f, + 0.4821837720791227f, 0.4822257676092572f, 0.4822677620312628f, 0.4823097553450429f, + 0.4823517475505010f, 0.4823937386475407f, 0.4824357286360655f, 0.4824777175159788f, + 0.4825197052871844f, 0.4825616919495854f, 0.4826036775030857f, 0.4826456619475885f, + 0.4826876452829975f, 0.4827296275092162f, 0.4827716086261480f, 0.4828135886336967f, + 0.4828555675317657f, 0.4828975453202584f, 0.4829395219990785f, 0.4829814975681295f, + 0.4830234720273150f, 0.4830654453765383f, 0.4831074176157032f, 0.4831493887447133f, + 0.4831913587634719f, 0.4832333276718827f, 0.4832752954698493f, 0.4833172621572751f, + 0.4833592277340638f, 0.4834011922001190f, 0.4834431555553442f, 0.4834851177996428f, + 0.4835270789329187f, 0.4835690389550753f, 0.4836109978660161f, 0.4836529556656449f, + 0.4836949123538651f, 0.4837368679305804f, 0.4837788223956942f, 0.4838207757491103f, + 0.4838627279907323f, 0.4839046791204635f, 0.4839466291382079f, 0.4839885780438689f, + 0.4840305258373500f, 0.4840724725185550f, 0.4841144180873875f, 0.4841563625437509f, + 0.4841983058875490f, 0.4842402481186854f, 0.4842821892370637f, 0.4843241292425875f, + 0.4843660681351604f, 0.4844080059146862f, 0.4844499425810683f, 0.4844918781342104f, + 0.4845338125740162f, 0.4845757459003893f, 0.4846176781132332f, 0.4846596092124518f, + 0.4847015391979487f, 0.4847434680696273f, 0.4847853958273915f, 0.4848273224711449f, + 0.4848692480007911f, 0.4849111724162338f, 0.4849530957173766f, 0.4849950179041232f, + 0.4850369389763773f, 0.4850788589340426f, 0.4851207777770227f, 0.4851626955052212f, + 0.4852046121185418f, 0.4852465276168884f, 0.4852884420001645f, 0.4853303552682736f, + 0.4853722674211198f, 0.4854141784586065f, 0.4854560883806374f, 0.4854979971871163f, + 0.4855399048779470f, 0.4855818114530329f, 0.4856237169122778f, 0.4856656212555855f, + 0.4857075244828598f, 0.4857494265940041f, 0.4857913275889223f, 0.4858332274675182f, + 0.4858751262296953f, 0.4859170238753575f, 0.4859589204044084f, 0.4860008158167518f, + 0.4860427101122913f, 0.4860846032909309f, 0.4861264953525741f, 0.4861683862971247f, + 0.4862102761244864f, 0.4862521648345630f, 0.4862940524272583f, 0.4863359389024758f, + 0.4863778242601194f, 0.4864197085000930f, 0.4864615916223001f, 0.4865034736266446f, + 0.4865453545130303f, 0.4865872342813607f, 0.4866291129315399f, 0.4866709904634715f, + 0.4867128668770593f, 0.4867547421722069f, 0.4867966163488183f, 0.4868384894067972f, + 0.4868803613460473f, 0.4869222321664726f, 0.4869641018679767f, 0.4870059704504634f, + 0.4870478379138364f, 0.4870897042579997f, 0.4871315694828570f, 0.4871734335883121f, + 0.4872152965742688f, 0.4872571584406308f, 0.4872990191873020f, 0.4873408788141863f, + 0.4873827373211874f, 0.4874245947082091f, 0.4874664509751551f, 0.4875083061219295f, + 0.4875501601484360f, 0.4875920130545782f, 0.4876338648402603f, 0.4876757155053859f, + 0.4877175650498588f, 0.4877594134735830f, 0.4878012607764622f, 0.4878431069584003f, + 0.4878849520193010f, 0.4879267959590684f, 0.4879686387776062f, 0.4880104804748182f, + 0.4880523210506083f, 0.4880941605048804f, 0.4881359988375382f, 0.4881778360484857f, + 0.4882196721376268f, 0.4882615071048653f, 0.4883033409501049f, 0.4883451736732497f, + 0.4883870052742035f, 0.4884288357528702f, 0.4884706651091536f, 0.4885124933429577f, + 0.4885543204541862f, 0.4885961464427431f, 0.4886379713085323f, 0.4886797950514578f, + 0.4887216176714231f, 0.4887634391683324f, 0.4888052595420897f, 0.4888470787925986f, + 0.4888888969197632f, 0.4889307139234873f, 0.4889725298036749f, 0.4890143445602298f, + 0.4890561581930560f, 0.4890979707020575f, 0.4891397820871379f, 0.4891815923482015f, + 0.4892234014851520f, 0.4892652094978934f, 0.4893070163863295f, 0.4893488221503643f, + 0.4893906267899019f, 0.4894324303048460f, 0.4894742326951007f, 0.4895160339605699f, + 0.4895578341011574f, 0.4895996331167674f, 0.4896414310073037f, 0.4896832277726702f, + 0.4897250234127709f, 0.4897668179275098f, 0.4898086113167909f, 0.4898504035805180f, + 0.4898921947185952f, 0.4899339847309264f, 0.4899757736174156f, 0.4900175613779667f, + 0.4900593480124839f, 0.4901011335208709f, 0.4901429179030317f, 0.4901847011588705f, + 0.4902264832882912f, 0.4902682642911976f, 0.4903100441674939f, 0.4903518229170841f, + 0.4903936005398721f, 0.4904353770357618f, 0.4904771524046574f, 0.4905189266464628f, + 0.4905606997610820f, 0.4906024717484191f, 0.4906442426083780f, 0.4906860123408628f, + 0.4907277809457774f, 0.4907695484230259f, 0.4908113147725124f, 0.4908530799941407f, + 0.4908948440878151f, 0.4909366070534394f, 0.4909783688909177f, 0.4910201296001542f, + 0.4910618891810526f, 0.4911036476335173f, 0.4911454049574520f, 0.4911871611527610f, + 0.4912289162193483f, 0.4912706701571178f, 0.4913124229659737f, 0.4913541746458200f, + 0.4913959251965608f, 0.4914376746181001f, 0.4914794229103421f, 0.4915211700731907f, + 0.4915629161065499f, 0.4916046610103240f, 0.4916464047844170f, 0.4916881474287328f, + 0.4917298889431758f, 0.4917716293276498f, 0.4918133685820590f, 0.4918551067063074f, + 0.4918968437002993f, 0.4919385795639386f, 0.4919803142971294f, 0.4920220478997758f, + 0.4920637803717820f, 0.4921055117130519f, 0.4921472419234899f, 0.4921889710029999f, + 0.4922306989514861f, 0.4922724257688524f, 0.4923141514550032f, 0.4923558760098425f, + 0.4923975994332744f, 0.4924393217252030f, 0.4924810428855326f, 0.4925227629141671f, + 0.4925644818110106f, 0.4926061995759675f, 0.4926479162089417f, 0.4926896317098374f, + 0.4927313460785588f, 0.4927730593150101f, 0.4928147714190952f, 0.4928564823907185f, + 0.4928981922297840f, 0.4929399009361960f, 0.4929816085098584f, 0.4930233149506756f, + 0.4930650202585517f, 0.4931067244333907f, 0.4931484274750971f, 0.4931901293835748f, + 0.4932318301587279f, 0.4932735298004609f, 0.4933152283086777f, 0.4933569256832827f, + 0.4933986219241798f, 0.4934403170312734f, 0.4934820110044677f, 0.4935237038436667f, + 0.4935653955487748f, 0.4936070861196961f, 0.4936487755563347f, 0.4936904638585949f, + 0.4937321510263810f, 0.4937738370595971f, 0.4938155219581473f, 0.4938572057219361f, + 0.4938988883508675f, 0.4939405698448456f, 0.4939822502037750f, 0.4940239294275595f, + 0.4940656075161037f, 0.4941072844693114f, 0.4941489602870873f, 0.4941906349693353f, + 0.4942323085159597f, 0.4942739809268648f, 0.4943156522019549f, 0.4943573223411341f, + 0.4943989913443066f, 0.4944406592113769f, 0.4944823259422491f, 0.4945239915368272f, + 0.4945656559950160f, 0.4946073193167193f, 0.4946489815018415f, 0.4946906425502869f, + 0.4947323024619599f, 0.4947739612367645f, 0.4948156188746050f, 0.4948572753753858f, + 0.4948989307390113f, 0.4949405849653853f, 0.4949822380544127f, 0.4950238900059973f, + 0.4950655408200436f, 0.4951071904964559f, 0.4951488390351383f, 0.4951904864359954f, + 0.4952321326989312f, 0.4952737778238502f, 0.4953154218106567f, 0.4953570646592548f, + 0.4953987063695490f, 0.4954403469414436f, 0.4954819863748429f, 0.4955236246696510f, + 0.4955652618257725f, 0.4956068978431117f, 0.4956485327215727f, 0.4956901664610600f, + 0.4957317990614780f, 0.4957734305227308f, 0.4958150608447229f, 0.4958566900273586f, + 0.4958983180705423f, 0.4959399449741781f, 0.4959815707381707f, 0.4960231953624242f, + 0.4960648188468429f, 0.4961064411913313f, 0.4961480623957938f, 0.4961896824601347f, + 0.4962313013842582f, 0.4962729191680689f, 0.4963145358114711f, 0.4963561513143690f, + 0.4963977656766672f, 0.4964393788982699f, 0.4964809909790815f, 0.4965226019190065f, + 0.4965642117179493f, 0.4966058203758141f, 0.4966474278925053f, 0.4966890342679274f, + 0.4967306395019848f, 0.4967722435945817f, 0.4968138465456228f, 0.4968554483550123f, + 0.4968970490226545f, 0.4969386485484540f, 0.4969802469323153f, 0.4970218441741426f, + 0.4970634402738403f, 0.4971050352313129f, 0.4971466290464648f, 0.4971882217192004f, + 0.4972298132494242f, 0.4972714036370406f, 0.4973129928819540f, 0.4973545809840687f, + 0.4973961679432893f, 0.4974377537595203f, 0.4974793384326658f, 0.4975209219626307f, + 0.4975625043493191f, 0.4976040855926356f, 0.4976456656924846f, 0.4976872446487706f, + 0.4977288224613980f, 0.4977703991302713f, 0.4978119746552949f, 0.4978535490363733f, + 0.4978951222734109f, 0.4979366943663123f, 0.4979782653149818f, 0.4980198351193241f, + 0.4980614037792434f, 0.4981029712946444f, 0.4981445376654315f, 0.4981861028915091f, + 0.4982276669727819f, 0.4982692299091541f, 0.4983107917005304f, 0.4983523523468153f, + 0.4983939118479132f, 0.4984354702037287f, 0.4984770274141661f, 0.4985185834791301f, + 0.4985601383985251f, 0.4986016921722557f, 0.4986432448002264f, 0.4986847962823416f, + 0.4987263466185059f, 0.4987678958086239f, 0.4988094438526000f, 0.4988509907503387f, + 0.4988925365017446f, 0.4989340811067223f, 0.4989756245651762f, 0.4990171668770108f, + 0.4990587080421309f, 0.4991002480604408f, 0.4991417869318451f, 0.4991833246562483f, + 0.4992248612335551f, 0.4992663966636699f, 0.4993079309464972f, 0.4993494640819419f, + 0.4993909960699082f, 0.4994325269103007f, 0.4994740566030242f, 0.4995155851479831f, + 0.4995571125450819f, 0.4995986387942252f, 0.4996401638953178f, 0.4996816878482641f, + 0.4997232106529685f, 0.4997647323093360f, 0.4998062528172709f, 0.4998477721766779f, + 0.4998892903874613f, 0.4999308074495262f, 0.4999723233627768f, 0.5000138381271177f, + 0.5000553517424539f, 0.5000968642086896f, 0.5001383755257295f, 0.5001798856934784f, + 0.5002213947118407f, 0.5002629025807210f, 0.5003044093000240f, 0.5003459148696543f, + 0.5003874192895166f, 0.5004289225595153f, 0.5004704246795554f, 0.5005119256495413f, + 0.5005534254693774f, 0.5005949241389689f, 0.5006364216582200f, 0.5006779180270354f, + 0.5007194132453199f, 0.5007609073129780f, 0.5008024002299144f, 0.5008438919960337f, + 0.5008853826112407f, 0.5009268720754401f, 0.5009683603885362f, 0.5010098475504340f, + 0.5010513335610380f, 0.5010928184202530f, 0.5011343021279834f, 0.5011757846841343f, + 0.5012172660886099f, 0.5012587463413153f, 0.5013002254421549f, 0.5013417033910336f, + 0.5013831801878559f, 0.5014246558325264f, 0.5014661303249501f, 0.5015076036650316f, + 0.5015490758526754f, 0.5015905468877864f, 0.5016320167702693f, 0.5016734855000285f, + 0.5017149530769691f, 0.5017564195009957f, 0.5017978847720130f, 0.5018393488899255f, + 0.5018808118546383f, 0.5019222736660559f, 0.5019637343240829f, 0.5020051938286243f, + 0.5020466521795847f, 0.5020881093768688f, 0.5021295654203813f, 0.5021710203100271f, + 0.5022124740457108f, 0.5022539266273371f, 0.5022953780548109f, 0.5023368283280369f, + 0.5023782774469199f, 0.5024197254113644f, 0.5024611722212754f, 0.5025026178765576f, + 0.5025440623771157f, 0.5025855057228545f, 0.5026269479136789f, 0.5026683889494934f, + 0.5027098288302030f, 0.5027512675557124f, 0.5027927051259263f, 0.5028341415407496f, + 0.5028755768000870f, 0.5029170109038432f, 0.5029584438519231f, 0.5029998756442317f, + 0.5030413062806735f, 0.5030827357611531f, 0.5031241640855758f, 0.5031655912538462f, + 0.5032070172658690f, 0.5032484421215491f, 0.5032898658207913f, 0.5033312883635004f, + 0.5033727097495810f, 0.5034141299789383f, 0.5034555490514770f, 0.5034969669671018f, + 0.5035383837257176f, 0.5035797993272292f, 0.5036212137715413f, 0.5036626270585590f, + 0.5037040391881871f, 0.5037454501603302f, 0.5037868599748933f, 0.5038282686317813f, + 0.5038696761308989f, 0.5039110824721511f, 0.5039524876554425f, 0.5039938916806783f, + 0.5040352945477632f, 0.5040766962566019f, 0.5041180968070994f, 0.5041594961991607f, + 0.5042008944326904f, 0.5042422915075936f, 0.5042836874237749f, 0.5043250821811396f, + 0.5043664757795920f, 0.5044078682190376f, 0.5044492594993809f, 0.5044906496205267f, + 0.5045320385823803f, 0.5045734263848461f, 0.5046148130278295f, 0.5046561985112349f, + 0.5046975828349676f, 0.5047389659989323f, 0.5047803480030338f, 0.5048217288471774f, + 0.5048631085312676f, 0.5049044870552094f, 0.5049458644189079f, 0.5049872406222679f, + 0.5050286156651942f, 0.5050699895475919f, 0.5051113622693658f, 0.5051527338304210f, + 0.5051941042306622f, 0.5052354734699946f, 0.5052768415483230f, 0.5053182084655522f, + 0.5053595742215873f, 0.5054009388163333f, 0.5054423022496950f, 0.5054836645215773f, + 0.5055250256318854f, 0.5055663855805241f, 0.5056077443673983f, 0.5056491019924131f, + 0.5056904584554734f, 0.5057318137564842f, 0.5057731678953503f, 0.5058145208719769f, + 0.5058558726862689f, 0.5058972233381310f, 0.5059385728274687f, 0.5059799211541867f, + 0.5060212683181898f, 0.5060626143193833f, 0.5061039591576720f, 0.5061453028329611f, + 0.5061866453451552f, 0.5062279866941598f, 0.5062693268798796f, 0.5063106659022195f, + 0.5063520037610848f, 0.5063933404563803f, 0.5064346759880112f, 0.5064760103558822f, + 0.5065173435598985f, 0.5065586755999653f, 0.5066000064759872f, 0.5066413361878697f, + 0.5066826647355176f, 0.5067239921188357f, 0.5067653183377294f, 0.5068066433921036f, + 0.5068479672818633f, 0.5068892900069135f, 0.5069306115671595f, 0.5069719319625060f, + 0.5070132511928582f, 0.5070545692581212f, 0.5070958861582000f, 0.5071372018929997f, + 0.5071785164624252f, 0.5072198298663818f, 0.5072611421047744f, 0.5073024531775080f, + 0.5073437630844879f, 0.5073850718256191f, 0.5074263794008066f, 0.5074676858099555f, + 0.5075089910529709f, 0.5075502951297578f, 0.5075915980402214f, 0.5076328997842667f, + 0.5076742003617989f, 0.5077154997727229f, 0.5077567980169441f, 0.5077980950943674f, + 0.5078393910048978f, 0.5078806857484406f, 0.5079219793249008f, 0.5079632717341837f, + 0.5080045629761940f, 0.5080458530508372f, 0.5080871419580183f, 0.5081284296976424f, + 0.5081697162696146f, 0.5082110016738401f, 0.5082522859102240f, 0.5082935689786714f, + 0.5083348508790874f, 0.5083761316113773f, 0.5084174111754459f, 0.5084586895711988f, + 0.5084999667985409f, 0.5085412428573772f, 0.5085825177476131f, 0.5086237914691537f, + 0.5086650640219041f, 0.5087063354057695f, 0.5087476056206550f, 0.5087888746664658f, + 0.5088301425431070f, 0.5088714092504839f, 0.5089126747885017f, 0.5089539391570653f, + 0.5089952023560801f, 0.5090364643854514f, 0.5090777252450840f, 0.5091189849348834f, + 0.5091602434547546f, 0.5092015008046030f, 0.5092427569843336f, 0.5092840119938518f, + 0.5093252658330625f, 0.5093665185018712f, 0.5094077700001828f, 0.5094490203279028f, + 0.5094902694849364f, 0.5095315174711884f, 0.5095727642865645f, 0.5096140099309697f, + 0.5096552544043094f, 0.5096964977064884f, 0.5097377398374123f, 0.5097789807969864f, + 0.5098202205851154f, 0.5098614592017051f, 0.5099026966466605f, 0.5099439329198869f, + 0.5099851680212895f, 0.5100264019507735f, 0.5100676347082443f, 0.5101088662936069f, + 0.5101500967067668f, 0.5101913259476291f, 0.5102325540160990f, 0.5102737809120821f, + 0.5103150066354832f, 0.5103562311862079f, 0.5103974545641614f, 0.5104386767692489f, + 0.5104798978013758f, 0.5105211176604472f, 0.5105623363463684f, 0.5106035538590449f, + 0.5106447701983816f, 0.5106859853642842f, 0.5107271993566578f, 0.5107684121754077f, + 0.5108096238204390f, 0.5108508342916575f, 0.5108920435889680f, 0.5109332517122760f, + 0.5109744586614868f, 0.5110156644365058f, 0.5110568690372381f, 0.5110980724635892f, + 0.5111392747154644f, 0.5111804757927689f, 0.5112216756954081f, 0.5112628744232873f, + 0.5113040719763120f, 0.5113452683543872f, 0.5113864635574185f, 0.5114276575853111f, + 0.5114688504379704f, 0.5115100421153017f, 0.5115512326172105f, 0.5115924219436019f, + 0.5116336100943812f, 0.5116747970694542f, 0.5117159828687259f, 0.5117571674921015f, + 0.5117983509394869f, 0.5118395332107870f, 0.5118807143059074f, 0.5119218942247532f, + 0.5119630729672302f, 0.5120042505332434f, 0.5120454269226983f, 0.5120866021355003f, + 0.5121277761715547f, 0.5121689490307669f, 0.5122101207130425f, 0.5122512912182867f, + 0.5122924605464050f, 0.5123336286973025f, 0.5123747956708850f, 0.5124159614670576f, + 0.5124571260857257f, 0.5124982895267950f, 0.5125394517901707f, 0.5125806128757583f, + 0.5126217727834630f, 0.5126629315131904f, 0.5127040890648460f, 0.5127452454383350f, + 0.5127864006335630f, 0.5128275546504354f, 0.5128687074888575f, 0.5129098591487349f, + 0.5129510096299730f, 0.5129921589324771f, 0.5130333070561527f, 0.5130744540009055f, + 0.5131155997666406f, 0.5131567443532634f, 0.5131978877606799f, 0.5132390299887950f, + 0.5132801710375143f, 0.5133213109067434f, 0.5133624495963877f, 0.5134035871063525f, + 0.5134447234365435f, 0.5134858585868660f, 0.5135269925572257f, 0.5135681253475277f, + 0.5136092569576778f, 0.5136503873875815f, 0.5136915166371441f, 0.5137326447062710f, + 0.5137737715948680f, 0.5138148973028405f, 0.5138560218300938f, 0.5138971451765336f, + 0.5139382673420654f, 0.5139793883265945f, 0.5140205081300266f, 0.5140616267522672f, + 0.5141027441932218f, 0.5141438604527957f, 0.5141849755308947f, 0.5142260894274242f, + 0.5142672021422897f, 0.5143083136753969f, 0.5143494240266511f, 0.5143905331959580f, + 0.5144316411832228f, 0.5144727479883515f, 0.5145138536112495f, 0.5145549580518221f, + 0.5145960613099750f, 0.5146371633856139f, 0.5146782642786442f, 0.5147193639889713f, + 0.5147604625165012f, 0.5148015598611390f, 0.5148426560227903f, 0.5148837510013611f, + 0.5149248447967565f, 0.5149659374088822f, 0.5150070288376439f, 0.5150481190829470f, + 0.5150892081446973f, 0.5151302960228000f, 0.5151713827171611f, 0.5152124682276860f, + 0.5152535525542802f, 0.5152946356968494f, 0.5153357176552993f, 0.5153767984295352f, + 0.5154178780194629f, 0.5154589564249881f, 0.5155000336460163f, 0.5155411096824528f, + 0.5155821845342038f, 0.5156232582011745f, 0.5156643306832704f, 0.5157054019803976f, + 0.5157464720924614f, 0.5157875410193674f, 0.5158286087610214f, 0.5158696753173290f, + 0.5159107406881956f, 0.5159518048735270f, 0.5159928678732290f, 0.5160339296872070f, + 0.5160749903153666f, 0.5161160497576137f, 0.5161571080138537f, 0.5161981650839925f, + 0.5162392209679355f, 0.5162802756655885f, 0.5163213291768572f, 0.5163623815016470f, + 0.5164034326398640f, 0.5164444825914135f, 0.5164855313562012f, 0.5165265789341330f, + 0.5165676253251144f, 0.5166086705290511f, 0.5166497145458487f, 0.5166907573754131f, + 0.5167317990176499f, 0.5167728394724647f, 0.5168138787397631f, 0.5168549168194512f, + 0.5168959537114343f, 0.5169369894156182f, 0.5169780239319086f, 0.5170190572602114f, + 0.5170600894004319f, 0.5171011203524762f, 0.5171421501162500f, 0.5171831786916586f, + 0.5172242060786083f, 0.5172652322770044f, 0.5173062572867527f, 0.5173472811077590f, + 0.5173883037399291f, 0.5174293251831685f, 0.5174703454373831f, 0.5175113645024787f, + 0.5175523823783609f, 0.5175933990649354f, 0.5176344145621082f, 0.5176754288697849f, + 0.5177164419878711f, 0.5177574539162727f, 0.5177984646548955f, 0.5178394742036453f, + 0.5178804825624277f, 0.5179214897311485f, 0.5179624957097136f, 0.5180035004980287f, + 0.5180445040959993f, 0.5180855065035317f, 0.5181265077205313f, 0.5181675077469039f, + 0.5182085065825555f, 0.5182495042273917f, 0.5182905006813183f, 0.5183314959442412f, + 0.5183724900160661f, 0.5184134828966990f, 0.5184544745860452f, 0.5184954650840111f, + 0.5185364543905022f, 0.5185774425054243f, 0.5186184294286832f, 0.5186594151601849f, + 0.5187003996998351f, 0.5187413830475395f, 0.5187823652032041f, 0.5188233461667346f, + 0.5188643259380369f, 0.5189053045170169f, 0.5189462819035804f, 0.5189872580976330f, + 0.5190282330990809f, 0.5190692069078296f, 0.5191101795237852f, 0.5191511509468535f, + 0.5191921211769402f, 0.5192330902139515f, 0.5192740580577927f, 0.5193150247083702f, + 0.5193559901655896f, 0.5193969544293568f, 0.5194379174995776f, 0.5194788793761580f, + 0.5195198400590038f, 0.5195607995480208f, 0.5196017578431150f, 0.5196427149441923f, + 0.5196836708511584f, 0.5197246255639195f, 0.5197655790823812f, 0.5198065314064495f, + 0.5198474825360302f, 0.5198884324710293f, 0.5199293812113528f, 0.5199703287569063f, + 0.5200112751075960f, 0.5200522202633278f, 0.5200931642240072f, 0.5201341069895407f, + 0.5201750485598338f, 0.5202159889347926f, 0.5202569281143228f, 0.5202978660983307f, + 0.5203388028867220f, 0.5203797384794024f, 0.5204206728762784f, 0.5204616060772556f, + 0.5205025380822398f, 0.5205434688911371f, 0.5205843985038535f, 0.5206253269202948f, + 0.5206662541403672f, 0.5207071801639763f, 0.5207481049910284f, 0.5207890286214292f, + 0.5208299510550847f, 0.5208708722919010f, 0.5209117923317841f, 0.5209527111746396f, + 0.5209936288203739f, 0.5210345452688927f, 0.5210754605201021f, 0.5211163745739080f, + 0.5211572874302166f, 0.5211981990889336f, 0.5212391095499651f, 0.5212800188132172f, + 0.5213209268785957f, 0.5213618337460065f, 0.5214027394153561f, 0.5214436438865500f, + 0.5214845471594943f, 0.5215254492340953f, 0.5215663501102588f, 0.5216072497878906f, + 0.5216481482668971f, 0.5216890455471841f, 0.5217299416286577f, 0.5217708365112238f, + 0.5218117301947885f, 0.5218526226792580f, 0.5218935139645380f, 0.5219344040505348f, + 0.5219752929371544f, 0.5220161806243027f, 0.5220570671118857f, 0.5220979523998098f, + 0.5221388364879808f, 0.5221797193763046f, 0.5222206010646875f, 0.5222614815530355f, + 0.5223023608412547f, 0.5223432389292509f, 0.5223841158169306f, 0.5224249915041995f, + 0.5224658659909638f, 0.5225067392771297f, 0.5225476113626030f, 0.5225884822472899f, + 0.5226293519310966f, 0.5226702204139291f, 0.5227110876956935f, 0.5227519537762957f, + 0.5227928186556421f, 0.5228336823336387f, 0.5228745448101914f, 0.5229154060852066f, + 0.5229562661585901f, 0.5229971250302483f, 0.5230379827000871f, 0.5230788391680127f, + 0.5231196944339312f, 0.5231605484977486f, 0.5232014013593713f, 0.5232422530187052f, + 0.5232831034756564f, 0.5233239527301312f, 0.5233648007820356f, 0.5234056476312758f, + 0.5234464932777578f, 0.5234873377213879f, 0.5235281809620722f, 0.5235690229997169f, + 0.5236098638342279f, 0.5236507034655117f, 0.5236915418934741f, 0.5237323791180216f, + 0.5237732151390602f, 0.5238140499564961f, 0.5238548835702351f, 0.5238957159801840f, + 0.5239365471862486f, 0.5239773771883350f, 0.5240182059863496f, 0.5240590335801985f, + 0.5240998599697878f, 0.5241406851550238f, 0.5241815091358125f, 0.5242223319120604f, + 0.5242631534836734f, 0.5243039738505578f, 0.5243447930126198f, 0.5243856109697655f, + 0.5244264277219014f, 0.5244672432689335f, 0.5245080576107679f, 0.5245488707473109f, + 0.5245896826784689f, 0.5246304934041479f, 0.5246713029242540f, 0.5247121112386939f, + 0.5247529183473734f, 0.5247937242501988f, 0.5248345289470763f, 0.5248753324379123f, + 0.5249161347226130f, 0.5249569358010845f, 0.5249977356732332f, 0.5250385343389652f, + 0.5250793317981868f, 0.5251201280508043f, 0.5251609230967240f, 0.5252017169358520f, + 0.5252425095680947f, 0.5252833009933582f, 0.5253240912115490f, 0.5253648802225730f, + 0.5254056680263369f, 0.5254464546227468f, 0.5254872400117087f, 0.5255280241931293f, + 0.5255688071669147f, 0.5256095889329711f, 0.5256503694912048f, 0.5256911488415223f, + 0.5257319269838298f, 0.5257727039180333f, 0.5258134796440395f, 0.5258542541617546f, + 0.5258950274710847f, 0.5259357995719363f, 0.5259765704642156f, 0.5260173401478291f, + 0.5260581086226828f, 0.5260988758886832f, 0.5261396419457368f, 0.5261804067937496f, + 0.5262211704326281f, 0.5262619328622785f, 0.5263026940826073f, 0.5263434540935207f, + 0.5263842128949251f, 0.5264249704867269f, 0.5264657268688322f, 0.5265064820411476f, + 0.5265472360035794f, 0.5265879887560339f, 0.5266287402984173f, 0.5266694906306363f, + 0.5267102397525970f, 0.5267509876642058f, 0.5267917343653691f, 0.5268324798559934f, + 0.5268732241359846f, 0.5269139672052496f, 0.5269547090636947f, 0.5269954497112260f, + 0.5270361891477501f, 0.5270769273731732f, 0.5271176643874019f, 0.5271584001903424f, + 0.5271991347819013f, 0.5272398681619849f, 0.5272806003304994f, 0.5273213312873515f, + 0.5273620610324475f, 0.5274027895656938f, 0.5274435168869966f, 0.5274842429962626f, + 0.5275249678933982f, 0.5275656915783096f, 0.5276064140509034f, 0.5276471353110860f, + 0.5276878553587637f, 0.5277285741938431f, 0.5277692918162306f, 0.5278100082258325f, + 0.5278507234225552f, 0.5278914374063055f, 0.5279321501769896f, 0.5279728617345137f, + 0.5280135720787846f, 0.5280542812097088f, 0.5280949891271924f, 0.5281356958311422f, + 0.5281764013214644f, 0.5282171055980657f, 0.5282578086608521f, 0.5282985105097308f, + 0.5283392111446077f, 0.5283799105653895f, 0.5284206087719825f, 0.5284613057642933f, + 0.5285020015422285f, 0.5285426961056943f, 0.5285833894545975f, 0.5286240815888443f, + 0.5286647725083413f, 0.5287054622129952f, 0.5287461507027122f, 0.5287868379773990f, + 0.5288275240369619f, 0.5288682088813076f, 0.5289088925103426f, 0.5289495749239731f, + 0.5289902561221060f, 0.5290309361046478f, 0.5290716148715047f, 0.5291122924225835f, + 0.5291529687577906f, 0.5291936438770327f, 0.5292343177802160f, 0.5292749904672474f, + 0.5293156619380333f, 0.5293563321924800f, 0.5293970012304944f, 0.5294376690519829f, + 0.5294783356568520f, 0.5295190010450083f, 0.5295596652163583f, 0.5296003281708087f, + 0.5296409899082659f, 0.5296816504286366f, 0.5297223097318272f, 0.5297629678177443f, + 0.5298036246862946f, 0.5298442803373846f, 0.5298849347709210f, 0.5299255879868100f, + 0.5299662399849586f, 0.5300068907652732f, 0.5300475403276603f, 0.5300881886720268f, + 0.5301288357982790f, 0.5301694817063235f, 0.5302101263960669f, 0.5302507698674160f, + 0.5302914121202773f, 0.5303320531545573f, 0.5303726929701628f, 0.5304133315670003f, + 0.5304539689449763f, 0.5304946051039977f, 0.5305352400439709f, 0.5305758737648026f, + 0.5306165062663993f, 0.5306571375486678f, 0.5306977676115148f, 0.5307383964548467f, + 0.5307790240785701f, 0.5308196504825921f, 0.5308602756668187f, 0.5309008996311571f, + 0.5309415223755136f, 0.5309821438997950f, 0.5310227642039079f, 0.5310633832877590f, + 0.5311040011512550f, 0.5311446177943023f, 0.5311852332168080f, 0.5312258474186785f, + 0.5312664603998205f, 0.5313070721601405f, 0.5313476826995456f, 0.5313882920179421f, + 0.5314289001152368f, 0.5314695069913364f, 0.5315101126461477f, 0.5315507170795771f, + 0.5315913202915317f, 0.5316319222819178f, 0.5316725230506424f, 0.5317131225976119f, + 0.5317537209227333f, 0.5317943180259131f, 0.5318349139070582f, 0.5318755085660751f, + 0.5319161020028706f, 0.5319566942173516f, 0.5319972852094245f, 0.5320378749789962f, + 0.5320784635259735f, 0.5321190508502629f, 0.5321596369517715f, 0.5322002218304056f, + 0.5322408054860722f, 0.5322813879186780f, 0.5323219691281298f, 0.5323625491143342f, + 0.5324031278771979f, 0.5324437054166280f, 0.5324842817325309f, 0.5325248568248135f, + 0.5325654306933826f, 0.5326060033381449f, 0.5326465747590071f, 0.5326871449558762f, + 0.5327277139286588f, 0.5327682816772616f, 0.5328088482015916f, 0.5328494135015553f, + 0.5328899775770598f, 0.5329305404280116f, 0.5329711020543176f, 0.5330116624558847f, + 0.5330522216326196f, 0.5330927795844290f, 0.5331333363112198f, 0.5331738918128990f, + 0.5332144460893730f, 0.5332549991405487f, 0.5332955509663333f, 0.5333361015666331f, + 0.5333766509413553f, 0.5334171990904066f, 0.5334577460136938f, 0.5334982917111236f, + 0.5335388361826031f, 0.5335793794280389f, 0.5336199214473378f, 0.5336604622404070f, + 0.5337010018071530f, 0.5337415401474827f, 0.5337820772613029f, 0.5338226131485206f, + 0.5338631478090426f, 0.5339036812427757f, 0.5339442134496268f, 0.5339847444295027f, + 0.5340252741823104f, 0.5340658027079566f, 0.5341063300063483f, 0.5341468560773923f, + 0.5341873809209954f, 0.5342279045370647f, 0.5342684269255068f, 0.5343089480862288f, + 0.5343494680191375f, 0.5343899867241397f, 0.5344305042011425f, 0.5344710204500527f, + 0.5345115354707771f, 0.5345520492632228f, 0.5345925618272963f, 0.5346330731629050f, + 0.5346735832699555f, 0.5347140921483547f, 0.5347545997980098f, 0.5347951062188274f, + 0.5348356114107147f, 0.5348761153735783f, 0.5349166181073253f, 0.5349571196118627f, + 0.5349976198870972f, 0.5350381189329360f, 0.5350786167492858f, 0.5351191133360537f, + 0.5351596086931466f, 0.5352001028204715f, 0.5352405957179353f, 0.5352810873854447f, + 0.5353215778229071f, 0.5353620670302291f, 0.5354025550073178f, 0.5354430417540803f, + 0.5354835272704234f, 0.5355240115562541f, 0.5355644946114791f, 0.5356049764360059f, + 0.5356454570297411f, 0.5356859363925917f, 0.5357264145244649f, 0.5357668914252675f, + 0.5358073670949064f, 0.5358478415332889f, 0.5358883147403218f, 0.5359287867159120f, + 0.5359692574599667f, 0.5360097269723928f, 0.5360501952530973f, 0.5360906623019871f, + 0.5361311281189695f, 0.5361715927039512f, 0.5362120560568394f, 0.5362525181775409f, + 0.5362929790659632f, 0.5363334387220128f, 0.5363738971455969f, 0.5364143543366227f, + 0.5364548102949971f, 0.5364952650206269f, 0.5365357185134196f, 0.5365761707732820f, + 0.5366166218001212f, 0.5366570715938440f, 0.5366975201543577f, 0.5367379674815694f, + 0.5367784135753859f, 0.5368188584357145f, 0.5368593020624622f, 0.5368997444555359f, + 0.5369401856148429f, 0.5369806255402901f, 0.5370210642317848f, 0.5370615016892337f, + 0.5371019379125441f, 0.5371423729016233f, 0.5371828066563779f, 0.5372232391767153f, + 0.5372636704625425f, 0.5373041005137668f, 0.5373445293302948f, 0.5373849569120341f, + 0.5374253832588916f, 0.5374658083707743f, 0.5375062322475894f, 0.5375466548892441f, + 0.5375870762956454f, 0.5376274964667005f, 0.5376679154023165f, 0.5377083331024004f, + 0.5377487495668594f, 0.5377891647956006f, 0.5378295787885312f, 0.5378699915455581f, + 0.5379104030665889f, 0.5379508133515304f, 0.5379912224002897f, 0.5380316302127740f, + 0.5380720367888906f, 0.5381124421285466f, 0.5381528462316488f, 0.5381932490981048f, + 0.5382336507278217f, 0.5382740511207064f, 0.5383144502766662f, 0.5383548481956084f, + 0.5383952448774399f, 0.5384356403220681f, 0.5384760345294002f, 0.5385164274993431f, + 0.5385568192318041f, 0.5385972097266906f, 0.5386375989839095f, 0.5386779870033681f, + 0.5387183737849736f, 0.5387587593286332f, 0.5387991436342541f, 0.5388395267017434f, + 0.5388799085310084f, 0.5389202891219563f, 0.5389606684744943f, 0.5390010465885297f, + 0.5390414234639694f, 0.5390817991007211f, 0.5391221734986915f, 0.5391625466577882f, + 0.5392029185779182f, 0.5392432892589889f, 0.5392836587009074f, 0.5393240269035812f, + 0.5393643938669170f, 0.5394047595908226f, 0.5394451240752050f, 0.5394854873199713f, + 0.5395258493250289f, 0.5395662100902852f, 0.5396065696156472f, 0.5396469279010222f, + 0.5396872849463176f, 0.5397276407514406f, 0.5397679953162985f, 0.5398083486407983f, + 0.5398487007248476f, 0.5398890515683535f, 0.5399294011712233f, 0.5399697495333644f, + 0.5400100966546840f, 0.5400504425350893f, 0.5400907871744878f, 0.5401311305727865f, + 0.5401714727298930f, 0.5402118136457141f, 0.5402521533201577f, 0.5402924917531309f, + 0.5403328289445407f, 0.5403731648942949f, 0.5404134996023005f, 0.5404538330684647f, + 0.5404941652926952f, 0.5405344962748990f, 0.5405748260149836f, 0.5406151545128561f, + 0.5406554817684242f, 0.5406958077815949f, 0.5407361325522756f, 0.5407764560803737f, + 0.5408167783657967f, 0.5408570994084516f, 0.5408974192082459f, 0.5409377377650869f, + 0.5409780550788821f, 0.5410183711495387f, 0.5410586859769642f, 0.5410989995610658f, + 0.5411393119017508f, 0.5411796229989269f, 0.5412199328525013f, 0.5412602414623812f, + 0.5413005488284741f, 0.5413408549506874f, 0.5413811598289285f, 0.5414214634631047f, + 0.5414617658531234f, 0.5415020669988921f, 0.5415423669003182f, 0.5415826655573087f, + 0.5416229629697715f, 0.5416632591376138f, 0.5417035540607429f, 0.5417438477390664f, + 0.5417841401724915f, 0.5418244313609257f, 0.5418647213042765f, 0.5419050100024514f, + 0.5419452974553575f, 0.5419855836629023f, 0.5420258686249935f, 0.5420661523415382f, + 0.5421064348124439f, 0.5421467160376182f, 0.5421869960169685f, 0.5422272747504020f, + 0.5422675522378265f, 0.5423078284791492f, 0.5423481034742776f, 0.5423883772231192f, + 0.5424286497255812f, 0.5424689209815715f, 0.5425091909909973f, 0.5425494597537660f, + 0.5425897272697853f, 0.5426299935389624f, 0.5426702585612048f, 0.5427105223364203f, + 0.5427507848645159f, 0.5427910461453994f, 0.5428313061789782f, 0.5428715649651599f, + 0.5429118225038517f, 0.5429520787949613f, 0.5429923338383963f, 0.5430325876340639f, + 0.5430728401818717f, 0.5431130914817275f, 0.5431533415335383f, 0.5431935903372119f, + 0.5432338378926559f, 0.5432740841997777f, 0.5433143292584848f, 0.5433545730686845f, + 0.5433948156302848f, 0.5434350569431928f, 0.5434752970073163f, 0.5435155358225627f, + 0.5435557733888395f, 0.5435960097060544f, 0.5436362447741148f, 0.5436764785929283f, + 0.5437167111624024f, 0.5437569424824447f, 0.5437971725529627f, 0.5438374013738639f, + 0.5438776289450560f, 0.5439178552664464f, 0.5439580803379429f, 0.5439983041594528f, + 0.5440385267308838f, 0.5440787480521436f, 0.5441189681231395f, 0.5441591869437792f, + 0.5441994045139703f, 0.5442396208336204f, 0.5442798359026371f, 0.5443200497209278f, + 0.5443602622884004f, 0.5444004736049622f, 0.5444406836705209f, 0.5444808924849842f, + 0.5445211000482596f, 0.5445613063602547f, 0.5446015114208772f, 0.5446417152300346f, + 0.5446819177876345f, 0.5447221190935847f, 0.5447623191477926f, 0.5448025179501661f, + 0.5448427155006124f, 0.5448829117990395f, 0.5449231068453549f, 0.5449633006394662f, + 0.5450034931812812f, 0.5450436844707073f, 0.5450838745076523f, 0.5451240632920237f, + 0.5451642508237293f, 0.5452044371026767f, 0.5452446221287736f, 0.5452848059019276f, + 0.5453249884220465f, 0.5453651696890376f, 0.5454053497028090f, 0.5454455284632680f, + 0.5454857059703225f, 0.5455258822238802f, 0.5455660572238487f, 0.5456062309701355f, + 0.5456464034626486f, 0.5456865747012954f, 0.5457267446859839f, 0.5457669134166215f, + 0.5458070808931161f, 0.5458472471153754f, 0.5458874120833068f, 0.5459275757968183f, + 0.5459677382558176f, 0.5460078994602122f, 0.5460480594099100f, 0.5460882181048187f, + 0.5461283755448459f, 0.5461685317298995f, 0.5462086866598871f, 0.5462488403347164f, + 0.5462889927542952f, 0.5463291439185312f, 0.5463692938273320f, 0.5464094424806057f, + 0.5464495898782596f, 0.5464897360202019f, 0.5465298809063400f, 0.5465700245365818f, + 0.5466101669108349f, 0.5466503080290072f, 0.5466904478910065f, 0.5467305864967403f, + 0.5467707238461168f, 0.5468108599390433f, 0.5468509947754280f, 0.5468911283551783f, + 0.5469312606782022f, 0.5469713917444073f, 0.5470115215537015f, 0.5470516501059927f, + 0.5470917774011885f, 0.5471319034391967f, 0.5471720282199252f, 0.5472121517432817f, + 0.5472522740091741f, 0.5472923950175100f, 0.5473325147681976f, 0.5473726332611443f, + 0.5474127504962579f, 0.5474528664734466f, 0.5474929811926179f, 0.5475330946536796f, + 0.5475732068565398f, 0.5476133178011061f, 0.5476534274872864f, 0.5476935359149884f, + 0.5477336430841201f, 0.5477737489945893f, 0.5478138536463038f, 0.5478539570391715f, + 0.5478940591731002f, 0.5479341600479977f, 0.5479742596637719f, 0.5480143580203306f, + 0.5480544551175819f, 0.5480945509554332f, 0.5481346455337929f, 0.5481747388525684f, + 0.5482148309116678f, 0.5482549217109990f, 0.5482950112504698f, 0.5483350995299880f, + 0.5483751865494616f, 0.5484152723087985f, 0.5484553568079065f, 0.5484954400466935f, + 0.5485355220250674f, 0.5485756027429362f, 0.5486156822002075f, 0.5486557603967895f, + 0.5486958373325901f, 0.5487359130075170f, 0.5487759874214782f, 0.5488160605743817f, + 0.5488561324661353f, 0.5488962030966469f, 0.5489362724658245f, 0.5489763405735761f, + 0.5490164074198095f, 0.5490564730044325f, 0.5490965373273533f, 0.5491366003884798f, + 0.5491766621877197f, 0.5492167227249812f, 0.5492567820001721f, 0.5492968400132003f, + 0.5493368967639740f, 0.5493769522524009f, 0.5494170064783891f, 0.5494570594418464f, + 0.5494971111426810f, 0.5495371615808006f, 0.5495772107561132f, 0.5496172586685271f, + 0.5496573053179499f, 0.5496973507042897f, 0.5497373948274544f, 0.5497774376873522f, + 0.5498174792838909f, 0.5498575196169785f, 0.5498975586865231f, 0.5499375964924326f, + 0.5499776330346149f, 0.5500176683129783f, 0.5500577023274305f, 0.5500977350778796f, + 0.5501377665642336f, 0.5501777967864006f, 0.5502178257442885f, 0.5502578534378053f, + 0.5502978798668592f, 0.5503379050313580f, 0.5503779289312100f, 0.5504179515663228f, + 0.5504579729366048f, 0.5504979930419639f, 0.5505380118823081f, 0.5505780294575456f, + 0.5506180457675843f, 0.5506580608123322f, 0.5506980745916975f, 0.5507380871055881f, + 0.5507780983539122f, 0.5508181083365777f, 0.5508581170534929f, 0.5508981245045655f, + 0.5509381306897039f, 0.5509781356088160f, 0.5510181392618099f, 0.5510581416485937f, + 0.5510981427690754f, 0.5511381426231632f, 0.5511781412107651f, 0.5512181385317891f, + 0.5512581345861436f, 0.5512981293737365f, 0.5513381228944756f, 0.5513781151482695f, + 0.5514181061350261f, 0.5514580958546533f, 0.5514980843070595f, 0.5515380714921526f, + 0.5515780574098410f, 0.5516180420600324f, 0.5516580254426352f, 0.5516980075575576f, + 0.5517379884047073f, 0.5517779679839929f, 0.5518179462953224f, 0.5518579233386038f, + 0.5518978991137452f, 0.5519378736206549f, 0.5519778468592411f, 0.5520178188294117f, + 0.5520577895310750f, 0.5520977589641392f, 0.5521377271285122f, 0.5521776940241023f, + 0.5522176596508179f, 0.5522576240085669f, 0.5522975870972574f, 0.5523375489167978f, + 0.5523775094670961f, 0.5524174687480604f, 0.5524574267595991f, 0.5524973835016204f, + 0.5525373389740322f, 0.5525772931767429f, 0.5526172461096606f, 0.5526571977726935f, + 0.5526971481657498f, 0.5527370972887378f, 0.5527770451415656f, 0.5528169917241412f, + 0.5528569370363733f, 0.5528968810781697f, 0.5529368238494388f, 0.5529767653500886f, + 0.5530167055800275f, 0.5530566445391638f, 0.5530965822274054f, 0.5531365186446610f, + 0.5531764537908384f, 0.5532163876658460f, 0.5532563202695920f, 0.5532962516019847f, + 0.5533361816629323f, 0.5533761104523430f, 0.5534160379701252f, 0.5534559642161869f, + 0.5534958891904366f, 0.5535358128927824f, 0.5535757353231326f, 0.5536156564813955f, + 0.5536555763674793f, 0.5536954949812922f, 0.5537354123227427f, 0.5537753283917388f, + 0.5538152431881891f, 0.5538551567120016f, 0.5538950689630846f, 0.5539349799413464f, + 0.5539748896466955f, 0.5540147980790401f, 0.5540547052382881f, 0.5540946111243483f, + 0.5541345157371289f, 0.5541744190765380f, 0.5542143211424840f, 0.5542542219348753f, + 0.5542941214536201f, 0.5543340196986267f, 0.5543739166698036f, 0.5544138123670589f, + 0.5544537067903009f, 0.5544935999394383f, 0.5545334918143789f, 0.5545733824150315f, + 0.5546132717413040f, 0.5546531597931051f, 0.5546930465703430f, 0.5547329320729260f, + 0.5547728163007625f, 0.5548126992537609f, 0.5548525809318293f, 0.5548924613348764f, + 0.5549323404628104f, 0.5549722183155396f, 0.5550120948929723f, 0.5550519701950172f, + 0.5550918442215824f, 0.5551317169725762f, 0.5551715884479073f, 0.5552114586474838f, + 0.5552513275712140f, 0.5552911952190066f, 0.5553310615907698f, 0.5553709266864121f, + 0.5554107905058416f, 0.5554506530489671f, 0.5554905143156967f, 0.5555303743059390f, + 0.5555702330196022f, 0.5556100904565949f, 0.5556499466168254f, 0.5556898015002021f, + 0.5557296551066334f, 0.5557695074360279f, 0.5558093584882937f, 0.5558492082633396f, + 0.5558890567610738f, 0.5559289039814047f, 0.5559687499242409f, 0.5560085945894908f, + 0.5560484379770627f, 0.5560882800868651f, 0.5561281209188065f, 0.5561679604727953f, + 0.5562077987487399f, 0.5562476357465489f, 0.5562874714661308f, 0.5563273059073938f, + 0.5563671390702464f, 0.5564069709545973f, 0.5564468015603549f, 0.5564866308874274f, + 0.5565264589357236f, 0.5565662857051520f, 0.5566061111956206f, 0.5566459354070386f, + 0.5566857583393139f, 0.5567255799923553f, 0.5567654003660710f, 0.5568052194603698f, + 0.5568450372751601f, 0.5568848538103502f, 0.5569246690658490f, 0.5569644830415649f, + 0.5570042957374060f, 0.5570441071532812f, 0.5570839172890991f, 0.5571237261447679f, + 0.5571635337201962f, 0.5572033400152928f, 0.5572431450299660f, 0.5572829487641241f, + 0.5573227512176762f, 0.5573625523905303f, 0.5574023522825953f, 0.5574421508937795f, + 0.5574819482239916f, 0.5575217442731401f, 0.5575615390411334f, 0.5576013325278804f, + 0.5576411247332894f, 0.5576809156572688f, 0.5577207052997277f, 0.5577604936605742f, + 0.5578002807397171f, 0.5578400665370647f, 0.5578798510525259f, 0.5579196342860092f, + 0.5579594162374230f, 0.5579991969066760f, 0.5580389762936768f, 0.5580787543983340f, + 0.5581185312205561f, 0.5581583067602518f, 0.5581980810173297f, 0.5582378539916982f, + 0.5582776256832663f, 0.5583173960919423f, 0.5583571652176348f, 0.5583969330602525f, + 0.5584366996197041f, 0.5584764648958981f, 0.5585162288887430f, 0.5585559915981477f, + 0.5585957530240208f, 0.5586355131662706f, 0.5586752720248062f, 0.5587150295995359f, + 0.5587547858903683f, 0.5587945408972124f, 0.5588342946199765f, 0.5588740470585695f, + 0.5589137982128998f, 0.5589535480828761f, 0.5589932966684074f, 0.5590330439694018f, + 0.5590727899857685f, 0.5591125347174158f, 0.5591522781642526f, 0.5591920203261873f, + 0.5592317612031289f, 0.5592715007949859f, 0.5593112391016669f, 0.5593509761230807f, + 0.5593907118591361f, 0.5594304463097415f, 0.5594701794748058f, 0.5595099113542378f, + 0.5595496419479459f, 0.5595893712558389f, 0.5596290992778256f, 0.5596688260138146f, + 0.5597085514637147f, 0.5597482756274347f, 0.5597879985048831f, 0.5598277200959687f, + 0.5598674404006002f, 0.5599071594186865f, 0.5599468771501361f, 0.5599865935948578f, + 0.5600263087527604f, 0.5600660226237526f, 0.5601057352077430f, 0.5601454465046406f, + 0.5601851565143541f, 0.5602248652367920f, 0.5602645726718632f, 0.5603042788194766f, + 0.5603439836795409f, 0.5603836872519645f, 0.5604233895366567f, 0.5604630905335259f, + 0.5605027902424811f, 0.5605424886634308f, 0.5605821857962842f, 0.5606218816409496f, + 0.5606615761973360f, 0.5607012694653523f, 0.5607409614449070f, 0.5607806521359091f, + 0.5608203415382674f, 0.5608600296518907f, 0.5608997164766878f, 0.5609394020125672f, + 0.5609790862594382f, 0.5610187692172093f, 0.5610584508857892f, 0.5610981312650870f, + 0.5611378103550114f, 0.5611774881554712f, 0.5612171646663753f, 0.5612568398876325f, + 0.5612965138191516f, 0.5613361864608413f, 0.5613758578126106f, 0.5614155278743683f, + 0.5614551966460233f, 0.5614948641274843f, 0.5615345303186603f, 0.5615741952194601f, + 0.5616138588297924f, 0.5616535211495662f, 0.5616931821786906f, 0.5617328419170738f, + 0.5617725003646253f, 0.5618121575212538f, 0.5618518133868680f, 0.5618914679613769f, + 0.5619311212446895f, 0.5619707732367143f, 0.5620104239373604f, 0.5620500733465369f, + 0.5620897214641525f, 0.5621293682901158f, 0.5621690138243363f, 0.5622086580667224f, + 0.5622483010171831f, 0.5622879426756275f, 0.5623275830419644f, 0.5623672221161027f, + 0.5624068598979511f, 0.5624464963874188f, 0.5624861315844147f, 0.5625257654888476f, + 0.5625653981006266f, 0.5626050294196603f, 0.5626446594458580f, 0.5626842881791283f, + 0.5627239156193804f, 0.5627635417665231f, 0.5628031666204654f, 0.5628427901811162f, + 0.5628824124483844f, 0.5629220334221791f, 0.5629616531024092f, 0.5630012714889836f, + 0.5630408885818113f, 0.5630805043808012f, 0.5631201188858623f, 0.5631597320969036f, + 0.5631993440138341f, 0.5632389546365627f, 0.5632785639649984f, 0.5633181719990502f, + 0.5633577787386270f, 0.5633973841836379f, 0.5634369883339919f, 0.5634765911895978f, + 0.5635161927503648f, 0.5635557930162018f, 0.5635953919870179f, 0.5636349896627220f, + 0.5636745860432231f, 0.5637141811284303f, 0.5637537749182524f, 0.5637933674125988f, + 0.5638329586113782f, 0.5638725485144996f, 0.5639121371218723f, 0.5639517244334050f, + 0.5639913104490070f, 0.5640308951685873f, 0.5640704785920547f, 0.5641100607193186f, + 0.5641496415502877f, 0.5641892210848712f, 0.5642287993229782f, 0.5642683762645176f, + 0.5643079519093986f, 0.5643475262575304f, 0.5643870993088217f, 0.5644266710631816f, + 0.5644662415205195f, 0.5645058106807441f, 0.5645453785437647f, 0.5645849451094903f, + 0.5646245103778301f, 0.5646640743486929f, 0.5647036370219880f, 0.5647431983976245f, + 0.5647827584755115f, 0.5648223172555579f, 0.5648618747376729f, 0.5649014309217657f, + 0.5649409858077452f, 0.5649805393955208f, 0.5650200916850013f, 0.5650596426760961f, + 0.5650991923687140f, 0.5651387407627644f, 0.5651782878581563f, 0.5652178336547986f, + 0.5652573781526008f, 0.5652969213514719f, 0.5653364632513209f, 0.5653760038520572f, + 0.5654155431535897f, 0.5654550811558277f, 0.5654946178586800f, 0.5655341532620562f, + 0.5655736873658653f, 0.5656132201700164f, 0.5656527516744185f, 0.5656922818789811f, + 0.5657318107836131f, 0.5657713383882239f, 0.5658108646927225f, 0.5658503896970180f, + 0.5658899134010196f, 0.5659294358046366f, 0.5659689569077782f, 0.5660084767103534f, + 0.5660479952122714f, 0.5660875124134417f, 0.5661270283137733f, 0.5661665429131751f, + 0.5662060562115567f, 0.5662455682088272f, 0.5662850789048957f, 0.5663245882996716f, + 0.5663640963930638f, 0.5664036031849817f, 0.5664431086753347f, 0.5664826128640318f, + 0.5665221157509821f, 0.5665616173360950f, 0.5666011176192798f, 0.5666406166004456f, + 0.5666801142795016f, 0.5667196106563572f, 0.5667591057309215f, 0.5667985995031039f, + 0.5668380919728133f, 0.5668775831399593f, 0.5669170730044510f, 0.5669565615661977f, + 0.5669960488251087f, 0.5670355347810931f, 0.5670750194340602f, 0.5671145027839195f, + 0.5671539848305801f, 0.5671934655739512f, 0.5672329450139422f, 0.5672724231504622f, + 0.5673118999834208f, 0.5673513755127270f, 0.5673908497382901f, 0.5674303226600196f, + 0.5674697942778245f, 0.5675092645916144f, 0.5675487336012985f, 0.5675882013067860f, + 0.5676276677079862f, 0.5676671328048086f, 0.5677065965971623f, 0.5677460590849567f, + 0.5677855202681011f, 0.5678249801465050f, 0.5678644387200774f, 0.5679038959887278f, + 0.5679433519523656f, 0.5679828066109001f, 0.5680222599642404f, 0.5680617120122960f, + 0.5681011627549765f, 0.5681406121921908f, 0.5681800603238486f, 0.5682195071498590f, + 0.5682589526701316f, 0.5682983968845754f, 0.5683378397931002f, 0.5683772813956151f, + 0.5684167216920293f, 0.5684561606822526f, 0.5684955983661940f, 0.5685350347437632f, + 0.5685744698148691f, 0.5686139035794217f, 0.5686533360373299f, 0.5686927671885031f, + 0.5687321970328511f, 0.5687716255702829f, 0.5688110528007080f, 0.5688504787240358f, + 0.5688899033401759f, 0.5689293266490374f, 0.5689687486505298f, 0.5690081693445626f, + 0.5690475887310451f, 0.5690870068098868f, 0.5691264235809971f, 0.5691658390442854f, + 0.5692052531996612f, 0.5692446660470338f, 0.5692840775863127f, 0.5693234878174075f, + 0.5693628967402272f, 0.5694023043546818f, 0.5694417106606803f, 0.5694811156581322f, + 0.5695205193469471f, 0.5695599217270345f, 0.5695993227983038f, 0.5696387225606643f, + 0.5696781210140256f, 0.5697175181582972f, 0.5697569139933885f, 0.5697963085192089f, + 0.5698357017356680f, 0.5698750936426752f, 0.5699144842401401f, 0.5699538735279721f, + 0.5699932615060807f, 0.5700326481743752f, 0.5700720335327654f, 0.5701114175811606f, + 0.5701508003194703f, 0.5701901817476042f, 0.5702295618654716f, 0.5702689406729819f, + 0.5703083181700449f, 0.5703476943565701f, 0.5703870692324667f, 0.5704264427976445f, + 0.5704658150520130f, 0.5705051859954816f, 0.5705445556279599f, 0.5705839239493574f, + 0.5706232909595838f, 0.5706626566585484f, 0.5707020210461607f, 0.5707413841223306f, + 0.5707807458869673f, 0.5708201063399805f, 0.5708594654812796f, 0.5708988233107745f, + 0.5709381798283745f, 0.5709775350339890f, 0.5710168889275279f, 0.5710562415089007f, + 0.5710955927780167f, 0.5711349427347858f, 0.5711742913791175f, 0.5712136387109211f, + 0.5712529847301067f, 0.5712923294365834f, 0.5713316728302610f, 0.5713710149110490f, + 0.5714103556788572f, 0.5714496951335951f, 0.5714890332751721f, 0.5715283701034981f, + 0.5715677056184826f, 0.5716070398200350f, 0.5716463727080652f, 0.5716857042824828f, + 0.5717250345431972f, 0.5717643634901181f, 0.5718036911231553f, 0.5718430174422182f, + 0.5718823424472166f, 0.5719216661380601f, 0.5719609885146582f, 0.5720003095769206f, + 0.5720396293247570f, 0.5720789477580771f, 0.5721182648767905f, 0.5721575806808067f, + 0.5721968951700356f, 0.5722362083443867f, 0.5722755202037696f, 0.5723148307480942f, + 0.5723541399772699f, 0.5723934478912066f, 0.5724327544898138f, 0.5724720597730013f, + 0.5725113637406788f, 0.5725506663927556f, 0.5725899677291421f, 0.5726292677497473f, + 0.5726685664544813f, 0.5727078638432535f, 0.5727471599159739f, 0.5727864546725520f, + 0.5728257481128975f, 0.5728650402369203f, 0.5729043310445299f, 0.5729436205356361f, + 0.5729829087101486f, 0.5730221955679771f, 0.5730614811090314f, 0.5731007653332211f, + 0.5731400482404559f, 0.5731793298306459f, 0.5732186101037002f, 0.5732578890595292f, + 0.5732971666980422f, 0.5733364430191490f, 0.5733757180227596f, 0.5734149917087834f, + 0.5734542640771304f, 0.5734935351277103f, 0.5735328048604327f, 0.5735720732752077f, + 0.5736113403719446f, 0.5736506061505535f, 0.5736898706109441f, 0.5737291337530263f, + 0.5737683955767096f, 0.5738076560819039f, 0.5738469152685189f, 0.5738861731364646f, + 0.5739254296856507f, 0.5739646849159870f, 0.5740039388273831f, 0.5740431914197490f, + 0.5740824426929945f, 0.5741216926470293f, 0.5741609412817632f, 0.5742001885971062f, + 0.5742394345929679f, 0.5742786792692581f, 0.5743179226258869f, 0.5743571646627638f, + 0.5743964053797987f, 0.5744356447769016f, 0.5744748828539822f, 0.5745141196109503f, + 0.5745533550477158f, 0.5745925891641885f, 0.5746318219602783f, 0.5746710534358949f, + 0.5747102835909483f, 0.5747495124253484f, 0.5747887399390049f, 0.5748279661318276f, + 0.5748671910037267f, 0.5749064145546118f, 0.5749456367843926f, 0.5749848576929794f, + 0.5750240772802817f, 0.5750632955462095f, 0.5751025124906728f, 0.5751417281135814f, + 0.5751809424148452f, 0.5752201553943739f, 0.5752593670520777f, 0.5752985773878663f, + 0.5753377864016495f, 0.5753769940933374f, 0.5754162004628400f, 0.5754554055100669f, + 0.5754946092349281f, 0.5755338116373337f, 0.5755730127171935f, 0.5756122124744173f, + 0.5756514109089151f, 0.5756906080205970f, 0.5757298038093726f, 0.5757689982751520f, + 0.5758081914178453f, 0.5758473832373622f, 0.5758865737336126f, 0.5759257629065067f, + 0.5759649507559542f, 0.5760041372818652f, 0.5760433224841496f, 0.5760825063627173f, + 0.5761216889174784f, 0.5761608701483427f, 0.5762000500552202f, 0.5762392286380210f, + 0.5762784058966549f, 0.5763175818310320f, 0.5763567564410622f, 0.5763959297266554f, + 0.5764351016877218f, 0.5764742723241713f, 0.5765134416359138f, 0.5765526096228593f, + 0.5765917762849178f, 0.5766309416219995f, 0.5766701056340140f, 0.5767092683208717f, + 0.5767484296824824f, 0.5767875897187561f, 0.5768267484296030f, 0.5768659058149329f, + 0.5769050618746560f, 0.5769442166086821f, 0.5769833700169213f, 0.5770225220992838f, + 0.5770616728556794f, 0.5771008222860184f, 0.5771399703902106f, 0.5771791171681662f, + 0.5772182626197949f, 0.5772574067450073f, 0.5772965495437129f, 0.5773356910158221f, + 0.5773748311612449f, 0.5774139699798913f, 0.5774531074716713f, 0.5774922436364951f, + 0.5775313784742727f, 0.5775705119849143f, 0.5776096441683297f, 0.5776487750244291f, + 0.5776879045531228f, 0.5777270327543205f, 0.5777661596279325f, 0.5778052851738690f, + 0.5778444093920400f, 0.5778835322823553f, 0.5779226538447254f, 0.5779617740790602f, + 0.5780008929852699f, 0.5780400105632646f, 0.5780791268129543f, 0.5781182417342491f, + 0.5781573553270594f, 0.5781964675912949f, 0.5782355785268661f, 0.5782746881336829f, + 0.5783137964116556f, 0.5783529033606941f, 0.5783920089807086f, 0.5784311132716095f, + 0.5784702162333066f, 0.5785093178657102f, 0.5785484181687305f, 0.5785875171422775f, + 0.5786266147862615f, 0.5786657111005925f, 0.5787048060851808f, 0.5787438997399365f, + 0.5787829920647697f, 0.5788220830595907f, 0.5788611727243096f, 0.5789002610588366f, + 0.5789393480630818f, 0.5789784337369556f, 0.5790175180803679f, 0.5790566010932290f, + 0.5790956827754491f, 0.5791347631269385f, 0.5791738421476071f, 0.5792129198373654f, + 0.5792519961961236f, 0.5792910712237916f, 0.5793301449202798f, 0.5793692172854985f, + 0.5794082883193579f, 0.5794473580217679f, 0.5794864263926393f, 0.5795254934318818f, + 0.5795645591394057f, 0.5796036235151215f, 0.5796426865589392f, 0.5796817482707691f, + 0.5797208086505214f, 0.5797598676981066f, 0.5797989254134346f, 0.5798379817964157f, + 0.5798770368469603f, 0.5799160905649786f, 0.5799551429503809f, 0.5799941940030772f, + 0.5800332437229782f, 0.5800722921099938f, 0.5801113391640343f, 0.5801503848850103f, + 0.5801894292728317f, 0.5802284723274088f, 0.5802675140486522f, 0.5803065544364719f, + 0.5803455934907784f, 0.5803846312114816f, 0.5804236675984923f, 0.5804627026517205f, + 0.5805017363710765f, 0.5805407687564708f, 0.5805797998078134f, 0.5806188295250149f, + 0.5806578579079853f, 0.5806968849566353f, 0.5807359106708749f, 0.5807749350506145f, + 0.5808139580957645f, 0.5808529798062353f, 0.5808920001819369f, 0.5809310192227800f, + 0.5809700369286748f, 0.5810090532995317f, 0.5810480683352608f, 0.5810870820357726f, + 0.5811260944009776f, 0.5811651054307859f, 0.5812041151251081f, 0.5812431234838543f, + 0.5812821305069351f, 0.5813211361942606f, 0.5813601405457415f, 0.5813991435612879f, + 0.5814381452408102f, 0.5814771455842189f, 0.5815161445914244f, 0.5815551422623368f, + 0.5815941385968669f, 0.5816331335949249f, 0.5816721272564210f, 0.5817111195812658f, + 0.5817501105693696f, 0.5817891002206430f, 0.5818280885349961f, 0.5818670755123396f, + 0.5819060611525838f, 0.5819450454556390f, 0.5819840284214158f, 0.5820230100498245f, + 0.5820619903407755f, 0.5821009692941793f, 0.5821399469099463f, 0.5821789231879870f, + 0.5822178981282117f, 0.5822568717305310f, 0.5822958439948551f, 0.5823348149210947f, + 0.5823737845091601f, 0.5824127527589619f, 0.5824517196704103f, 0.5824906852434160f, + 0.5825296494778893f, 0.5825686123737407f, 0.5826075739308807f, 0.5826465341492197f, + 0.5826854930286685f, 0.5827244505691370f, 0.5827634067705361f, 0.5828023616327761f, + 0.5828413151557676f, 0.5828802673394210f, 0.5829192181836469f, 0.5829581676883556f, + 0.5829971158534578f, 0.5830360626788638f, 0.5830750081644843f, 0.5831139523102297f, + 0.5831528951160104f, 0.5831918365817372f, 0.5832307767073205f, 0.5832697154926706f, + 0.5833086529376983f, 0.5833475890423140f, 0.5833865238064282f, 0.5834254572299514f, + 0.5834643893127943f, 0.5835033200548674f, 0.5835422494560810f, 0.5835811775163460f, + 0.5836201042355728f, 0.5836590296136717f, 0.5836979536505535f, 0.5837368763461289f, + 0.5837757977003082f, 0.5838147177130019f, 0.5838536363841209f, 0.5838925537135755f, + 0.5839314697012762f, 0.5839703843471339f, 0.5840092976510589f, 0.5840482096129620f, + 0.5840871202327534f, 0.5841260295103442f, 0.5841649374456446f, 0.5842038440385653f, + 0.5842427492890170f, 0.5842816531969102f, 0.5843205557621554f, 0.5843594569846633f, + 0.5843983568643446f, 0.5844372554011099f, 0.5844761525948696f, 0.5845150484455346f, + 0.5845539429530153f, 0.5845928361172223f, 0.5846317279380665f, 0.5846706184154584f, + 0.5847095075493085f, 0.5847483953395275f, 0.5847872817860261f, 0.5848261668887149f, + 0.5848650506475045f, 0.5849039330623056f, 0.5849428141330290f, 0.5849816938595849f, + 0.5850205722418845f, 0.5850594492798381f, 0.5850983249733566f, 0.5851371993223504f, + 0.5851760723267304f, 0.5852149439864072f, 0.5852538143012913f, 0.5852926832712937f, + 0.5853315508963249f, 0.5853704171762955f, 0.5854092821111164f, 0.5854481457006981f, + 0.5854870079449515f, 0.5855258688437870f, 0.5855647283971156f, 0.5856035866048478f, + 0.5856424434668944f, 0.5856812989831661f, 0.5857201531535736f, 0.5857590059780277f, + 0.5857978574564389f, 0.5858367075887181f, 0.5858755563747760f, 0.5859144038145232f, + 0.5859532499078706f, 0.5859920946547289f, 0.5860309380550087f, 0.5860697801086210f, + 0.5861086208154764f, 0.5861474601754856f, 0.5861862981885593f, 0.5862251348546084f, + 0.5862639701735436f, 0.5863028041452756f, 0.5863416367697153f, 0.5863804680467734f, + 0.5864192979763606f, 0.5864581265583876f, 0.5864969537927655f, 0.5865357796794047f, + 0.5865746042182162f, 0.5866134274091107f, 0.5866522492519991f, 0.5866910697467921f, + 0.5867298888934004f, 0.5867687066917351f, 0.5868075231417066f, 0.5868463382432260f, + 0.5868851519962039f, 0.5869239644005513f, 0.5869627754561788f, 0.5870015851629975f, + 0.5870403935209180f, 0.5870792005298512f, 0.5871180061897078f, 0.5871568105003988f, + 0.5871956134618349f, 0.5872344150739269f, 0.5872732153365859f, 0.5873120142497226f, + 0.5873508118132477f, 0.5873896080270721f, 0.5874284028911068f, 0.5874671964052625f, + 0.5875059885694500f, 0.5875447793835804f, 0.5875835688475645f, 0.5876223569613128f, + 0.5876611437247367f, 0.5876999291377467f, 0.5877387132002538f, 0.5877774959121690f, + 0.5878162772734029f, 0.5878550572838667f, 0.5878938359434709f, 0.5879326132521268f, + 0.5879713892097450f, 0.5880101638162365f, 0.5880489370715123f, 0.5880877089754831f, + 0.5881264795280600f, 0.5881652487291535f, 0.5882040165786752f, 0.5882427830765354f, + 0.5882815482226452f, 0.5883203120169158f, 0.5883590744592577f, 0.5883978355495820f, + 0.5884365952877998f, 0.5884753536738219f, 0.5885141107075591f, 0.5885528663889223f, + 0.5885916207178229f, 0.5886303736941714f, 0.5886691253178788f, 0.5887078755888563f, + 0.5887466245070145f, 0.5887853720722648f, 0.5888241182845176f, 0.5888628631436844f, + 0.5889016066496758f, 0.5889403488024030f, 0.5889790896017768f, 0.5890178290477084f, + 0.5890565671401085f, 0.5890953038788882f, 0.5891340392639586f, 0.5891727732952305f, + 0.5892115059726150f, 0.5892502372960231f, 0.5892889672653657f, 0.5893276958805539f, + 0.5893664231414988f, 0.5894051490481111f, 0.5894438736003020f, 0.5894825967979826f, + 0.5895213186410639f, 0.5895600391294568f, 0.5895987582630722f, 0.5896374760418215f, + 0.5896761924656154f, 0.5897149075343650f, 0.5897536212479815f, 0.5897923336063757f, + 0.5898310446094589f, 0.5898697542571418f, 0.5899084625493358f, 0.5899471694859519f, + 0.5899858750669009f, 0.5900245792920941f, 0.5900632821614424f, 0.5901019836748570f, + 0.5901406838322488f, 0.5901793826335292f, 0.5902180800786089f, 0.5902567761673990f, + 0.5902954708998108f, 0.5903341642757554f, 0.5903728562951436f, 0.5904115469578868f, + 0.5904502362638958f, 0.5904889242130820f, 0.5905276108053561f, 0.5905662960406296f, + 0.5906049799188134f, 0.5906436624398187f, 0.5906823436035565f, 0.5907210234099380f, + 0.5907597018588742f, 0.5907983789502763f, 0.5908370546840556f, 0.5908757290601230f, + 0.5909144020783895f, 0.5909530737387665f, 0.5909917440411652f, 0.5910304129854963f, + 0.5910690805716714f, 0.5911077467996014f, 0.5911464116691976f, 0.5911850751803710f, + 0.5912237373330329f, 0.5912623981270944f, 0.5913010575624664f, 0.5913397156390604f, + 0.5913783723567876f, 0.5914170277155588f, 0.5914556817152856f, 0.5914943343558789f, + 0.5915329856372500f, 0.5915716355593099f, 0.5916102841219701f, 0.5916489313251416f, + 0.5916875771687354f, 0.5917262216526631f, 0.5917648647768357f, 0.5918035065411642f, + 0.5918421469455601f, 0.5918807859899345f, 0.5919194236741987f, 0.5919580599982637f, + 0.5919966949620410f, 0.5920353285654415f, 0.5920739608083766f, 0.5921125916907576f, + 0.5921512212124955f, 0.5921898493735018f, 0.5922284761736875f, 0.5922671016129639f, + 0.5923057256912424f, 0.5923443484084341f, 0.5923829697644503f, 0.5924215897592021f, + 0.5924602083926008f, 0.5924988256645579f, 0.5925374415749846f, 0.5925760561237918f, + 0.5926146693108911f, 0.5926532811361938f, 0.5926918915996110f, 0.5927305007010539f, + 0.5927691084404341f, 0.5928077148176626f, 0.5928463198326507f, 0.5928849234853099f, + 0.5929235257755513f, 0.5929621267032863f, 0.5930007262684260f, 0.5930393244708820f, + 0.5930779213105655f, 0.5931165167873876f, 0.5931551109012598f, 0.5931937036520935f, + 0.5932322950397998f, 0.5932708850642902f, 0.5933094737254758f, 0.5933480610232682f, + 0.5933866469575785f, 0.5934252315283181f, 0.5934638147353984f, 0.5935023965787307f, + 0.5935409770582264f, 0.5935795561737967f, 0.5936181339253531f, 0.5936567103128068f, + 0.5936952853360692f, 0.5937338589950518f, 0.5937724312896657f, 0.5938110022198225f, + 0.5938495717854336f, 0.5938881399864101f, 0.5939267068226636f, 0.5939652722941053f, + 0.5940038364006468f, 0.5940423991421991f, 0.5940809605186741f, 0.5941195205299828f, + 0.5941580791760368f, 0.5941966364567474f, 0.5942351923720260f, 0.5942737469217840f, + 0.5943123001059328f, 0.5943508519243839f, 0.5943894023770486f, 0.5944279514638382f, + 0.5944664991846644f, 0.5945050455394385f, 0.5945435905280718f, 0.5945821341504760f, + 0.5946206764065622f, 0.5946592172962422f, 0.5946977568194269f, 0.5947362949760283f, + 0.5947748317659576f, 0.5948133671891260f, 0.5948519012454455f, 0.5948904339348271f, + 0.5949289652571825f, 0.5949674952124229f, 0.5950060238004601f, 0.5950445510212052f, + 0.5950830768745700f, 0.5951216013604658f, 0.5951601244788040f, 0.5951986462294961f, + 0.5952371666124538f, 0.5952756856275885f, 0.5953142032748115f, 0.5953527195540343f, + 0.5953912344651687f, 0.5954297480081259f, 0.5954682601828174f, 0.5955067709891549f, + 0.5955452804270498f, 0.5955837884964136f, 0.5956222951971577f, 0.5956608005291938f, + 0.5956993044924334f, 0.5957378070867878f, 0.5957763083121688f, 0.5958148081684879f, + 0.5958533066556563f, 0.5958918037735859f, 0.5959302995221881f, 0.5959687939013745f, + 0.5960072869110565f, 0.5960457785511458f, 0.5960842688215539f, 0.5961227577221923f, + 0.5961612452529725f, 0.5961997314138062f, 0.5962382162046049f, 0.5962766996252803f, + 0.5963151816757437f, 0.5963536623559069f, 0.5963921416656813f, 0.5964306196049786f, + 0.5964690961737104f, 0.5965075713717880f, 0.5965460451991234f, 0.5965845176556279f, + 0.5966229887412133f, 0.5966614584557910f, 0.5966999267992728f, 0.5967383937715700f, + 0.5967768593725944f, 0.5968153236022578f, 0.5968537864604715f, 0.5968922479471471f, + 0.5969307080621965f, 0.5969691668055311f, 0.5970076241770625f, 0.5970460801767026f, + 0.5970845348043627f, 0.5971229880599547f, 0.5971614399433899f, 0.5971998904545803f, + 0.5972383395934374f, 0.5972767873598729f, 0.5973152337537982f, 0.5973536787751254f, + 0.5973921224237657f, 0.5974305646996310f, 0.5974690056026328f, 0.5975074451326831f, + 0.5975458832896932f, 0.5975843200735750f, 0.5976227554842402f, 0.5976611895216002f, + 0.5976996221855668f, 0.5977380534760519f, 0.5977764833929670f, 0.5978149119362237f, + 0.5978533391057339f, 0.5978917649014092f, 0.5979301893231612f, 0.5979686123709018f, + 0.5980070340445427f, 0.5980454543439955f, 0.5980838732691718f, 0.5981222908199835f, + 0.5981607069963423f, 0.5981991217981598f, 0.5982375352253479f, 0.5982759472778183f, + 0.5983143579554826f, 0.5983527672582526f, 0.5983911751860401f, 0.5984295817387568f, + 0.5984679869163143f, 0.5985063907186245f, 0.5985447931455993f, 0.5985831941971501f, + 0.5986215938731889f, 0.5986599921736274f, 0.5986983890983774f, 0.5987367846473505f, + 0.5987751788204587f, 0.5988135716176137f, 0.5988519630387271f, 0.5988903530837110f, + 0.5989287417524769f, 0.5989671290449367f, 0.5990055149610021f, 0.5990438995005850f, + 0.5990822826635973f, 0.5991206644499505f, 0.5991590448595566f, 0.5991974238923274f, + 0.5992358015481746f, 0.5992741778270101f, 0.5993125527287457f, 0.5993509262532933f, + 0.5993892984005645f, 0.5994276691704713f, 0.5994660385629256f, 0.5995044065778389f, + 0.5995427732151234f, 0.5995811384746907f, 0.5996195023564527f, 0.5996578648603212f, + 0.5996962259862083f, 0.5997345857340255f, 0.5997729441036848f, 0.5998113010950982f, + 0.5998496567081772f, 0.5998880109428339f, 0.5999263637989803f, 0.5999647152765281f, + 0.6000030653753891f, 0.6000414140954752f, 0.6000797614366984f, 0.6001181073989704f, + 0.6001564519822032f, 0.6001947951863088f, 0.6002331370111990f, 0.6002714774567854f, + 0.6003098165229804f, 0.6003481542096956f, 0.6003864905168429f, 0.6004248254443343f, + 0.6004631589920816f, 0.6005014911599968f, 0.6005398219479918f, 0.6005781513559786f, + 0.6006164793838690f, 0.6006548060315748f, 0.6006931312990083f, 0.6007314551860811f, + 0.6007697776927052f, 0.6008080988187926f, 0.6008464185642554f, 0.6008847369290052f, + 0.6009230539129541f, 0.6009613695160141f, 0.6009996837380972f, 0.6010379965791153f, + 0.6010763080389802f, 0.6011146181176039f, 0.6011529268148987f, 0.6011912341307761f, + 0.6012295400651485f, 0.6012678446179276f, 0.6013061477890255f, 0.6013444495783541f, + 0.6013827499858254f, 0.6014210490113514f, 0.6014593466548441f, 0.6014976429162155f, + 0.6015359377953777f, 0.6015742312922424f, 0.6016125234067219f, 0.6016508141387281f, + 0.6016891034881731f, 0.6017273914549687f, 0.6017656780390270f, 0.6018039632402602f, + 0.6018422470585800f, 0.6018805294938988f, 0.6019188105461284f, 0.6019570902151807f, + 0.6019953685009680f, 0.6020336454034023f, 0.6020719209223956f, 0.6021101950578599f, + 0.6021484678097072f, 0.6021867391778497f, 0.6022250091621993f, 0.6022632777626683f, + 0.6023015449791685f, 0.6023398108116121f, 0.6023780752599112f, 0.6024163383239777f, + 0.6024546000037238f, 0.6024928602990615f, 0.6025311192099030f, 0.6025693767361603f, + 0.6026076328777454f, 0.6026458876345707f, 0.6026841410065480f, 0.6027223929935895f, + 0.6027606435956072f, 0.6027988928125133f, 0.6028371406442200f, 0.6028753870906391f, + 0.6029136321516830f, 0.6029518758272638f, 0.6029901181172935f, 0.6030283590216843f, + 0.6030665985403482f, 0.6031048366731975f, 0.6031430734201441f, 0.6031813087811004f, + 0.6032195427559784f, 0.6032577753446902f, 0.6032960065471481f, 0.6033342363632641f, + 0.6033724647929504f, 0.6034106918361191f, 0.6034489174926825f, 0.6034871417625526f, + 0.6035253646456415f, 0.6035635861418617f, 0.6036018062511251f, 0.6036400249733439f, + 0.6036782423084304f, 0.6037164582562966f, 0.6037546728168548f, 0.6037928859900171f, + 0.6038310977756959f, 0.6038693081738031f, 0.6039075171842511f, 0.6039457248069520f, + 0.6039839310418180f, 0.6040221358887614f, 0.6040603393476942f, 0.6040985414185289f, + 0.6041367421011775f, 0.6041749413955523f, 0.6042131393015655f, 0.6042513358191294f, + 0.6042895309481560f, 0.6043277246885578f, 0.6043659170402469f, 0.6044041080031355f, + 0.6044422975771359f, 0.6044804857621604f, 0.6045186725581211f, 0.6045568579649303f, + 0.6045950419825004f, 0.6046332246107434f, 0.6046714058495718f, 0.6047095856988977f, + 0.6047477641586334f, 0.6047859412286912f, 0.6048241169089833f, 0.6048622911994221f, + 0.6049004640999198f, 0.6049386356103886f, 0.6049768057307411f, 0.6050149744608893f, + 0.6050531418007454f, 0.6050913077502219f, 0.6051294723092311f, 0.6051676354776852f, + 0.6052057972554965f, 0.6052439576425774f, 0.6052821166388402f, 0.6053202742441971f, + 0.6053584304585605f, 0.6053965852818427f, 0.6054347387139561f, 0.6054728907548129f, + 0.6055110414043255f, 0.6055491906624062f, 0.6055873385289673f, 0.6056254850039213f, + 0.6056636300871804f, 0.6057017737786570f, 0.6057399160782633f, 0.6057780569859119f, + 0.6058161965015150f, 0.6058543346249849f, 0.6058924713562341f, 0.6059306066951750f, + 0.6059687406417197f, 0.6060068731957808f, 0.6060450043572708f, 0.6060831341261018f, + 0.6061212625021861f, 0.6061593894854365f, 0.6061975150757650f, 0.6062356392730842f, + 0.6062737620773064f, 0.6063118834883441f, 0.6063500035061096f, 0.6063881221305152f, + 0.6064262393614736f, 0.6064643551988970f, 0.6065024696426976f, 0.6065405826927883f, + 0.6065786943490813f, 0.6066168046114889f, 0.6066549134799237f, 0.6066930209542981f, + 0.6067311270345246f, 0.6067692317205152f, 0.6068073350121829f, 0.6068454369094398f, + 0.6068835374121985f, 0.6069216365203713f, 0.6069597342338710f, 0.6069978305526095f, + 0.6070359254764996f, 0.6070740190054539f, 0.6071121111393846f, 0.6071502018782041f, + 0.6071882912218252f, 0.6072263791701601f, 0.6072644657231213f, 0.6073025508806215f, + 0.6073406346425729f, 0.6073787170088881f, 0.6074167979794796f, 0.6074548775542600f, + 0.6074929557331415f, 0.6075310325160369f, 0.6075691079028587f, 0.6076071818935191f, + 0.6076452544879308f, 0.6076833256860064f, 0.6077213954876584f, 0.6077594638927991f, + 0.6077975309013411f, 0.6078355965131971f, 0.6078736607282795f, 0.6079117235465008f, + 0.6079497849677736f, 0.6079878449920105f, 0.6080259036191239f, 0.6080639608490264f, + 0.6081020166816304f, 0.6081400711168488f, 0.6081781241545938f, 0.6082161757947782f, + 0.6082542260373145f, 0.6082922748821150f, 0.6083303223290927f, 0.6083683683781599f, + 0.6084064130292293f, 0.6084444562822132f, 0.6084824981370246f, 0.6085205385935758f, + 0.6085585776517795f, 0.6085966153115481f, 0.6086346515727945f, 0.6086726864354309f, + 0.6087107198993703f, 0.6087487519645252f, 0.6087867826308080f, 0.6088248118981314f, + 0.6088628397664082f, 0.6089008662355507f, 0.6089388913054717f, 0.6089769149760840f, + 0.6090149372472998f, 0.6090529581190320f, 0.6090909775911932f, 0.6091289956636960f, + 0.6091670123364532f, 0.6092050276093771f, 0.6092430414823806f, 0.6092810539553764f, + 0.6093190650282768f, 0.6093570747009948f, 0.6093950829734429f, 0.6094330898455339f, + 0.6094710953171802f, 0.6095090993882948f, 0.6095471020587901f, 0.6095851033285788f, + 0.6096231031975737f, 0.6096611016656874f, 0.6096990987328327f, 0.6097370943989221f, + 0.6097750886638684f, 0.6098130815275843f, 0.6098510729899823f, 0.6098890630509753f, + 0.6099270517104761f, 0.6099650389683972f, 0.6100030248246513f, 0.6100410092791513f, + 0.6100789923318097f, 0.6101169739825393f, 0.6101549542312529f, 0.6101929330778630f, + 0.6102309105222826f, 0.6102688865644244f, 0.6103068612042009f, 0.6103448344415250f, + 0.6103828062763095f, 0.6104207767084670f, 0.6104587457379103f, 0.6104967133645521f, + 0.6105346795883053f, 0.6105726444090825f, 0.6106106078267965f, 0.6106485698413602f, + 0.6106865304526863f, 0.6107244896606874f, 0.6107624474652763f, 0.6108004038663660f, + 0.6108383588638692f, 0.6108763124576985f, 0.6109142646477669f, 0.6109522154339870f, + 0.6109901648162717f, 0.6110281127945338f, 0.6110660593686862f, 0.6111040045386416f, + 0.6111419483043126f, 0.6111798906656122f, 0.6112178316224534f, 0.6112557711747486f, + 0.6112937093224109f, 0.6113316460653532f, 0.6113695814034880f, 0.6114075153367283f, + 0.6114454478649870f, 0.6114833789881770f, 0.6115213087062108f, 0.6115592370190015f, + 0.6115971639264619f, 0.6116350894285048f, 0.6116730135250431f, 0.6117109362159897f, + 0.6117488575012574f, 0.6117867773807589f, 0.6118246958544074f, 0.6118626129221154f, + 0.6119005285837961f, 0.6119384428393621f, 0.6119763556887264f, 0.6120142671318018f, + 0.6120521771685015f, 0.6120900857987380f, 0.6121279930224244f, 0.6121658988394734f, + 0.6122038032497980f, 0.6122417062533112f, 0.6122796078499256f, 0.6123175080395545f, + 0.6123554068221106f, 0.6123933041975069f, 0.6124312001656561f, 0.6124690947264714f, + 0.6125069878798656f, 0.6125448796257514f, 0.6125827699640420f, 0.6126206588946504f, + 0.6126585464174893f, 0.6126964325324717f, 0.6127343172395107f, 0.6127722005385190f, + 0.6128100824294097f, 0.6128479629120958f, 0.6128858419864900f, 0.6129237196525055f, + 0.6129615959100552f, 0.6129994707590519f, 0.6130373441994089f, 0.6130752162310388f, + 0.6131130868538549f, 0.6131509560677699f, 0.6131888238726970f, 0.6132266902685490f, + 0.6132645552552390f, 0.6133024188326800f, 0.6133402810007850f, 0.6133781417594668f, + 0.6134160011086387f, 0.6134538590482134f, 0.6134917155781041f, 0.6135295706982238f, + 0.6135674244084853f, 0.6136052767088019f, 0.6136431275990866f, 0.6136809770792521f, + 0.6137188251492117f, 0.6137566718088785f, 0.6137945170581653f, 0.6138323608969852f, + 0.6138702033252513f, 0.6139080443428767f, 0.6139458839497742f, 0.6139837221458572f, + 0.6140215589310384f, 0.6140593943052310f, 0.6140972282683481f, 0.6141350608203028f, + 0.6141728919610080f, 0.6142107216903768f, 0.6142485500083223f, 0.6142863769147577f, + 0.6143242024095960f, 0.6143620264927501f, 0.6143998491641333f, 0.6144376704236586f, + 0.6144754902712390f, 0.6145133087067879f, 0.6145511257302181f, 0.6145889413414427f, + 0.6146267555403750f, 0.6146645683269280f, 0.6147023797010147f, 0.6147401896625484f, + 0.6147779982114421f, 0.6148158053476089f, 0.6148536110709620f, 0.6148914153814146f, + 0.6149292182788796f, 0.6149670197632702f, 0.6150048198344997f, 0.6150426184924811f, + 0.6150804157371276f, 0.6151182115683521f, 0.6151560059860681f, 0.6151937989901887f, + 0.6152315905806268f, 0.6152693807572958f, 0.6153071695201088f, 0.6153449568689788f, + 0.6153827428038192f, 0.6154205273245431f, 0.6154583104310637f, 0.6154960921232940f, + 0.6155338724011473f, 0.6155716512645369f, 0.6156094287133758f, 0.6156472047475773f, + 0.6156849793670546f, 0.6157227525717208f, 0.6157605243614891f, 0.6157982947362728f, + 0.6158360636959851f, 0.6158738312405390f, 0.6159115973698480f, 0.6159493620838252f, + 0.6159871253823838f, 0.6160248872654371f, 0.6160626477328982f, 0.6161004067846805f, + 0.6161381644206969f, 0.6161759206408610f, 0.6162136754450859f, 0.6162514288332848f, + 0.6162891808053710f, 0.6163269313612577f, 0.6163646805008582f, 0.6164024282240858f, + 0.6164401745308536f, 0.6164779194210750f, 0.6165156628946632f, 0.6165534049515314f, + 0.6165911455915931f, 0.6166288848147614f, 0.6166666226209496f, 0.6167043590100710f, + 0.6167420939820388f, 0.6167798275367664f, 0.6168175596741671f, 0.6168552903941541f, + 0.6168930196966407f, 0.6169307475815403f, 0.6169684740487662f, 0.6170061990982315f, + 0.6170439227298498f, 0.6170816449435341f, 0.6171193657391981f, 0.6171570851167547f, + 0.6171948030761176f, 0.6172325196171999f, 0.6172702347399149f, 0.6173079484441761f, + 0.6173456607298968f, 0.6173833715969903f, 0.6174210810453699f, 0.6174587890749490f, + 0.6174964956856409f, 0.6175342008773589f, 0.6175719046500165f, 0.6176096070035272f, + 0.6176473079378039f, 0.6176850074527603f, 0.6177227055483098f, 0.6177604022243656f, + 0.6177980974808410f, 0.6178357913176498f, 0.6178734837347049f, 0.6179111747319198f, + 0.6179488643092081f, 0.6179865524664832f, 0.6180242392036582f, 0.6180619245206467f, + 0.6180996084173620f, 0.6181372908937177f, 0.6181749719496269f, 0.6182126515850033f, + 0.6182503297997602f, 0.6182880065938109f, 0.6183256819670691f, 0.6183633559194480f, + 0.6184010284508611f, 0.6184386995612217f, 0.6184763692504435f, 0.6185140375184397f, + 0.6185517043651237f, 0.6185893697904093f, 0.6186270337942097f, 0.6186646963764383f, + 0.6187023575370085f, 0.6187400172758341f, 0.6187776755928283f, 0.6188153324879044f, + 0.6188529879609763f, 0.6188906420119572f, 0.6189282946407605f, 0.6189659458472999f, + 0.6190035956314887f, 0.6190412439932405f, 0.6190788909324686f, 0.6191165364490868f, + 0.6191541805430084f, 0.6191918232141468f, 0.6192294644624157f, 0.6192671042877285f, + 0.6193047426899987f, 0.6193423796691399f, 0.6193800152250655f, 0.6194176493576891f, + 0.6194552820669240f, 0.6194929133526840f, 0.6195305432148825f, 0.6195681716534331f, + 0.6196057986682493f, 0.6196434242592447f, 0.6196810484263326f, 0.6197186711694267f, + 0.6197562924884407f, 0.6197939123832878f, 0.6198315308538819f, 0.6198691479001364f, + 0.6199067635219647f, 0.6199443777192806f, 0.6199819904919976f, 0.6200196018400294f, + 0.6200572117632892f, 0.6200948202616908f, 0.6201324273351478f, 0.6201700329835739f, + 0.6202076372068824f, 0.6202452400049870f, 0.6202828413778014f, 0.6203204413252392f, + 0.6203580398472137f, 0.6203956369436389f, 0.6204332326144282f, 0.6204708268594951f, + 0.6205084196787534f, 0.6205460110721166f, 0.6205836010394983f, 0.6206211895808122f, + 0.6206587766959721f, 0.6206963623848913f, 0.6207339466474835f, 0.6207715294836625f, + 0.6208091108933419f, 0.6208466908764351f, 0.6208842694328560f, 0.6209218465625181f, + 0.6209594222653352f, 0.6209969965412209f, 0.6210345693900887f, 0.6210721408118525f, + 0.6211097108064256f, 0.6211472793737222f, 0.6211848465136556f, 0.6212224122261394f, + 0.6212599765110876f, 0.6212975393684137f, 0.6213351007980313f, 0.6213726607998542f, + 0.6214102193737961f, 0.6214477765197707f, 0.6214853322376915f, 0.6215228865274725f, + 0.6215604393890273f, 0.6215979908222693f, 0.6216355408271127f, 0.6216730894034709f, + 0.6217106365512578f, 0.6217481822703869f, 0.6217857265607720f, 0.6218232694223269f, + 0.6218608108549654f, 0.6218983508586010f, 0.6219358894331476f, 0.6219734265785190f, + 0.6220109622946286f, 0.6220484965813905f, 0.6220860294387184f, 0.6221235608665259f, + 0.6221610908647268f, 0.6221986194332351f, 0.6222361465719641f, 0.6222736722808280f, + 0.6223111965597403f, 0.6223487194086149f, 0.6223862408273655f, 0.6224237608159059f, + 0.6224612793741500f, 0.6224987965020113f, 0.6225363121994040f, 0.6225738264662415f, + 0.6226113393024377f, 0.6226488507079065f, 0.6226863606825618f, 0.6227238692263172f, + 0.6227613763390863f, 0.6227988820207835f, 0.6228363862713221f, 0.6228738890906161f, + 0.6229113904785795f, 0.6229488904351258f, 0.6229863889601690f, 0.6230238860536228f, + 0.6230613817154013f, 0.6230988759454181f, 0.6231363687435871f, 0.6231738601098222f, + 0.6232113500440373f, 0.6232488385461459f, 0.6232863256160623f, 0.6233238112537002f, + 0.6233612954589733f, 0.6233987782317957f, 0.6234362595720810f, 0.6234737394797434f, + 0.6235112179546964f, 0.6235486949968543f, 0.6235861706061306f, 0.6236236447824395f, + 0.6236611175256945f, 0.6236985888358099f, 0.6237360587126994f, 0.6237735271562768f, + 0.6238109941664561f, 0.6238484597431513f, 0.6238859238862762f, 0.6239233865957446f, + 0.6239608478714707f, 0.6239983077133682f, 0.6240357661213509f, 0.6240732230953331f, + 0.6241106786352285f, 0.6241481327409509f, 0.6241855854124145f, 0.6242230366495332f, + 0.6242604864522207f, 0.6242979348203911f, 0.6243353817539584f, 0.6243728272528366f, + 0.6244102713169393f, 0.6244477139461808f, 0.6244851551404751f, 0.6245225948997358f, + 0.6245600332238772f, 0.6245974701128132f, 0.6246349055664577f, 0.6246723395847246f, + 0.6247097721675281f, 0.6247472033147821f, 0.6247846330264003f, 0.6248220613022971f, + 0.6248594881423863f, 0.6248969135465819f, 0.6249343375147981f, 0.6249717600469485f, + 0.6250091811429476f, 0.6250466008027088f, 0.6250840190261466f, 0.6251214358131749f, + 0.6251588511637076f, 0.6251962650776589f, 0.6252336775549427f, 0.6252710885954731f, + 0.6253084981991640f, 0.6253459063659296f, 0.6253833130956837f, 0.6254207183883407f, + 0.6254581222438144f, 0.6254955246620187f, 0.6255329256428680f, 0.6255703251862762f, + 0.6256077232921574f, 0.6256451199604256f, 0.6256825151909948f, 0.6257199089837793f, + 0.6257573013386929f, 0.6257946922556498f, 0.6258320817345641f, 0.6258694697753499f, + 0.6259068563779211f, 0.6259442415421921f, 0.6259816252680768f, 0.6260190075554892f, + 0.6260563884043435f, 0.6260937678145539f, 0.6261311457860345f, 0.6261685223186990f, + 0.6262058974124621f, 0.6262432710672377f, 0.6262806432829398f, 0.6263180140594824f, + 0.6263553833967800f, 0.6263927512947465f, 0.6264301177532959f, 0.6264674827723428f, + 0.6265048463518008f, 0.6265422084915844f, 0.6265795691916076f, 0.6266169284517845f, + 0.6266542862720295f, 0.6266916426522563f, 0.6267289975923795f, 0.6267663510923132f, + 0.6268037031519712f, 0.6268410537712681f, 0.6268784029501179f, 0.6269157506884346f, + 0.6269530969861327f, 0.6269904418431261f, 0.6270277852593292f, 0.6270651272346561f, + 0.6271024677690209f, 0.6271398068623381f, 0.6271771445145213f, 0.6272144807254854f, + 0.6272518154951441f, 0.6272891488234119f, 0.6273264807102027f, 0.6273638111554311f, + 0.6274011401590111f, 0.6274384677208569f, 0.6274757938408827f, 0.6275131185190029f, + 0.6275504417551315f, 0.6275877635491830f, 0.6276250839010714f, 0.6276624028107112f, + 0.6276997202780162f, 0.6277370363029011f, 0.6277743508852800f, 0.6278116640250669f, + 0.6278489757221765f, 0.6278862859765229f, 0.6279235947880202f, 0.6279609021565826f, + 0.6279982080821247f, 0.6280355125645607f, 0.6280728156038046f, 0.6281101171997711f, + 0.6281474173523740f, 0.6281847160615279f, 0.6282220133271471f, 0.6282593091491459f, + 0.6282966035274384f, 0.6283338964619390f, 0.6283711879525621f, 0.6284084779992219f, + 0.6284457666018327f, 0.6284830537603089f, 0.6285203394745648f, 0.6285576237445145f, + 0.6285949065700726f, 0.6286321879511534f, 0.6286694678876711f, 0.6287067463795400f, + 0.6287440234266747f, 0.6287812990289894f, 0.6288185731863982f, 0.6288558458988158f, + 0.6288931171661565f, 0.6289303869883344f, 0.6289676553652640f, 0.6290049222968598f, + 0.6290421877830360f, 0.6290794518237068f, 0.6291167144187870f, 0.6291539755681907f, + 0.6291912352718323f, 0.6292284935296263f, 0.6292657503414869f, 0.6293030057073286f, + 0.6293402596270656f, 0.6293775121006127f, 0.6294147631278839f, 0.6294520127087937f, + 0.6294892608432566f, 0.6295265075311871f, 0.6295637527724993f, 0.6296009965671078f, + 0.6296382389149270f, 0.6296754798158714f, 0.6297127192698552f, 0.6297499572767929f, + 0.6297871938365992f, 0.6298244289491881f, 0.6298616626144744f, 0.6298988948323724f, + 0.6299361256027965f, 0.6299733549256612f, 0.6300105828008810f, 0.6300478092283701f, + 0.6300850342080432f, 0.6301222577398148f, 0.6301594798235992f, 0.6301967004593110f, + 0.6302339196468644f, 0.6302711373861742f, 0.6303083536771548f, 0.6303455685197205f, + 0.6303827819137859f, 0.6304199938592656f, 0.6304572043560739f, 0.6304944134041254f, + 0.6305316210033346f, 0.6305688271536160f, 0.6306060318548840f, 0.6306432351070531f, + 0.6306804369100379f, 0.6307176372637530f, 0.6307548361681128f, 0.6307920336230318f, + 0.6308292296284245f, 0.6308664241842056f, 0.6309036172902894f, 0.6309408089465905f, + 0.6309779991530235f, 0.6310151879095031f, 0.6310523752159435f, 0.6310895610722593f, + 0.6311267454783653f, 0.6311639284341759f, 0.6312011099396057f, 0.6312382899945690f, + 0.6312754685989808f, 0.6313126457527554f, 0.6313498214558073f, 0.6313869957080512f, + 0.6314241685094019f, 0.6314613398597734f, 0.6314985097590808f, 0.6315356782072385f, + 0.6315728452041611f, 0.6316100107497632f, 0.6316471748439594f, 0.6316843374866642f, + 0.6317214986777923f, 0.6317586584172583f, 0.6317958167049769f, 0.6318329735408625f, + 0.6318701289248299f, 0.6319072828567935f, 0.6319444353366683f, 0.6319815863643685f, + 0.6320187359398091f, 0.6320558840629044f, 0.6320930307335692f, 0.6321301759517182f, + 0.6321673197172659f, 0.6322044620301271f, 0.6322416028902162f, 0.6322787422974483f, + 0.6323158802517376f, 0.6323530167529989f, 0.6323901518011470f, 0.6324272853960965f, + 0.6324644175377618f, 0.6325015482260580f, 0.6325386774608995f, 0.6325758052422011f, + 0.6326129315698774f, 0.6326500564438432f, 0.6326871798640131f, 0.6327243018303018f, + 0.6327614223426240f, 0.6327985414008944f, 0.6328356590050277f, 0.6328727751549386f, + 0.6329098898505418f, 0.6329470030917521f, 0.6329841148784840f, 0.6330212252106525f, + 0.6330583340881721f, 0.6330954415109576f, 0.6331325474789239f, 0.6331696519919856f, + 0.6332067550500573f, 0.6332438566530538f, 0.6332809568008899f, 0.6333180554934804f, + 0.6333551527307399f, 0.6333922485125835f, 0.6334293428389255f, 0.6334664357096809f, + 0.6335035271247643f, 0.6335406170840907f, 0.6335777055875748f, 0.6336147926351312f, + 0.6336518782266749f, 0.6336889623621206f, 0.6337260450413829f, 0.6337631262643769f, + 0.6338002060310173f, 0.6338372843412187f, 0.6338743611948960f, 0.6339114365919641f, + 0.6339485105323378f, 0.6339855830159317f, 0.6340226540426608f, 0.6340597236124399f, + 0.6340967917251837f, 0.6341338583808072f, 0.6341709235792251f, 0.6342079873203522f, + 0.6342450496041033f, 0.6342821104303934f, 0.6343191697991373f, 0.6343562277102496f, + 0.6343932841636455f, 0.6344303391592396f, 0.6344673926969469f, 0.6345044447766820f, + 0.6345414953983600f, 0.6345785445618958f, 0.6346155922672040f, 0.6346526385141997f, + 0.6346896833027977f, 0.6347267266329129f, 0.6347637685044600f, 0.6348008089173541f, + 0.6348378478715101f, 0.6348748853668427f, 0.6349119214032668f, 0.6349489559806974f, + 0.6349859890990495f, 0.6350230207582377f, 0.6350600509581772f, 0.6350970796987827f, + 0.6351341069799692f, 0.6351711328016516f, 0.6352081571637449f, 0.6352451800661638f, + 0.6352822015088234f, 0.6353192214916387f, 0.6353562400145244f, 0.6353932570773956f, + 0.6354302726801672f, 0.6354672868227541f, 0.6355042995050711f, 0.6355413107270336f, + 0.6355783204885561f, 0.6356153287895537f, 0.6356523356299415f, 0.6356893410096344f, + 0.6357263449285472f, 0.6357633473865949f, 0.6358003483836926f, 0.6358373479197552f, + 0.6358743459946977f, 0.6359113426084351f, 0.6359483377608823f, 0.6359853314519543f, + 0.6360223236815663f, 0.6360593144496330f, 0.6360963037560696f, 0.6361332916007909f, + 0.6361702779837122f, 0.6362072629047483f, 0.6362442463638140f, 0.6362812283608248f, + 0.6363182088956955f, 0.6363551879683409f, 0.6363921655786764f, 0.6364291417266168f, + 0.6364661164120772f, 0.6365030896349725f, 0.6365400613952180f, 0.6365770316927285f, + 0.6366140005274191f, 0.6366509678992051f, 0.6366879338080011f, 0.6367248982537226f, + 0.6367618612362842f, 0.6367988227556014f, 0.6368357828115890f, 0.6368727414041621f, + 0.6369096985332359f, 0.6369466541987253f, 0.6369836084005455f, 0.6370205611386115f, + 0.6370575124128386f, 0.6370944622231416f, 0.6371314105694357f, 0.6371683574516359f, + 0.6372053028696576f, 0.6372422468234156f, 0.6372791893128251f, 0.6373161303378013f, + 0.6373530698982591f, 0.6373900079941138f, 0.6374269446252805f, 0.6374638797916743f, + 0.6375008134932102f, 0.6375377457298035f, 0.6375746765013693f, 0.6376116058078226f, + 0.6376485336490788f, 0.6376854600250528f, 0.6377223849356598f, 0.6377593083808150f, + 0.6377962303604335f, 0.6378331508744306f, 0.6378700699227211f, 0.6379069875052207f, + 0.6379439036218441f, 0.6379808182725066f, 0.6380177314571235f, 0.6380546431756099f, + 0.6380915534278809f, 0.6381284622138518f, 0.6381653695334376f, 0.6382022753865538f, + 0.6382391797731153f, 0.6382760826930375f, 0.6383129841462355f, 0.6383498841326245f, + 0.6383867826521196f, 0.6384236797046362f, 0.6384605752900895f, 0.6384974694083946f, + 0.6385343620594668f, 0.6385712532432213f, 0.6386081429595732f, 0.6386450312084380f, + 0.6386819179897307f, 0.6387188033033667f, 0.6387556871492611f, 0.6387925695273292f, + 0.6388294504374863f, 0.6388663298796475f, 0.6389032078537283f, 0.6389400843596438f, + 0.6389769593973091f, 0.6390138329666397f, 0.6390507050675509f, 0.6390875756999578f, + 0.6391244448637757f, 0.6391613125589199f, 0.6391981787853058f, 0.6392350435428485f, + 0.6392719068314635f, 0.6393087686510659f, 0.6393456290015710f, 0.6393824878828941f, + 0.6394193452949507f, 0.6394562012376559f, 0.6394930557109250f, 0.6395299087146733f, + 0.6395667602488163f, 0.6396036103132692f, 0.6396404589079473f, 0.6396773060327660f, + 0.6397141516876406f, 0.6397509958724862f, 0.6397878385872184f, 0.6398246798317526f, + 0.6398615196060039f, 0.6398983579098878f, 0.6399351947433197f, 0.6399720301062148f, + 0.6400088639984884f, 0.6400456964200562f, 0.6400825273708332f, 0.6401193568507347f, + 0.6401561848596765f, 0.6401930113975738f, 0.6402298364643417f, 0.6402666600598959f, + 0.6403034821841517f, 0.6403403028370244f, 0.6403771220184294f, 0.6404139397282822f, + 0.6404507559664981f, 0.6404875707329925f, 0.6405243840276809f, 0.6405611958504787f, + 0.6405980062013010f, 0.6406348150800636f, 0.6406716224866817f, 0.6407084284210710f, + 0.6407452328831464f, 0.6407820358728239f, 0.6408188373900185f, 0.6408556374346458f, + 0.6408924360066214f, 0.6409292331058604f, 0.6409660287322785f, 0.6410028228857909f, + 0.6410396155663134f, 0.6410764067737612f, 0.6411131965080498f, 0.6411499847690946f, + 0.6411867715568113f, 0.6412235568711150f, 0.6412603407119215f, 0.6412971230791461f, + 0.6413339039727044f, 0.6413706833925117f, 0.6414074613384836f, 0.6414442378105356f, + 0.6414810128085832f, 0.6415177863325418f, 0.6415545583823269f, 0.6415913289578541f, + 0.6416280980590388f, 0.6416648656857966f, 0.6417016318380431f, 0.6417383965156934f, + 0.6417751597186635f, 0.6418119214468687f, 0.6418486817002245f, 0.6418854404786464f, + 0.6419221977820502f, 0.6419589536103510f, 0.6419957079634647f, 0.6420324608413067f, + 0.6420692122437925f, 0.6421059621708377f, 0.6421427106223579f, 0.6421794575982687f, + 0.6422162030984854f, 0.6422529471229237f, 0.6422896896714994f, 0.6423264307441277f, + 0.6423631703407243f, 0.6423999084612049f, 0.6424366451054849f, 0.6424733802734799f, + 0.6425101139651057f, 0.6425468461802777f, 0.6425835769189114f, 0.6426203061809226f, + 0.6426570339662269f, 0.6426937602747398f, 0.6427304851063768f, 0.6427672084610536f, + 0.6428039303386860f, 0.6428406507391894f, 0.6428773696624794f, 0.6429140871084719f, + 0.6429508030770822f, 0.6429875175682259f, 0.6430242305818190f, 0.6430609421177769f, + 0.6430976521760151f, 0.6431343607564496f, 0.6431710678589957f, 0.6432077734835693f, + 0.6432444776300859f, 0.6432811802984612f, 0.6433178814886108f, 0.6433545812004504f, + 0.6433912794338958f, 0.6434279761888626f, 0.6434646714652663f, 0.6435013652630228f, + 0.6435380575820477f, 0.6435747484222567f, 0.6436114377835653f, 0.6436481256658896f, + 0.6436848120691449f, 0.6437214969932470f, 0.6437581804381116f, 0.6437948624036546f, + 0.6438315428897915f, 0.6438682218964380f, 0.6439048994235099f, 0.6439415754709229f, + 0.6439782500385927f, 0.6440149231264350f, 0.6440515947343656f, 0.6440882648623002f, + 0.6441249335101545f, 0.6441616006778443f, 0.6441982663652853f, 0.6442349305723931f, + 0.6442715932990838f, 0.6443082545452730f, 0.6443449143108761f, 0.6443815725958094f, + 0.6444182293999884f, 0.6444548847233288f, 0.6444915385657465f, 0.6445281909271572f, + 0.6445648418074768f, 0.6446014912066208f, 0.6446381391245053f, 0.6446747855610458f, + 0.6447114305161583f, 0.6447480739897586f, 0.6447847159817625f, 0.6448213564920856f, + 0.6448579955206437f, 0.6448946330673528f, 0.6449312691321287f, 0.6449679037148871f, + 0.6450045368155439f, 0.6450411684340149f, 0.6450777985702159f, 0.6451144272240626f, + 0.6451510543954712f, 0.6451876800843571f, 0.6452243042906364f, 0.6452609270142249f, + 0.6452975482550384f, 0.6453341680129926f, 0.6453707862880037f, 0.6454074030799873f, + 0.6454440183888593f, 0.6454806322145356f, 0.6455172445569320f, 0.6455538554159644f, + 0.6455904647915487f, 0.6456270726836008f, 0.6456636790920365f, 0.6457002840167716f, + 0.6457368874577223f, 0.6457734894148042f, 0.6458100898879332f, 0.6458466888770252f, + 0.6458832863819963f, 0.6459198824027623f, 0.6459564769392390f, 0.6459930699913423f, + 0.6460296615589883f, 0.6460662516420927f, 0.6461028402405716f, 0.6461394273543409f, + 0.6461760129833164f, 0.6462125971274140f, 0.6462491797865498f, 0.6462857609606397f, + 0.6463223406495995f, 0.6463589188533453f, 0.6463954955717930f, 0.6464320708048585f, + 0.6464686445524578f, 0.6465052168145069f, 0.6465417875909216f, 0.6465783568816180f, + 0.6466149246865120f, 0.6466514910055197f, 0.6466880558385568f, 0.6467246191855396f, + 0.6467611810463839f, 0.6467977414210058f, 0.6468343003093209f, 0.6468708577112458f, + 0.6469074136266960f, 0.6469439680555876f, 0.6469805209978368f, 0.6470170724533595f, + 0.6470536224220717f, 0.6470901709038892f, 0.6471267178987284f, 0.6471632634065051f, + 0.6471998074271352f, 0.6472363499605350f, 0.6472728910066204f, 0.6473094305653073f, + 0.6473459686365121f, 0.6473825052201504f, 0.6474190403161385f, 0.6474555739243923f, + 0.6474921060448281f, 0.6475286366773617f, 0.6475651658219091f, 0.6476016934783867f, + 0.6476382196467103f, 0.6476747443267959f, 0.6477112675185599f, 0.6477477892219180f, + 0.6477843094367866f, 0.6478208281630814f, 0.6478573454007188f, 0.6478938611496148f, + 0.6479303754096853f, 0.6479668881808468f, 0.6480033994630151f, 0.6480399092561063f, + 0.6480764175600365f, 0.6481129243747220f, 0.6481494297000787f, 0.6481859335360228f, + 0.6482224358824704f, 0.6482589367393377f, 0.6482954361065406f, 0.6483319339839955f, + 0.6483684303716183f, 0.6484049252693254f, 0.6484414186770325f, 0.6484779105946562f, + 0.6485144010221124f, 0.6485508899593173f, 0.6485873774061871f, 0.6486238633626379f, + 0.6486603478285859f, 0.6486968308039471f, 0.6487333122886380f, 0.6487697922825744f, + 0.6488062707856725f, 0.6488427477978488f, 0.6488792233190193f, 0.6489156973491000f, + 0.6489521698880073f, 0.6489886409356574f, 0.6490251104919664f, 0.6490615785568505f, + 0.6490980451302260f, 0.6491345102120090f, 0.6491709738021155f, 0.6492074359004621f, + 0.6492438965069649f, 0.6492803556215400f, 0.6493168132441037f, 0.6493532693745723f, + 0.6493897240128618f, 0.6494261771588885f, 0.6494626288125688f, 0.6494990789738189f, + 0.6495355276425547f, 0.6495719748186929f, 0.6496084205021496f, 0.6496448646928409f, + 0.6496813073906832f, 0.6497177485955927f, 0.6497541883074857f, 0.6497906265262784f, + 0.6498270632518871f, 0.6498634984842281f, 0.6498999322232176f, 0.6499363644687720f, + 0.6499727952208075f, 0.6500092244792404f, 0.6500456522439869f, 0.6500820785149634f, + 0.6501185032920862f, 0.6501549265752715f, 0.6501913483644357f, 0.6502277686594951f, + 0.6502641874603660f, 0.6503006047669646f, 0.6503370205792073f, 0.6503734348970105f, + 0.6504098477202903f, 0.6504462590489634f, 0.6504826688829457f, 0.6505190772221537f, + 0.6505554840665039f, 0.6505918894159125f, 0.6506282932702958f, 0.6506646956295702f, + 0.6507010964936520f, 0.6507374958624577f, 0.6507738937359034f, 0.6508102901139058f, + 0.6508466849963809f, 0.6508830783832453f, 0.6509194702744153f, 0.6509558606698074f, + 0.6509922495693377f, 0.6510286369729227f, 0.6510650228804790f, 0.6511014072919227f, + 0.6511377902071703f, 0.6511741716261382f, 0.6512105515487429f, 0.6512469299749006f, + 0.6512833069045277f, 0.6513196823375409f, 0.6513560562738564f, 0.6513924287133904f, + 0.6514287996560598f, 0.6514651691017807f, 0.6515015370504695f, 0.6515379035020429f, + 0.6515742684564170f, 0.6516106319135084f, 0.6516469938732335f, 0.6516833543355089f, + 0.6517197133002509f, 0.6517560707673760f, 0.6517924267368005f, 0.6518287812084411f, + 0.6518651341822140f, 0.6519014856580359f, 0.6519378356358231f, 0.6519741841154922f, + 0.6520105310969595f, 0.6520468765801417f, 0.6520832205649552f, 0.6521195630513162f, + 0.6521559040391416f, 0.6521922435283478f, 0.6522285815188511f, 0.6522649180105681f, + 0.6523012530034155f, 0.6523375864973094f, 0.6523739184921665f, 0.6524102489879036f, + 0.6524465779844367f, 0.6524829054816828f, 0.6525192314795579f, 0.6525555559779791f, + 0.6525918789768625f, 0.6526282004761248f, 0.6526645204756826f, 0.6527008389754523f, + 0.6527371559753503f, 0.6527734714752935f, 0.6528097854751984f, 0.6528460979749813f, + 0.6528824089745588f, 0.6529187184738477f, 0.6529550264727645f, 0.6529913329712255f, + 0.6530276379691475f, 0.6530639414664472f, 0.6531002434630407f, 0.6531365439588451f, + 0.6531728429537768f, 0.6532091404477522f, 0.6532454364406881f, 0.6532817309325011f, + 0.6533180239231077f, 0.6533543154124244f, 0.6533906054003681f, 0.6534268938868553f, + 0.6534631808718024f, 0.6534994663551261f, 0.6535357503367433f, 0.6535720328165704f, + 0.6536083137945239f, 0.6536445932705206f, 0.6536808712444772f, 0.6537171477163101f, + 0.6537534226859361f, 0.6537896961532719f, 0.6538259681182340f, 0.6538622385807390f, + 0.6538985075407038f, 0.6539347749980449f, 0.6539710409526789f, 0.6540073054045226f, + 0.6540435683534926f, 0.6540798297995056f, 0.6541160897424781f, 0.6541523481823271f, + 0.6541886051189690f, 0.6542248605523207f, 0.6542611144822986f, 0.6542973669088197f, + 0.6543336178318004f, 0.6543698672511578f, 0.6544061151668082f, 0.6544423615786685f, + 0.6544786064866553f, 0.6545148498906854f, 0.6545510917906756f, 0.6545873321865424f, + 0.6546235710782027f, 0.6546598084655731f, 0.6546960443485703f, 0.6547322787271113f, + 0.6547685116011126f, 0.6548047429704910f, 0.6548409728351632f, 0.6548772011950460f, + 0.6549134280500560f, 0.6549496534001102f, 0.6549858772451252f, 0.6550220995850179f, + 0.6550583204197049f, 0.6550945397491030f, 0.6551307575731290f, 0.6551669738916998f, + 0.6552031887047318f, 0.6552394020121423f, 0.6552756138138476f, 0.6553118241097647f, + 0.6553480328998105f, 0.6553842401839016f, 0.6554204459619550f, 0.6554566502338872f, + 0.6554928529996153f, 0.6555290542590561f, 0.6555652540121261f, 0.6556014522587424f, + 0.6556376489988218f, 0.6556738442322810f, 0.6557100379590369f, 0.6557462301790064f, + 0.6557824208921061f, 0.6558186100982530f, 0.6558547977973640f, 0.6558909839893559f, + 0.6559271686741454f, 0.6559633518516494f, 0.6559995335217850f, 0.6560357136844688f, + 0.6560718923396176f, 0.6561080694871486f, 0.6561442451269783f, 0.6561804192590238f, + 0.6562165918832019f, 0.6562527629994296f, 0.6562889326076234f, 0.6563251007077007f, + 0.6563612672995780f, 0.6563974323831724f, 0.6564335959584006f, 0.6564697580251797f, + 0.6565059185834266f, 0.6565420776330578f, 0.6565782351739908f, 0.6566143912061423f, + 0.6566505457294290f, 0.6566866987437681f, 0.6567228502490763f, 0.6567590002452707f, + 0.6567951487322681f, 0.6568312957099856f, 0.6568674411783398f, 0.6569035851372480f, + 0.6569397275866271f, 0.6569758685263939f, 0.6570120079564653f, 0.6570481458767584f, + 0.6570842822871902f, 0.6571204171876776f, 0.6571565505781374f, 0.6571926824584867f, + 0.6572288128286425f, 0.6572649416885219f, 0.6573010690380415f, 0.6573371948771187f, + 0.6573733192056703f, 0.6574094420236132f, 0.6574455633308645f, 0.6574816831273411f, + 0.6575178014129601f, 0.6575539181876385f, 0.6575900334512933f, 0.6576261472038415f, + 0.6576622594452001f, 0.6576983701752860f, 0.6577344793940164f, 0.6577705871013083f, + 0.6578066932970786f, 0.6578427979812446f, 0.6578789011537229f, 0.6579150028144309f, + 0.6579511029632855f, 0.6579872016002039f, 0.6580232987251028f, 0.6580593943378996f, + 0.6580954884385112f, 0.6581315810268547f, 0.6581676721028471f, 0.6582037616664055f, + 0.6582398497174470f, 0.6582759362558885f, 0.6583120212816475f, 0.6583481047946406f, + 0.6583841867947851f, 0.6584202672819981f, 0.6584563462561966f, 0.6584924237172978f, + 0.6585284996652186f, 0.6585645740998765f, 0.6586006470211883f, 0.6586367184290709f, + 0.6586727883234419f, 0.6587088567042181f, 0.6587449235713166f, 0.6587809889246548f, + 0.6588170527641495f, 0.6588531150897180f, 0.6588891759012773f, 0.6589252351987448f, + 0.6589612929820373f, 0.6589973492510722f, 0.6590334040057665f, 0.6590694572460375f, + 0.6591055089718021f, 0.6591415591829777f, 0.6591776078794814f, 0.6592136550612303f, + 0.6592497007281415f, 0.6592857448801324f, 0.6593217875171199f, 0.6593578286390213f, + 0.6593938682457539f, 0.6594299063372348f, 0.6594659429133809f, 0.6595019779741099f, + 0.6595380115193387f, 0.6595740435489845f, 0.6596100740629645f, 0.6596461030611960f, + 0.6596821305435961f, 0.6597181565100820f, 0.6597541809605711f, 0.6597902038949806f, + 0.6598262253132274f, 0.6598622452152290f, 0.6598982636009025f, 0.6599342804701653f, + 0.6599702958229345f, 0.6600063096591274f, 0.6600423219786612f, 0.6600783327814531f, + 0.6601143420674205f, 0.6601503498364805f, 0.6601863560885505f, 0.6602223608235475f, + 0.6602583640413890f, 0.6602943657419923f, 0.6603303659252745f, 0.6603663645911529f, + 0.6604023617395450f, 0.6604383573703678f, 0.6604743514835386f, 0.6605103440789750f, + 0.6605463351565939f, 0.6605823247163127f, 0.6606183127580489f, 0.6606542992817197f, + 0.6606902842872423f, 0.6607262677745340f, 0.6607622497435124f, 0.6607982301940944f, + 0.6608342091261976f, 0.6608701865397393f, 0.6609061624346366f, 0.6609421368108070f, + 0.6609781096681681f, 0.6610140810066368f, 0.6610500508261306f, 0.6610860191265668f, + 0.6611219859078629f, 0.6611579511699361f, 0.6611939149127039f, 0.6612298771360834f, + 0.6612658378399923f, 0.6613017970243475f, 0.6613377546890669f, 0.6613737108340676f, + 0.6614096654592669f, 0.6614456185645824f, 0.6614815701499313f, 0.6615175202152310f, + 0.6615534687603989f, 0.6615894157853526f, 0.6616253612900092f, 0.6616613052742861f, + 0.6616972477381010f, 0.6617331886813711f, 0.6617691281040139f, 0.6618050660059466f, + 0.6618410023870869f, 0.6618769372473520f, 0.6619128705866594f, 0.6619488024049266f, + 0.6619847327020709f, 0.6620206614780099f, 0.6620565887326608f, 0.6620925144659413f, + 0.6621284386777687f, 0.6621643613680605f, 0.6622002825367341f, 0.6622362021837070f, + 0.6622721203088966f, 0.6623080369122204f, 0.6623439519935959f, 0.6623798655529406f, + 0.6624157775901718f, 0.6624516881052070f, 0.6624875970979640f, 0.6625235045683598f, + 0.6625594105163123f, 0.6625953149417388f, 0.6626312178445568f, 0.6626671192246838f, + 0.6627030190820374f, 0.6627389174165350f, 0.6627748142280940f, 0.6628107095166321f, + 0.6628466032820669f, 0.6628824955243156f, 0.6629183862432959f, 0.6629542754389254f, + 0.6629901631111215f, 0.6630260492598017f, 0.6630619338848838f, 0.6630978169862850f, + 0.6631336985639230f, 0.6631695786177154f, 0.6632054571475797f, 0.6632413341534333f, + 0.6632772096351941f, 0.6633130835927794f, 0.6633489560261068f, 0.6633848269350938f, + 0.6634206963196583f, 0.6634565641797174f, 0.6634924305151890f, 0.6635282953259906f, + 0.6635641586120398f, 0.6636000203732542f, 0.6636358806095513f, 0.6636717393208487f, + 0.6637075965070641f, 0.6637434521681150f, 0.6637793063039192f, 0.6638151589143941f, + 0.6638510099994573f, 0.6638868595590266f, 0.6639227075930195f, 0.6639585541013537f, + 0.6639943990839466f, 0.6640302425407162f, 0.6640660844715798f, 0.6641019248764551f, + 0.6641377637552600f, 0.6641736011079118f, 0.6642094369343283f, 0.6642452712344272f, + 0.6642811040081262f, 0.6643169352553429f, 0.6643527649759947f, 0.6643885931699997f, + 0.6644244198372752f, 0.6644602449777390f, 0.6644960685913089f, 0.6645318906779025f, + 0.6645677112374375f, 0.6646035302698315f, 0.6646393477750023f, 0.6646751637528675f, + 0.6647109782033448f, 0.6647467911263520f, 0.6647826025218068f, 0.6648184123896267f, + 0.6648542207297297f, 0.6648900275420333f, 0.6649258328264553f, 0.6649616365829133f, + 0.6649974388113253f, 0.6650332395116089f, 0.6650690386836816f, 0.6651048363274614f, + 0.6651406324428661f, 0.6651764270298133f, 0.6652122200882206f, 0.6652480116180061f, + 0.6652838016190872f, 0.6653195900913819f, 0.6653553770348078f, 0.6653911624492829f, + 0.6654269463347247f, 0.6654627286910511f, 0.6654985095181798f, 0.6655342888160287f, + 0.6655700665845155f, 0.6656058428235579f, 0.6656416175330740f, 0.6656773907129812f, + 0.6657131623631976f, 0.6657489324836408f, 0.6657847010742287f, 0.6658204681348791f, + 0.6658562336655097f, 0.6658919976660385f, 0.6659277601363831f, 0.6659635210764615f, + 0.6659992804861915f, 0.6660350383654908f, 0.6660707947142774f, 0.6661065495324691f, + 0.6661423028199835f, 0.6661780545767387f, 0.6662138048026526f, 0.6662495534976429f, + 0.6662853006616273f, 0.6663210462945240f, 0.6663567903962506f, 0.6663925329667251f, + 0.6664282740058652f, 0.6664640135135891f, 0.6664997514898143f, 0.6665354879344588f, + 0.6665712228474406f, 0.6666069562286776f, 0.6666426880780874f, 0.6666784183955881f, + 0.6667141471810977f, 0.6667498744345338f, 0.6667856001558145f, 0.6668213243448576f, + 0.6668570470015812f, 0.6668927681259030f, 0.6669284877177412f, 0.6669642057770133f, + 0.6669999223036375f, 0.6670356372975317f, 0.6670713507586138f, 0.6671070626868016f, + 0.6671427730820133f, 0.6671784819441666f, 0.6672141892731797f, 0.6672498950689703f, + 0.6672855993314564f, 0.6673213020605561f, 0.6673570032561872f, 0.6673927029182677f, + 0.6674284010467155f, 0.6674640976414488f, 0.6674997927023854f, 0.6675354862294431f, + 0.6675711782225403f, 0.6676068686815946f, 0.6676425576065242f, 0.6676782449972470f, + 0.6677139308536811f, 0.6677496151757443f, 0.6677852979633548f, 0.6678209792164305f, + 0.6678566589348893f, 0.6678923371186495f, 0.6679280137676289f, 0.6679636888817455f, + 0.6679993624609174f, 0.6680350345050627f, 0.6680707050140993f, 0.6681063739879451f, + 0.6681420414265185f, 0.6681777073297372f, 0.6682133716975195f, 0.6682490345297832f, + 0.6682846958264467f, 0.6683203555874276f, 0.6683560138126442f, 0.6683916705020146f, + 0.6684273256554568f, 0.6684629792728889f, 0.6684986313542289f, 0.6685342818993949f, + 0.6685699309083050f, 0.6686055783808773f, 0.6686412243170299f, 0.6686768687166808f, + 0.6687125115797480f, 0.6687481529061499f, 0.6687837926958043f, 0.6688194309486295f, + 0.6688550676645436f, 0.6688907028434646f, 0.6689263364853106f, 0.6689619685899998f, + 0.6689975991574503f, 0.6690332281875802f, 0.6690688556803076f, 0.6691044816355507f, + 0.6691401060532276f, 0.6691757289332564f, 0.6692113502755553f, 0.6692469700800425f, + 0.6692825883466361f, 0.6693182050752541f, 0.6693538202658148f, 0.6693894339182364f, + 0.6694250460324369f, 0.6694606566083346f, 0.6694962656458477f, 0.6695318731448942f, + 0.6695674791053925f, 0.6696030835272606f, 0.6696386864104167f, 0.6696742877547790f, + 0.6697098875602658f, 0.6697454858267953f, 0.6697810825542854f, 0.6698166777426546f, + 0.6698522713918210f, 0.6698878635017029f, 0.6699234540722183f, 0.6699590431032857f, + 0.6699946305948231f, 0.6700302165467487f, 0.6700658009589809f, 0.6701013838314378f, + 0.6701369651640376f, 0.6701725449566989f, 0.6702081232093394f, 0.6702436999218777f, + 0.6702792750942318f, 0.6703148487263202f, 0.6703504208180611f, 0.6703859913693726f, + 0.6704215603801731f, 0.6704571278503808f, 0.6704926937799141f, 0.6705282581686910f, + 0.6705638210166300f, 0.6705993823236494f, 0.6706349420896672f, 0.6706705003146021f, + 0.6707060569983722f, 0.6707416121408956f, 0.6707771657420908f, 0.6708127178018761f, + 0.6708482683201697f, 0.6708838172968901f, 0.6709193647319553f, 0.6709549106252840f, + 0.6709904549767942f, 0.6710259977864044f, 0.6710615390540329f, 0.6710970787795978f, + 0.6711326169630177f, 0.6711681536042110f, 0.6712036887030958f, 0.6712392222595904f, + 0.6712747542736135f, 0.6713102847450831f, 0.6713458136739178f, 0.6713813410600357f, + 0.6714168669033554f, 0.6714523912037952f, 0.6714879139612733f, 0.6715234351757082f, + 0.6715589548470184f, 0.6715944729751221f, 0.6716299895599377f, 0.6716655046013837f, + 0.6717010180993783f, 0.6717365300538400f, 0.6717720404646874f, 0.6718075493318385f, + 0.6718430566552119f, 0.6718785624347261f, 0.6719140666702994f, 0.6719495693618501f, + 0.6719850705092969f, 0.6720205701125580f, 0.6720560681715519f, 0.6720915646861970f, + 0.6721270596564117f, 0.6721625530821146f, 0.6721980449632239f, 0.6722335352996582f, + 0.6722690240913359f, 0.6723045113381755f, 0.6723399970400954f, 0.6723754811970141f, + 0.6724109638088499f, 0.6724464448755214f, 0.6724819243969471f, 0.6725174023730455f, + 0.6725528788037347f, 0.6725883536889338f, 0.6726238270285608f, 0.6726592988225343f, + 0.6726947690707729f, 0.6727302377731950f, 0.6727657049297191f, 0.6728011705402637f, + 0.6728366346047473f, 0.6728720971230885f, 0.6729075580952055f, 0.6729430175210173f, + 0.6729784754004421f, 0.6730139317333984f, 0.6730493865198047f, 0.6730848397595798f, + 0.6731202914526421f, 0.6731557415989099f, 0.6731911901983020f, 0.6732266372507368f, + 0.6732620827561330f, 0.6732975267144090f, 0.6733329691254835f, 0.6733684099892749f, + 0.6734038493057017f, 0.6734392870746828f, 0.6734747232961366f, 0.6735101579699814f, + 0.6735455910961361f, 0.6735810226745191f, 0.6736164527050492f, 0.6736518811876446f, + 0.6736873081222243f, 0.6737227335087067f, 0.6737581573470104f, 0.6737935796370540f, + 0.6738290003787560f, 0.6738644195720352f, 0.6738998372168101f, 0.6739352533129994f, + 0.6739706678605216f, 0.6740060808592954f, 0.6740414923092394f, 0.6740769022102722f, + 0.6741123105623124f, 0.6741477173652787f, 0.6741831226190897f, 0.6742185263236641f, + 0.6742539284789204f, 0.6742893290847775f, 0.6743247281411539f, 0.6743601256479681f, + 0.6743955216051390f, 0.6744309160125852f, 0.6744663088702253f, 0.6745017001779781f, + 0.6745370899357620f, 0.6745724781434961f, 0.6746078648010986f, 0.6746432499084886f, + 0.6746786334655845f, 0.6747140154723051f, 0.6747493959285692f, 0.6747847748342953f, + 0.6748201521894022f, 0.6748555279938087f, 0.6748909022474333f, 0.6749262749501949f, + 0.6749616461020119f, 0.6749970157028036f, 0.6750323837524882f, 0.6750677502509845f, + 0.6751031151982114f, 0.6751384785940877f, 0.6751738404385319f, 0.6752092007314628f, + 0.6752445594727993f, 0.6752799166624599f, 0.6753152723003636f, 0.6753506263864290f, + 0.6753859789205748f, 0.6754213299027200f, 0.6754566793327831f, 0.6754920272106831f, + 0.6755273735363386f, 0.6755627183096684f, 0.6755980615305914f, 0.6756334031990263f, + 0.6756687433148919f, 0.6757040818781069f, 0.6757394188885903f, 0.6757747543462607f, + 0.6758100882510369f, 0.6758454206028379f, 0.6758807514015824f, 0.6759160806471891f, + 0.6759514083395770f, 0.6759867344786648f, 0.6760220590643713f, 0.6760573820966154f, + 0.6760927035753159f, 0.6761280235003918f, 0.6761633418717615f, 0.6761986586893444f, + 0.6762339739530590f, 0.6762692876628240f, 0.6763045998185586f, 0.6763399104201816f, + 0.6763752194676116f, 0.6764105269607678f, 0.6764458328995688f, 0.6764811372839337f, + 0.6765164401137811f, 0.6765517413890301f, 0.6765870411095994f, 0.6766223392754080f, + 0.6766576358863750f, 0.6766929309424188f, 0.6767282244434587f, 0.6767635163894133f, + 0.6767988067802018f, 0.6768340956157429f, 0.6768693828959554f, 0.6769046686207586f, + 0.6769399527900711f, 0.6769752354038120f, 0.6770105164619000f, 0.6770457959642543f, + 0.6770810739107936f, 0.6771163503014369f, 0.6771516251361032f, 0.6771868984147115f, + 0.6772221701371803f, 0.6772574403034293f, 0.6772927089133768f, 0.6773279759669421f, + 0.6773632414640439f, 0.6773985054046014f, 0.6774337677885336f, 0.6774690286157592f, + 0.6775042878861974f, 0.6775395455997671f, 0.6775748017563872f, 0.6776100563559768f, + 0.6776453093984549f, 0.6776805608837404f, 0.6777158108117523f, 0.6777510591824096f, + 0.6777863059956315f, 0.6778215512513367f, 0.6778567949494444f, 0.6778920370898734f, + 0.6779272776725430f, 0.6779625166973722f, 0.6779977541642798f, 0.6780329900731850f, + 0.6780682244240066f, 0.6781034572166639f, 0.6781386884510758f, 0.6781739181271614f, + 0.6782091462448399f, 0.6782443728040299f, 0.6782795978046510f, 0.6783148212466217f, + 0.6783500431298615f, 0.6783852634542893f, 0.6784204822198240f, 0.6784556994263850f, + 0.6784909150738911f, 0.6785261291622615f, 0.6785613416914154f, 0.6785965526612716f, + 0.6786317620717495f, 0.6786669699227678f, 0.6787021762142459f, 0.6787373809461029f, + 0.6787725841182577f, 0.6788077857306296f, 0.6788429857831376f, 0.6788781842757008f, + 0.6789133812082384f, 0.6789485765806695f, 0.6789837703929132f, 0.6790189626448886f, + 0.6790541533365149f, 0.6790893424677111f, 0.6791245300383965f, 0.6791597160484901f, + 0.6791949004979112f, 0.6792300833865789f, 0.6792652647144121f, 0.6793004444813303f, + 0.6793356226872526f, 0.6793707993320980f, 0.6794059744157858f, 0.6794411479382351f, + 0.6794763198993650f, 0.6795114902990949f, 0.6795466591373438f, 0.6795818264140310f, + 0.6796169921290756f, 0.6796521562823967f, 0.6796873188739138f, 0.6797224799035457f, + 0.6797576393712120f, 0.6797927972768317f, 0.6798279536203240f, 0.6798631084016081f, + 0.6798982616206033f, 0.6799334132772288f, 0.6799685633714037f, 0.6800037119030473f, + 0.6800388588720789f, 0.6800740042784178f, 0.6801091481219830f, 0.6801442904026940f, + 0.6801794311204699f, 0.6802145702752297f, 0.6802497078668932f, 0.6802848438953792f, + 0.6803199783606072f, 0.6803551112624965f, 0.6803902426009661f, 0.6804253723759355f, + 0.6804605005873239f, 0.6804956272350505f, 0.6805307523190348f, 0.6805658758391958f, + 0.6806009977954530f, 0.6806361181877257f, 0.6806712370159330f, 0.6807063542799944f, + 0.6807414699798291f, 0.6807765841153565f, 0.6808116966864957f, 0.6808468076931662f, + 0.6808819171352872f, 0.6809170250127782f, 0.6809521313255583f, 0.6809872360735471f, + 0.6810223392566637f, 0.6810574408748274f, 0.6810925409279578f, 0.6811276394159740f, + 0.6811627363387954f, 0.6811978316963414f, 0.6812329254885314f, 0.6812680177152846f, + 0.6813031083765205f, 0.6813381974721584f, 0.6813732850021178f, 0.6814083709663178f, + 0.6814434553646779f, 0.6814785381971176f, 0.6815136194635560f, 0.6815486991639129f, + 0.6815837772981075f, 0.6816188538660589f, 0.6816539288676869f, 0.6816890023029107f, + 0.6817240741716498f, 0.6817591444738235f, 0.6817942132093513f, 0.6818292803781526f, + 0.6818643459801467f, 0.6818994100152532f, 0.6819344724833915f, 0.6819695333844809f, + 0.6820045927184408f, 0.6820396504851909f, 0.6820747066846504f, 0.6821097613167387f, + 0.6821448143813756f, 0.6821798658784802f, 0.6822149158079721f, 0.6822499641697707f, + 0.6822850109637956f, 0.6823200561899661f, 0.6823550998482015f, 0.6823901419384217f, + 0.6824251824605461f, 0.6824602214144938f, 0.6824952588001846f, 0.6825302946175380f, + 0.6825653288664733f, 0.6826003615469101f, 0.6826353926587679f, 0.6826704222019663f, + 0.6827054501764246f, 0.6827404765820624f, 0.6827755014187993f, 0.6828105246865546f, + 0.6828455463852481f, 0.6828805665147991f, 0.6829155850751272f, 0.6829506020661519f, + 0.6829856174877927f, 0.6830206313399694f, 0.6830556436226012f, 0.6830906543356078f, + 0.6831256634789087f, 0.6831606710524235f, 0.6831956770560718f, 0.6832306814897730f, + 0.6832656843534468f, 0.6833006856470126f, 0.6833356853703902f, 0.6833706835234991f, + 0.6834056801062587f, 0.6834406751185889f, 0.6834756685604090f, 0.6835106604316387f, + 0.6835456507321975f, 0.6835806394620051f, 0.6836156266209812f, 0.6836506122090451f, + 0.6836855962261166f, 0.6837205786721153f, 0.6837555595469609f, 0.6837905388505728f, + 0.6838255165828707f, 0.6838604927437744f, 0.6838954673332033f, 0.6839304403510771f, + 0.6839654117973154f, 0.6840003816718380f, 0.6840353499745643f, 0.6840703167054142f, + 0.6841052818643071f, 0.6841402454511628f, 0.6841752074659009f, 0.6842101679084411f, + 0.6842451267787031f, 0.6842800840766065f, 0.6843150398020709f, 0.6843499939550161f, + 0.6843849465353617f, 0.6844198975430275f, 0.6844548469779331f, 0.6844897948399981f, + 0.6845247411291423f, 0.6845596858452854f, 0.6845946289883470f, 0.6846295705582470f, + 0.6846645105549050f, 0.6846994489782404f, 0.6847343858281735f, 0.6847693211046236f, + 0.6848042548075106f, 0.6848391869367542f, 0.6848741174922740f, 0.6849090464739899f, + 0.6849439738818215f, 0.6849788997156886f, 0.6850138239755109f, 0.6850487466612083f, + 0.6850836677727004f, 0.6851185873099069f, 0.6851535052727478f, 0.6851884216611426f, + 0.6852233364750112f, 0.6852582497142733f, 0.6852931613788488f, 0.6853280714686573f, + 0.6853629799836187f, 0.6853978869236528f, 0.6854327922886791f, 0.6854676960786179f, + 0.6855025982933886f, 0.6855374989329110f, 0.6855723979971052f, 0.6856072954858907f, + 0.6856421913991875f, 0.6856770857369152f, 0.6857119784989939f, 0.6857468696853433f, + 0.6857817592958830f, 0.6858166473305330f, 0.6858515337892134f, 0.6858864186718435f, + 0.6859213019783436f, 0.6859561837086333f, 0.6859910638626325f, 0.6860259424402609f, + 0.6860608194414387f, 0.6860956948660855f, 0.6861305687141210f, 0.6861654409854655f, + 0.6862003116800386f, 0.6862351807977601f, 0.6862700483385501f, 0.6863049143023283f, + 0.6863397786890146f, 0.6863746414985289f, 0.6864095027307912f, 0.6864443623857213f, + 0.6864792204632389f, 0.6865140769632643f, 0.6865489318857171f, 0.6865837852305172f, + 0.6866186369975846f, 0.6866534871868394f, 0.6866883357982012f, 0.6867231828315901f, + 0.6867580282869259f, 0.6867928721641287f, 0.6868277144631182f, 0.6868625551838146f, + 0.6868973943261376f, 0.6869322318900073f, 0.6869670678753435f, 0.6870019022820664f, + 0.6870367351100957f, 0.6870715663593513f, 0.6871063960297535f, 0.6871412241212220f, + 0.6871760506336768f, 0.6872108755670380f, 0.6872456989212254f, 0.6872805206961592f, + 0.6873153408917591f, 0.6873501595079452f, 0.6873849765446377f, 0.6874197920017562f, + 0.6874546058792210f, 0.6874894181769520f, 0.6875242288948692f, 0.6875590380328925f, + 0.6875938455909422f, 0.6876286515689380f, 0.6876634559668001f, 0.6876982587844485f, + 0.6877330600218032f, 0.6877678596787842f, 0.6878026577553116f, 0.6878374542513054f, + 0.6878722491666855f, 0.6879070425013722f, 0.6879418342552854f, 0.6879766244283453f, + 0.6880114130204716f, 0.6880462000315848f, 0.6880809854616046f, 0.6881157693104513f, + 0.6881505515780448f, 0.6881853322643053f, 0.6882201113691528f, 0.6882548888925075f, + 0.6882896648342893f, 0.6883244391944185f, 0.6883592119728149f, 0.6883939831693989f, + 0.6884287527840904f, 0.6884635208168097f, 0.6884982872674765f, 0.6885330521360115f, + 0.6885678154223343f, 0.6886025771263652f, 0.6886373372480243f, 0.6886720957872319f, + 0.6887068527439077f, 0.6887416081179724f, 0.6887763619093457f, 0.6888111141179479f, + 0.6888458647436990f, 0.6888806137865194f, 0.6889153612463291f, 0.6889501071230483f, + 0.6889848514165970f, 0.6890195941268956f, 0.6890543352538642f, 0.6890890747974227f, + 0.6891238127574916f, 0.6891585491339910f, 0.6891932839268409f, 0.6892280171359617f, + 0.6892627487612735f, 0.6892974788026963f, 0.6893322072601508f, 0.6893669341335567f, + 0.6894016594228344f, 0.6894363831279040f, 0.6894711052486858f, 0.6895058257851001f, + 0.6895405447370668f, 0.6895752621045066f, 0.6896099778873394f, 0.6896446920854853f, + 0.6896794046988648f, 0.6897141157273980f, 0.6897488251710052f, 0.6897835330296066f, + 0.6898182393031225f, 0.6898529439914730f, 0.6898876470945785f, 0.6899223486123592f, + 0.6899570485447354f, 0.6899917468916273f, 0.6900264436529551f, 0.6900611388286393f, + 0.6900958324186000f, 0.6901305244227574f, 0.6901652148410319f, 0.6901999036733438f, + 0.6902345909196134f, 0.6902692765797609f, 0.6903039606537067f, 0.6903386431413709f, + 0.6903733240426740f, 0.6904080033575364f, 0.6904426810858780f, 0.6904773572276195f, + 0.6905120317826811f, 0.6905467047509831f, 0.6905813761324459f, 0.6906160459269894f, + 0.6906507141345346f, 0.6906853807550015f, 0.6907200457883104f, 0.6907547092343816f, + 0.6907893710931357f, 0.6908240313644928f, 0.6908586900483733f, 0.6908933471446977f, + 0.6909280026533863f, 0.6909626565743593f, 0.6909973089075372f, 0.6910319596528404f, + 0.6910666088101892f, 0.6911012563795040f, 0.6911359023607053f, 0.6911705467537134f, + 0.6912051895584485f, 0.6912398307748312f, 0.6912744704027819f, 0.6913091084422209f, + 0.6913437448930687f, 0.6913783797552457f, 0.6914130130286722f, 0.6914476447132688f, + 0.6914822748089559f, 0.6915169033156536f, 0.6915515302332826f, 0.6915861555617634f, + 0.6916207793010163f, 0.6916554014509617f, 0.6916900220115201f, 0.6917246409826120f, + 0.6917592583641577f, 0.6917938741560778f, 0.6918284883582928f, 0.6918631009707229f, + 0.6918977119932888f, 0.6919323214259108f, 0.6919669292685096f, 0.6920015355210053f, + 0.6920361401833187f, 0.6920707432553703f, 0.6921053447370804f, 0.6921399446283695f, + 0.6921745429291581f, 0.6922091396393668f, 0.6922437347589160f, 0.6922783282877264f, + 0.6923129202257182f, 0.6923475105728121f, 0.6923820993289285f, 0.6924166864939880f, + 0.6924512720679112f, 0.6924858560506184f, 0.6925204384420304f, 0.6925550192420675f, + 0.6925895984506504f, 0.6926241760676994f, 0.6926587520931354f, 0.6926933265268786f, + 0.6927278993688498f, 0.6927624706189695f, 0.6927970402771582f, 0.6928316083433362f, + 0.6928661748174246f, 0.6929007396993437f, 0.6929353029890141f, 0.6929698646863562f, + 0.6930044247912909f, 0.6930389833037386f, 0.6930735402236198f, 0.6931080955508552f, + 0.6931426492853654f, 0.6931772014270710f, 0.6932117519758926f, 0.6932463009317508f, + 0.6932808482945660f, 0.6933153940642592f, 0.6933499382407509f, 0.6933844808239615f, + 0.6934190218138118f, 0.6934535612102224f, 0.6934880990131139f, 0.6935226352224070f, + 0.6935571698380223f, 0.6935917028598805f, 0.6936262342879020f, 0.6936607641220077f, + 0.6936952923621182f, 0.6937298190081542f, 0.6937643440600363f, 0.6937988675176850f, + 0.6938333893810213f, 0.6938679096499656f, 0.6939024283244387f, 0.6939369454043613f, + 0.6939714608896540f, 0.6940059747802375f, 0.6940404870760325f, 0.6940749977769598f, + 0.6941095068829398f, 0.6941440143938935f, 0.6941785203097416f, 0.6942130246304046f, + 0.6942475273558033f, 0.6942820284858585f, 0.6943165280204908f, 0.6943510259596209f, + 0.6943855223031697f, 0.6944200170510579f, 0.6944545102032060f, 0.6944890017595350f, + 0.6945234917199655f, 0.6945579800844184f, 0.6945924668528141f, 0.6946269520250737f, + 0.6946614356011178f, 0.6946959175808672f, 0.6947303979642427f, 0.6947648767511651f, + 0.6947993539415550f, 0.6948338295353331f, 0.6948683035324206f, 0.6949027759327379f, + 0.6949372467362058f, 0.6949717159427454f, 0.6950061835522773f, 0.6950406495647221f, + 0.6950751139800009f, 0.6951095767980343f, 0.6951440380187432f, 0.6951784976420484f, + 0.6952129556678708f, 0.6952474120961312f, 0.6952818669267501f, 0.6953163201596487f, + 0.6953507717947477f, 0.6953852218319679f, 0.6954196702712303f, 0.6954541171124555f, + 0.6954885623555644f, 0.6955230060004780f, 0.6955574480471171f, 0.6955918884954024f, + 0.6956263273452549f, 0.6956607645965954f, 0.6956952002493448f, 0.6957296343034240f, + 0.6957640667587537f, 0.6957984976152550f, 0.6958329268728488f, 0.6958673545314557f, + 0.6959017805909968f, 0.6959362050513930f, 0.6959706279125650f, 0.6960050491744340f, + 0.6960394688369207f, 0.6960738868999460f, 0.6961083033634309f, 0.6961427182272962f, + 0.6961771314914630f, 0.6962115431558520f, 0.6962459532203842f, 0.6962803616849806f, + 0.6963147685495622f, 0.6963491738140497f, 0.6963835774783642f, 0.6964179795424267f, + 0.6964523800061578f, 0.6964867788694789f, 0.6965211761323107f, 0.6965555717945742f, + 0.6965899658561904f, 0.6966243583170803f, 0.6966587491771646f, 0.6966931384363646f, + 0.6967275260946012f, 0.6967619121517953f, 0.6967962966078678f, 0.6968306794627399f, + 0.6968650607163325f, 0.6968994403685664f, 0.6969338184193630f, 0.6969681948686430f, + 0.6970025697163275f, 0.6970369429623374f, 0.6970713146065939f, 0.6971056846490179f, + 0.6971400530895304f, 0.6971744199280525f, 0.6972087851645052f, 0.6972431487988097f, + 0.6972775108308865f, 0.6973118712606572f, 0.6973462300880426f, 0.6973805873129637f, + 0.6974149429353418f, 0.6974492969550977f, 0.6974836493721525f, 0.6975180001864273f, + 0.6975523493978432f, 0.6975866970063213f, 0.6976210430117824f, 0.6976553874141479f, + 0.6976897302133388f, 0.6977240714092759f, 0.6977584110018807f, 0.6977927489910742f, + 0.6978270853767773f, 0.6978614201589112f, 0.6978957533373971f, 0.6979300849121558f, + 0.6979644148831087f, 0.6979987432501769f, 0.6980330700132814f, 0.6980673951723433f, + 0.6981017187272838f, 0.6981360406780240f, 0.6981703610244852f, 0.6982046797665882f, + 0.6982389969042543f, 0.6982733124374048f, 0.6983076263659604f, 0.6983419386898428f, + 0.6983762494089729f, 0.6984105585232717f, 0.6984448660326605f, 0.6984791719370607f, + 0.6985134762363931f, 0.6985477789305790f, 0.6985820800195396f, 0.6986163795031960f, + 0.6986506773814695f, 0.6986849736542813f, 0.6987192683215524f, 0.6987535613832042f, + 0.6987878528391577f, 0.6988221426893343f, 0.6988564309336551f, 0.6988907175720412f, + 0.6989250026044141f, 0.6989592860306948f, 0.6989935678508045f, 0.6990278480646646f, + 0.6990621266721961f, 0.6990964036733205f, 0.6991306790679587f, 0.6991649528560321f, + 0.6991992250374621f, 0.6992334956121696f, 0.6992677645800762f, 0.6993020319411030f, + 0.6993362976951712f, 0.6993705618422021f, 0.6994048243821170f, 0.6994390853148372f, + 0.6994733446402838f, 0.6995076023583783f, 0.6995418584690417f, 0.6995761129721955f, + 0.6996103658677610f, 0.6996446171556594f, 0.6996788668358120f, 0.6997131149081400f, + 0.6997473613725650f, 0.6997816062290080f, 0.6998158494773904f, 0.6998500911176335f, + 0.6998843311496588f, 0.6999185695733873f, 0.6999528063887405f, 0.6999870415956397f, + 0.7000212751940064f, 0.7000555071837615f, 0.7000897375648268f, 0.7001239663371235f, + 0.7001581935005727f, 0.7001924190550960f, 0.7002266430006148f, 0.7002608653370502f, + 0.7002950860643238f, 0.7003293051823568f, 0.7003635226910707f, 0.7003977385903868f, + 0.7004319528802264f, 0.7004661655605110f, 0.7005003766311619f, 0.7005345860921006f, + 0.7005687939432483f, 0.7006030001845267f, 0.7006372048158568f, 0.7006714078371602f, + 0.7007056092483585f, 0.7007398090493726f, 0.7007740072401244f, 0.7008082038205351f, + 0.7008423987905262f, 0.7008765921500190f, 0.7009107838989350f, 0.7009449740371957f, + 0.7009791625647224f, 0.7010133494814367f, 0.7010475347872598f, 0.7010817184821133f, + 0.7011159005659187f, 0.7011500810385973f, 0.7011842599000707f, 0.7012184371502602f, + 0.7012526127890875f, 0.7012867868164738f, 0.7013209592323406f, 0.7013551300366097f, + 0.7013892992292022f, 0.7014234668100398f, 0.7014576327790438f, 0.7014917971361359f, + 0.7015259598812374f, 0.7015601210142699f, 0.7015942805351550f, 0.7016284384438141f, + 0.7016625947401685f, 0.7016967494241400f, 0.7017309024956501f, 0.7017650539546202f, + 0.7017992038009717f, 0.7018333520346264f, 0.7018674986555058f, 0.7019016436635311f, + 0.7019357870586244f, 0.7019699288407067f, 0.7020040690096998f, 0.7020382075655254f, + 0.7020723445081046f, 0.7021064798373594f, 0.7021406135532111f, 0.7021747456555815f, + 0.7022088761443919f, 0.7022430050195638f, 0.7022771322810192f, 0.7023112579286793f, + 0.7023453819624659f, 0.7023795043823005f, 0.7024136251881046f, 0.7024477443798000f, + 0.7024818619573080f, 0.7025159779205504f, 0.7025500922694489f, 0.7025842050039249f, + 0.7026183161239001f, 0.7026524256292962f, 0.7026865335200346f, 0.7027206397960370f, + 0.7027547444572253f, 0.7027888475035208f, 0.7028229489348452f, 0.7028570487511202f, + 0.7028911469522674f, 0.7029252435382084f, 0.7029593385088651f, 0.7029934318641587f, + 0.7030275236040113f, 0.7030616137283443f, 0.7030957022370794f, 0.7031297891301383f, + 0.7031638744074428f, 0.7031979580689144f, 0.7032320401144747f, 0.7032661205440457f, + 0.7033001993575487f, 0.7033342765549057f, 0.7033683521360382f, 0.7034024261008679f, + 0.7034364984493167f, 0.7034705691813061f, 0.7035046382967579f, 0.7035387057955939f, + 0.7035727716777356f, 0.7036068359431048f, 0.7036408985916232f, 0.7036749596232126f, + 0.7037090190377948f, 0.7037430768352912f, 0.7037771330156241f, 0.7038111875787146f, + 0.7038452405244849f, 0.7038792918528566f, 0.7039133415637515f, 0.7039473896570912f, + 0.7039814361327976f, 0.7040154809907925f, 0.7040495242309976f, 0.7040835658533345f, + 0.7041176058577253f, 0.7041516442440917f, 0.7041856810123552f, 0.7042197161624379f, + 0.7042537496942615f, 0.7042877816077477f, 0.7043218119028184f, 0.7043558405793954f, + 0.7043898676374004f, 0.7044238930767552f, 0.7044579168973819f, 0.7044919390992020f, + 0.7045259596821375f, 0.7045599786461100f, 0.7045939959910416f, 0.7046280117168540f, + 0.7046620258234688f, 0.7046960383108083f, 0.7047300491787941f, 0.7047640584273480f, + 0.7047980660563919f, 0.7048320720658477f, 0.7048660764556373f, 0.7049000792256823f, + 0.7049340803759049f, 0.7049680799062268f, 0.7050020778165698f, 0.7050360741068558f, + 0.7050700687770068f, 0.7051040618269446f, 0.7051380532565911f, 0.7051720430658682f, + 0.7052060312546978f, 0.7052400178230017f, 0.7052740027707020f, 0.7053079860977204f, + 0.7053419678039790f, 0.7053759478893994f, 0.7054099263539039f, 0.7054439031974141f, + 0.7054778784198521f, 0.7055118520211399f, 0.7055458240011993f, 0.7055797943599521f, + 0.7056137630973205f, 0.7056477302132264f, 0.7056816957075915f, 0.7057156595803380f, + 0.7057496218313878f, 0.7057835824606629f, 0.7058175414680851f, 0.7058514988535765f, + 0.7058854546170590f, 0.7059194087584545f, 0.7059533612776853f, 0.7059873121746730f, + 0.7060212614493399f, 0.7060552091016076f, 0.7060891551313984f, 0.7061230995386343f, + 0.7061570423232371f, 0.7061909834851289f, 0.7062249230242318f, 0.7062588609404676f, + 0.7062927972337585f, 0.7063267319040264f, 0.7063606649511934f, 0.7063945963751815f, + 0.7064285261759128f, 0.7064624543533091f, 0.7064963809072927f, 0.7065303058377854f, + 0.7065642291447095f, 0.7065981508279869f, 0.7066320708875395f, 0.7066659893232897f, + 0.7066999061351594f, 0.7067338213230705f, 0.7067677348869452f, 0.7068016468267057f, + 0.7068355571422739f, 0.7068694658335718f, 0.7069033729005216f, 0.7069372783430455f, + 0.7069711821610654f, 0.7070050843545035f, 0.7070389849232818f, 0.7070728838673224f, + 0.7071067811865475f, 0.7071406768808792f, 0.7071745709502395f, 0.7072084633945506f, + 0.7072423542137346f, 0.7072762434077137f, 0.7073101309764098f, 0.7073440169197452f, + 0.7073779012376421f, 0.7074117839300225f, 0.7074456649968085f, 0.7074795444379224f, + 0.7075134222532863f, 0.7075472984428222f, 0.7075811730064524f, 0.7076150459440991f, + 0.7076489172556844f, 0.7076827869411303f, 0.7077166550003593f, 0.7077505214332933f, + 0.7077843862398546f, 0.7078182494199654f, 0.7078521109735478f, 0.7078859709005240f, + 0.7079198292008163f, 0.7079536858743468f, 0.7079875409210376f, 0.7080213943408111f, + 0.7080552461335895f, 0.7080890962992948f, 0.7081229448378494f, 0.7081567917491756f, + 0.7081906370331953f, 0.7082244806898309f, 0.7082583227190048f, 0.7082921631206390f, + 0.7083260018946559f, 0.7083598390409774f, 0.7083936745595263f, 0.7084275084502244f, + 0.7084613407129940f, 0.7084951713477576f, 0.7085290003544373f, 0.7085628277329553f, + 0.7085966534832341f, 0.7086304776051957f, 0.7086643000987625f, 0.7086981209638566f, + 0.7087319402004006f, 0.7087657578083166f, 0.7087995737875270f, 0.7088333881379539f, + 0.7088672008595198f, 0.7089010119521468f, 0.7089348214157574f, 0.7089686292502738f, + 0.7090024354556183f, 0.7090362400317132f, 0.7090700429784810f, 0.7091038442958438f, + 0.7091376439837239f, 0.7091714420420440f, 0.7092052384707260f, 0.7092390332696925f, + 0.7092728264388656f, 0.7093066179781680f, 0.7093404078875217f, 0.7093741961668493f, + 0.7094079828160730f, 0.7094417678351153f, 0.7094755512238983f, 0.7095093329823448f, + 0.7095431131103768f, 0.7095768916079167f, 0.7096106684748871f, 0.7096444437112102f, + 0.7096782173168085f, 0.7097119892916043f, 0.7097457596355200f, 0.7097795283484781f, + 0.7098132954304009f, 0.7098470608812107f, 0.7098808247008302f, 0.7099145868891816f, + 0.7099483474461874f, 0.7099821063717699f, 0.7100158636658518f, 0.7100496193283552f, + 0.7100833733592027f, 0.7101171257583168f, 0.7101508765256197f, 0.7101846256610340f, + 0.7102183731644822f, 0.7102521190358867f, 0.7102858632751698f, 0.7103196058822543f, + 0.7103533468570623f, 0.7103870861995165f, 0.7104208239095393f, 0.7104545599870531f, + 0.7104882944319805f, 0.7105220272442438f, 0.7105557584237658f, 0.7105894879704687f, + 0.7106232158842750f, 0.7106569421651074f, 0.7106906668128883f, 0.7107243898275400f, + 0.7107581112089854f, 0.7107918309571467f, 0.7108255490719465f, 0.7108592655533073f, + 0.7108929804011517f, 0.7109266936154022f, 0.7109604051959811f, 0.7109941151428114f, + 0.7110278234558153f, 0.7110615301349154f, 0.7110952351800341f, 0.7111289385910943f, + 0.7111626403680184f, 0.7111963405107287f, 0.7112300390191481f, 0.7112637358931990f, + 0.7112974311328040f, 0.7113311247378856f, 0.7113648167083666f, 0.7113985070441693f, + 0.7114321957452164f, 0.7114658828114305f, 0.7114995682427343f, 0.7115332520390500f, + 0.7115669342003007f, 0.7116006147264087f, 0.7116342936172967f, 0.7116679708728871f, + 0.7117016464931030f, 0.7117353204778665f, 0.7117689928271004f, 0.7118026635407274f, + 0.7118363326186701f, 0.7118700000608511f, 0.7119036658671929f, 0.7119373300376184f, + 0.7119709925720501f, 0.7120046534704106f, 0.7120383127326226f, 0.7120719703586089f, + 0.7121056263482919f, 0.7121392807015944f, 0.7121729334184391f, 0.7122065844987486f, + 0.7122402339424455f, 0.7122738817494526f, 0.7123075279196927f, 0.7123411724530880f, + 0.7123748153495617f, 0.7124084566090363f, 0.7124420962314344f, 0.7124757342166789f, + 0.7125093705646923f, 0.7125430052753975f, 0.7125766383487170f, 0.7126102697845736f, + 0.7126438995828902f, 0.7126775277435892f, 0.7127111542665935f, 0.7127447791518259f, + 0.7127784023992090f, 0.7128120240086655f, 0.7128456439801183f, 0.7128792623134900f, + 0.7129128790087034f, 0.7129464940656813f, 0.7129801074843464f, 0.7130137192646214f, + 0.7130473294064292f, 0.7130809379096925f, 0.7131145447743341f, 0.7131481500002766f, + 0.7131817535874431f, 0.7132153555357561f, 0.7132489558451385f, 0.7132825545155130f, + 0.7133161515468026f, 0.7133497469389298f, 0.7133833406918176f, 0.7134169328053889f, + 0.7134505232795663f, 0.7134841121142725f, 0.7135176993094307f, 0.7135512848649634f, + 0.7135848687807935f, 0.7136184510568440f, 0.7136520316930376f, 0.7136856106892970f, + 0.7137191880455451f, 0.7137527637617049f, 0.7137863378376993f, 0.7138199102734507f, + 0.7138534810688825f, 0.7138870502239172f, 0.7139206177384776f, 0.7139541836124870f, + 0.7139877478458678f, 0.7140213104385432f, 0.7140548713904358f, 0.7140884307014688f, + 0.7141219883715647f, 0.7141555444006467f, 0.7141890987886376f, 0.7142226515354602f, + 0.7142562026410375f, 0.7142897521052923f, 0.7143232999281477f, 0.7143568461095264f, + 0.7143903906493514f, 0.7144239335475456f, 0.7144574748040320f, 0.7144910144187334f, + 0.7145245523915729f, 0.7145580887224732f, 0.7145916234113574f, 0.7146251564581483f, + 0.7146586878627690f, 0.7146922176251425f, 0.7147257457451914f, 0.7147592722228390f, + 0.7147927970580081f, 0.7148263202506219f, 0.7148598418006029f, 0.7148933617078745f, + 0.7149268799723595f, 0.7149603965939808f, 0.7149939115726616f, 0.7150274249083246f, + 0.7150609366008930f, 0.7150944466502898f, 0.7151279550564379f, 0.7151614618192603f, + 0.7151949669386800f, 0.7152284704146201f, 0.7152619722470036f, 0.7152954724357534f, + 0.7153289709807926f, 0.7153624678820442f, 0.7153959631394312f, 0.7154294567528767f, + 0.7154629487223036f, 0.7154964390476353f, 0.7155299277287943f, 0.7155634147657040f, + 0.7155969001582874f, 0.7156303839064675f, 0.7156638660101673f, 0.7156973464693100f, + 0.7157308252838187f, 0.7157643024536162f, 0.7157977779786259f, 0.7158312518587706f, + 0.7158647240939734f, 0.7158981946841576f, 0.7159316636292462f, 0.7159651309291621f, + 0.7159985965838287f, 0.7160320605931689f, 0.7160655229571058f, 0.7160989836755626f, + 0.7161324427484623f, 0.7161659001757281f, 0.7161993559572830f, 0.7162328100930504f, + 0.7162662625829531f, 0.7162997134269145f, 0.7163331626248574f, 0.7163666101767052f, + 0.7164000560823810f, 0.7164335003418079f, 0.7164669429549090f, 0.7165003839216075f, + 0.7165338232418266f, 0.7165672609154895f, 0.7166006969425192f, 0.7166341313228389f, + 0.7166675640563719f, 0.7167009951430413f, 0.7167344245827703f, 0.7167678523754819f, + 0.7168012785210995f, 0.7168347030195462f, 0.7168681258707452f, 0.7169015470746198f, + 0.7169349666310931f, 0.7169683845400884f, 0.7170018008015286f, 0.7170352154153372f, + 0.7170686283814375f, 0.7171020396997524f, 0.7171354493702053f, 0.7171688573927195f, + 0.7172022637672182f, 0.7172356684936244f, 0.7172690715718616f, 0.7173024730018530f, + 0.7173358727835217f, 0.7173692709167911f, 0.7174026674015844f, 0.7174360622378249f, + 0.7174694554254358f, 0.7175028469643404f, 0.7175362368544620f, 0.7175696250957238f, + 0.7176030116880491f, 0.7176363966313611f, 0.7176697799255832f, 0.7177031615706387f, + 0.7177365415664508f, 0.7177699199129429f, 0.7178032966100382f, 0.7178366716576601f, + 0.7178700450557317f, 0.7179034168041766f, 0.7179367869029178f, 0.7179701553518789f, + 0.7180035221509831f, 0.7180368873001538f, 0.7180702507993142f, 0.7181036126483876f, + 0.7181369728472975f, 0.7181703313959672f, 0.7182036882943200f, 0.7182370435422792f, + 0.7182703971397683f, 0.7183037490867105f, 0.7183370993830291f, 0.7183704480286478f, + 0.7184037950234897f, 0.7184371403674783f, 0.7184704840605367f, 0.7185038261025887f, + 0.7185371664935574f, 0.7185705052333661f, 0.7186038423219384f, 0.7186371777591977f, + 0.7186705115450673f, 0.7187038436794706f, 0.7187371741623310f, 0.7187705029935720f, + 0.7188038301731169f, 0.7188371557008891f, 0.7188704795768123f, 0.7189038018008095f, + 0.7189371223728044f, 0.7189704412927205f, 0.7190037585604809f, 0.7190370741760093f, + 0.7190703881392292f, 0.7191037004500638f, 0.7191370111084366f, 0.7191703201142714f, + 0.7192036274674912f, 0.7192369331680197f, 0.7192702372157803f, 0.7193035396106965f, + 0.7193368403526919f, 0.7193701394416896f, 0.7194034368776134f, 0.7194367326603868f, + 0.7194700267899330f, 0.7195033192661758f, 0.7195366100890386f, 0.7195698992584448f, + 0.7196031867743180f, 0.7196364726365818f, 0.7196697568451595f, 0.7197030393999747f, + 0.7197363203009510f, 0.7197695995480118f, 0.7198028771410806f, 0.7198361530800812f, + 0.7198694273649369f, 0.7199026999955712f, 0.7199359709719076f, 0.7199692402938700f, + 0.7200025079613817f, 0.7200357739743661f, 0.7200690383327470f, 0.7201023010364479f, + 0.7201355620853924f, 0.7201688214795039f, 0.7202020792187063f, 0.7202353353029228f, + 0.7202685897320771f, 0.7203018425060930f, 0.7203350936248938f, 0.7203683430884031f, + 0.7204015908965448f, 0.7204348370492422f, 0.7204680815464191f, 0.7205013243879987f, + 0.7205345655739053f, 0.7205678051040619f, 0.7206010429783923f, 0.7206342791968203f, + 0.7206675137592694f, 0.7207007466656633f, 0.7207339779159253f, 0.7207672075099795f, + 0.7208004354477493f, 0.7208336617291583f, 0.7208668863541302f, 0.7209001093225887f, + 0.7209333306344575f, 0.7209665502896602f, 0.7209997682881204f, 0.7210329846297618f, + 0.7210661993145081f, 0.7210994123422829f, 0.7211326237130101f, 0.7211658334266130f, + 0.7211990414830157f, 0.7212322478821417f, 0.7212654526239145f, 0.7212986557082582f, + 0.7213318571350962f, 0.7213650569043524f, 0.7213982550159502f, 0.7214314514698137f, + 0.7214646462658664f, 0.7214978394040319f, 0.7215310308842342f, 0.7215642207063969f, + 0.7215974088704438f, 0.7216305953762984f, 0.7216637802238848f, 0.7216969634131265f, + 0.7217301449439472f, 0.7217633248162708f, 0.7217965030300211f, 0.7218296795851216f, + 0.7218628544814963f, 0.7218960277190689f, 0.7219291992977632f, 0.7219623692175029f, + 0.7219955374782119f, 0.7220287040798138f, 0.7220618690222325f, 0.7220950323053917f, + 0.7221281939292153f, 0.7221613538936271f, 0.7221945121985508f, 0.7222276688439103f, + 0.7222608238296294f, 0.7222939771556318f, 0.7223271288218415f, 0.7223602788281821f, + 0.7223934271745776f, 0.7224265738609517f, 0.7224597188872284f, 0.7224928622533313f, + 0.7225260039591844f, 0.7225591440047117f, 0.7225922823898366f, 0.7226254191144833f, + 0.7226585541785756f, 0.7226916875820373f, 0.7227248193247923f, 0.7227579494067644f, + 0.7227910778278775f, 0.7228242045880555f, 0.7228573296872223f, 0.7228904531253018f, + 0.7229235749022177f, 0.7229566950178939f, 0.7229898134722547f, 0.7230229302652235f, + 0.7230560453967245f, 0.7230891588666813f, 0.7231222706750183f, 0.7231553808216590f, + 0.7231884893065273f, 0.7232215961295475f, 0.7232547012906432f, 0.7232878047897383f, + 0.7233209066267569f, 0.7233540068016229f, 0.7233871053142602f, 0.7234202021645926f, + 0.7234532973525444f, 0.7234863908780392f, 0.7235194827410011f, 0.7235525729413541f, + 0.7235856614790220f, 0.7236187483539290f, 0.7236518335659989f, 0.7236849171151558f, + 0.7237179990013235f, 0.7237510792244261f, 0.7237841577843874f, 0.7238172346811318f, + 0.7238503099145829f, 0.7238833834846647f, 0.7239164553913016f, 0.7239495256344172f, + 0.7239825942139355f, 0.7240156611297808f, 0.7240487263818769f, 0.7240817899701479f, + 0.7241148518945179f, 0.7241479121549106f, 0.7241809707512504f, 0.7242140276834611f, + 0.7242470829514669f, 0.7242801365551917f, 0.7243131884945596f, 0.7243462387694948f, + 0.7243792873799211f, 0.7244123343257627f, 0.7244453796069436f, 0.7244784232233878f, + 0.7245114651750196f, 0.7245445054617629f, 0.7245775440835417f, 0.7246105810402803f, + 0.7246436163319026f, 0.7246766499583327f, 0.7247096819194949f, 0.7247427122153129f, + 0.7247757408457113f, 0.7248087678106138f, 0.7248417931099447f, 0.7248748167436279f, + 0.7249078387115878f, 0.7249408590137484f, 0.7249738776500336f, 0.7250068946203679f, + 0.7250399099246754f, 0.7250729235628799f, 0.7251059355349057f, 0.7251389458406770f, + 0.7251719544801180f, 0.7252049614531526f, 0.7252379667597052f, 0.7252709703996999f, + 0.7253039723730607f, 0.7253369726797120f, 0.7253699713195778f, 0.7254029682925824f, + 0.7254359635986498f, 0.7254689572377043f, 0.7255019492096701f, 0.7255349395144713f, + 0.7255679281520323f, 0.7256009151222770f, 0.7256339004251298f, 0.7256668840605146f, + 0.7256998660283561f, 0.7257328463285782f, 0.7257658249611050f, 0.7257988019258610f, + 0.7258317772227704f, 0.7258647508517571f, 0.7258977228127457f, 0.7259306931056602f, + 0.7259636617304249f, 0.7259966286869641f, 0.7260295939752021f, 0.7260625575950629f, + 0.7260955195464709f, 0.7261284798293505f, 0.7261614384436257f, 0.7261943953892208f, + 0.7262273506660603f, 0.7262603042740683f, 0.7262932562131690f, 0.7263262064832868f, + 0.7263591550843460f, 0.7263921020162708f, 0.7264250472789855f, 0.7264579908724144f, + 0.7264909327964819f, 0.7265238730511122f, 0.7265568116362295f, 0.7265897485517584f, + 0.7266226837976230f, 0.7266556173737475f, 0.7266885492800566f, 0.7267214795164743f, + 0.7267544080829249f, 0.7267873349793330f, 0.7268202602056228f, 0.7268531837617187f, + 0.7268861056475450f, 0.7269190258630259f, 0.7269519444080860f, 0.7269848612826494f, + 0.7270177764866407f, 0.7270506900199841f, 0.7270836018826041f, 0.7271165120744248f, + 0.7271494205953710f, 0.7271823274453668f, 0.7272152326243365f, 0.7272481361322047f, + 0.7272810379688958f, 0.7273139381343340f, 0.7273468366284438f, 0.7273797334511496f, + 0.7274126286023758f, 0.7274455220820467f, 0.7274784138900871f, 0.7275113040264208f, + 0.7275441924909728f, 0.7275770792836672f, 0.7276099644044285f, 0.7276428478531811f, + 0.7276757296298496f, 0.7277086097343582f, 0.7277414881666315f, 0.7277743649265940f, + 0.7278072400141700f, 0.7278401134292839f, 0.7278729851718604f, 0.7279058552418237f, + 0.7279387236390986f, 0.7279715903636093f, 0.7280044554152802f, 0.7280373187940361f, + 0.7280701804998012f, 0.7281030405325001f, 0.7281358988920573f, 0.7281687555783973f, + 0.7282016105914445f, 0.7282344639311236f, 0.7282673155973589f, 0.7283001655900750f, + 0.7283330139091964f, 0.7283658605546476f, 0.7283987055263531f, 0.7284315488242374f, + 0.7284643904482252f, 0.7284972303982409f, 0.7285300686742090f, 0.7285629052760541f, + 0.7285957402037008f, 0.7286285734570735f, 0.7286614050360969f, 0.7286942349406954f, + 0.7287270631707937f, 0.7287598897263163f, 0.7287927146071879f, 0.7288255378133328f, + 0.7288583593446758f, 0.7288911792011413f, 0.7289239973826540f, 0.7289568138891386f, + 0.7289896287205193f, 0.7290224418767212f, 0.7290552533576685f, 0.7290880631632860f, + 0.7291208712934982f, 0.7291536777482298f, 0.7291864825274055f, 0.7292192856309495f, + 0.7292520870587870f, 0.7292848868108421f, 0.7293176848870397f, 0.7293504812873045f, + 0.7293832760115611f, 0.7294160690597339f, 0.7294488604317476f, 0.7294816501275272f, + 0.7295144381469970f, 0.7295472244900818f, 0.7295800091567062f, 0.7296127921467949f, + 0.7296455734602725f, 0.7296783530970637f, 0.7297111310570933f, 0.7297439073402859f, + 0.7297766819465660f, 0.7298094548758586f, 0.7298422261280881f, 0.7298749957031794f, + 0.7299077636010571f, 0.7299405298216459f, 0.7299732943648706f, 0.7300060572306557f, + 0.7300388184189261f, 0.7300715779296066f, 0.7301043357626217f, 0.7301370919178962f, + 0.7301698463953549f, 0.7302025991949223f, 0.7302353503165234f, 0.7302680997600829f, + 0.7303008475255255f, 0.7303335936127758f, 0.7303663380217588f, 0.7303990807523991f, + 0.7304318218046215f, 0.7304645611783508f, 0.7304972988735118f, 0.7305300348900290f, + 0.7305627692278276f, 0.7305955018868320f, 0.7306282328669672f, 0.7306609621681579f, + 0.7306936897903289f, 0.7307264157334050f, 0.7307591399973110f, 0.7307918625819718f, + 0.7308245834873121f, 0.7308573027132567f, 0.7308900202597303f, 0.7309227361266579f, + 0.7309554503139644f, 0.7309881628215744f, 0.7310208736494128f, 0.7310535827974045f, + 0.7310862902654742f, 0.7311189960535470f, 0.7311517001615475f, 0.7311844025894007f, + 0.7312171033370312f, 0.7312498024043641f, 0.7312824997913243f, 0.7313151954978364f, + 0.7313478895238255f, 0.7313805818692164f, 0.7314132725339340f, 0.7314459615179030f, + 0.7314786488210485f, 0.7315113344432953f, 0.7315440183845683f, 0.7315767006447924f, + 0.7316093812238925f, 0.7316420601217936f, 0.7316747373384204f, 0.7317074128736979f, + 0.7317400867275511f, 0.7317727588999047f, 0.7318054293906838f, 0.7318380981998134f, + 0.7318707653272183f, 0.7319034307728234f, 0.7319360945365537f, 0.7319687566183340f, + 0.7320014170180895f, 0.7320340757357451f, 0.7320667327712256f, 0.7320993881244560f, + 0.7321320417953613f, 0.7321646937838665f, 0.7321973440898963f, 0.7322299927133762f, + 0.7322626396542307f, 0.7322952849123849f, 0.7323279284877640f, 0.7323605703802927f, + 0.7323932105898960f, 0.7324258491164991f, 0.7324584859600269f, 0.7324911211204045f, + 0.7325237545975566f, 0.7325563863914086f, 0.7325890165018852f, 0.7326216449289117f, + 0.7326542716724128f, 0.7326868967323138f, 0.7327195201085396f, 0.7327521418010152f, + 0.7327847618096658f, 0.7328173801344162f, 0.7328499967751917f, 0.7328826117319172f, + 0.7329152250045178f, 0.7329478365929185f, 0.7329804464970443f, 0.7330130547168205f, + 0.7330456612521720f, 0.7330782661030238f, 0.7331108692693012f, 0.7331434707509292f, + 0.7331760705478328f, 0.7332086686599371f, 0.7332412650871671f, 0.7332738598294483f, + 0.7333064528867053f, 0.7333390442588634f, 0.7333716339458478f, 0.7334042219475835f, + 0.7334368082639957f, 0.7334693928950095f, 0.7335019758405499f, 0.7335345571005421f, + 0.7335671366749114f, 0.7335997145635826f, 0.7336322907664811f, 0.7336648652835319f, + 0.7336974381146603f, 0.7337300092597913f, 0.7337625787188501f, 0.7337951464917618f, + 0.7338277125784518f, 0.7338602769788449f, 0.7338928396928666f, 0.7339254007204419f, + 0.7339579600614959f, 0.7339905177159540f, 0.7340230736837413f, 0.7340556279647830f, + 0.7340881805590040f, 0.7341207314663299f, 0.7341532806866858f, 0.7341858282199968f, + 0.7342183740661882f, 0.7342509182251852f, 0.7342834606969130f, 0.7343160014812966f, + 0.7343485405782616f, 0.7343810779877330f, 0.7344136137096361f, 0.7344461477438962f, + 0.7344786800904384f, 0.7345112107491879f, 0.7345437397200701f, 0.7345762670030103f, + 0.7346087925979337f, 0.7346413165047653f, 0.7346738387234306f, 0.7347063592538550f, + 0.7347388780959634f, 0.7347713952496815f, 0.7348039107149342f, 0.7348364244916470f, + 0.7348689365797451f, 0.7349014469791538f, 0.7349339556897985f, 0.7349664627116043f, + 0.7349989680444966f, 0.7350314716884008f, 0.7350639736432421f, 0.7350964739089457f, + 0.7351289724854372f, 0.7351614693726417f, 0.7351939645704846f, 0.7352264580788912f, + 0.7352589498977868f, 0.7352914400270968f, 0.7353239284667467f, 0.7353564152166615f, + 0.7353889002767666f, 0.7354213836469877f, 0.7354538653272499f, 0.7354863453174785f, + 0.7355188236175989f, 0.7355513002275366f, 0.7355837751472167f, 0.7356162483765649f, + 0.7356487199155064f, 0.7356811897639667f, 0.7357136579218710f, 0.7357461243891448f, + 0.7357785891657135f, 0.7358110522515026f, 0.7358435136464371f, 0.7358759733504429f, + 0.7359084313634452f, 0.7359408876853692f, 0.7359733423161408f, 0.7360057952556850f, + 0.7360382465039275f, 0.7360706960607933f, 0.7361031439262085f, 0.7361355901000980f, + 0.7361680345823873f, 0.7362004773730021f, 0.7362329184718678f, 0.7362653578789096f, + 0.7362977955940531f, 0.7363302316172239f, 0.7363626659483472f, 0.7363950985873486f, + 0.7364275295341537f, 0.7364599587886878f, 0.7364923863508763f, 0.7365248122206450f, + 0.7365572363979191f, 0.7365896588826243f, 0.7366220796746858f, 0.7366544987740294f, + 0.7366869161805806f, 0.7367193318942645f, 0.7367517459150071f, 0.7367841582427338f, + 0.7368165688773698f, 0.7368489778188411f, 0.7368813850670728f, 0.7369137906219907f, + 0.7369461944835202f, 0.7369785966515869f, 0.7370109971261164f, 0.7370433959070340f, + 0.7370757929942656f, 0.7371081883877366f, 0.7371405820873724f, 0.7371729740930988f, + 0.7372053644048412f, 0.7372377530225253f, 0.7372701399460764f, 0.7373025251754205f, + 0.7373349087104828f, 0.7373672905511891f, 0.7373996706974649f, 0.7374320491492359f, + 0.7374644259064276f, 0.7374968009689655f, 0.7375291743367755f, 0.7375615460097830f, + 0.7375939159879135f, 0.7376262842710929f, 0.7376586508592466f, 0.7376910157523003f, + 0.7377233789501796f, 0.7377557404528102f, 0.7377881002601178f, 0.7378204583720278f, + 0.7378528147884660f, 0.7378851695093580f, 0.7379175225346295f, 0.7379498738642061f, + 0.7379822234980136f, 0.7380145714359774f, 0.7380469176780233f, 0.7380792622240770f, + 0.7381116050740644f, 0.7381439462279106f, 0.7381762856855418f, 0.7382086234468834f, + 0.7382409595118613f, 0.7382732938804011f, 0.7383056265524284f, 0.7383379575278690f, + 0.7383702868066485f, 0.7384026143886929f, 0.7384349402739276f, 0.7384672644622784f, + 0.7384995869536711f, 0.7385319077480313f, 0.7385642268452849f, 0.7385965442453575f, + 0.7386288599481748f, 0.7386611739536627f, 0.7386934862617468f, 0.7387257968723530f, + 0.7387581057854069f, 0.7387904130008343f, 0.7388227185185610f, 0.7388550223385126f, + 0.7388873244606152f, 0.7389196248847942f, 0.7389519236109756f, 0.7389842206390852f, + 0.7390165159690486f, 0.7390488096007918f, 0.7390811015342404f, 0.7391133917693204f, + 0.7391456803059574f, 0.7391779671440774f, 0.7392102522836059f, 0.7392425357244691f, + 0.7392748174665925f, 0.7393070975099021f, 0.7393393758543235f, 0.7393716524997829f, + 0.7394039274462058f, 0.7394362006935181f, 0.7394684722416457f, 0.7395007420905145f, + 0.7395330102400502f, 0.7395652766901788f, 0.7395975414408260f, 0.7396298044919178f, + 0.7396620658433799f, 0.7396943254951384f, 0.7397265834471189f, 0.7397588396992476f, + 0.7397910942514500f, 0.7398233471036522f, 0.7398555982557800f, 0.7398878477077593f, + 0.7399200954595161f, 0.7399523415109762f, 0.7399845858620656f, 0.7400168285127100f, + 0.7400490694628356f, 0.7400813087123680f, 0.7401135462612333f, 0.7401457821093573f, + 0.7401780162566662f, 0.7402102487030856f, 0.7402424794485416f, 0.7402747084929601f, + 0.7403069358362671f, 0.7403391614783883f, 0.7403713854192500f, 0.7404036076587779f, + 0.7404358281968980f, 0.7404680470335364f, 0.7405002641686189f, 0.7405324796020716f, + 0.7405646933338202f, 0.7405969053637911f, 0.7406291156919099f, 0.7406613243181027f, + 0.7406935312422956f, 0.7407257364644145f, 0.7407579399843854f, 0.7407901418021343f, + 0.7408223419175873f, 0.7408545403306702f, 0.7408867370413091f, 0.7409189320494300f, + 0.7409511253549591f, 0.7409833169578222f, 0.7410155068579454f, 0.7410476950552547f, + 0.7410798815496761f, 0.7411120663411357f, 0.7411442494295596f, 0.7411764308148738f, + 0.7412086104970043f, 0.7412407884758772f, 0.7412729647514185f, 0.7413051393235542f, + 0.7413373121922107f, 0.7413694833573137f, 0.7414016528187894f, 0.7414338205765639f, + 0.7414659866305633f, 0.7414981509807136f, 0.7415303136269409f, 0.7415624745691715f, + 0.7415946338073311f, 0.7416267913413461f, 0.7416589471711426f, 0.7416911012966465f, + 0.7417232537177842f, 0.7417554044344815f, 0.7417875534466648f, 0.7418197007542601f, + 0.7418518463571935f, 0.7418839902553911f, 0.7419161324487792f, 0.7419482729372838f, + 0.7419804117208310f, 0.7420125487993471f, 0.7420446841727582f, 0.7420768178409903f, + 0.7421089498039698f, 0.7421410800616228f, 0.7421732086138753f, 0.7422053354606537f, + 0.7422374606018840f, 0.7422695840374924f, 0.7423017057674052f, 0.7423338257915485f, + 0.7423659441098485f, 0.7423980607222312f, 0.7424301756286232f, 0.7424622888289505f, + 0.7424944003231392f, 0.7425265101111157f, 0.7425586181928061f, 0.7425907245681366f, + 0.7426228292370334f, 0.7426549321994229f, 0.7426870334552311f, 0.7427191330043844f, + 0.7427512308468091f, 0.7427833269824312f, 0.7428154214111771f, 0.7428475141329729f, + 0.7428796051477451f, 0.7429116944554198f, 0.7429437820559233f, 0.7429758679491818f, + 0.7430079521351217f, 0.7430400346136691f, 0.7430721153847505f, 0.7431041944482919f, + 0.7431362718042198f, 0.7431683474524604f, 0.7432004213929401f, 0.7432324936255851f, + 0.7432645641503215f, 0.7432966329670760f, 0.7433287000757747f, 0.7433607654763439f, + 0.7433928291687100f, 0.7434248911527992f, 0.7434569514285380f, 0.7434890099958524f, + 0.7435210668546691f, 0.7435531220049143f, 0.7435851754465141f, 0.7436172271793954f, + 0.7436492772034841f, 0.7436813255187066f, 0.7437133721249892f, 0.7437454170222585f, + 0.7437774602104408f, 0.7438095016894622f, 0.7438415414592495f, 0.7438735795197289f, + 0.7439056158708265f, 0.7439376505124690f, 0.7439696834445827f, 0.7440017146670940f, + 0.7440337441799292f, 0.7440657719830149f, 0.7440977980762773f, 0.7441298224596429f, + 0.7441618451330381f, 0.7441938660963894f, 0.7442258853496230f, 0.7442579028926654f, + 0.7442899187254431f, 0.7443219328478826f, 0.7443539452599102f, 0.7443859559614524f, + 0.7444179649524356f, 0.7444499722327862f, 0.7444819778024307f, 0.7445139816612957f, + 0.7445459838093074f, 0.7445779842463923f, 0.7446099829724770f, 0.7446419799874880f, + 0.7446739752913516f, 0.7447059688839944f, 0.7447379607653429f, 0.7447699509353235f, + 0.7448019393938626f, 0.7448339261408868f, 0.7448659111763228f, 0.7448978945000967f, + 0.7449298761121353f, 0.7449618560123651f, 0.7449938342007123f, 0.7450258106771038f, + 0.7450577854414659f, 0.7450897584937253f, 0.7451217298338083f, 0.7451536994616416f, + 0.7451856673771516f, 0.7452176335802649f, 0.7452495980709082f, 0.7452815608490079f, + 0.7453135219144904f, 0.7453454812672826f, 0.7453774389073108f, 0.7454093948345016f, + 0.7454413490487817f, 0.7454733015500775f, 0.7455052523383157f, 0.7455372014134227f, + 0.7455691487753254f, 0.7456010944239501f, 0.7456330383592236f, 0.7456649805810722f, + 0.7456969210894228f, 0.7457288598842019f, 0.7457607969653359f, 0.7457927323327518f, + 0.7458246659863760f, 0.7458565979261351f, 0.7458885281519557f, 0.7459204566637646f, + 0.7459523834614883f, 0.7459843085450534f, 0.7460162319143866f, 0.7460481535694145f, + 0.7460800735100638f, 0.7461119917362611f, 0.7461439082479331f, 0.7461758230450064f, + 0.7462077361274077f, 0.7462396474950637f, 0.7462715571479011f, 0.7463034650858462f, + 0.7463353713088263f, 0.7463672758167677f, 0.7463991786095970f, 0.7464310796872411f, + 0.7464629790496268f, 0.7464948766966805f, 0.7465267726283289f, 0.7465586668444990f, + 0.7465905593451173f, 0.7466224501301104f, 0.7466543391994054f, 0.7466862265529287f, + 0.7467181121906070f, 0.7467499961123674f, 0.7467818783181361f, 0.7468137588078404f, + 0.7468456375814065f, 0.7468775146387615f, 0.7469093899798320f, 0.7469412636045448f, + 0.7469731355128267f, 0.7470050057046045f, 0.7470368741798048f, 0.7470687409383544f, + 0.7471006059801801f, 0.7471324693052088f, 0.7471643309133671f, 0.7471961908045819f, + 0.7472280489787799f, 0.7472599054358878f, 0.7472917601758328f, 0.7473236131985413f, + 0.7473554645039403f, 0.7473873140919564f, 0.7474191619625167f, 0.7474510081155478f, + 0.7474828525509766f, 0.7475146952687298f, 0.7475465362687346f, 0.7475783755509173f, + 0.7476102131152051f, 0.7476420489615249f, 0.7476738830898032f, 0.7477057154999670f, + 0.7477375461919433f, 0.7477693751656589f, 0.7478012024210404f, 0.7478330279580150f, + 0.7478648517765094f, 0.7478966738764505f, 0.7479284942577651f, 0.7479603129203802f, + 0.7479921298642227f, 0.7480239450892193f, 0.7480557585952972f, 0.7480875703823829f, + 0.7481193804504035f, 0.7481511887992860f, 0.7481829954289573f, 0.7482148003393441f, + 0.7482466035303734f, 0.7482784050019722f, 0.7483102047540674f, 0.7483420027865858f, + 0.7483737990994546f, 0.7484055936926004f, 0.7484373865659504f, 0.7484691777194313f, + 0.7485009671529704f, 0.7485327548664944f, 0.7485645408599301f, 0.7485963251332048f, + 0.7486281076862453f, 0.7486598885189786f, 0.7486916676313315f, 0.7487234450232313f, + 0.7487552206946048f, 0.7487869946453789f, 0.7488187668754807f, 0.7488505373848371f, + 0.7488823061733750f, 0.7489140732410218f, 0.7489458385877041f, 0.7489776022133492f, + 0.7490093641178838f, 0.7490411243012352f, 0.7490728827633302f, 0.7491046395040959f, + 0.7491363945234593f, 0.7491681478213476f, 0.7491998993976875f, 0.7492316492524064f, + 0.7492633973854310f, 0.7492951437966887f, 0.7493268884861062f, 0.7493586314536108f, + 0.7493903726991296f, 0.7494221122225893f, 0.7494538500239173f, 0.7494855861030406f, + 0.7495173204598862f, 0.7495490530943811f, 0.7495807840064527f, 0.7496125131960277f, + 0.7496442406630335f, 0.7496759664073970f, 0.7497076904290454f, 0.7497394127279057f, + 0.7497711333039050f, 0.7498028521569705f, 0.7498345692870294f, 0.7498662846940085f, + 0.7498979983778352f, 0.7499297103384366f, 0.7499614205757397f, 0.7499931290896718f, + 0.7500248358801598f, 0.7500565409471309f, 0.7500882442905125f, 0.7501199459102315f, + 0.7501516458062151f, 0.7501833439783904f, 0.7502150404266846f, 0.7502467351510250f, + 0.7502784281513386f, 0.7503101194275528f, 0.7503418089795945f, 0.7503734968073908f, + 0.7504051829108692f, 0.7504368672899568f, 0.7504685499445808f, 0.7505002308746682f, + 0.7505319100801464f, 0.7505635875609425f, 0.7505952633169838f, 0.7506269373481974f, + 0.7506586096545106f, 0.7506902802358506f, 0.7507219490921446f, 0.7507536162233198f, + 0.7507852816293036f, 0.7508169453100230f, 0.7508486072654054f, 0.7508802674953780f, + 0.7509119259998680f, 0.7509435827788026f, 0.7509752378321093f, 0.7510068911597151f, + 0.7510385427615472f, 0.7510701926375333f, 0.7511018407876003f, 0.7511334872116756f, + 0.7511651319096864f, 0.7511967748815601f, 0.7512284161272238f, 0.7512600556466049f, + 0.7512916934396309f, 0.7513233295062287f, 0.7513549638463258f, 0.7513865964598496f, + 0.7514182273467274f, 0.7514498565068862f, 0.7514814839402537f, 0.7515131096467571f, + 0.7515447336263237f, 0.7515763558788807f, 0.7516079764043556f, 0.7516395952026758f, + 0.7516712122737684f, 0.7517028276175610f, 0.7517344412339808f, 0.7517660531229552f, + 0.7517976632844114f, 0.7518292717182771f, 0.7518608784244795f, 0.7518924834029457f, + 0.7519240866536036f, 0.7519556881763800f, 0.7519872879712027f, 0.7520188860379990f, + 0.7520504823766964f, 0.7520820769872220f, 0.7521136698695032f, 0.7521452610234677f, + 0.7521768504490427f, 0.7522084381461557f, 0.7522400241147340f, 0.7522716083547051f, + 0.7523031908659965f, 0.7523347716485353f, 0.7523663507022494f, 0.7523979280270660f, + 0.7524295036229124f, 0.7524610774897162f, 0.7524926496274048f, 0.7525242200359057f, + 0.7525557887151464f, 0.7525873556650542f, 0.7526189208855566f, 0.7526504843765811f, + 0.7526820461380552f, 0.7527136061699065f, 0.7527451644720621f, 0.7527767210444497f, + 0.7528082758869969f, 0.7528398289996310f, 0.7528713803822796f, 0.7529029300348702f, + 0.7529344779573303f, 0.7529660241495871f, 0.7529975686115686f, 0.7530291113432022f, + 0.7530606523444151f, 0.7530921916151351f, 0.7531237291552896f, 0.7531552649648062f, + 0.7531867990436124f, 0.7532183313916359f, 0.7532498620088039f, 0.7532813908950442f, + 0.7533129180502843f, 0.7533444434744517f, 0.7533759671674740f, 0.7534074891292788f, + 0.7534390093597936f, 0.7534705278589460f, 0.7535020446266634f, 0.7535335596628737f, + 0.7535650729675042f, 0.7535965845404826f, 0.7536280943817366f, 0.7536596024911936f, + 0.7536911088687813f, 0.7537226135144272f, 0.7537541164280590f, 0.7537856176096044f, + 0.7538171170589907f, 0.7538486147761458f, 0.7538801107609973f, 0.7539116050134727f, + 0.7539430975334996f, 0.7539745883210058f, 0.7540060773759190f, 0.7540375646981664f, + 0.7540690502876761f, 0.7541005341443756f, 0.7541320162681924f, 0.7541634966590544f, + 0.7541949753168892f, 0.7542264522416242f, 0.7542579274331874f, 0.7542894008915064f, + 0.7543208726165089f, 0.7543523426081223f, 0.7543838108662747f, 0.7544152773908934f, + 0.7544467421819063f, 0.7544782052392411f, 0.7545096665628256f, 0.7545411261525873f, + 0.7545725840084538f, 0.7546040401303532f, 0.7546354945182129f, 0.7546669471719607f, + 0.7546983980915244f, 0.7547298472768317f, 0.7547612947278103f, 0.7547927404443878f, + 0.7548241844264922f, 0.7548556266740513f, 0.7548870671869924f, 0.7549185059652436f, + 0.7549499430087326f, 0.7549813783173871f, 0.7550128118911349f, 0.7550442437299039f, + 0.7550756738336216f, 0.7551071022022159f, 0.7551385288356147f, 0.7551699537337456f, + 0.7552013768965365f, 0.7552327983239152f, 0.7552642180158093f, 0.7552956359721469f, + 0.7553270521928556f, 0.7553584666778633f, 0.7553898794270978f, 0.7554212904404868f, + 0.7554526997179581f, 0.7554841072594398f, 0.7555155130648595f, 0.7555469171341451f, + 0.7555783194672245f, 0.7556097200640254f, 0.7556411189244757f, 0.7556725160485033f, + 0.7557039114360360f, 0.7557353050870015f, 0.7557666970013279f, 0.7557980871789431f, + 0.7558294756197748f, 0.7558608623237508f, 0.7558922472907992f, 0.7559236305208478f, + 0.7559550120138243f, 0.7559863917696569f, 0.7560177697882733f, 0.7560491460696014f, + 0.7560805206135691f, 0.7561118934201044f, 0.7561432644891350f, 0.7561746338205891f, + 0.7562060014143945f, 0.7562373672704791f, 0.7562687313887706f, 0.7563000937691973f, + 0.7563314544116869f, 0.7563628133161674f, 0.7563941704825667f, 0.7564255259108129f, + 0.7564568796008337f, 0.7564882315525572f, 0.7565195817659114f, 0.7565509302408242f, + 0.7565822769772235f, 0.7566136219750373f, 0.7566449652341937f, 0.7566763067546204f, + 0.7567076465362457f, 0.7567389845789974f, 0.7567703208828035f, 0.7568016554475919f, + 0.7568329882732908f, 0.7568643193598281f, 0.7568956487071318f, 0.7569269763151300f, + 0.7569583021837505f, 0.7569896263129214f, 0.7570209487025709f, 0.7570522693526268f, + 0.7570835882630172f, 0.7571149054336701f, 0.7571462208645137f, 0.7571775345554758f, + 0.7572088465064845f, 0.7572401567174680f, 0.7572714651883542f, 0.7573027719190712f, + 0.7573340769095471f, 0.7573653801597100f, 0.7573966816694878f, 0.7574279814388086f, + 0.7574592794676007f, 0.7574905757557919f, 0.7575218703033104f, 0.7575531631100844f, + 0.7575844541760418f, 0.7576157435011107f, 0.7576470310852194f, 0.7576783169282958f, + 0.7577096010302681f, 0.7577408833910643f, 0.7577721640106128f, 0.7578034428888414f, + 0.7578347200256783f, 0.7578659954210517f, 0.7578972690748899f, 0.7579285409871206f, + 0.7579598111576723f, 0.7579910795864729f, 0.7580223462734509f, 0.7580536112185340f, + 0.7580848744216506f, 0.7581161358827290f, 0.7581473956016971f, 0.7581786535784830f, + 0.7582099098130153f, 0.7582411643052218f, 0.7582724170550307f, 0.7583036680623704f, + 0.7583349173271690f, 0.7583661648493544f, 0.7583974106288552f, 0.7584286546655995f, + 0.7584598969595154f, 0.7584911375105311f, 0.7585223763185749f, 0.7585536133835751f, + 0.7585848487054595f, 0.7586160822841569f, 0.7586473141195952f, 0.7586785442117026f, + 0.7587097725604074f, 0.7587409991656379f, 0.7587722240273223f, 0.7588034471453887f, + 0.7588346685197657f, 0.7588658881503813f, 0.7588971060371636f, 0.7589283221800414f, + 0.7589595365789424f, 0.7589907492337952f, 0.7590219601445279f, 0.7590531693110689f, + 0.7590843767333465f, 0.7591155824112888f, 0.7591467863448245f, 0.7591779885338814f, + 0.7592091889783881f, 0.7592403876782727f, 0.7592715846334637f, 0.7593027798438894f, + 0.7593339733094779f, 0.7593651650301577f, 0.7593963550058572f, 0.7594275432365045f, + 0.7594587297220282f, 0.7594899144623565f, 0.7595210974574176f, 0.7595522787071399f, + 0.7595834582114520f, 0.7596146359702820f, 0.7596458119835583f, 0.7596769862512094f, + 0.7597081587731634f, 0.7597393295493489f, 0.7597704985796941f, 0.7598016658641276f, + 0.7598328314025775f, 0.7598639951949723f, 0.7598951572412405f, 0.7599263175413105f, + 0.7599574760951103f, 0.7599886329025688f, 0.7600197879636142f, 0.7600509412781750f, + 0.7600820928461792f, 0.7601132426675559f, 0.7601443907422329f, 0.7601755370701390f, + 0.7602066816512024f, 0.7602378244853517f, 0.7602689655725152f, 0.7603001049126216f, + 0.7603312425055990f, 0.7603623783513760f, 0.7603935124498811f, 0.7604246448010427f, + 0.7604557754047893f, 0.7604869042610491f, 0.7605180313697510f, 0.7605491567308234f, + 0.7605802803441944f, 0.7606114022097928f, 0.7606425223275470f, 0.7606736406973856f, + 0.7607047573192369f, 0.7607358721930295f, 0.7607669853186919f, 0.7607980966961525f, + 0.7608292063253400f, 0.7608603142061828f, 0.7608914203386093f, 0.7609225247225483f, + 0.7609536273579280f, 0.7609847282446773f, 0.7610158273827243f, 0.7610469247719980f, + 0.7610780204124266f, 0.7611091143039387f, 0.7611402064464629f, 0.7611712968399278f, + 0.7612023854842618f, 0.7612334723793936f, 0.7612645575252518f, 0.7612956409217648f, + 0.7613267225688612f, 0.7613578024664699f, 0.7613888806145190f, 0.7614199570129374f, + 0.7614510316616535f, 0.7614821045605961f, 0.7615131757096937f, 0.7615442451088748f, + 0.7615753127580680f, 0.7616063786572022f, 0.7616374428062056f, 0.7616685052050071f, + 0.7616995658535353f, 0.7617306247517187f, 0.7617616818994860f, 0.7617927372967659f, + 0.7618237909434868f, 0.7618548428395777f, 0.7618858929849669f, 0.7619169413795833f, + 0.7619479880233555f, 0.7619790329162119f, 0.7620100760580816f, 0.7620411174488929f, + 0.7620721570885746f, 0.7621031949770554f, 0.7621342311142639f, 0.7621652655001288f, + 0.7621962981345789f, 0.7622273290175428f, 0.7622583581489492f, 0.7622893855287267f, + 0.7623204111568042f, 0.7623514350331103f, 0.7623824571575736f, 0.7624134775301230f, + 0.7624444961506871f, 0.7624755130191947f, 0.7625065281355744f, 0.7625375414997552f, + 0.7625685531116655f, 0.7625995629712341f, 0.7626305710783899f, 0.7626615774330616f, + 0.7626925820351779f, 0.7627235848846676f, 0.7627545859814594f, 0.7627855853254821f, + 0.7628165829166643f, 0.7628475787549351f, 0.7628785728402231f, 0.7629095651724570f, + 0.7629405557515657f, 0.7629715445774780f, 0.7630025316501224f, 0.7630335169694281f, + 0.7630645005353237f, 0.7630954823477381f, 0.7631264624065998f, 0.7631574407118380f, + 0.7631884172633813f, 0.7632193920611585f, 0.7632503651050986f, 0.7632813363951303f, + 0.7633123059311824f, 0.7633432737131838f, 0.7633742397410633f, 0.7634052040147498f, + 0.7634361665341720f, 0.7634671272992589f, 0.7634980863099394f, 0.7635290435661422f, + 0.7635599990677961f, 0.7635909528148302f, 0.7636219048071734f, 0.7636528550447542f, + 0.7636838035275019f, 0.7637147502553451f, 0.7637456952282127f, 0.7637766384460338f, + 0.7638075799087372f, 0.7638385196162516f, 0.7638694575685061f, 0.7639003937654297f, + 0.7639313282069511f, 0.7639622608929992f, 0.7639931918235032f, 0.7640241209983918f, + 0.7640550484175939f, 0.7640859740810385f, 0.7641168979886546f, 0.7641478201403710f, + 0.7641787405361167f, 0.7642096591758207f, 0.7642405760594119f, 0.7642714911868191f, + 0.7643024045579717f, 0.7643333161727982f, 0.7643642260312278f, 0.7643951341331894f, + 0.7644260404786121f, 0.7644569450674247f, 0.7644878478995561f, 0.7645187489749357f, + 0.7645496482934921f, 0.7645805458551544f, 0.7646114416598517f, 0.7646423357075129f, + 0.7646732279980671f, 0.7647041185314433f, 0.7647350073075704f, 0.7647658943263774f, + 0.7647967795877935f, 0.7648276630917475f, 0.7648585448381687f, 0.7648894248269860f, + 0.7649203030581284f, 0.7649511795315250f, 0.7649820542471049f, 0.7650129272047970f, + 0.7650437984045304f, 0.7650746678462343f, 0.7651055355298376f, 0.7651364014552694f, + 0.7651672656224590f, 0.7651981280313351f, 0.7652289886818270f, 0.7652598475738637f, + 0.7652907047073744f, 0.7653215600822880f, 0.7653524136985338f, 0.7653832655560409f, + 0.7654141156547382f, 0.7654449639945550f, 0.7654758105754204f, 0.7655066553972634f, + 0.7655374984600131f, 0.7655683397635987f, 0.7655991793079494f, 0.7656300170929943f, + 0.7656608531186624f, 0.7656916873848830f, 0.7657225198915852f, 0.7657533506386981f, + 0.7657841796261510f, 0.7658150068538728f, 0.7658458323217928f, 0.7658766560298402f, + 0.7659074779779442f, 0.7659382981660339f, 0.7659691165940384f, 0.7659999332618871f, + 0.7660307481695090f, 0.7660615613168333f, 0.7660923727037893f, 0.7661231823303061f, + 0.7661539901963128f, 0.7661847963017390f, 0.7662156006465135f, 0.7662464032305656f, + 0.7662772040538247f, 0.7663080031162198f, 0.7663388004176803f, 0.7663695959581354f, + 0.7664003897375141f, 0.7664311817557460f, 0.7664619720127601f, 0.7664927605084857f, + 0.7665235472428521f, 0.7665543322157886f, 0.7665851154272242f, 0.7666158968770884f, + 0.7666466765653105f, 0.7666774544918195f, 0.7667082306565449f, 0.7667390050594161f, + 0.7667697777003619f, 0.7668005485793121f, 0.7668313176961957f, 0.7668620850509422f, + 0.7668928506434807f, 0.7669236144737406f, 0.7669543765416511f, 0.7669851368471415f, + 0.7670158953901415f, 0.7670466521705800f, 0.7670774071883864f, 0.7671081604434901f, + 0.7671389119358204f, 0.7671696616653066f, 0.7672004096318781f, 0.7672311558354643f, + 0.7672619002759944f, 0.7672926429533978f, 0.7673233838676040f, 0.7673541230185421f, + 0.7673848604061417f, 0.7674155960303319f, 0.7674463298910424f, 0.7674770619882024f, + 0.7675077923217413f, 0.7675385208915884f, 0.7675692476976732f, 0.7675999727399250f, + 0.7676306960182733f, 0.7676614175326475f, 0.7676921372829769f, 0.7677228552691909f, + 0.7677535714912190f, 0.7677842859489906f, 0.7678149986424351f, 0.7678457095714820f, + 0.7678764187360606f, 0.7679071261361005f, 0.7679378317715307f, 0.7679685356422813f, + 0.7679992377482813f, 0.7680299380894602f, 0.7680606366657476f, 0.7680913334770728f, + 0.7681220285233653f, 0.7681527218045547f, 0.7681834133205704f, 0.7682141030713417f, + 0.7682447910567982f, 0.7682754772768695f, 0.7683061617314849f, 0.7683368444205739f, + 0.7683675253440663f, 0.7683982045018911f, 0.7684288818939782f, 0.7684595575202569f, + 0.7684902313806568f, 0.7685209034751074f, 0.7685515738035381f, 0.7685822423658786f, + 0.7686129091620583f, 0.7686435741920068f, 0.7686742374556536f, 0.7687048989529283f, + 0.7687355586837603f, 0.7687662166480792f, 0.7687968728458148f, 0.7688275272768963f, + 0.7688581799412533f, 0.7688888308388155f, 0.7689194799695125f, 0.7689501273332737f, + 0.7689807729300289f, 0.7690114167597074f, 0.7690420588222391f, 0.7690726991175532f, + 0.7691033376455796f, 0.7691339744062479f, 0.7691646093994874f, 0.7691952426252280f, + 0.7692258740833993f, 0.7692565037739306f, 0.7692871316967519f, 0.7693177578517926f, + 0.7693483822389823f, 0.7693790048582507f, 0.7694096257095275f, 0.7694402447927423f, + 0.7694708621078246f, 0.7695014776547042f, 0.7695320914333107f, 0.7695627034435738f, + 0.7695933136854229f, 0.7696239221587881f, 0.7696545288635986f, 0.7696851337997844f, + 0.7697157369672750f, 0.7697463383660003f, 0.7697769379958896f, 0.7698075358568729f, + 0.7698381319488798f, 0.7698687262718400f, 0.7698993188256832f, 0.7699299096103390f, + 0.7699604986257372f, 0.7699910858718074f, 0.7700216713484795f, 0.7700522550556831f, + 0.7700828369933480f, 0.7701134171614037f, 0.7701439955597802f, 0.7701745721884071f, + 0.7702051470472141f, 0.7702357201361311f, 0.7702662914550877f, 0.7702968610040136f, + 0.7703274287828388f, 0.7703579947914929f, 0.7703885590299056f, 0.7704191214980066f, + 0.7704496821957260f, 0.7704802411229933f, 0.7705107982797382f, 0.7705413536658908f, + 0.7705719072813807f, 0.7706024591261377f, 0.7706330092000915f, 0.7706635575031721f, + 0.7706941040353091f, 0.7707246487964325f, 0.7707551917864720f, 0.7707857330053574f, + 0.7708162724530184f, 0.7708468101293852f, 0.7708773460343873f, 0.7709078801679546f, + 0.7709384125300169f, 0.7709689431205042f, 0.7709994719393463f, 0.7710299989864727f, + 0.7710605242618137f, 0.7710910477652990f, 0.7711215694968585f, 0.7711520894564219f, + 0.7711826076439192f, 0.7712131240592803f, 0.7712436387024350f, 0.7712741515733131f, + 0.7713046626718447f, 0.7713351719979595f, 0.7713656795515875f, 0.7713961853326586f, + 0.7714266893411027f, 0.7714571915768494f, 0.7714876920398291f, 0.7715181907299714f, + 0.7715486876472063f, 0.7715791827914638f, 0.7716096761626736f, 0.7716401677607658f, + 0.7716706575856703f, 0.7717011456373171f, 0.7717316319156361f, 0.7717621164205570f, + 0.7717925991520102f, 0.7718230801099253f, 0.7718535592942324f, 0.7718840367048614f, + 0.7719145123417424f, 0.7719449862048052f, 0.7719754582939797f, 0.7720059286091963f, + 0.7720363971503845f, 0.7720668639174745f, 0.7720973289103963f, 0.7721277921290799f, + 0.7721582535734552f, 0.7721887132434523f, 0.7722191711390012f, 0.7722496272600319f, + 0.7722800816064743f, 0.7723105341782586f, 0.7723409849753147f, 0.7723714339975726f, + 0.7724018812449623f, 0.7724323267174141f, 0.7724627704148578f, 0.7724932123372236f, + 0.7725236524844413f, 0.7725540908564411f, 0.7725845274531531f, 0.7726149622745073f, + 0.7726453953204339f, 0.7726758265908625f, 0.7727062560857239f, 0.7727366838049475f, + 0.7727671097484639f, 0.7727975339162027f, 0.7728279563080943f, 0.7728583769240689f, + 0.7728887957640562f, 0.7729192128279866f, 0.7729496281157902f, 0.7729800416273969f, + 0.7730104533627370f, 0.7730408633217405f, 0.7730712715043376f, 0.7731016779104584f, + 0.7731320825400331f, 0.7731624853929917f, 0.7731928864692643f, 0.7732232857687812f, + 0.7732536832914726f, 0.7732840790372684f, 0.7733144730060988f, 0.7733448651978941f, + 0.7733752556125846f, 0.7734056442500999f, 0.7734360311103708f, 0.7734664161933271f, + 0.7734967994988990f, 0.7735271810270169f, 0.7735575607776108f, 0.7735879387506109f, + 0.7736183149459475f, 0.7736486893635506f, 0.7736790620033506f, 0.7737094328652776f, + 0.7737398019492618f, 0.7737701692552336f, 0.7738005347831228f, 0.7738308985328601f, + 0.7738612605043755f, 0.7738916206975993f, 0.7739219791124615f, 0.7739523357488927f, + 0.7739826906068228f, 0.7740130436861823f, 0.7740433949869013f, 0.7740737445089101f, + 0.7741040922521391f, 0.7741344382165183f, 0.7741647824019781f, 0.7741951248084489f, + 0.7742254654358606f, 0.7742558042841439f, 0.7742861413532289f, 0.7743164766430458f, + 0.7743468101535250f, 0.7743771418845969f, 0.7744074718361916f, 0.7744378000082395f, + 0.7744681264006709f, 0.7744984510134161f, 0.7745287738464053f, 0.7745590948995690f, + 0.7745894141728376f, 0.7746197316661411f, 0.7746500473794100f, 0.7746803613125748f, + 0.7747106734655657f, 0.7747409838383128f, 0.7747712924307469f, 0.7748015992427981f, + 0.7748319042743969f, 0.7748622075254734f, 0.7748925089959582f, 0.7749228086857816f, + 0.7749531065948738f, 0.7749834027231656f, 0.7750136970705870f, 0.7750439896370684f, + 0.7750742804225405f, 0.7751045694269334f, 0.7751348566501775f, 0.7751651420922033f, + 0.7751954257529413f, 0.7752257076323218f, 0.7752559877302752f, 0.7752862660467319f, + 0.7753165425816224f, 0.7753468173348771f, 0.7753770903064263f, 0.7754073614962007f, + 0.7754376309041305f, 0.7754678985301462f, 0.7754981643741784f, 0.7755284284361573f, + 0.7755586907160136f, 0.7755889512136775f, 0.7756192099290797f, 0.7756494668621505f, + 0.7756797220128205f, 0.7757099753810203f, 0.7757402269666800f, 0.7757704767697302f, + 0.7758007247901015f, 0.7758309710277246f, 0.7758612154825295f, 0.7758914581544470f, + 0.7759216990434076f, 0.7759519381493418f, 0.7759821754721800f, 0.7760124110118528f, + 0.7760426447682909f, 0.7760728767414243f, 0.7761031069311841f, 0.7761333353375006f, + 0.7761635619603043f, 0.7761937867995258f, 0.7762240098550957f, 0.7762542311269444f, + 0.7762844506150024f, 0.7763146683192005f, 0.7763448842394692f, 0.7763750983757389f, + 0.7764053107279404f, 0.7764355212960040f, 0.7764657300798606f, 0.7764959370794404f, + 0.7765261422946744f, 0.7765563457254929f, 0.7765865473718266f, 0.7766167472336062f, + 0.7766469453107621f, 0.7766771416032249f, 0.7767073361109254f, 0.7767375288337940f, + 0.7767677197717615f, 0.7767979089247585f, 0.7768280962927155f, 0.7768582818755634f, + 0.7768884656732324f, 0.7769186476856536f, 0.7769488279127573f, 0.7769790063544743f, + 0.7770091830107353f, 0.7770393578814708f, 0.7770695309666117f, 0.7770997022660883f, + 0.7771298717798316f, 0.7771600395077721f, 0.7771902054498406f, 0.7772203696059676f, + 0.7772505319760841f, 0.7772806925601204f, 0.7773108513580074f, 0.7773410083696758f, + 0.7773711635950563f, 0.7774013170340794f, 0.7774314686866762f, 0.7774616185527772f, + 0.7774917666323129f, 0.7775219129252144f, 0.7775520574314123f, 0.7775822001508372f, + 0.7776123410834199f, 0.7776424802290913f, 0.7776726175877819f, 0.7777027531594225f, + 0.7777328869439440f, 0.7777630189412771f, 0.7777931491513524f, 0.7778232775741009f, + 0.7778534042094530f, 0.7778835290573399f, 0.7779136521176921f, 0.7779437733904406f, + 0.7779738928755160f, 0.7780040105728491f, 0.7780341264823708f, 0.7780642406040117f, + 0.7780943529377028f, 0.7781244634833748f, 0.7781545722409585f, 0.7781846792103848f, + 0.7782147843915844f, 0.7782448877844883f, 0.7782749893890272f, 0.7783050892051318f, + 0.7783351872327331f, 0.7783652834717620f, 0.7783953779221492f, 0.7784254705838255f, + 0.7784555614567219f, 0.7784856505407692f, 0.7785157378358982f, 0.7785458233420398f, + 0.7785759070591249f, 0.7786059889870844f, 0.7786360691258490f, 0.7786661474753498f, + 0.7786962240355175f, 0.7787262988062831f, 0.7787563717875775f, 0.7787864429793314f, + 0.7788165123814759f, 0.7788465799939419f, 0.7788766458166602f, 0.7789067098495618f, + 0.7789367720925775f, 0.7789668325456384f, 0.7789968912086752f, 0.7790269480816189f, + 0.7790570031644006f, 0.7790870564569511f, 0.7791171079592013f, 0.7791471576710821f, + 0.7791772055925247f, 0.7792072517234598f, 0.7792372960638184f, 0.7792673386135316f, + 0.7792973793725303f, 0.7793274183407453f, 0.7793574555181079f, 0.7793874909045487f, + 0.7794175244999989f, 0.7794475563043894f, 0.7794775863176514f, 0.7795076145397156f, + 0.7795376409705131f, 0.7795676656099751f, 0.7795976884580323f, 0.7796277095146159f, + 0.7796577287796568f, 0.7796877462530861f, 0.7797177619348349f, 0.7797477758248339f, + 0.7797777879230144f, 0.7798077982293076f, 0.7798378067436440f, 0.7798678134659552f, + 0.7798978183961719f, 0.7799278215342254f, 0.7799578228800464f, 0.7799878224335663f, + 0.7800178201947160f, 0.7800478161634266f, 0.7800778103396292f, 0.7801078027232549f, + 0.7801377933142345f, 0.7801677821124995f, 0.7801977691179808f, 0.7802277543306094f, + 0.7802577377503166f, 0.7802877193770333f, 0.7803176992106907f, 0.7803476772512199f, + 0.7803776534985520f, 0.7804076279526182f, 0.7804376006133494f, 0.7804675714806769f, + 0.7804975405545319f, 0.7805275078348454f, 0.7805574733215485f, 0.7805874370145724f, + 0.7806173989138483f, 0.7806473590193073f, 0.7806773173308805f, 0.7807072738484993f, + 0.7807372285720945f, 0.7807671815015974f, 0.7807971326369393f, 0.7808270819780513f, + 0.7808570295248645f, 0.7808869752773102f, 0.7809169192353195f, 0.7809468613988236f, + 0.7809768017677537f, 0.7810067403420411f, 0.7810366771216168f, 0.7810666121064123f, + 0.7810965452963584f, 0.7811264766913868f, 0.7811564062914282f, 0.7811863340964142f, + 0.7812162601062761f, 0.7812461843209447f, 0.7812761067403516f, 0.7813060273644279f, + 0.7813359461931050f, 0.7813658632263137f, 0.7813957784639859f, 0.7814256919060524f, + 0.7814556035524445f, 0.7814855134030937f, 0.7815154214579311f, 0.7815453277168879f, + 0.7815752321798956f, 0.7816051348468852f, 0.7816350357177883f, 0.7816649347925358f, + 0.7816948320710594f, 0.7817247275532901f, 0.7817546212391595f, 0.7817845131285985f, + 0.7818144032215388f, 0.7818442915179116f, 0.7818741780176480f, 0.7819040627206796f, + 0.7819339456269376f, 0.7819638267363532f, 0.7819937060488581f, 0.7820235835643834f, + 0.7820534592828604f, 0.7820833332042204f, 0.7821132053283950f, 0.7821430756553154f, + 0.7821729441849129f, 0.7822028109171191f, 0.7822326758518651f, 0.7822625389890824f, + 0.7822924003287024f, 0.7823222598706564f, 0.7823521176148758f, 0.7823819735612920f, + 0.7824118277098364f, 0.7824416800604405f, 0.7824715306130355f, 0.7825013793675529f, + 0.7825312263239242f, 0.7825610714820808f, 0.7825909148419539f, 0.7826207564034751f, + 0.7826505961665757f, 0.7826804341311874f, 0.7827102702972413f, 0.7827401046646691f, + 0.7827699372334020f, 0.7827997680033718f, 0.7828295969745096f, 0.7828594241467470f, + 0.7828892495200155f, 0.7829190730942465f, 0.7829488948693715f, 0.7829787148453218f, + 0.7830085330220291f, 0.7830383493994248f, 0.7830681639774405f, 0.7830979767560075f, + 0.7831277877350573f, 0.7831575969145216f, 0.7831874042943315f, 0.7832172098744190f, + 0.7832470136547154f, 0.7832768156351521f, 0.7833066158156607f, 0.7833364141961727f, + 0.7833662107766197f, 0.7833960055569332f, 0.7834257985370446f, 0.7834555897168858f, + 0.7834853790963878f, 0.7835151666754826f, 0.7835449524541016f, 0.7835747364321762f, + 0.7836045186096382f, 0.7836342989864191f, 0.7836640775624504f, 0.7836938543376636f, + 0.7837236293119905f, 0.7837534024853625f, 0.7837831738577111f, 0.7838129434289682f, + 0.7838427111990652f, 0.7838724771679336f, 0.7839022413355052f, 0.7839320037017115f, + 0.7839617642664841f, 0.7839915230297546f, 0.7840212799914547f, 0.7840510351515160f, + 0.7840807885098700f, 0.7841105400664484f, 0.7841402898211829f, 0.7841700377740051f, + 0.7841997839248466f, 0.7842295282736391f, 0.7842592708203142f, 0.7842890115648036f, + 0.7843187505070389f, 0.7843484876469519f, 0.7843782229844740f, 0.7844079565195371f, + 0.7844376882520727f, 0.7844674181820128f, 0.7844971463092887f, 0.7845268726338323f, + 0.7845565971555752f, 0.7845863198744492f, 0.7846160407903859f, 0.7846457599033171f, + 0.7846754772131743f, 0.7847051927198895f, 0.7847349064233942f, 0.7847646183236202f, + 0.7847943284204992f, 0.7848240367139629f, 0.7848537432039432f, 0.7848834478903716f, + 0.7849131507731800f, 0.7849428518523002f, 0.7849725511276636f, 0.7850022485992023f, + 0.7850319442668481f, 0.7850616381305324f, 0.7850913301901873f, 0.7851210204457444f, + 0.7851507088971356f, 0.7851803955442925f, 0.7852100803871470f, 0.7852397634256308f, + 0.7852694446596760f, 0.7852991240892139f, 0.7853288017141766f, 0.7853584775344959f, + 0.7853881515501036f, 0.7854178237609314f, 0.7854474941669112f, 0.7854771627679747f, + 0.7855068295640539f, 0.7855364945550806f, 0.7855661577409866f, 0.7855958191217036f, + 0.7856254786971637f, 0.7856551364672986f, 0.7856847924320400f, 0.7857144465913199f, + 0.7857440989450704f, 0.7857737494932229f, 0.7858033982357095f, 0.7858330451724621f, + 0.7858626903034126f, 0.7858923336284926f, 0.7859219751476344f, 0.7859516148607696f, + 0.7859812527678302f, 0.7860108888687479f, 0.7860405231634550f, 0.7860701556518830f, + 0.7860997863339638f, 0.7861294152096298f, 0.7861590422788124f, 0.7861886675414437f, + 0.7862182909974555f, 0.7862479126467801f, 0.7862775324893491f, 0.7863071505250945f, + 0.7863367667539483f, 0.7863663811758423f, 0.7863959937907086f, 0.7864256045984791f, + 0.7864552135990858f, 0.7864848207924605f, 0.7865144261785354f, 0.7865440297572422f, + 0.7865736315285132f, 0.7866032314922802f, 0.7866328296484750f, 0.7866624259970300f, + 0.7866920205378767f, 0.7867216132709475f, 0.7867512041961743f, 0.7867807933134889f, + 0.7868103806228235f, 0.7868399661241101f, 0.7868695498172806f, 0.7868991317022671f, + 0.7869287117790017f, 0.7869582900474164f, 0.7869878665074430f, 0.7870174411590138f, + 0.7870470140020608f, 0.7870765850365159f, 0.7871061542623112f, 0.7871357216793788f, + 0.7871652872876509f, 0.7871948510870592f, 0.7872244130775362f, 0.7872539732590136f, + 0.7872835316314236f, 0.7873130881946983f, 0.7873426429487698f, 0.7873721958935701f, + 0.7874017470290313f, 0.7874312963550857f, 0.7874608438716652f, 0.7874903895787018f, + 0.7875199334761278f, 0.7875494755638752f, 0.7875790158418763f, 0.7876085543100629f, + 0.7876380909683675f, 0.7876676258167218f, 0.7876971588550583f, 0.7877266900833090f, + 0.7877562195014060f, 0.7877857471092815f, 0.7878152729068675f, 0.7878447968940964f, + 0.7878743190709002f, 0.7879038394372111f, 0.7879333579929613f, 0.7879628747380828f, + 0.7879923896725080f, 0.7880219027961688f, 0.7880514141089977f, 0.7880809236109267f, + 0.7881104313018881f, 0.7881399371818139f, 0.7881694412506365f, 0.7881989435082879f, + 0.7882284439547005f, 0.7882579425898064f, 0.7882874394135378f, 0.7883169344258271f, + 0.7883464276266062f, 0.7883759190158077f, 0.7884054085933635f, 0.7884348963592060f, + 0.7884643823132674f, 0.7884938664554800f, 0.7885233487857760f, 0.7885528293040877f, + 0.7885823080103472f, 0.7886117849044869f, 0.7886412599864391f, 0.7886707332561359f, + 0.7887002047135097f, 0.7887296743584927f, 0.7887591421910174f, 0.7887886082110157f, + 0.7888180724184202f, 0.7888475348131632f, 0.7888769953951767f, 0.7889064541643933f, + 0.7889359111207451f, 0.7889653662641647f, 0.7889948195945841f, 0.7890242711119356f, + 0.7890537208161519f, 0.7890831687071650f, 0.7891126147849072f, 0.7891420590493111f, + 0.7891715015003089f, 0.7892009421378329f, 0.7892303809618154f, 0.7892598179721889f, + 0.7892892531688857f, 0.7893186865518381f, 0.7893481181209785f, 0.7893775478762394f, + 0.7894069758175528f, 0.7894364019448515f, 0.7894658262580677f, 0.7894952487571338f, + 0.7895246694419822f, 0.7895540883125453f, 0.7895835053687553f, 0.7896129206105449f, + 0.7896423340378463f, 0.7896717456505921f, 0.7897011554487144f, 0.7897305634321460f, + 0.7897599696008191f, 0.7897893739546661f, 0.7898187764936195f, 0.7898481772176118f, + 0.7898775761265754f, 0.7899069732204426f, 0.7899363684991459f, 0.7899657619626180f, + 0.7899951536107911f, 0.7900245434435976f, 0.7900539314609702f, 0.7900833176628413f, + 0.7901127020491433f, 0.7901420846198086f, 0.7901714653747699f, 0.7902008443139595f, + 0.7902302214373100f, 0.7902595967447539f, 0.7902889702362236f, 0.7903183419116516f, + 0.7903477117709705f, 0.7903770798141128f, 0.7904064460410108f, 0.7904358104515974f, + 0.7904651730458049f, 0.7904945338235657f, 0.7905238927848126f, 0.7905532499294781f, + 0.7905826052574945f, 0.7906119587687945f, 0.7906413104633107f, 0.7906706603409756f, + 0.7907000084017216f, 0.7907293546454816f, 0.7907586990721878f, 0.7907880416817730f, + 0.7908173824741697f, 0.7908467214493106f, 0.7908760586071281f, 0.7909053939475547f, + 0.7909347274705233f, 0.7909640591759663f, 0.7909933890638163f, 0.7910227171340060f, + 0.7910520433864680f, 0.7910813678211346f, 0.7911106904379389f, 0.7911400112368132f, + 0.7911693302176902f, 0.7911986473805025f, 0.7912279627251828f, 0.7912572762516636f, + 0.7912865879598777f, 0.7913158978497578f, 0.7913452059212364f, 0.7913745121742460f, + 0.7914038166087195f, 0.7914331192245896f, 0.7914624200217888f, 0.7914917190002497f, + 0.7915210161599052f, 0.7915503115006879f, 0.7915796050225304f, 0.7916088967253655f, + 0.7916381866091258f, 0.7916674746737440f, 0.7916967609191529f, 0.7917260453452850f, + 0.7917553279520733f, 0.7917846087394501f, 0.7918138877073485f, 0.7918431648557011f, + 0.7918724401844405f, 0.7919017136934996f, 0.7919309853828110f, 0.7919602552523075f, + 0.7919895233019218f, 0.7920187895315868f, 0.7920480539412350f, 0.7920773165307992f, + 0.7921065773002124f, 0.7921358362494071f, 0.7921650933783161f, 0.7921943486868722f, + 0.7922236021750083f, 0.7922528538426571f, 0.7922821036897512f, 0.7923113517162237f, + 0.7923405979220071f, 0.7923698423070343f, 0.7923990848712382f, 0.7924283256145516f, + 0.7924575645369071f, 0.7924868016382376f, 0.7925160369184761f, 0.7925452703775551f, + 0.7925745020154076f, 0.7926037318319665f, 0.7926329598271646f, 0.7926621860009346f, + 0.7926914103532094f, 0.7927206328839220f, 0.7927498535930051f, 0.7927790724803915f, + 0.7928082895460141f, 0.7928375047898059f, 0.7928667182116995f, 0.7928959298116280f, + 0.7929251395895243f, 0.7929543475453210f, 0.7929835536789512f, 0.7930127579903479f, + 0.7930419604794436f, 0.7930711611461716f, 0.7931003599904646f, 0.7931295570122555f, + 0.7931587522114771f, 0.7931879455880626f, 0.7932171371419448f, 0.7932463268730565f, + 0.7932755147813306f, 0.7933047008667004f, 0.7933338851290983f, 0.7933630675684575f, + 0.7933922481847111f, 0.7934214269777918f, 0.7934506039476328f, 0.7934797790941666f, + 0.7935089524173267f, 0.7935381239170456f, 0.7935672935932565f, 0.7935964614458925f, + 0.7936256274748862f, 0.7936547916801708f, 0.7936839540616795f, 0.7937131146193449f, + 0.7937422733531002f, 0.7937714302628782f, 0.7938005853486122f, 0.7938297386102351f, + 0.7938588900476796f, 0.7938880396608792f, 0.7939171874497666f, 0.7939463334142750f, + 0.7939754775543372f, 0.7940046198698864f, 0.7940337603608555f, 0.7940628990271776f, + 0.7940920358687860f, 0.7941211708856133f, 0.7941503040775928f, 0.7941794354446575f, + 0.7942085649867406f, 0.7942376927037750f, 0.7942668185956936f, 0.7942959426624299f, + 0.7943250649039166f, 0.7943541853200869f, 0.7943833039108740f, 0.7944124206762109f, + 0.7944415356160306f, 0.7944706487302663f, 0.7944997600188511f, 0.7945288694817181f, + 0.7945579771188003f, 0.7945870829300310f, 0.7946161869153432f, 0.7946452890746699f, + 0.7946743894079445f, 0.7947034879151000f, 0.7947325845960695f, 0.7947616794507861f, + 0.7947907724791832f, 0.7948198636811935f, 0.7948489530567505f, 0.7948780406057873f, + 0.7949071263282370f, 0.7949362102240327f, 0.7949652922931076f, 0.7949943725353951f, + 0.7950234509508282f, 0.7950525275393399f, 0.7950816023008636f, 0.7951106752353324f, + 0.7951397463426796f, 0.7951688156228383f, 0.7951978830757417f, 0.7952269487013230f, + 0.7952560124995155f, 0.7952850744702524f, 0.7953141346134668f, 0.7953431929290919f, + 0.7953722494170612f, 0.7954013040773077f, 0.7954303569097646f, 0.7954594079143653f, + 0.7954884570910430f, 0.7955175044397309f, 0.7955465499603621f, 0.7955755936528701f, + 0.7956046355171882f, 0.7956336755532494f, 0.7956627137609871f, 0.7956917501403346f, + 0.7957207846912251f, 0.7957498174135920f, 0.7957788483073686f, 0.7958078773724879f, + 0.7958369046088835f, 0.7958659300164886f, 0.7958949535952365f, 0.7959239753450604f, + 0.7959529952658939f, 0.7959820133576700f, 0.7960110296203222f, 0.7960400440537837f, + 0.7960690566579880f, 0.7960980674328683f, 0.7961270763783578f, 0.7961560834943900f, + 0.7961850887808984f, 0.7962140922378161f, 0.7962430938650765f, 0.7962720936626131f, + 0.7963010916303591f, 0.7963300877682479f, 0.7963590820762130f, 0.7963880745541875f, + 0.7964170652021050f, 0.7964460540198988f, 0.7964750410075023f, 0.7965040261648489f, + 0.7965330094918720f, 0.7965619909885050f, 0.7965909706546812f, 0.7966199484903341f, + 0.7966489244953971f, 0.7966778986698038f, 0.7967068710134873f, 0.7967358415263811f, + 0.7967648102084187f, 0.7967937770595336f, 0.7968227420796591f, 0.7968517052687287f, + 0.7968806666266759f, 0.7969096261534340f, 0.7969385838489366f, 0.7969675397131170f, + 0.7969964937459088f, 0.7970254459472453f, 0.7970543963170603f, 0.7970833448552870f, + 0.7971122915618589f, 0.7971412364367095f, 0.7971701794797724f, 0.7971991206909810f, + 0.7972280600702687f, 0.7972569976175692f, 0.7972859333328158f, 0.7973148672159421f, + 0.7973437992668817f, 0.7973727294855680f, 0.7974016578719345f, 0.7974305844259149f, + 0.7974595091474425f, 0.7974884320364509f, 0.7975173530928737f, 0.7975462723166444f, + 0.7975751897076967f, 0.7976041052659638f, 0.7976330189913796f, 0.7976619308838776f, + 0.7976908409433910f, 0.7977197491698539f, 0.7977486555631995f, 0.7977775601233617f, + 0.7978064628502736f, 0.7978353637438691f, 0.7978642628040818f, 0.7978931600308452f, + 0.7979220554240930f, 0.7979509489837587f, 0.7979798407097759f, 0.7980087306020782f, + 0.7980376186605994f, 0.7980665048852729f, 0.7980953892760323f, 0.7981242718328114f, + 0.7981531525555439f, 0.7981820314441630f, 0.7982109084986028f, 0.7982397837187967f, + 0.7982686571046783f, 0.7982975286561815f, 0.7983263983732398f, 0.7983552662557869f, + 0.7983841323037564f, 0.7984129965170820f, 0.7984418588956973f, 0.7984707194395361f, + 0.7984995781485320f, 0.7985284350226188f, 0.7985572900617300f, 0.7985861432657995f, + 0.7986149946347608f, 0.7986438441685478f, 0.7986726918670940f, 0.7987015377303333f, + 0.7987303817581992f, 0.7987592239506255f, 0.7987880643075461f, 0.7988169028288945f, + 0.7988457395146046f, 0.7988745743646100f, 0.7989034073788445f, 0.7989322385572418f, + 0.7989610678997358f, 0.7989898954062600f, 0.7990187210767484f, 0.7990475449111346f, + 0.7990763669093524f, 0.7991051870713356f, 0.7991340053970180f, 0.7991628218863331f, + 0.7991916365392152f, 0.7992204493555977f, 0.7992492603354144f, 0.7992780694785994f, + 0.7993068767850862f, 0.7993356822548086f, 0.7993644858877005f, 0.7993932876836957f, + 0.7994220876427280f, 0.7994508857647313f, 0.7994796820496394f, 0.7995084764973860f, + 0.7995372691079050f, 0.7995660598811303f, 0.7995948488169957f, 0.7996236359154351f, + 0.7996524211763821f, 0.7996812045997710f, 0.7997099861855352f, 0.7997387659336088f, + 0.7997675438439257f, 0.7997963199164196f, 0.7998250941510245f, 0.7998538665476743f, + 0.7998826371063028f, 0.7999114058268439f, 0.7999401727092315f, 0.7999689377533995f, + 0.7999977009592819f, 0.8000264623268124f, 0.8000552218559250f, 0.8000839795465537f, + 0.8001127353986324f, 0.8001414894120948f, 0.8001702415868751f, 0.8001989919229071f, + 0.8002277404201248f, 0.8002564870784620f, 0.8002852318978528f, 0.8003139748782311f, + 0.8003427160195307f, 0.8003714553216857f, 0.8004001927846301f, 0.8004289284082978f, + 0.8004576621926227f, 0.8004863941375390f, 0.8005151242429803f, 0.8005438525088809f, + 0.8005725789351748f, 0.8006013035217958f, 0.8006300262686779f, 0.8006587471757551f, + 0.8006874662429616f, 0.8007161834702312f, 0.8007448988574980f, 0.8007736124046959f, + 0.8008023241117591f, 0.8008310339786214f, 0.8008597420052171f, 0.8008884481914801f, + 0.8009171525373443f, 0.8009458550427440f, 0.8009745557076129f, 0.8010032545318854f, + 0.8010319515154953f, 0.8010606466583768f, 0.8010893399604639f, 0.8011180314216907f, + 0.8011467210419912f, 0.8011754088212997f, 0.8012040947595499f, 0.8012327788566762f, + 0.8012614611126125f, 0.8012901415272929f, 0.8013188201006516f, 0.8013474968326227f, + 0.8013761717231402f, 0.8014048447721382f, 0.8014335159795510f, 0.8014621853453125f, + 0.8014908528693568f, 0.8015195185516183f, 0.8015481823920310f, 0.8015768443905288f, + 0.8016055045470460f, 0.8016341628615169f, 0.8016628193338755f, 0.8016914739640559f, + 0.8017201267519923f, 0.8017487776976189f, 0.8017774268008698f, 0.8018060740616793f, + 0.8018347194799813f, 0.8018633630557103f, 0.8018920047888001f, 0.8019206446791852f, + 0.8019492827267998f, 0.8019779189315778f, 0.8020065532934536f, 0.8020351858123616f, + 0.8020638164882355f, 0.8020924453210099f, 0.8021210723106189f, 0.8021496974569967f, + 0.8021783207600774f, 0.8022069422197956f, 0.8022355618360851f, 0.8022641796088804f, + 0.8022927955381157f, 0.8023214096237252f, 0.8023500218656431f, 0.8023786322638037f, + 0.8024072408181413f, 0.8024358475285901f, 0.8024644523950843f, 0.8024930554175583f, + 0.8025216565959463f, 0.8025502559301827f, 0.8025788534202015f, 0.8026074490659373f, + 0.8026360428673243f, 0.8026646348242965f, 0.8026932249367886f, 0.8027218132047347f, + 0.8027503996280692f, 0.8027789842067262f, 0.8028075669406404f, 0.8028361478297457f, + 0.8028647268739766f, 0.8028933040732675f, 0.8029218794275528f, 0.8029504529367665f, + 0.8029790246008431f, 0.8030075944197171f, 0.8030361623933228f, 0.8030647285215944f, + 0.8030932928044664f, 0.8031218552418731f, 0.8031504158337487f, 0.8031789745800280f, + 0.8032075314806449f, 0.8032360865355340f, 0.8032646397446298f, 0.8032931911078665f, + 0.8033217406251786f, 0.8033502882965003f, 0.8033788341217662f, 0.8034073781009108f, + 0.8034359202338681f, 0.8034644605205730f, 0.8034929989609595f, 0.8035215355549622f, + 0.8035500703025156f, 0.8035786032035541f, 0.8036071342580120f, 0.8036356634658238f, + 0.8036641908269241f, 0.8036927163412472f, 0.8037212400087274f, 0.8037497618292994f, + 0.8037782818028976f, 0.8038067999294564f, 0.8038353162089102f, 0.8038638306411937f, + 0.8038923432262413f, 0.8039208539639873f, 0.8039493628543665f, 0.8039778698973130f, + 0.8040063750927615f, 0.8040348784406466f, 0.8040633799409027f, 0.8040918795934642f, + 0.8041203773982657f, 0.8041488733552418f, 0.8041773674643269f, 0.8042058597254556f, + 0.8042343501385623f, 0.8042628387035816f, 0.8042913254204481f, 0.8043198102890963f, + 0.8043482933094608f, 0.8043767744814759f, 0.8044052538050764f, 0.8044337312801969f, + 0.8044622069067718f, 0.8044906806847356f, 0.8045191526140231f, 0.8045476226945687f, + 0.8045760909263071f, 0.8046045573091727f, 0.8046330218431003f, 0.8046614845280243f, + 0.8046899453638795f, 0.8047184043506003f, 0.8047468614881214f, 0.8047753167763774f, + 0.8048037702153028f, 0.8048322218048325f, 0.8048606715449008f, 0.8048891194354425f, + 0.8049175654763921f, 0.8049460096676845f, 0.8049744520092541f, 0.8050028925010355f, + 0.8050313311429637f, 0.8050597679349728f, 0.8050882028769979f, 0.8051166359689734f, + 0.8051450672108342f, 0.8051734966025147f, 0.8052019241439499f, 0.8052303498350741f, + 0.8052587736758222f, 0.8052871956661289f, 0.8053156158059288f, 0.8053440340951566f, + 0.8053724505337471f, 0.8054008651216349f, 0.8054292778587547f, 0.8054576887450412f, + 0.8054860977804291f, 0.8055145049648533f, 0.8055429102982483f, 0.8055713137805490f, + 0.8055997154116900f, 0.8056281151916060f, 0.8056565131202319f, 0.8056849091975024f, + 0.8057133034233521f, 0.8057416957977159f, 0.8057700863205286f, 0.8057984749917247f, + 0.8058268618112393f, 0.8058552467790070f, 0.8058836298949625f, 0.8059120111590408f, + 0.8059403905711763f, 0.8059687681313041f, 0.8059971438393591f, 0.8060255176952756f, + 0.8060538896989889f, 0.8060822598504337f, 0.8061106281495447f, 0.8061389945962566f, + 0.8061673591905043f, 0.8061957219322228f, 0.8062240828213467f, 0.8062524418578110f, + 0.8062807990415504f, 0.8063091543724997f, 0.8063375078505940f, 0.8063658594757679f, + 0.8063942092479564f, 0.8064225571670941f, 0.8064509032331161f, 0.8064792474459572f, + 0.8065075898055523f, 0.8065359303118361f, 0.8065642689647438f, 0.8065926057642100f, + 0.8066209407101697f, 0.8066492738025577f, 0.8066776050413089f, 0.8067059344263583f, + 0.8067342619576408f, 0.8067625876350912f, 0.8067909114586445f, 0.8068192334282355f, + 0.8068475535437992f, 0.8068758718052707f, 0.8069041882125845f, 0.8069325027656759f, + 0.8069608154644796f, 0.8069891263089307f, 0.8070174352989642f, 0.8070457424345148f, + 0.8070740477155176f, 0.8071023511419075f, 0.8071306527136196f, 0.8071589524305888f, + 0.8071872502927498f, 0.8072155463000381f, 0.8072438404523883f, 0.8072721327497353f, + 0.8073004231920144f, 0.8073287117791605f, 0.8073569985111084f, 0.8073852833877934f, + 0.8074135664091502f, 0.8074418475751139f, 0.8074701268856197f, 0.8074984043406024f, + 0.8075266799399972f, 0.8075549536837389f, 0.8075832255717627f, 0.8076114956040035f, + 0.8076397637803965f, 0.8076680301008765f, 0.8076962945653788f, 0.8077245571738385f, + 0.8077528179261904f, 0.8077810768223695f, 0.8078093338623112f, 0.8078375890459505f, + 0.8078658423732221f, 0.8078940938440615f, 0.8079223434584036f, 0.8079505912161835f, + 0.8079788371173363f, 0.8080070811617971f, 0.8080353233495009f, 0.8080635636803829f, + 0.8080918021543783f, 0.8081200387714220f, 0.8081482735314492f, 0.8081765064343951f, + 0.8082047374801947f, 0.8082329666687832f, 0.8082611940000957f, 0.8082894194740674f, + 0.8083176430906333f, 0.8083458648497286f, 0.8083740847512886f, 0.8084023027952483f, + 0.8084305189815427f, 0.8084587333101073f, 0.8084869457808771f, 0.8085151563937872f, + 0.8085433651487730f, 0.8085715720457695f, 0.8085997770847118f, 0.8086279802655352f, + 0.8086561815881750f, 0.8086843810525662f, 0.8087125786586441f, 0.8087407744063440f, + 0.8087689682956009f, 0.8087971603263500f, 0.8088253504985267f, 0.8088535388120662f, + 0.8088817252669036f, 0.8089099098629742f, 0.8089380926002133f, 0.8089662734785560f, + 0.8089944524979376f, 0.8090226296582934f, 0.8090508049595586f, 0.8090789784016684f, + 0.8091071499845581f, 0.8091353197081631f, 0.8091634875724185f, 0.8091916535772596f, + 0.8092198177226217f, 0.8092479800084402f, 0.8092761404346501f, 0.8093042990011869f, + 0.8093324557079858f, 0.8093606105549823f, 0.8093887635421114f, 0.8094169146693085f, + 0.8094450639365092f, 0.8094732113436484f, 0.8095013568906616f, 0.8095295005774841f, + 0.8095576424040513f, 0.8095857823702984f, 0.8096139204761609f, 0.8096420567215740f, + 0.8096701911064731f, 0.8096983236307935f, 0.8097264542944707f, 0.8097545830974399f, + 0.8097827100396364f, 0.8098108351209958f, 0.8098389583414535f, 0.8098670797009444f, + 0.8098951991994044f, 0.8099233168367688f, 0.8099514326129726f, 0.8099795465279517f, + 0.8100076585816411f, 0.8100357687739764f, 0.8100638771048930f, 0.8100919835743263f, + 0.8101200881822117f, 0.8101481909284844f, 0.8101762918130803f, 0.8102043908359344f, + 0.8102324879969823f, 0.8102605832961595f, 0.8102886767334012f, 0.8103167683086432f, + 0.8103448580218205f, 0.8103729458728690f, 0.8104010318617239f, 0.8104291159883206f, + 0.8104571982525948f, 0.8104852786544818f, 0.8105133571939170f, 0.8105414338708362f, + 0.8105695086851746f, 0.8105975816368678f, 0.8106256527258511f, 0.8106537219520603f, + 0.8106817893154307f, 0.8107098548158977f, 0.8107379184533972f, 0.8107659802278644f, + 0.8107940401392348f, 0.8108220981874440f, 0.8108501543724276f, 0.8108782086941210f, + 0.8109062611524597f, 0.8109343117473794f, 0.8109623604788156f, 0.8109904073467037f, + 0.8110184523509795f, 0.8110464954915784f, 0.8110745367684359f, 0.8111025761814876f, + 0.8111306137306692f, 0.8111586494159161f, 0.8111866832371639f, 0.8112147151943483f, + 0.8112427452874048f, 0.8112707735162690f, 0.8112987998808765f, 0.8113268243811629f, + 0.8113548470170637f, 0.8113828677885147f, 0.8114108866954514f, 0.8114389037378094f, + 0.8114669189155242f, 0.8114949322285318f, 0.8115229436767675f, 0.8115509532601669f, + 0.8115789609786659f, 0.8116069668321999f, 0.8116349708207047f, 0.8116629729441158f, + 0.8116909732023690f, 0.8117189715954000f, 0.8117469681231442f, 0.8117749627855374f, + 0.8118029555825154f, 0.8118309465140138f, 0.8118589355799680f, 0.8118869227803142f, + 0.8119149081149877f, 0.8119428915839243f, 0.8119708731870597f, 0.8119988529243296f, + 0.8120268307956697f, 0.8120548068010157f, 0.8120827809403034f, 0.8121107532134685f, + 0.8121387236204465f, 0.8121666921611733f, 0.8121946588355847f, 0.8122226236436163f, + 0.8122505865852039f, 0.8122785476602833f, 0.8123065068687901f, 0.8123344642106601f, + 0.8123624196858291f, 0.8123903732942329f, 0.8124183250358072f, 0.8124462749104878f, + 0.8124742229182105f, 0.8125021690589109f, 0.8125301133325250f, 0.8125580557389884f, + 0.8125859962782371f, 0.8126139349502067f, 0.8126418717548332f, 0.8126698066920521f, + 0.8126977397617995f, 0.8127256709640110f, 0.8127536002986226f, 0.8127815277655701f, + 0.8128094533647892f, 0.8128373770962157f, 0.8128652989597857f, 0.8128932189554346f, + 0.8129211370830988f, 0.8129490533427137f, 0.8129769677342152f, 0.8130048802575394f, + 0.8130327909126219f, 0.8130606996993988f, 0.8130886066178057f, 0.8131165116677787f, + 0.8131444148492536f, 0.8131723161621661f, 0.8132002156064524f, 0.8132281131820482f, + 0.8132560088888894f, 0.8132839027269120f, 0.8133117946960517f, 0.8133396847962446f, + 0.8133675730274266f, 0.8133954593895335f, 0.8134233438825014f, 0.8134512265062659f, + 0.8134791072607632f, 0.8135069861459292f, 0.8135348631616998f, 0.8135627383080108f, + 0.8135906115847985f, 0.8136184829919986f, 0.8136463525295469f, 0.8136742201973797f, + 0.8137020859954327f, 0.8137299499236420f, 0.8137578119819435f, 0.8137856721702732f, + 0.8138135304885672f, 0.8138413869367612f, 0.8138692415147916f, 0.8138970942225940f, + 0.8139249450601045f, 0.8139527940272593f, 0.8139806411239942f, 0.8140084863502451f, + 0.8140363297059483f, 0.8140641711910398f, 0.8140920108054553f, 0.8141198485491312f, + 0.8141476844220034f, 0.8141755184240077f, 0.8142033505550804f, 0.8142311808151577f, + 0.8142590092041753f, 0.8142868357220693f, 0.8143146603687759f, 0.8143424831442311f, + 0.8143703040483711f, 0.8143981230811316f, 0.8144259402424491f, 0.8144537555322594f, + 0.8144815689504987f, 0.8145093804971030f, 0.8145371901720084f, 0.8145649979751513f, + 0.8145928039064673f, 0.8146206079658928f, 0.8146484101533639f, 0.8146762104688166f, + 0.8147040089121871f, 0.8147318054834115f, 0.8147596001824260f, 0.8147873930091665f, + 0.8148151839635693f, 0.8148429730455707f, 0.8148707602551065f, 0.8148985455921132f, + 0.8149263290565266f, 0.8149541106482830f, 0.8149818903673187f, 0.8150096682135697f, + 0.8150374441869722f, 0.8150652182874624f, 0.8150929905149764f, 0.8151207608694506f, + 0.8151485293508208f, 0.8151762959590236f, 0.8152040606939950f, 0.8152318235556711f, + 0.8152595845439883f, 0.8152873436588827f, 0.8153151009002905f, 0.8153428562681480f, + 0.8153706097623913f, 0.8153983613829567f, 0.8154261111297804f, 0.8154538590027987f, + 0.8154816050019478f, 0.8155093491271639f, 0.8155370913783831f, 0.8155648317555421f, + 0.8155925702585767f, 0.8156203068874234f, 0.8156480416420183f, 0.8156757745222979f, + 0.8157035055281984f, 0.8157312346596558f, 0.8157589619166067f, 0.8157866872989873f, + 0.8158144108067338f, 0.8158421324397825f, 0.8158698521980700f, 0.8158975700815321f, + 0.8159252860901054f, 0.8159530002237263f, 0.8159807124823309f, 0.8160084228658556f, + 0.8160361313742367f, 0.8160638380074107f, 0.8160915427653136f, 0.8161192456478820f, + 0.8161469466550522f, 0.8161746457867605f, 0.8162023430429431f, 0.8162300384235367f, + 0.8162577319284774f, 0.8162854235577016f, 0.8163131133111458f, 0.8163408011887462f, + 0.8163684871904392f, 0.8163961713161613f, 0.8164238535658487f, 0.8164515339394380f, + 0.8164792124368654f, 0.8165068890580673f, 0.8165345638029804f, 0.8165622366715407f, + 0.8165899076636849f, 0.8166175767793493f, 0.8166452440184702f, 0.8166729093809842f, + 0.8167005728668278f, 0.8167282344759372f, 0.8167558942082489f, 0.8167835520636995f, + 0.8168112080422253f, 0.8168388621437627f, 0.8168665143682482f, 0.8168941647156184f, + 0.8169218131858095f, 0.8169494597787581f, 0.8169771044944008f, 0.8170047473326739f, + 0.8170323882935139f, 0.8170600273768573f, 0.8170876645826407f, 0.8171152999108003f, + 0.8171429333612730f, 0.8171705649339950f, 0.8171981946289029f, 0.8172258224459331f, + 0.8172534483850222f, 0.8172810724461068f, 0.8173086946291234f, 0.8173363149340084f, + 0.8173639333606985f, 0.8173915499091300f, 0.8174191645792396f, 0.8174467773709638f, + 0.8174743882842394f, 0.8175019973190024f, 0.8175296044751899f, 0.8175572097527380f, + 0.8175848131515837f, 0.8176124146716632f, 0.8176400143129134f, 0.8176676120752707f, + 0.8176952079586717f, 0.8177228019630529f, 0.8177503940883510f, 0.8177779843345026f, + 0.8178055727014443f, 0.8178331591891126f, 0.8178607437974442f, 0.8178883265263758f, + 0.8179159073758437f, 0.8179434863457850f, 0.8179710634361358f, 0.8179986386468331f, + 0.8180262119778134f, 0.8180537834290134f, 0.8180813530003697f, 0.8181089206918188f, + 0.8181364865032977f, 0.8181640504347427f, 0.8181916124860907f, 0.8182191726572783f, + 0.8182467309482420f, 0.8182742873589187f, 0.8183018418892450f, 0.8183293945391575f, + 0.8183569453085932f, 0.8183844941974883f, 0.8184120412057798f, 0.8184395863334043f, + 0.8184671295802987f, 0.8184946709463995f, 0.8185222104316433f, 0.8185497480359671f, + 0.8185772837593075f, 0.8186048176016013f, 0.8186323495627850f, 0.8186598796427955f, + 0.8186874078415697f, 0.8187149341590439f, 0.8187424585951553f, 0.8187699811498405f, + 0.8187975018230360f, 0.8188250206146789f, 0.8188525375247059f, 0.8188800525530536f, + 0.8189075656996589f, 0.8189350769644586f, 0.8189625863473894f, 0.8189900938483881f, + 0.8190175994673915f, 0.8190451032043364f, 0.8190726050591597f, 0.8191001050317980f, + 0.8191276031221882f, 0.8191550993302672f, 0.8191825936559717f, 0.8192100860992385f, + 0.8192375766600045f, 0.8192650653382065f, 0.8192925521337814f, 0.8193200370466659f, + 0.8193475200767970f, 0.8193750012241113f, 0.8194024804885460f, 0.8194299578700377f, + 0.8194574333685233f, 0.8194849069839396f, 0.8195123787162237f, 0.8195398485653123f, + 0.8195673165311422f, 0.8195947826136505f, 0.8196222468127740f, 0.8196497091284494f, + 0.8196771695606138f, 0.8197046281092041f, 0.8197320847741570f, 0.8197595395554097f, + 0.8197869924528990f, 0.8198144434665617f, 0.8198418925963348f, 0.8198693398421552f, + 0.8198967852039598f, 0.8199242286816857f, 0.8199516702752696f, 0.8199791099846486f, + 0.8200065478097597f, 0.8200339837505396f, 0.8200614178069255f, 0.8200888499788542f, + 0.8201162802662627f, 0.8201437086690881f, 0.8201711351872673f, 0.8201985598207371f, + 0.8202259825694347f, 0.8202534034332969f, 0.8202808224122609f, 0.8203082395062635f, + 0.8203356547152418f, 0.8203630680391328f, 0.8203904794778735f, 0.8204178890314009f, + 0.8204452966996520f, 0.8204727024825638f, 0.8205001063800734f, 0.8205275083921177f, + 0.8205549085186339f, 0.8205823067595589f, 0.8206097031148298f, 0.8206370975843836f, + 0.8206644901681575f, 0.8206918808660884f, 0.8207192696781133f, 0.8207466566041693f, + 0.8207740416441937f, 0.8208014247981232f, 0.8208288060658953f, 0.8208561854474467f, + 0.8208835629427146f, 0.8209109385516362f, 0.8209383122741484f, 0.8209656841101886f, + 0.8209930540596935f, 0.8210204221226005f, 0.8210477882988466f, 0.8210751525883689f, + 0.8211025149911046f, 0.8211298755069908f, 0.8211572341359646f, 0.8211845908779631f, + 0.8212119457329236f, 0.8212392987007829f, 0.8212666497814786f, 0.8212939989749475f, + 0.8213213462811267f, 0.8213486916999536f, 0.8213760352313654f, 0.8214033768752990f, + 0.8214307166316918f, 0.8214580545004808f, 0.8214853904816033f, 0.8215127245749966f, + 0.8215400567805976f, 0.8215673870983436f, 0.8215947155281719f, 0.8216220420700195f, + 0.8216493667238238f, 0.8216766894895220f, 0.8217040103670512f, 0.8217313293563487f, + 0.8217586464573517f, 0.8217859616699974f, 0.8218132749942231f, 0.8218405864299659f, + 0.8218678959771631f, 0.8218952036357522f, 0.8219225094056700f, 0.8219498132868540f, + 0.8219771152792416f, 0.8220044153827697f, 0.8220317135973758f, 0.8220590099229972f, + 0.8220863043595711f, 0.8221135969070347f, 0.8221408875653253f, 0.8221681763343804f, + 0.8221954632141372f, 0.8222227482045328f, 0.8222500313055047f, 0.8222773125169901f, + 0.8223045918389265f, 0.8223318692712508f, 0.8223591448139008f, 0.8223864184668135f, + 0.8224136902299264f, 0.8224409601031767f, 0.8224682280865019f, 0.8224954941798392f, + 0.8225227583831259f, 0.8225500206962996f, 0.8225772811192974f, 0.8226045396520567f, + 0.8226317962945150f, 0.8226590510466095f, 0.8226863039082776f, 0.8227135548794569f, + 0.8227408039600844f, 0.8227680511500978f, 0.8227952964494343f, 0.8228225398580313f, + 0.8228497813758263f, 0.8228770210027566f, 0.8229042587387598f, 0.8229314945837731f, + 0.8229587285377340f, 0.8229859606005798f, 0.8230131907722481f, 0.8230404190526763f, + 0.8230676454418017f, 0.8230948699395618f, 0.8231220925458941f, 0.8231493132607359f, + 0.8231765320840249f, 0.8232037490156983f, 0.8232309640556937f, 0.8232581772039484f, + 0.8232853884604001f, 0.8233125978249861f, 0.8233398052976439f, 0.8233670108783111f, + 0.8233942145669251f, 0.8234214163634233f, 0.8234486162677432f, 0.8234758142798225f, + 0.8235030103995985f, 0.8235302046270087f, 0.8235573969619908f, 0.8235845874044821f, + 0.8236117759544203f, 0.8236389626117427f, 0.8236661473763870f, 0.8236933302482907f, + 0.8237205112273913f, 0.8237476903136265f, 0.8237748675069336f, 0.8238020428072502f, + 0.8238292162145140f, 0.8238563877286624f, 0.8238835573496330f, 0.8239107250773635f, + 0.8239378909117914f, 0.8239650548528541f, 0.8239922169004893f, 0.8240193770546347f, + 0.8240465353152278f, 0.8240736916822060f, 0.8241008461555072f, 0.8241279987350688f, + 0.8241551494208286f, 0.8241822982127239f, 0.8242094451106927f, 0.8242365901146723f, + 0.8242637332246004f, 0.8242908744404148f, 0.8243180137620530f, 0.8243451511894525f, + 0.8243722867225513f, 0.8243994203612867f, 0.8244265521055963f, 0.8244536819554180f, + 0.8244808099106895f, 0.8245079359713483f, 0.8245350601373320f, 0.8245621824085785f, + 0.8245893027850253f, 0.8246164212666101f, 0.8246435378532706f, 0.8246706525449445f, + 0.8246977653415695f, 0.8247248762430832f, 0.8247519852494235f, 0.8247790923605280f, + 0.8248061975763343f, 0.8248333008967803f, 0.8248604023218037f, 0.8248875018513421f, + 0.8249145994853331f, 0.8249416952237149f, 0.8249687890664247f, 0.8249958810134006f, + 0.8250229710645802f, 0.8250500592199013f, 0.8250771454793017f, 0.8251042298427189f, + 0.8251313123100910f, 0.8251583928813556f, 0.8251854715564504f, 0.8252125483353133f, + 0.8252396232178821f, 0.8252666962040945f, 0.8252937672938884f, 0.8253208364872013f, + 0.8253479037839714f, 0.8253749691841362f, 0.8254020326876336f, 0.8254290942944015f, + 0.8254561540043774f, 0.8254832118174996f, 0.8255102677337056f, 0.8255373217529333f, + 0.8255643738751205f, 0.8255914241002050f, 0.8256184724281249f, 0.8256455188588177f, + 0.8256725633922214f, 0.8256996060282739f, 0.8257266467669130f, 0.8257536856080765f, + 0.8257807225517024f, 0.8258077575977285f, 0.8258347907460927f, 0.8258618219967329f, + 0.8258888513495869f, 0.8259158788045925f, 0.8259429043616879f, 0.8259699280208108f, + 0.8259969497818990f, 0.8260239696448907f, 0.8260509876097235f, 0.8260780036763355f, + 0.8261050178446646f, 0.8261320301146486f, 0.8261590404862257f, 0.8261860489593336f, + 0.8262130555339101f, 0.8262400602098936f, 0.8262670629872216f, 0.8262940638658323f, + 0.8263210628456634f, 0.8263480599266533f, 0.8263750551087395f, 0.8264020483918603f, + 0.8264290397759534f, 0.8264560292609570f, 0.8264830168468089f, 0.8265100025334473f, + 0.8265369863208100f, 0.8265639682088350f, 0.8265909481974604f, 0.8266179262866242f, + 0.8266449024762642f, 0.8266718767663187f, 0.8266988491567256f, 0.8267258196474229f, + 0.8267527882383485f, 0.8267797549294407f, 0.8268067197206374f, 0.8268336826118764f, + 0.8268606436030961f, 0.8268876026942344f, 0.8269145598852293f, 0.8269415151760191f, + 0.8269684685665415f, 0.8269954200567348f, 0.8270223696465370f, 0.8270493173358860f, + 0.8270762631247203f, 0.8271032070129776f, 0.8271301490005961f, 0.8271570890875140f, + 0.8271840272736690f, 0.8272109635589998f, 0.8272378979434440f, 0.8272648304269401f, + 0.8272917610094258f, 0.8273186896908395f, 0.8273456164711193f, 0.8273725413502032f, + 0.8273994643280294f, 0.8274263854045361f, 0.8274533045796613f, 0.8274802218533431f, + 0.8275071372255198f, 0.8275340506961296f, 0.8275609622651104f, 0.8275878719324007f, + 0.8276147796979384f, 0.8276416855616616f, 0.8276685895235089f, 0.8276954915834179f, + 0.8277223917413272f, 0.8277492899971749f, 0.8277761863508991f, 0.8278030808024380f, + 0.8278299733517298f, 0.8278568639987128f, 0.8278837527433253f, 0.8279106395855051f, + 0.8279375245251909f, 0.8279644075623205f, 0.8279912886968325f, 0.8280181679286647f, + 0.8280450452577558f, 0.8280719206840437f, 0.8280987942074667f, 0.8281256658279632f, + 0.8281525355454714f, 0.8281794033599295f, 0.8282062692712756f, 0.8282331332794483f, + 0.8282599953843857f, 0.8282868555860259f, 0.8283137138843075f, 0.8283405702791686f, + 0.8283674247705475f, 0.8283942773583824f, 0.8284211280426119f, 0.8284479768231741f, + 0.8284748237000071f, 0.8285016686730495f, 0.8285285117422396f, 0.8285553529075155f, + 0.8285821921688158f, 0.8286090295260785f, 0.8286358649792422f, 0.8286626985282451f, + 0.8286895301730257f, 0.8287163599135222f, 0.8287431877496729f, 0.8287700136814162f, + 0.8287968377086906f, 0.8288236598314342f, 0.8288504800495856f, 0.8288772983630830f, + 0.8289041147718649f, 0.8289309292758695f, 0.8289577418750355f, 0.8289845525693009f, + 0.8290113613586044f, 0.8290381682428842f, 0.8290649732220788f, 0.8290917762961266f, + 0.8291185774649660f, 0.8291453767285353f, 0.8291721740867731f, 0.8291989695396177f, + 0.8292257630870076f, 0.8292525547288812f, 0.8292793444651767f, 0.8293061322958329f, + 0.8293329182207883f, 0.8293597022399809f, 0.8293864843533495f, 0.8294132645608324f, + 0.8294400428623683f, 0.8294668192578952f, 0.8294935937473521f, 0.8295203663306772f, + 0.8295471370078088f, 0.8295739057786857f, 0.8296006726432464f, 0.8296274376014292f, + 0.8296542006531726f, 0.8296809617984152f, 0.8297077210370954f, 0.8297344783691519f, + 0.8297612337945230f, 0.8297879873131474f, 0.8298147389249635f, 0.8298414886299097f, + 0.8298682364279248f, 0.8298949823189473f, 0.8299217263029155f, 0.8299484683797682f, + 0.8299752085494438f, 0.8300019468118810f, 0.8300286831670182f, 0.8300554176147940f, + 0.8300821501551470f, 0.8301088807880157f, 0.8301356095133389f, 0.8301623363310549f, + 0.8301890612411024f, 0.8302157842434199f, 0.8302425053379462f, 0.8302692245246197f, + 0.8302959418033791f, 0.8303226571741630f, 0.8303493706369099f, 0.8303760821915586f, + 0.8304027918380475f, 0.8304294995763154f, 0.8304562054063008f, 0.8304829093279426f, + 0.8305096113411791f, 0.8305363114459491f, 0.8305630096421911f, 0.8305897059298440f, + 0.8306164003088463f, 0.8306430927791366f, 0.8306697833406538f, 0.8306964719933363f, + 0.8307231587371229f, 0.8307498435719521f, 0.8307765264977630f, 0.8308032075144939f, + 0.8308298866220836f, 0.8308565638204708f, 0.8308832391095942f, 0.8309099124893925f, + 0.8309365839598044f, 0.8309632535207686f, 0.8309899211722238f, 0.8310165869141088f, + 0.8310432507463623f, 0.8310699126689229f, 0.8310965726817295f, 0.8311232307847208f, + 0.8311498869778354f, 0.8311765412610123f, 0.8312031936341900f, 0.8312298440973074f, + 0.8312564926503032f, 0.8312831392931161f, 0.8313097840256851f, 0.8313364268479488f, + 0.8313630677598459f, 0.8313897067613154f, 0.8314163438522959f, 0.8314429790327262f, + 0.8314696123025452f, 0.8314962436616916f, 0.8315228731101044f, 0.8315495006477220f, + 0.8315761262744836f, 0.8316027499903280f, 0.8316293717951937f, 0.8316559916890198f, + 0.8316826096717451f, 0.8317092257433084f, 0.8317358399036484f, 0.8317624521527042f, + 0.8317890624904144f, 0.8318156709167179f, 0.8318422774315538f, 0.8318688820348608f, + 0.8318954847265776f, 0.8319220855066433f, 0.8319486843749966f, 0.8319752813315766f, + 0.8320018763763218f, 0.8320284695091715f, 0.8320550607300645f, 0.8320816500389395f, + 0.8321082374357355f, 0.8321348229203915f, 0.8321614064928463f, 0.8321879881530387f, + 0.8322145679009080f, 0.8322411457363927f, 0.8322677216594319f, 0.8322942956699646f, + 0.8323208677679297f, 0.8323474379532659f, 0.8323740062259126f, 0.8324005725858084f, + 0.8324271370328923f, 0.8324536995671034f, 0.8324802601883804f, 0.8325068188966626f, + 0.8325333756918887f, 0.8325599305739978f, 0.8325864835429289f, 0.8326130345986208f, + 0.8326395837410128f, 0.8326661309700435f, 0.8326926762856522f, 0.8327192196877778f, + 0.8327457611763595f, 0.8327723007513359f, 0.8327988384126462f, 0.8328253741602296f, + 0.8328519079940250f, 0.8328784399139714f, 0.8329049699200077f, 0.8329314980120731f, + 0.8329580241901067f, 0.8329845484540473f, 0.8330110708038343f, 0.8330375912394065f, + 0.8330641097607029f, 0.8330906263676627f, 0.8331171410602251f, 0.8331436538383288f, + 0.8331701647019132f, 0.8331966736509172f, 0.8332231806852800f, 0.8332496858049406f, + 0.8332761890098382f, 0.8333026902999118f, 0.8333291896751005f, 0.8333556871353435f, + 0.8333821826805797f, 0.8334086763107486f, 0.8334351680257888f, 0.8334616578256399f, + 0.8334881457102408f, 0.8335146316795305f, 0.8335411157334485f, 0.8335675978719337f, + 0.8335940780949253f, 0.8336205564023622f, 0.8336470327941841f, 0.8336735072703296f, + 0.8336999798307383f, 0.8337264504753491f, 0.8337529192041013f, 0.8337793860169339f, + 0.8338058509137863f, 0.8338323138945977f, 0.8338587749593070f, 0.8338852341078536f, + 0.8339116913401767f, 0.8339381466562156f, 0.8339646000559092f, 0.8339910515391971f, + 0.8340175011060181f, 0.8340439487563117f, 0.8340703944900171f, 0.8340968383070735f, + 0.8341232802074201f, 0.8341497201909961f, 0.8341761582577408f, 0.8342025944075935f, + 0.8342290286404934f, 0.8342554609563797f, 0.8342818913551918f, 0.8343083198368688f, + 0.8343347464013501f, 0.8343611710485749f, 0.8343875937784825f, 0.8344140145910121f, + 0.8344404334861032f, 0.8344668504636948f, 0.8344932655237265f, 0.8345196786661373f, + 0.8345460898908668f, 0.8345724991978541f, 0.8345989065870386f, 0.8346253120583595f, + 0.8346517156117563f, 0.8346781172471682f, 0.8347045169645346f, 0.8347309147637949f, + 0.8347573106448882f, 0.8347837046077541f, 0.8348100966523317f, 0.8348364867785607f, + 0.8348628749863800f, 0.8348892612757294f, 0.8349156456465480f, 0.8349420280987752f, + 0.8349684086323504f, 0.8349947872472131f, 0.8350211639433026f, 0.8350475387205581f, + 0.8350739115789193f, 0.8351002825183255f, 0.8351266515387159f, 0.8351530186400302f, + 0.8351793838222076f, 0.8352057470851877f, 0.8352321084289096f, 0.8352584678533130f, + 0.8352848253583374f, 0.8353111809439220f, 0.8353375346100063f, 0.8353638863565298f, + 0.8353902361834318f, 0.8354165840906520f, 0.8354429300781296f, 0.8354692741458043f, + 0.8354956162936154f, 0.8355219565215023f, 0.8355482948294047f, 0.8355746312172618f, + 0.8356009656850134f, 0.8356272982325987f, 0.8356536288599574f, 0.8356799575670288f, + 0.8357062843537526f, 0.8357326092200681f, 0.8357589321659149f, 0.8357852531912326f, + 0.8358115722959606f, 0.8358378894800385f, 0.8358642047434056f, 0.8358905180860018f, + 0.8359168295077664f, 0.8359431390086389f, 0.8359694465885590f, 0.8359957522474661f, + 0.8360220559852999f, 0.8360483578019998f, 0.8360746576975054f, 0.8361009556717565f, + 0.8361272517246922f, 0.8361535458562525f, 0.8361798380663767f, 0.8362061283550045f, + 0.8362324167220756f, 0.8362587031675295f, 0.8362849876913057f, 0.8363112702933437f, + 0.8363375509735835f, 0.8363638297319644f, 0.8363901065684262f, 0.8364163814829083f, + 0.8364426544753505f, 0.8364689255456922f, 0.8364951946938733f, 0.8365214619198333f, + 0.8365477272235119f, 0.8365739906048487f, 0.8366002520637834f, 0.8366265116002556f, + 0.8366527692142049f, 0.8366790249055711f, 0.8367052786742938f, 0.8367315305203126f, + 0.8367577804435672f, 0.8367840284439974f, 0.8368102745215428f, 0.8368365186761429f, + 0.8368627609077378f, 0.8368890012162670f, 0.8369152396016700f, 0.8369414760638868f, + 0.8369677106028570f, 0.8369939432185203f, 0.8370201739108164f, 0.8370464026796851f, + 0.8370726295250660f, 0.8370988544468989f, 0.8371250774451237f, 0.8371512985196798f, + 0.8371775176705072f, 0.8372037348975456f, 0.8372299502007348f, 0.8372561635800144f, + 0.8372823750353243f, 0.8373085845666043f, 0.8373347921737940f, 0.8373609978568333f, + 0.8373872016156619f, 0.8374134034502198f, 0.8374396033604464f, 0.8374658013462819f, + 0.8374919974076659f, 0.8375181915445381f, 0.8375443837568385f, 0.8375705740445070f, + 0.8375967624074830f, 0.8376229488457068f, 0.8376491333591178f, 0.8376753159476562f, + 0.8377014966112617f, 0.8377276753498740f, 0.8377538521634331f, 0.8377800270518788f, + 0.8378062000151509f, 0.8378323710531893f, 0.8378585401659340f, 0.8378847073533245f, + 0.8379108726153011f, 0.8379370359518035f, 0.8379631973627714f, 0.8379893568481448f, + 0.8380155144078637f, 0.8380416700418680f, 0.8380678237500974f, 0.8380939755324919f, + 0.8381201253889915f, 0.8381462733195360f, 0.8381724193240653f, 0.8381985634025193f, + 0.8382247055548381f, 0.8382508457809613f, 0.8382769840808292f, 0.8383031204543816f, + 0.8383292549015583f, 0.8383553874222994f, 0.8383815180165448f, 0.8384076466842345f, + 0.8384337734253083f, 0.8384598982397063f, 0.8384860211273686f, 0.8385121420882348f, + 0.8385382611222452f, 0.8385643782293397f, 0.8385904934094581f, 0.8386166066625407f, + 0.8386427179885273f, 0.8386688273873579f, 0.8386949348589725f, 0.8387210404033112f, + 0.8387471440203139f, 0.8387732457099207f, 0.8387993454720716f, 0.8388254433067066f, + 0.8388515392137658f, 0.8388776331931891f, 0.8389037252449165f, 0.8389298153688883f, + 0.8389559035650443f, 0.8389819898333248f, 0.8390080741736696f, 0.8390341565860189f, + 0.8390602370703126f, 0.8390863156264911f, 0.8391123922544942f, 0.8391384669542620f, + 0.8391645397257346f, 0.8391906105688521f, 0.8392166794835547f, 0.8392427464697824f, + 0.8392688115274752f, 0.8392948746565734f, 0.8393209358570169f, 0.8393469951287460f, + 0.8393730524717008f, 0.8393991078858212f, 0.8394251613710476f, 0.8394512129273201f, + 0.8394772625545786f, 0.8395033102527634f, 0.8395293560218147f, 0.8395553998616726f, + 0.8395814417722771f, 0.8396074817535686f, 0.8396335198054872f, 0.8396595559279729f, + 0.8396855901209661f, 0.8397116223844069f, 0.8397376527182353f, 0.8397636811223917f, + 0.8397897075968163f, 0.8398157321414491f, 0.8398417547562305f, 0.8398677754411005f, + 0.8398937941959995f, 0.8399198110208675f, 0.8399458259156450f, 0.8399718388802720f, + 0.8399978499146887f, 0.8400238590188356f, 0.8400498661926527f, 0.8400758714360802f, + 0.8401018747490584f, 0.8401278761315276f, 0.8401538755834280f, 0.8401798731046999f, + 0.8402058686952836f, 0.8402318623551192f, 0.8402578540841471f, 0.8402838438823075f, + 0.8403098317495408f, 0.8403358176857870f, 0.8403618016909867f, 0.8403877837650802f, + 0.8404137639080075f, 0.8404397421197091f, 0.8404657184001252f, 0.8404916927491963f, + 0.8405176651668625f, 0.8405436356530642f, 0.8405696042077418f, 0.8405955708308356f, + 0.8406215355222857f, 0.8406474982820327f, 0.8406734591100169f, 0.8406994180061785f, + 0.8407253749704581f, 0.8407513300027958f, 0.8407772831031320f, 0.8408032342714071f, + 0.8408291835075616f, 0.8408551308115357f, 0.8408810761832698f, 0.8409070196227043f, + 0.8409329611297797f, 0.8409589007044362f, 0.8409848383466142f, 0.8410107740562542f, + 0.8410367078332966f, 0.8410626396776818f, 0.8410885695893502f, 0.8411144975682421f, + 0.8411404236142981f, 0.8411663477274585f, 0.8411922699076637f, 0.8412181901548543f, + 0.8412441084689706f, 0.8412700248499531f, 0.8412959392977422f, 0.8413218518122783f, + 0.8413477623935020f, 0.8413736710413536f, 0.8413995777557738f, 0.8414254825367028f, + 0.8414513853840813f, 0.8414772862978495f, 0.8415031852779482f, 0.8415290823243176f, + 0.8415549774368983f, 0.8415808706156310f, 0.8416067618604559f, 0.8416326511713136f, + 0.8416585385481448f, 0.8416844239908896f, 0.8417103074994888f, 0.8417361890738830f, + 0.8417620687140125f, 0.8417879464198180f, 0.8418138221912399f, 0.8418396960282188f, + 0.8418655679306953f, 0.8418914378986099f, 0.8419173059319031f, 0.8419431720305155f, + 0.8419690361943877f, 0.8419948984234602f, 0.8420207587176737f, 0.8420466170769685f, + 0.8420724735012854f, 0.8420983279905651f, 0.8421241805447479f, 0.8421500311637744f, + 0.8421758798475856f, 0.8422017265961216f, 0.8422275714093234f, 0.8422534142871312f, + 0.8422792552294859f, 0.8423050942363283f, 0.8423309313075985f, 0.8423567664432374f, + 0.8423825996431860f, 0.8424084309073843f, 0.8424342602357732f, 0.8424600876282935f, + 0.8424859130848856f, 0.8425117366054903f, 0.8425375581900484f, 0.8425633778385002f, + 0.8425891955507866f, 0.8426150113268484f, 0.8426408251666259f, 0.8426666370700602f, + 0.8426924470370916f, 0.8427182550676611f, 0.8427440611617092f, 0.8427698653191766f, + 0.8427956675400041f, 0.8428214678241326f, 0.8428472661715023f, 0.8428730625820543f, + 0.8428988570557293f, 0.8429246495924678f, 0.8429504401922108f, 0.8429762288548990f, + 0.8430020155804728f, 0.8430278003688734f, 0.8430535832200413f, 0.8430793641339173f, + 0.8431051431104423f, 0.8431309201495566f, 0.8431566952512014f, 0.8431824684153175f, + 0.8432082396418454f, 0.8432340089307261f, 0.8432597762819003f, 0.8432855416953087f, + 0.8433113051708920f, 0.8433370667085915f, 0.8433628263083475f, 0.8433885839701010f, + 0.8434143396937928f, 0.8434400934793637f, 0.8434658453267544f, 0.8434915952359060f, + 0.8435173432067591f, 0.8435430892392547f, 0.8435688333333334f, 0.8435945754889362f, + 0.8436203157060042f, 0.8436460539844777f, 0.8436717903242978f, 0.8436975247254056f, + 0.8437232571877415f, 0.8437489877112468f, 0.8437747162958622f, 0.8438004429415286f, + 0.8438261676481867f, 0.8438518904157777f, 0.8438776112442422f, 0.8439033301335213f, + 0.8439290470835559f, 0.8439547620942868f, 0.8439804751656548f, 0.8440061862976012f, + 0.8440318954900664f, 0.8440576027429918f, 0.8440833080563179f, 0.8441090114299860f, + 0.8441347128639369f, 0.8441604123581115f, 0.8441861099124507f, 0.8442118055268956f, + 0.8442374992013870f, 0.8442631909358659f, 0.8442888807302734f, 0.8443145685845502f, + 0.8443402544986376f, 0.8443659384724763f, 0.8443916205060074f, 0.8444173005991717f, + 0.8444429787519107f, 0.8444686549641648f, 0.8444943292358753f, 0.8445200015669831f, + 0.8445456719574292f, 0.8445713404071549f, 0.8445970069161007f, 0.8446226714842080f, + 0.8446483341114178f, 0.8446739947976709f, 0.8446996535429085f, 0.8447253103470718f, + 0.8447509652101015f, 0.8447766181319388f, 0.8448022691125249f, 0.8448279181518006f, + 0.8448535652497070f, 0.8448792104061854f, 0.8449048536211766f, 0.8449304948946219f, + 0.8449561342264621f, 0.8449817716166385f, 0.8450074070650923f, 0.8450330405717641f, + 0.8450586721365955f, 0.8450843017595274f, 0.8451099294405009f, 0.8451355551794570f, + 0.8451611789763371f, 0.8451868008310821f, 0.8452124207436332f, 0.8452380387139317f, + 0.8452636547419182f, 0.8452892688275343f, 0.8453148809707212f, 0.8453404911714195f, + 0.8453660994295711f, 0.8453917057451165f, 0.8454173101179971f, 0.8454429125481543f, + 0.8454685130355288f, 0.8454941115800622f, 0.8455197081816954f, 0.8455453028403697f, + 0.8455708955560263f, 0.8455964863286063f, 0.8456220751580510f, 0.8456476620443014f, + 0.8456732469872991f, 0.8456988299869849f, 0.8457244110433001f, 0.8457499901561861f, + 0.8457755673255839f, 0.8458011425514350f, 0.8458267158336803f, 0.8458522871722612f, + 0.8458778565671190f, 0.8459034240181948f, 0.8459289895254299f, 0.8459545530887658f, + 0.8459801147081433f, 0.8460056743835038f, 0.8460312321147889f, 0.8460567879019395f, + 0.8460823417448969f, 0.8461078936436027f, 0.8461334435979978f, 0.8461589916080237f, + 0.8461845376736217f, 0.8462100817947329f, 0.8462356239712987f, 0.8462611642032606f, + 0.8462867024905597f, 0.8463122388331373f, 0.8463377732309348f, 0.8463633056838936f, + 0.8463888361919549f, 0.8464143647550600f, 0.8464398913731503f, 0.8464654160461673f, + 0.8464909387740520f, 0.8465164595567460f, 0.8465419783941908f, 0.8465674952863272f, + 0.8465930102330972f, 0.8466185232344418f, 0.8466440342903024f, 0.8466695434006204f, + 0.8466950505653374f, 0.8467205557843945f, 0.8467460590577333f, 0.8467715603852949f, + 0.8467970597670209f, 0.8468225572028528f, 0.8468480526927319f, 0.8468735462365995f, + 0.8468990378343974f, 0.8469245274860664f, 0.8469500151915484f, 0.8469755009507848f, + 0.8470009847637169f, 0.8470264666302861f, 0.8470519465504340f, 0.8470774245241020f, + 0.8471029005512315f, 0.8471283746317640f, 0.8471538467656409f, 0.8471793169528038f, + 0.8472047851931940f, 0.8472302514867530f, 0.8472557158334226f, 0.8472811782331438f, + 0.8473066386858583f, 0.8473320971915078f, 0.8473575537500334f, 0.8473830083613769f, + 0.8474084610254797f, 0.8474339117422833f, 0.8474593605117292f, 0.8474848073337592f, + 0.8475102522083143f, 0.8475356951353364f, 0.8475611361147670f, 0.8475865751465476f, + 0.8476120122306198f, 0.8476374473669248f, 0.8476628805554046f, 0.8476883117960007f, + 0.8477137410886543f, 0.8477391684333073f, 0.8477645938299012f, 0.8477900172783776f, + 0.8478154387786779f, 0.8478408583307440f, 0.8478662759345171f, 0.8478916915899390f, + 0.8479171052969514f, 0.8479425170554957f, 0.8479679268655137f, 0.8479933347269469f, + 0.8480187406397368f, 0.8480441446038253f, 0.8480695466191537f, 0.8480949466856638f, + 0.8481203448032973f, 0.8481457409719957f, 0.8481711351917006f, 0.8481965274623540f, + 0.8482219177838970f, 0.8482473061562716f, 0.8482726925794196f, 0.8482980770532823f, + 0.8483234595778015f, 0.8483488401529191f, 0.8483742187785764f, 0.8483995954547153f, + 0.8484249701812776f, 0.8484503429582047f, 0.8484757137854385f, 0.8485010826629206f, + 0.8485264495905926f, 0.8485518145683966f, 0.8485771775962739f, 0.8486025386741664f, + 0.8486278978020159f, 0.8486532549797638f, 0.8486786102073522f, 0.8487039634847228f, + 0.8487293148118170f, 0.8487546641885769f, 0.8487800116149442f, 0.8488053570908604f, + 0.8488307006162675f, 0.8488560421911072f, 0.8488813818153212f, 0.8489067194888514f, + 0.8489320552116396f, 0.8489573889836274f, 0.8489827208047567f, 0.8490080506749692f, + 0.8490333785942067f, 0.8490587045624113f, 0.8490840285795243f, 0.8491093506454878f, + 0.8491346707602436f, 0.8491599889237336f, 0.8491853051358993f, 0.8492106193966830f, + 0.8492359317060260f, 0.8492612420638704f, 0.8492865504701582f, 0.8493118569248310f, + 0.8493371614278307f, 0.8493624639790992f, 0.8493877645785783f, 0.8494130632262100f, + 0.8494383599219359f, 0.8494636546656982f, 0.8494889474574385f, 0.8495142382970987f, + 0.8495395271846209f, 0.8495648141199468f, 0.8495900991030183f, 0.8496153821337773f, + 0.8496406632121659f, 0.8496659423381258f, 0.8496912195115988f, 0.8497164947325272f, + 0.8497417680008524f, 0.8497670393165168f, 0.8497923086794622f, 0.8498175760896303f, + 0.8498428415469633f, 0.8498681050514031f, 0.8498933666028915f, 0.8499186262013706f, + 0.8499438838467822f, 0.8499691395390684f, 0.8499943932781713f, 0.8500196450640325f, + 0.8500448948965941f, 0.8500701427757983f, 0.8500953887015869f, 0.8501206326739018f, + 0.8501458746926852f, 0.8501711147578790f, 0.8501963528694251f, 0.8502215890272657f, + 0.8502468232313427f, 0.8502720554815981f, 0.8502972857779739f, 0.8503225141204122f, + 0.8503477405088551f, 0.8503729649432443f, 0.8503981874235221f, 0.8504234079496307f, + 0.8504486265215117f, 0.8504738431391075f, 0.8504990578023600f, 0.8505242705112113f, + 0.8505494812656034f, 0.8505746900654786f, 0.8505998969107786f, 0.8506251018014458f, + 0.8506503047374222f, 0.8506755057186497f, 0.8507007047450706f, 0.8507259018166270f, + 0.8507510969332608f, 0.8507762900949143f, 0.8508014813015294f, 0.8508266705530485f, + 0.8508518578494136f, 0.8508770431905667f, 0.8509022265764499f, 0.8509274080070056f, + 0.8509525874821757f, 0.8509777650019025f, 0.8510029405661280f, 0.8510281141747943f, + 0.8510532858278438f, 0.8510784555252184f, 0.8511036232668605f, 0.8511287890527121f, + 0.8511539528827153f, 0.8511791147568125f, 0.8512042746749459f, 0.8512294326370573f, + 0.8512545886430891f, 0.8512797426929838f, 0.8513048947866831f, 0.8513300449241294f, + 0.8513551931052652f, 0.8513803393300322f, 0.8514054835983729f, 0.8514306259102297f, + 0.8514557662655443f, 0.8514809046642593f, 0.8515060411063170f, 0.8515311755916595f, + 0.8515563081202289f, 0.8515814386919678f, 0.8516065673068181f, 0.8516316939647223f, + 0.8516568186656224f, 0.8516819414094609f, 0.8517070621961801f, 0.8517321810257220f, + 0.8517572978980291f, 0.8517824128130437f, 0.8518075257707080f, 0.8518326367709642f, + 0.8518577458137548f, 0.8518828528990220f, 0.8519079580267082f, 0.8519330611967555f, + 0.8519581624091064f, 0.8519832616637030f, 0.8520083589604880f, 0.8520334542994034f, + 0.8520585476803917f, 0.8520836391033950f, 0.8521087285683560f, 0.8521338160752169f, + 0.8521589016239198f, 0.8521839852144073f, 0.8522090668466219f, 0.8522341465205057f, + 0.8522592242360011f, 0.8522842999930507f, 0.8523093737915964f, 0.8523344456315811f, + 0.8523595155129471f, 0.8523845834356364f, 0.8524096493995917f, 0.8524347134047556f, + 0.8524597754510701f, 0.8524848355384779f, 0.8525098936669211f, 0.8525349498363423f, + 0.8525600040466841f, 0.8525850562978886f, 0.8526101065898984f, 0.8526351549226561f, + 0.8526602012961038f, 0.8526852457101841f, 0.8527102881648395f, 0.8527353286600124f, + 0.8527603671956453f, 0.8527854037716807f, 0.8528104383880608f, 0.8528354710447283f, + 0.8528605017416259f, 0.8528855304786955f, 0.8529105572558802f, 0.8529355820731220f, + 0.8529606049303636f, 0.8529856258275477f, 0.8530106447646164f, 0.8530356617415124f, + 0.8530606767581783f, 0.8530856898145566f, 0.8531107009105896f, 0.8531357100462201f, + 0.8531607172213904f, 0.8531857224360432f, 0.8532107256901211f, 0.8532357269835664f, + 0.8532607263163218f, 0.8532857236883299f, 0.8533107190995330f, 0.8533357125498741f, + 0.8533607040392954f, 0.8533856935677396f, 0.8534106811351493f, 0.8534356667414670f, + 0.8534606503866353f, 0.8534856320705969f, 0.8535106117932942f, 0.8535355895546700f, + 0.8535605653546668f, 0.8535855391932272f, 0.8536105110702938f, 0.8536354809858094f, + 0.8536604489397163f, 0.8536854149319573f, 0.8537103789624751f, 0.8537353410312122f, + 0.8537603011381113f, 0.8537852592831151f, 0.8538102154661661f, 0.8538351696872072f, + 0.8538601219461807f, 0.8538850722430295f, 0.8539100205776963f, 0.8539349669501236f, + 0.8539599113602541f, 0.8539848538080307f, 0.8540097942933959f, 0.8540347328162923f, + 0.8540596693766628f, 0.8540846039744500f, 0.8541095366095965f, 0.8541344672820453f, + 0.8541593959917387f, 0.8541843227386198f, 0.8542092475226312f, 0.8542341703437155f, + 0.8542590912018155f, 0.8542840100968739f, 0.8543089270288335f, 0.8543338419976372f, + 0.8543587550032274f, 0.8543836660455471f, 0.8544085751245389f, 0.8544334822401457f, + 0.8544583873923101f, 0.8544832905809752f, 0.8545081918060833f, 0.8545330910675775f, + 0.8545579883654005f, 0.8545828836994951f, 0.8546077770698041f, 0.8546326684762703f, + 0.8546575579188365f, 0.8546824453974455f, 0.8547073309120400f, 0.8547322144625630f, + 0.8547570960489572f, 0.8547819756711654f, 0.8548068533291305f, 0.8548317290227955f, + 0.8548566027521028f, 0.8548814745169956f, 0.8549063443174167f, 0.8549312121533088f, + 0.8549560780246148f, 0.8549809419312778f, 0.8550058038732403f, 0.8550306638504453f, + 0.8550555218628360f, 0.8550803779103547f, 0.8551052319929447f, 0.8551300841105487f, + 0.8551549342631096f, 0.8551797824505705f, 0.8552046286728741f, 0.8552294729299632f, + 0.8552543152217811f, 0.8552791555482703f, 0.8553039939093738f, 0.8553288303050348f, + 0.8553536647351960f, 0.8553784971998003f, 0.8554033276987909f, 0.8554281562321103f, + 0.8554529827997018f, 0.8554778074015084f, 0.8555026300374726f, 0.8555274507075378f, + 0.8555522694116470f, 0.8555770861497427f, 0.8556019009217684f, 0.8556267137276666f, + 0.8556515245673807f, 0.8556763334408535f, 0.8557011403480279f, 0.8557259452888470f, + 0.8557507482632539f, 0.8557755492711914f, 0.8558003483126025f, 0.8558251453874306f, + 0.8558499404956182f, 0.8558747336371086f, 0.8558995248118449f, 0.8559243140197700f, + 0.8559491012608268f, 0.8559738865349587f, 0.8559986698421084f, 0.8560234511822191f, + 0.8560482305552338f, 0.8560730079610956f, 0.8560977833997477f, 0.8561225568711329f, + 0.8561473283751945f, 0.8561720979118754f, 0.8561968654811187f, 0.8562216310828676f, + 0.8562463947170652f, 0.8562711563836545f, 0.8562959160825785f, 0.8563206738137806f, + 0.8563454295772036f, 0.8563701833727908f, 0.8563949352004854f, 0.8564196850602301f, + 0.8564444329519686f, 0.8564691788756437f, 0.8564939228311984f, 0.8565186648185762f, + 0.8565434048377200f, 0.8565681428885730f, 0.8565928789710784f, 0.8566176130851793f, + 0.8566423452308187f, 0.8566670754079403f, 0.8566918036164867f, 0.8567165298564013f, + 0.8567412541276275f, 0.8567659764301080f, 0.8567906967637864f, 0.8568154151286058f, + 0.8568401315245092f, 0.8568648459514401f, 0.8568895584093414f, 0.8569142688981566f, + 0.8569389774178288f, 0.8569636839683010f, 0.8569883885495169f, 0.8570130911614193f, + 0.8570377918039517f, 0.8570624904770571f, 0.8570871871806790f, 0.8571118819147605f, + 0.8571365746792449f, 0.8571612654740755f, 0.8571859542991953f, 0.8572106411545479f, + 0.8572353260400765f, 0.8572600089557242f, 0.8572846899014346f, 0.8573093688771505f, + 0.8573340458828156f, 0.8573587209183732f, 0.8573833939837662f, 0.8574080650789383f, + 0.8574327342038327f, 0.8574574013583925f, 0.8574820665425614f, 0.8575067297562825f, + 0.8575313909994990f, 0.8575560502721545f, 0.8575807075741922f, 0.8576053629055554f, + 0.8576300162661876f, 0.8576546676560320f, 0.8576793170750320f, 0.8577039645231309f, + 0.8577286100002721f, 0.8577532535063990f, 0.8577778950414550f, 0.8578025346053832f, + 0.8578271721981273f, 0.8578518078196308f, 0.8578764414698367f, 0.8579010731486885f, + 0.8579257028561298f, 0.8579503305921038f, 0.8579749563565540f, 0.8579995801494238f, + 0.8580242019706565f, 0.8580488218201957f, 0.8580734396979848f, 0.8580980556039671f, + 0.8581226695380860f, 0.8581472815002853f, 0.8581718914905081f, 0.8581964995086979f, + 0.8582211055547982f, 0.8582457096287524f, 0.8582703117305042f, 0.8582949118599966f, + 0.8583195100171734f, 0.8583441062019782f, 0.8583687004143542f, 0.8583932926542449f, + 0.8584178829215940f, 0.8584424712163448f, 0.8584670575384408f, 0.8584916418878257f, + 0.8585162242644427f, 0.8585408046682356f, 0.8585653830991479f, 0.8585899595571228f, + 0.8586145340421042f, 0.8586391065540354f, 0.8586636770928600f, 0.8586882456585215f, + 0.8587128122509635f, 0.8587373768701295f, 0.8587619395159632f, 0.8587865001884081f, + 0.8588110588874075f, 0.8588356156129053f, 0.8588601703648449f, 0.8588847231431698f, + 0.8589092739478239f, 0.8589338227787504f, 0.8589583696358931f, 0.8589829145191956f, + 0.8590074574286014f, 0.8590319983640543f, 0.8590565373254976f, 0.8590810743128751f, + 0.8591056093261304f, 0.8591301423652071f, 0.8591546734300488f, 0.8591792025205993f, + 0.8592037296368019f, 0.8592282547786005f, 0.8592527779459388f, 0.8592772991387602f, + 0.8593018183570084f, 0.8593263356006272f, 0.8593508508695602f, 0.8593753641637509f, + 0.8593998754831434f, 0.8594243848276809f, 0.8594488921973075f, 0.8594733975919664f, + 0.8594979010116016f, 0.8595224024561569f, 0.8595469019255757f, 0.8595713994198019f, + 0.8595958949387791f, 0.8596203884824510f, 0.8596448800507615f, 0.8596693696436541f, + 0.8596938572610726f, 0.8597183429029608f, 0.8597428265692624f, 0.8597673082599210f, + 0.8597917879748805f, 0.8598162657140848f, 0.8598407414774771f, 0.8598652152650018f, + 0.8598896870766023f, 0.8599141569122224f, 0.8599386247718059f, 0.8599630906552965f, + 0.8599875545626382f, 0.8600120164937747f, 0.8600364764486496f, 0.8600609344272068f, + 0.8600853904293901f, 0.8601098444551435f, 0.8601342965044104f, 0.8601587465771351f, + 0.8601831946732609f, 0.8602076407927319f, 0.8602320849354921f, 0.8602565271014849f, + 0.8602809672906545f, 0.8603054055029445f, 0.8603298417382990f, 0.8603542759966616f, + 0.8603787082779761f, 0.8604031385821866f, 0.8604275669092369f, 0.8604519932590707f, + 0.8604764176316321f, 0.8605008400268649f, 0.8605252604447128f, 0.8605496788851198f, + 0.8605740953480300f, 0.8605985098333869f, 0.8606229223411347f, 0.8606473328712173f, + 0.8606717414235784f, 0.8606961479981620f, 0.8607205525949121f, 0.8607449552137725f, + 0.8607693558546872f, 0.8607937545176000f, 0.8608181512024550f, 0.8608425459091962f, + 0.8608669386377673f, 0.8608913293881123f, 0.8609157181601754f, 0.8609401049539003f, + 0.8609644897692309f, 0.8609888726061115f, 0.8610132534644858f, 0.8610376323442976f, + 0.8610620092454915f, 0.8610863841680109f, 0.8611107571118000f, 0.8611351280768028f, + 0.8611594970629634f, 0.8611838640702255f, 0.8612082290985333f, 0.8612325921478309f, + 0.8612569532180623f, 0.8612813123091712f, 0.8613056694211019f, 0.8613300245537985f, + 0.8613543777072048f, 0.8613787288812650f, 0.8614030780759232f, 0.8614274252911233f, + 0.8614517705268092f, 0.8614761137829254f, 0.8615004550594156f, 0.8615247943562240f, + 0.8615491316732947f, 0.8615734670105717f, 0.8615978003679990f, 0.8616221317455209f, + 0.8616464611430813f, 0.8616707885606244f, 0.8616951139980943f, 0.8617194374554349f, + 0.8617437589325907f, 0.8617680784295054f, 0.8617923959461233f, 0.8618167114823887f, + 0.8618410250382453f, 0.8618653366136376f, 0.8618896462085096f, 0.8619139538228054f, + 0.8619382594564692f, 0.8619625631094452f, 0.8619868647816773f, 0.8620111644731100f, + 0.8620354621836872f, 0.8620597579133532f, 0.8620840516620522f, 0.8621083434297281f, + 0.8621326332163254f, 0.8621569210217882f, 0.8621812068460606f, 0.8622054906890869f, + 0.8622297725508112f, 0.8622540524311778f, 0.8622783303301308f, 0.8623026062476146f, + 0.8623268801835731f, 0.8623511521379507f, 0.8623754221106917f, 0.8623996901017402f, + 0.8624239561110405f, 0.8624482201385368f, 0.8624724821841735f, 0.8624967422478946f, + 0.8625210003296445f, 0.8625452564293673f, 0.8625695105470076f, 0.8625937626825092f, + 0.8626180128358167f, 0.8626422610068745f, 0.8626665071956264f, 0.8626907514020170f, + 0.8627149936259907f, 0.8627392338674915f, 0.8627634721264638f, 0.8627877084028520f, + 0.8628119426966003f, 0.8628361750076531f, 0.8628604053359546f, 0.8628846336814493f, + 0.8629088600440814f, 0.8629330844237951f, 0.8629573068205350f, 0.8629815272342453f, + 0.8630057456648702f, 0.8630299621123544f, 0.8630541765766420f, 0.8630783890576773f, + 0.8631025995554048f, 0.8631268080697689f, 0.8631510146007140f, 0.8631752191481842f, + 0.8631994217121242f, 0.8632236222924782f, 0.8632478208891905f, 0.8632720175022058f, + 0.8632962121314682f, 0.8633204047769224f, 0.8633445954385125f, 0.8633687841161830f, + 0.8633929708098784f, 0.8634171555195431f, 0.8634413382451215f, 0.8634655189865581f, + 0.8634896977437971f, 0.8635138745167832f, 0.8635380493054609f, 0.8635622221097742f, + 0.8635863929296680f, 0.8636105617650867f, 0.8636347286159745f, 0.8636588934822760f, + 0.8636830563639359f, 0.8637072172608984f, 0.8637313761731080f, 0.8637555331005092f, + 0.8637796880430466f, 0.8638038410006648f, 0.8638279919733078f, 0.8638521409609206f, + 0.8638762879634475f, 0.8639004329808331f, 0.8639245760130217f, 0.8639487170599581f, + 0.8639728561215867f, 0.8639969931978519f, 0.8640211282886987f, 0.8640452613940710f, + 0.8640693925139137f, 0.8640935216481714f, 0.8641176487967884f, 0.8641417739597096f, + 0.8641658971368793f, 0.8641900183282420f, 0.8642141375337427f, 0.8642382547533254f, + 0.8642623699869350f, 0.8642864832345162f, 0.8643105944960132f, 0.8643347037713709f, + 0.8643588110605340f, 0.8643829163634468f, 0.8644070196800540f, 0.8644311210103004f, + 0.8644552203541302f, 0.8644793177114884f, 0.8645034130823197f, 0.8645275064665684f, + 0.8645515978641792f, 0.8645756872750970f, 0.8645997746992661f, 0.8646238601366315f, + 0.8646479435871375f, 0.8646720250507288f, 0.8646961045273505f, 0.8647201820169467f, + 0.8647442575194624f, 0.8647683310348422f, 0.8647924025630307f, 0.8648164721039727f, + 0.8648405396576130f, 0.8648646052238959f, 0.8648886688027664f, 0.8649127303941693f, + 0.8649367899980490f, 0.8649608476143503f, 0.8649849032430182f, 0.8650089568839970f, + 0.8650330085372319f, 0.8650570582026671f, 0.8650811058802477f, 0.8651051515699184f, + 0.8651291952716237f, 0.8651532369853087f, 0.8651772767109179f, 0.8652013144483961f, + 0.8652253501976881f, 0.8652493839587388f, 0.8652734157314927f, 0.8652974455158947f, + 0.8653214733118898f, 0.8653454991194224f, 0.8653695229384375f, 0.8653935447688800f, + 0.8654175646106944f, 0.8654415824638257f, 0.8654655983282188f, 0.8654896122038183f, + 0.8655136240905691f, 0.8655376339884160f, 0.8655616418973039f, 0.8655856478171776f, + 0.8656096517479819f, 0.8656336536896617f, 0.8656576536421619f, 0.8656816516054270f, + 0.8657056475794023f, 0.8657296415640324f, 0.8657536335592623f, 0.8657776235650367f, + 0.8658016115813008f, 0.8658255976079990f, 0.8658495816450766f, 0.8658735636924783f, + 0.8658975437501488f, 0.8659215218180335f, 0.8659454978960768f, 0.8659694719842238f, + 0.8659934440824195f, 0.8660174141906087f, 0.8660413823087364f, 0.8660653484367475f, + 0.8660893125745868f, 0.8661132747221993f, 0.8661372348795301f, 0.8661611930465239f, + 0.8661851492231257f, 0.8662091034092807f, 0.8662330556049336f, 0.8662570058100294f, + 0.8662809540245130f, 0.8663049002483294f, 0.8663288444814239f, 0.8663527867237409f, + 0.8663767269752258f, 0.8664006652358235f, 0.8664246015054788f, 0.8664485357841371f, + 0.8664724680717431f, 0.8664963983682417f, 0.8665203266735781f, 0.8665442529876974f, + 0.8665681773105444f, 0.8665920996420642f, 0.8666160199822021f, 0.8666399383309026f, + 0.8666638546881110f, 0.8666877690537726f, 0.8667116814278321f, 0.8667355918102347f, + 0.8667595002009253f, 0.8667834065998491f, 0.8668073110069513f, 0.8668312134221766f, + 0.8668551138454703f, 0.8668790122767777f, 0.8669029087160434f, 0.8669268031632128f, + 0.8669506956182310f, 0.8669745860810428f, 0.8669984745515937f, 0.8670223610298287f, + 0.8670462455156926f, 0.8670701280091309f, 0.8670940085100886f, 0.8671178870185107f, + 0.8671417635343425f, 0.8671656380575290f, 0.8671895105880153f, 0.8672133811257469f, + 0.8672372496706684f, 0.8672611162227253f, 0.8672849807818628f, 0.8673088433480258f, + 0.8673327039211597f, 0.8673565625012096f, 0.8673804190881206f, 0.8674042736818379f, + 0.8674281262823069f, 0.8674519768894725f, 0.8674758255032800f, 0.8674996721236746f, + 0.8675235167506015f, 0.8675473593840060f, 0.8675712000238330f, 0.8675950386700281f, + 0.8676188753225363f, 0.8676427099813029f, 0.8676665426462730f, 0.8676903733173921f, + 0.8677142019946051f, 0.8677380286778575f, 0.8677618533670945f, 0.8677856760622613f, + 0.8678094967633032f, 0.8678333154701655f, 0.8678571321827933f, 0.8678809469011319f, + 0.8679047596251269f, 0.8679285703547232f, 0.8679523790898662f, 0.8679761858305012f, + 0.8679999905765734f, 0.8680237933280284f, 0.8680475940848111f, 0.8680713928468672f, + 0.8680951896141417f, 0.8681189843865800f, 0.8681427771641275f, 0.8681665679467295f, + 0.8681903567343313f, 0.8682141435268782f, 0.8682379283243157f, 0.8682617111265889f, + 0.8682854919336432f, 0.8683092707454242f, 0.8683330475618770f, 0.8683568223829472f, + 0.8683805952085798f, 0.8684043660387204f, 0.8684281348733145f, 0.8684519017123072f, + 0.8684756665556441f, 0.8684994294032706f, 0.8685231902551319f, 0.8685469491111735f, + 0.8685707059713409f, 0.8685944608355793f, 0.8686182137038343f, 0.8686419645760514f, + 0.8686657134521756f, 0.8686894603321527f, 0.8687132052159281f, 0.8687369481034471f, + 0.8687606889946553f, 0.8687844278894979f, 0.8688081647879206f, 0.8688318996898688f, + 0.8688556325952878f, 0.8688793635041232f, 0.8689030924163205f, 0.8689268193318250f, + 0.8689505442505824f, 0.8689742671725381f, 0.8689979880976374f, 0.8690217070258260f, + 0.8690454239570495f, 0.8690691388912531f, 0.8690928518283825f, 0.8691165627683831f, + 0.8691402717112006f, 0.8691639786567802f, 0.8691876836050678f, 0.8692113865560086f, + 0.8692350875095484f, 0.8692587864656325f, 0.8692824834242066f, 0.8693061783852162f, + 0.8693298713486067f, 0.8693535623143239f, 0.8693772512823134f, 0.8694009382525205f, + 0.8694246232248908f, 0.8694483061993702f, 0.8694719871759038f, 0.8694956661544375f, + 0.8695193431349170f, 0.8695430181172874f, 0.8695666911014948f, 0.8695903620874845f, + 0.8696140310752023f, 0.8696376980645937f, 0.8696613630556043f, 0.8696850260481797f, + 0.8697086870422657f, 0.8697323460378076f, 0.8697560030347513f, 0.8697796580330426f, + 0.8698033110326266f, 0.8698269620334494f, 0.8698506110354566f, 0.8698742580385936f, + 0.8698979030428063f, 0.8699215460480404f, 0.8699451870542413f, 0.8699688260613548f, + 0.8699924630693269f, 0.8700160980781028f, 0.8700397310876284f, 0.8700633620978494f, + 0.8700869911087113f, 0.8701106181201603f, 0.8701342431321416f, 0.8701578661446011f, + 0.8701814871574846f, 0.8702051061707377f, 0.8702287231843060f, 0.8702523381981355f, + 0.8702759512121718f, 0.8702995622263607f, 0.8703231712406480f, 0.8703467782549792f, + 0.8703703832693002f, 0.8703939862835569f, 0.8704175872976948f, 0.8704411863116598f, + 0.8704647833253977f, 0.8704883783388542f, 0.8705119713519751f, 0.8705355623647062f, + 0.8705591513769932f, 0.8705827383887822f, 0.8706063234000186f, 0.8706299064106484f, + 0.8706534874206175f, 0.8706770664298715f, 0.8707006434383563f, 0.8707242184460179f, + 0.8707477914528018f, 0.8707713624586539f, 0.8707949314635204f, 0.8708184984673467f, + 0.8708420634700790f, 0.8708656264716628f, 0.8708891874720440f, 0.8709127464711688f, + 0.8709363034689828f, 0.8709598584654318f, 0.8709834114604619f, 0.8710069624540187f, + 0.8710305114460483f, 0.8710540584364966f, 0.8710776034253093f, 0.8711011464124324f, + 0.8711246873978119f, 0.8711482263813936f, 0.8711717633631233f, 0.8711952983429472f, + 0.8712188313208109f, 0.8712423622966605f, 0.8712658912704421f, 0.8712894182421012f, + 0.8713129432115840f, 0.8713364661788364f, 0.8713599871438045f, 0.8713835061064340f, + 0.8714070230666709f, 0.8714305380244612f, 0.8714540509797510f, 0.8714775619324860f, + 0.8715010708826125f, 0.8715245778300763f, 0.8715480827748232f, 0.8715715857167995f, + 0.8715950866559511f, 0.8716185855922238f, 0.8716420825255637f, 0.8716655774559172f, + 0.8716890703832297f, 0.8717125613074477f, 0.8717360502285167f, 0.8717595371463832f, + 0.8717830220609931f, 0.8718065049722924f, 0.8718299858802270f, 0.8718534647847432f, + 0.8718769416857869f, 0.8719004165833041f, 0.8719238894772410f, 0.8719473603675435f, + 0.8719708292541577f, 0.8719942961370299f, 0.8720177610161058f, 0.8720412238913318f, + 0.8720646847626540f, 0.8720881436300181f, 0.8721116004933706f, 0.8721350553526572f, + 0.8721585082078245f, 0.8721819590588182f, 0.8722054079055845f, 0.8722288547480697f, + 0.8722522995862199f, 0.8722757424199808f, 0.8722991832492990f, 0.8723226220741206f, + 0.8723460588943915f, 0.8723694937100579f, 0.8723929265210661f, 0.8724163573273622f, + 0.8724397861288923f, 0.8724632129256026f, 0.8724866377174392f, 0.8725100605043483f, + 0.8725334812862761f, 0.8725569000631688f, 0.8725803168349726f, 0.8726037316016335f, + 0.8726271443630980f, 0.8726505551193121f, 0.8726739638702220f, 0.8726973706157740f, + 0.8727207753559143f, 0.8727441780905890f, 0.8727675788197444f, 0.8727909775433269f, + 0.8728143742612824f, 0.8728377689735574f, 0.8728611616800980f, 0.8728845523808504f, + 0.8729079410757611f, 0.8729313277647760f, 0.8729547124478416f, 0.8729780951249042f, + 0.8730014757959099f, 0.8730248544608050f, 0.8730482311195360f, 0.8730716057720489f, + 0.8730949784182901f, 0.8731183490582060f, 0.8731417176917425f, 0.8731650843188463f, + 0.8731884489394638f, 0.8732118115535409f, 0.8732351721610241f, 0.8732585307618598f, + 0.8732818873559942f, 0.8733052419433737f, 0.8733285945239446f, 0.8733519450976532f, + 0.8733752936644461f, 0.8733986402242692f, 0.8734219847770691f, 0.8734453273227923f, + 0.8734686678613849f, 0.8734920063927933f, 0.8735153429169641f, 0.8735386774338434f, + 0.8735620099433777f, 0.8735853404455135f, 0.8736086689401968f, 0.8736319954273745f, + 0.8736553199069926f, 0.8736786423789977f, 0.8737019628433361f, 0.8737252812999545f, + 0.8737485977487989f, 0.8737719121898160f, 0.8737952246229519f, 0.8738185350481534f, + 0.8738418434653669f, 0.8738651498745386f, 0.8738884542756150f, 0.8739117566685428f, + 0.8739350570532681f, 0.8739583554297377f, 0.8739816517978978f, 0.8740049461576950f, + 0.8740282385090756f, 0.8740515288519863f, 0.8740748171863735f, 0.8740981035121836f, + 0.8741213878293633f, 0.8741446701378589f, 0.8741679504376170f, 0.8741912287285839f, + 0.8742145050107063f, 0.8742377792839308f, 0.8742610515482035f, 0.8742843218034715f, + 0.8743075900496809f, 0.8743308562867784f, 0.8743541205147105f, 0.8743773827334239f, + 0.8744006429428648f, 0.8744239011429800f, 0.8744471573337160f, 0.8744704115150193f, + 0.8744936636868365f, 0.8745169138491143f, 0.8745401620017991f, 0.8745634081448376f, + 0.8745866522781761f, 0.8746098944017615f, 0.8746331345155404f, 0.8746563726194592f, + 0.8746796087134645f, 0.8747028427975032f, 0.8747260748715215f, 0.8747493049354662f, + 0.8747725329892841f, 0.8747957590329216f, 0.8748189830663253f, 0.8748422050894421f, + 0.8748654251022182f, 0.8748886431046007f, 0.8749118590965360f, 0.8749350730779707f, + 0.8749582850488516f, 0.8749814950091254f, 0.8750047029587384f, 0.8750279088976379f, + 0.8750511128257700f, 0.8750743147430816f, 0.8750975146495195f, 0.8751207125450301f, + 0.8751439084295602f, 0.8751671023030568f, 0.8751902941654662f, 0.8752134840167353f, + 0.8752366718568109f, 0.8752598576856394f, 0.8752830415031677f, 0.8753062233093427f, + 0.8753294031041108f, 0.8753525808874190f, 0.8753757566592140f, 0.8753989304194423f, + 0.8754221021680509f, 0.8754452719049866f, 0.8754684396301958f, 0.8754916053436257f, + 0.8755147690452227f, 0.8755379307349339f, 0.8755610904127059f, 0.8755842480784853f, + 0.8756074037322192f, 0.8756305573738544f, 0.8756537090033374f, 0.8756768586206152f, + 0.8757000062256346f, 0.8757231518183423f, 0.8757462953986852f, 0.8757694369666101f, + 0.8757925765220639f, 0.8758157140649934f, 0.8758388495953452f, 0.8758619831130664f, + 0.8758851146181038f, 0.8759082441104041f, 0.8759313715899143f, 0.8759544970565812f, + 0.8759776205103517f, 0.8760007419511726f, 0.8760238613789908f, 0.8760469787937532f, + 0.8760700941954066f, 0.8760932075838980f, 0.8761163189591741f, 0.8761394283211820f, + 0.8761625356698685f, 0.8761856410051804f, 0.8762087443270649f, 0.8762318456354685f, + 0.8762549449303384f, 0.8762780422116216f, 0.8763011374792647f, 0.8763242307332149f, + 0.8763473219734190f, 0.8763704111998240f, 0.8763934984123768f, 0.8764165836110244f, + 0.8764396667957136f, 0.8764627479663916f, 0.8764858271230052f, 0.8765089042655013f, + 0.8765319793938271f, 0.8765550525079294f, 0.8765781236077552f, 0.8766011926932515f, + 0.8766242597643653f, 0.8766473248210436f, 0.8766703878632335f, 0.8766934488908816f, + 0.8767165079039354f, 0.8767395649023417f, 0.8767626198860474f, 0.8767856728549998f, + 0.8768087238091458f, 0.8768317727484322f, 0.8768548196728063f, 0.8768778645822152f, + 0.8769009074766057f, 0.8769239483559248f, 0.8769469872201200f, 0.8769700240691379f, + 0.8769930589029259f, 0.8770160917214308f, 0.8770391225245998f, 0.8770621513123800f, + 0.8770851780847183f, 0.8771082028415620f, 0.8771312255828582f, 0.8771542463085538f, + 0.8771772650185959f, 0.8772002817129320f, 0.8772232963915086f, 0.8772463090542734f, + 0.8772693197011732f, 0.8772923283321550f, 0.8773153349471662f, 0.8773383395461539f, + 0.8773613421290651f, 0.8773843426958470f, 0.8774073412464468f, 0.8774303377808116f, + 0.8774533322988887f, 0.8774763248006249f, 0.8774993152859676f, 0.8775223037548641f, + 0.8775452902072612f, 0.8775682746431065f, 0.8775912570623470f, 0.8776142374649298f, + 0.8776372158508021f, 0.8776601922199114f, 0.8776831665722045f, 0.8777061389076287f, + 0.8777291092261316f, 0.8777520775276598f, 0.8777750438121609f, 0.8777980080795821f, + 0.8778209703298705f, 0.8778439305629735f, 0.8778668887788382f, 0.8778898449774118f, + 0.8779127991586418f, 0.8779357513224753f, 0.8779587014688593f, 0.8779816495977416f, + 0.8780045957090691f, 0.8780275398027890f, 0.8780504818788489f, 0.8780734219371958f, + 0.8780963599777771f, 0.8781192960005402f, 0.8781422300054321f, 0.8781651619924004f, + 0.8781880919613922f, 0.8782110199123548f, 0.8782339458452358f, 0.8782568697599823f, + 0.8782797916565415f, 0.8783027115348609f, 0.8783256293948878f, 0.8783485452365696f, + 0.8783714590598536f, 0.8783943708646870f, 0.8784172806510172f, 0.8784401884187918f, + 0.8784630941679579f, 0.8784859978984628f, 0.8785088996102542f, 0.8785317993032793f, + 0.8785546969774853f, 0.8785775926328200f, 0.8786004862692303f, 0.8786233778866640f, + 0.8786462674850681f, 0.8786691550643904f, 0.8786920406245781f, 0.8787149241655786f, + 0.8787378056873393f, 0.8787606851898078f, 0.8787835626729313f, 0.8788064381366574f, + 0.8788293115809334f, 0.8788521830057068f, 0.8788750524109250f, 0.8788979197965355f, + 0.8789207851624858f, 0.8789436485087232f, 0.8789665098351954f, 0.8789893691418497f, + 0.8790122264286335f, 0.8790350816954944f, 0.8790579349423798f, 0.8790807861692373f, + 0.8791036353760143f, 0.8791264825626582f, 0.8791493277291169f, 0.8791721708753374f, + 0.8791950120012674f, 0.8792178511068546f, 0.8792406881920461f, 0.8792635232567899f, + 0.8792863563010332f, 0.8793091873247236f, 0.8793320163278088f, 0.8793548433102362f, + 0.8793776682719532f, 0.8794004912129076f, 0.8794233121330469f, 0.8794461310323185f, + 0.8794689479106702f, 0.8794917627680493f, 0.8795145756044036f, 0.8795373864196807f, + 0.8795601952138279f, 0.8795830019867930f, 0.8796058067385236f, 0.8796286094689673f, + 0.8796514101780715f, 0.8796742088657842f, 0.8796970055320525f, 0.8797198001768244f, + 0.8797425928000474f, 0.8797653834016691f, 0.8797881719816372f, 0.8798109585398993f, + 0.8798337430764029f, 0.8798565255910960f, 0.8798793060839258f, 0.8799020845548402f, + 0.8799248610037870f, 0.8799476354307134f, 0.8799704078355675f, 0.8799931782182968f, + 0.8800159465788490f, 0.8800387129171717f, 0.8800614772332128f, 0.8800842395269197f, + 0.8801069997982404f, 0.8801297580471223f, 0.8801525142735133f, 0.8801752684773609f, + 0.8801980206586132f, 0.8802207708172175f, 0.8802435189531219f, 0.8802662650662737f, + 0.8802890091566209f, 0.8803117512241113f, 0.8803344912686925f, 0.8803572292903121f, + 0.8803799652889183f, 0.8804026992644584f, 0.8804254312168802f, 0.8804481611461319f, + 0.8804708890521608f, 0.8804936149349147f, 0.8805163387943419f, 0.8805390606303894f, + 0.8805617804430056f, 0.8805844982321381f, 0.8806072139977346f, 0.8806299277397430f, + 0.8806526394581110f, 0.8806753491527866f, 0.8806980568237175f, 0.8807207624708514f, + 0.8807434660941362f, 0.8807661676935200f, 0.8807888672689502f, 0.8808115648203749f, + 0.8808342603477420f, 0.8808569538509992f, 0.8808796453300942f, 0.8809023347849753f, + 0.8809250222155899f, 0.8809477076218860f, 0.8809703910038118f, 0.8809930723613147f, + 0.8810157516943429f, 0.8810384290028441f, 0.8810611042867663f, 0.8810837775460574f, + 0.8811064487806651f, 0.8811291179905376f, 0.8811517851756226f, 0.8811744503358682f, + 0.8811971134712220f, 0.8812197745816323f, 0.8812424336670467f, 0.8812650907274132f, + 0.8812877457626801f, 0.8813103987727948f, 0.8813330497577055f, 0.8813556987173603f, + 0.8813783456517068f, 0.8814009905606933f, 0.8814236334442676f, 0.8814462743023775f, + 0.8814689131349714f, 0.8814915499419970f, 0.8815141847234021f, 0.8815368174791351f, + 0.8815594482091438f, 0.8815820769133761f, 0.8816047035917801f, 0.8816273282443038f, + 0.8816499508708953f, 0.8816725714715025f, 0.8816951900460732f, 0.8817178065945558f, + 0.8817404211168983f, 0.8817630336130485f, 0.8817856440829546f, 0.8818082525265647f, + 0.8818308589438266f, 0.8818534633346886f, 0.8818760656990986f, 0.8818986660370047f, + 0.8819212643483550f, 0.8819438606330976f, 0.8819664548911804f, 0.8819890471225518f, + 0.8820116373271596f, 0.8820342255049519f, 0.8820568116558770f, 0.8820793957798828f, + 0.8821019778769176f, 0.8821245579469292f, 0.8821471359898660f, 0.8821697120056760f, + 0.8821922859943074f, 0.8822148579557082f, 0.8822374278898266f, 0.8822599957966107f, + 0.8822825616760086f, 0.8823051255279687f, 0.8823276873524388f, 0.8823502471493673f, + 0.8823728049187023f, 0.8823953606603918f, 0.8824179143743842f, 0.8824404660606276f, + 0.8824630157190700f, 0.8824855633496599f, 0.8825081089523453f, 0.8825306525270744f, + 0.8825531940737954f, 0.8825757335924567f, 0.8825982710830060f, 0.8826208065453921f, + 0.8826433399795628f, 0.8826658713854665f, 0.8826884007630513f, 0.8827109281122656f, + 0.8827334534330575f, 0.8827559767253754f, 0.8827784979891674f, 0.8828010172243816f, + 0.8828235344309667f, 0.8828460496088705f, 0.8828685627580415f, 0.8828910738784279f, + 0.8829135829699780f, 0.8829360900326401f, 0.8829585950663623f, 0.8829810980710932f, + 0.8830035990467808f, 0.8830260979933735f, 0.8830485949108197f, 0.8830710897990676f, + 0.8830935826580654f, 0.8831160734877616f, 0.8831385622881045f, 0.8831610490590422f, + 0.8831835338005233f, 0.8832060165124961f, 0.8832284971949088f, 0.8832509758477097f, + 0.8832734524708474f, 0.8832959270642701f, 0.8833183996279260f, 0.8833408701617638f, + 0.8833633386657316f, 0.8833858051397778f, 0.8834082695838509f, 0.8834307319978991f, + 0.8834531923818710f, 0.8834756507357148f, 0.8834981070593788f, 0.8835205613528119f, + 0.8835430136159619f, 0.8835654638487774f, 0.8835879120512071f, 0.8836103582231990f, + 0.8836328023647018f, 0.8836552444756639f, 0.8836776845560335f, 0.8837001226057593f, + 0.8837225586247897f, 0.8837449926130728f, 0.8837674245705576f, 0.8837898544971922f, + 0.8838122823929251f, 0.8838347082577048f, 0.8838571320914798f, 0.8838795538941985f, + 0.8839019736658095f, 0.8839243914062610f, 0.8839468071155018f, 0.8839692207934803f, + 0.8839916324401449f, 0.8840140420554441f, 0.8840364496393266f, 0.8840588551917407f, + 0.8840812587126350f, 0.8841036602019580f, 0.8841260596596582f, 0.8841484570856841f, + 0.8841708524799845f, 0.8841932458425075f, 0.8842156371732021f, 0.8842380264720163f, + 0.8842604137388991f, 0.8842827989737990f, 0.8843051821766643f, 0.8843275633474439f, + 0.8843499424860861f, 0.8843723195925397f, 0.8843946946667530f, 0.8844170677086749f, + 0.8844394387182537f, 0.8844618076954381f, 0.8844841746401769f, 0.8845065395524184f, + 0.8845289024321114f, 0.8845512632792044f, 0.8845736220936461f, 0.8845959788753851f, + 0.8846183336243699f, 0.8846406863405493f, 0.8846630370238718f, 0.8846853856742862f, + 0.8847077322917409f, 0.8847300768761849f, 0.8847524194275665f, 0.8847747599458345f, + 0.8847970984309378f, 0.8848194348828247f, 0.8848417693014439f, 0.8848641016867443f, + 0.8848864320386746f, 0.8849087603571831f, 0.8849310866422190f, 0.8849534108937305f, + 0.8849757331116668f, 0.8849980532959761f, 0.8850203714466074f, 0.8850426875635096f, + 0.8850650016466309f, 0.8850873136959204f, 0.8851096237113270f, 0.8851319316927988f, + 0.8851542376402851f, 0.8851765415537345f, 0.8851988434330955f, 0.8852211432783172f, + 0.8852434410893483f, 0.8852657368661373f, 0.8852880306086331f, 0.8853103223167847f, + 0.8853326119905406f, 0.8853548996298497f, 0.8853771852346607f, 0.8853994688049224f, + 0.8854217503405837f, 0.8854440298415932f, 0.8854663073078999f, 0.8854885827394525f, + 0.8855108561362000f, 0.8855331274980909f, 0.8855553968250742f, 0.8855776641170988f, + 0.8855999293741134f, 0.8856221925960669f, 0.8856444537829080f, 0.8856667129345858f, + 0.8856889700510490f, 0.8857112251322464f, 0.8857334781781270f, 0.8857557291886395f, + 0.8857779781637329f, 0.8858002251033562f, 0.8858224700074578f, 0.8858447128759871f, + 0.8858669537088928f, 0.8858891925061236f, 0.8859114292676288f, 0.8859336639933569f, + 0.8859558966832570f, 0.8859781273372780f, 0.8860003559553689f, 0.8860225825374783f, + 0.8860448070835555f, 0.8860670295935493f, 0.8860892500674086f, 0.8861114685050822f, + 0.8861336849065193f, 0.8861558992716687f, 0.8861781116004795f, 0.8862003218929004f, + 0.8862225301488806f, 0.8862447363683690f, 0.8862669405513145f, 0.8862891426976661f, + 0.8863113428073729f, 0.8863335408803836f, 0.8863557369166475f, 0.8863779309161135f, + 0.8864001228787305f, 0.8864223128044476f, 0.8864445006932139f, 0.8864666865449782f, + 0.8864888703596896f, 0.8865110521372972f, 0.8865332318777499f, 0.8865554095809969f, + 0.8865775852469870f, 0.8865997588756694f, 0.8866219304669932f, 0.8866441000209074f, + 0.8866662675373609f, 0.8866884330163031f, 0.8867105964576827f, 0.8867327578614489f, + 0.8867549172275510f, 0.8867770745559376f, 0.8867992298465581f, 0.8868213830993618f, + 0.8868435343142973f, 0.8868656834913140f, 0.8868878306303610f, 0.8869099757313874f, + 0.8869321187943422f, 0.8869542598191745f, 0.8869763988058336f, 0.8869985357542686f, + 0.8870206706644284f, 0.8870428035362623f, 0.8870649343697196f, 0.8870870631647491f, + 0.8871091899213001f, 0.8871313146393219f, 0.8871534373187635f, 0.8871755579595740f, + 0.8871976765617029f, 0.8872197931250989f, 0.8872419076497116f, 0.8872640201354900f, + 0.8872861305823831f, 0.8873082389903405f, 0.8873303453593110f, 0.8873524496892441f, + 0.8873745519800889f, 0.8873966522317944f, 0.8874187504443102f, 0.8874408466175853f, + 0.8874629407515688f, 0.8874850328462102f, 0.8875071229014586f, 0.8875292109172632f, + 0.8875512968935734f, 0.8875733808303383f, 0.8875954627275071f, 0.8876175425850292f, + 0.8876396204028539f, 0.8876616961809304f, 0.8876837699192078f, 0.8877058416176357f, + 0.8877279112761630f, 0.8877499788947394f, 0.8877720444733138f, 0.8877941080118357f, + 0.8878161695102545f, 0.8878382289685193f, 0.8878602863865794f, 0.8878823417643844f, + 0.8879043951018832f, 0.8879264463990254f, 0.8879484956557604f, 0.8879705428720374f, + 0.8879925880478056f, 0.8880146311830145f, 0.8880366722776134f, 0.8880587113315518f, + 0.8880807483447789f, 0.8881027833172440f, 0.8881248162488966f, 0.8881468471396861f, + 0.8881688759895616f, 0.8881909027984729f, 0.8882129275663690f, 0.8882349502931995f, + 0.8882569709789139f, 0.8882789896234612f, 0.8883010062267911f, 0.8883230207888531f, + 0.8883450333095962f, 0.8883670437889702f, 0.8883890522269245f, 0.8884110586234084f, + 0.8884330629783713f, 0.8884550652917628f, 0.8884770655635320f, 0.8884990637936289f, + 0.8885210599820023f, 0.8885430541286021f, 0.8885650462333777f, 0.8885870362962784f, + 0.8886090243172537f, 0.8886310102962534f, 0.8886529942332265f, 0.8886749761281227f, + 0.8886969559808917f, 0.8887189337914826f, 0.8887409095598451f, 0.8887628832859287f, + 0.8887848549696828f, 0.8888068246110571f, 0.8888287922100010f, 0.8888507577664639f, + 0.8888727212803956f, 0.8888946827517454f, 0.8889166421804630f, 0.8889385995664978f, + 0.8889605549097993f, 0.8889825082103172f, 0.8890044594680010f, 0.8890264086828003f, + 0.8890483558546646f, 0.8890703009835434f, 0.8890922440693864f, 0.8891141851121431f, + 0.8891361241117632f, 0.8891580610681962f, 0.8891799959813915f, 0.8892019288512991f, + 0.8892238596778682f, 0.8892457884610487f, 0.8892677152007901f, 0.8892896398970419f, + 0.8893115625497540f, 0.8893334831588756f, 0.8893554017243567f, 0.8893773182461469f, + 0.8893992327241955f, 0.8894211451584525f, 0.8894430555488676f, 0.8894649638953901f, + 0.8894868701979698f, 0.8895087744565565f, 0.8895306766710998f, 0.8895525768415492f, + 0.8895744749678546f, 0.8895963710499656f, 0.8896182650878318f, 0.8896401570814030f, + 0.8896620470306288f, 0.8896839349354591f, 0.8897058207958433f, 0.8897277046117313f, + 0.8897495863830729f, 0.8897714661098175f, 0.8897933437919150f, 0.8898152194293153f, + 0.8898370930219679f, 0.8898589645698225f, 0.8898808340728291f, 0.8899027015309373f, + 0.8899245669440967f, 0.8899464303122573f, 0.8899682916353687f, 0.8899901509133807f, + 0.8900120081462433f, 0.8900338633339058f, 0.8900557164763183f, 0.8900775675734306f, + 0.8900994166251922f, 0.8901212636315534f, 0.8901431085924635f, 0.8901649515078724f, + 0.8901867923777302f, 0.8902086312019866f, 0.8902304679805910f, 0.8902523027134939f, + 0.8902741354006445f, 0.8902959660419930f, 0.8903177946374893f, 0.8903396211870829f, + 0.8903614456907237f, 0.8903832681483620f, 0.8904050885599470f, 0.8904269069254291f, + 0.8904487232447579f, 0.8904705375178832f, 0.8904923497447552f, 0.8905141599253233f, + 0.8905359680595378f, 0.8905577741473485f, 0.8905795781887050f, 0.8906013801835575f, + 0.8906231801318559f, 0.8906449780335499f, 0.8906667738885896f, 0.8906885676969249f, + 0.8907103594585055f, 0.8907321491732816f, 0.8907539368412031f, 0.8907757224622197f, + 0.8907975060362816f, 0.8908192875633385f, 0.8908410670433404f, 0.8908628444762375f, + 0.8908846198619795f, 0.8909063932005165f, 0.8909281644917985f, 0.8909499337357751f, + 0.8909717009323967f, 0.8909934660816133f, 0.8910152291833745f, 0.8910369902376306f, + 0.8910587492443316f, 0.8910805062034273f, 0.8911022611148677f, 0.8911240139786031f, + 0.8911457647945832f, 0.8911675135627583f, 0.8911892602830781f, 0.8912110049554929f, + 0.8912327475799526f, 0.8912544881564072f, 0.8912762266848069f, 0.8912979631651017f, + 0.8913196975972414f, 0.8913414299811764f, 0.8913631603168567f, 0.8913848886042320f, + 0.8914066148432529f, 0.8914283390338692f, 0.8914500611760310f, 0.8914717812696883f, + 0.8914934993147914f, 0.8915152153112902f, 0.8915369292591350f, 0.8915586411582755f, + 0.8915803510086623f, 0.8916020588102452f, 0.8916237645629744f, 0.8916454682668000f, + 0.8916671699216724f, 0.8916888695275412f, 0.8917105670843569f, 0.8917322625920696f, + 0.8917539560506295f, 0.8917756474599864f, 0.8917973368200910f, 0.8918190241308930f, + 0.8918407093923427f, 0.8918623926043904f, 0.8918840737669861f, 0.8919057528800801f, + 0.8919274299436225f, 0.8919491049575635f, 0.8919707779218535f, 0.8919924488364424f, + 0.8920141177012804f, 0.8920357845163179f, 0.8920574492815051f, 0.8920791119967920f, + 0.8921007726621292f, 0.8921224312774664f, 0.8921440878427542f, 0.8921657423579429f, + 0.8921873948229825f, 0.8922090452378233f, 0.8922306936024157f, 0.8922523399167097f, + 0.8922739841806557f, 0.8922956263942041f, 0.8923172665573049f, 0.8923389046699086f, + 0.8923605407319654f, 0.8923821747434254f, 0.8924038067042391f, 0.8924254366143568f, + 0.8924470644737287f, 0.8924686902823051f, 0.8924903140400363f, 0.8925119357468727f, + 0.8925335554027647f, 0.8925551730076623f, 0.8925767885615159f, 0.8925984020642762f, + 0.8926200135158930f, 0.8926416229163171f, 0.8926632302654987f, 0.8926848355633878f, + 0.8927064388099354f, 0.8927280400050912f, 0.8927496391488060f, 0.8927712362410301f, + 0.8927928312817136f, 0.8928144242708073f, 0.8928360152082613f, 0.8928576040940259f, + 0.8928791909280517f, 0.8929007757102891f, 0.8929223584406883f, 0.8929439391191999f, + 0.8929655177457743f, 0.8929870943203618f, 0.8930086688429129f, 0.8930302413133779f, + 0.8930518117317074f, 0.8930733800978518f, 0.8930949464117613f, 0.8931165106733867f, + 0.8931380728826783f, 0.8931596330395865f, 0.8931811911440617f, 0.8932027471960545f, + 0.8932243011955153f, 0.8932458531423946f, 0.8932674030366429f, 0.8932889508782106f, + 0.8933104966670481f, 0.8933320404031062f, 0.8933535820863351f, 0.8933751217166854f, + 0.8933966592941076f, 0.8934181948185522f, 0.8934397282899699f, 0.8934612597083109f, + 0.8934827890735259f, 0.8935043163855654f, 0.8935258416443798f, 0.8935473648499198f, + 0.8935688860021360f, 0.8935904051009788f, 0.8936119221463987f, 0.8936334371383464f, + 0.8936549500767724f, 0.8936764609616273f, 0.8936979697928618f, 0.8937194765704261f, + 0.8937409812942710f, 0.8937624839643472f, 0.8937839845806052f, 0.8938054831429953f, + 0.8938269796514686f, 0.8938484741059755f, 0.8938699665064664f, 0.8938914568528922f, + 0.8939129451452033f, 0.8939344313833504f, 0.8939559155672842f, 0.8939773976969552f, + 0.8939988777723142f, 0.8940203557933117f, 0.8940418317598984f, 0.8940633056720250f, + 0.8940847775296420f, 0.8941062473327001f, 0.8941277150811502f, 0.8941491807749427f, + 0.8941706444140283f, 0.8941921059983577f, 0.8942135655278818f, 0.8942350230025510f, + 0.8942564784223160f, 0.8942779317871278f, 0.8942993830969368f, 0.8943208323516938f, + 0.8943422795513495f, 0.8943637246958547f, 0.8943851677851599f, 0.8944066088192160f, + 0.8944280477979738f, 0.8944494847213839f, 0.8944709195893971f, 0.8944923524019641f, + 0.8945137831590356f, 0.8945352118605624f, 0.8945566385064955f, 0.8945780630967852f, + 0.8945994856313827f, 0.8946209061102385f, 0.8946423245333034f, 0.8946637409005284f, + 0.8946851552118640f, 0.8947065674672611f, 0.8947279776666706f, 0.8947493858100430f, + 0.8947707918973296f, 0.8947921959284808f, 0.8948135979034475f, 0.8948349978221806f, + 0.8948563956846309f, 0.8948777914907493f, 0.8948991852404864f, 0.8949205769337933f, + 0.8949419665706208f, 0.8949633541509195f, 0.8949847396746405f, 0.8950061231417346f, + 0.8950275045521526f, 0.8950488839058455f, 0.8950702612027640f, 0.8950916364428592f, + 0.8951130096260818f, 0.8951343807523826f, 0.8951557498217128f, 0.8951771168340229f, + 0.8951984817892642f, 0.8952198446873874f, 0.8952412055283434f, 0.8952625643120831f, + 0.8952839210385576f, 0.8953052757077175f, 0.8953266283195140f, 0.8953479788738979f, + 0.8953693273708203f, 0.8953906738102320f, 0.8954120181920839f, 0.8954333605163270f, + 0.8954547007829124f, 0.8954760389917908f, 0.8954973751429135f, 0.8955187092362312f, + 0.8955400412716948f, 0.8955613712492556f, 0.8955826991688645f, 0.8956040250304722f, + 0.8956253488340300f, 0.8956466705794889f, 0.8956679902667997f, 0.8956893078959134f, + 0.8957106234667813f, 0.8957319369793543f, 0.8957532484335833f, 0.8957745578294193f, + 0.8957958651668134f, 0.8958171704457168f, 0.8958384736660804f, 0.8958597748278552f, + 0.8958810739309924f, 0.8959023709754429f, 0.8959236659611578f, 0.8959449588880882f, + 0.8959662497561851f, 0.8959875385653997f, 0.8960088253156830f, 0.8960301100069861f, + 0.8960513926392600f, 0.8960726732124561f, 0.8960939517265251f, 0.8961152281814183f, + 0.8961365025770868f, 0.8961577749134817f, 0.8961790451905541f, 0.8962003134082551f, + 0.8962215795665359f, 0.8962428436653477f, 0.8962641057046414f, 0.8962853656843683f, + 0.8963066236044797f, 0.8963278794649263f, 0.8963491332656596f, 0.8963703850066308f, + 0.8963916346877908f, 0.8964128823090910f, 0.8964341278704825f, 0.8964553713719164f, + 0.8964766128133441f, 0.8964978521947166f, 0.8965190895159850f, 0.8965403247771008f, + 0.8965615579780150f, 0.8965827891186787f, 0.8966040181990435f, 0.8966252452190602f, + 0.8966464701786802f, 0.8966676930778548f, 0.8966889139165350f, 0.8967101326946724f, + 0.8967313494122179f, 0.8967525640691228f, 0.8967737766653385f, 0.8967949872008163f, + 0.8968161956755072f, 0.8968374020893627f, 0.8968586064423339f, 0.8968798087343721f, + 0.8969010089654288f, 0.8969222071354549f, 0.8969434032444019f, 0.8969645972922212f, + 0.8969857892788640f, 0.8970069792042815f, 0.8970281670684251f, 0.8970493528712461f, + 0.8970705366126959f, 0.8970917182927257f, 0.8971128979112868f, 0.8971340754683306f, + 0.8971552509638085f, 0.8971764243976716f, 0.8971975957698717f, 0.8972187650803597f, + 0.8972399323290871f, 0.8972610975160054f, 0.8972822606410656f, 0.8973034217042195f, + 0.8973245807054183f, 0.8973457376446132f, 0.8973668925217558f, 0.8973880453367976f, + 0.8974091960896897f, 0.8974303447803835f, 0.8974514914088307f, 0.8974726359749825f, + 0.8974937784787902f, 0.8975149189202055f, 0.8975360572991796f, 0.8975571936156641f, + 0.8975783278696102f, 0.8975994600609695f, 0.8976205901896934f, 0.8976417182557334f, + 0.8976628442590407f, 0.8976839681995672f, 0.8977050900772640f, 0.8977262098920826f, + 0.8977473276439747f, 0.8977684433328915f, 0.8977895569587846f, 0.8978106685216055f, + 0.8978317780213056f, 0.8978528854578365f, 0.8978739908311496f, 0.8978950941411965f, + 0.8979161953879286f, 0.8979372945712975f, 0.8979583916912546f, 0.8979794867477516f, + 0.8980005797407399f, 0.8980216706701709f, 0.8980427595359965f, 0.8980638463381679f, + 0.8980849310766368f, 0.8981060137513547f, 0.8981270943622731f, 0.8981481729093437f, + 0.8981692493925181f, 0.8981903238117476f, 0.8982113961669840f, 0.8982324664581788f, + 0.8982535346852836f, 0.8982746008482498f, 0.8982956649470294f, 0.8983167269815736f, + 0.8983377869518343f, 0.8983588448577629f, 0.8983799006993111f, 0.8984009544764304f, + 0.8984220061890725f, 0.8984430558371892f, 0.8984641034207319f, 0.8984851489396523f, + 0.8985061923939018f, 0.8985272337834327f, 0.8985482731081960f, 0.8985693103681435f, + 0.8985903455632270f, 0.8986113786933981f, 0.8986324097586085f, 0.8986534387588099f, + 0.8986744656939538f, 0.8986954905639921f, 0.8987165133688764f, 0.8987375341085582f, + 0.8987585527829896f, 0.8987795693921218f, 0.8988005839359069f, 0.8988215964142966f, + 0.8988426068272423f, 0.8988636151746959f, 0.8988846214566094f, 0.8989056256729341f, + 0.8989266278236219f, 0.8989476279086246f, 0.8989686259278938f, 0.8989896218813813f, + 0.8990106157690391f, 0.8990316075908186f, 0.8990525973466718f, 0.8990735850365502f, + 0.8990945706604058f, 0.8991155542181903f, 0.8991365357098555f, 0.8991575151353532f, + 0.8991784924946353f, 0.8991994677876534f, 0.8992204410143593f, 0.8992414121747049f, + 0.8992623812686420f, 0.8992833482961223f, 0.8993043132570979f, 0.8993252761515204f, + 0.8993462369793415f, 0.8993671957405134f, 0.8993881524349876f, 0.8994091070627163f, + 0.8994300596236509f, 0.8994510101177434f, 0.8994719585449460f, 0.8994929049052102f, + 0.8995138491984879f, 0.8995347914247311f, 0.8995557315838917f, 0.8995766696759213f, + 0.8995976057007722f, 0.8996185396583959f, 0.8996394715487445f, 0.8996604013717699f, + 0.8996813291274239f, 0.8997022548156586f, 0.8997231784364257f, 0.8997440999896772f, + 0.8997650194753650f, 0.8997859368934412f, 0.8998068522438576f, 0.8998277655265661f, + 0.8998486767415186f, 0.8998695858886671f, 0.8998904929679638f, 0.8999113979793602f, + 0.8999323009228084f, 0.8999532017982608f, 0.8999741006056687f, 0.8999949973449846f, + 0.9000158920161603f, 0.9000367846191476f, 0.9000576751538988f, 0.9000785636203658f, + 0.9000994500185003f, 0.9001203343482548f, 0.9001412166095810f, 0.9001620968024310f, + 0.9001829749267568f, 0.9002038509825104f, 0.9002247249696438f, 0.9002455968881092f, + 0.9002664667378585f, 0.9002873345188437f, 0.9003082002310170f, 0.9003290638743302f, + 0.9003499254487356f, 0.9003707849541852f, 0.9003916423906311f, 0.9004124977580251f, + 0.9004333510563198f, 0.9004542022854668f, 0.9004750514454183f, 0.9004958985361267f, + 0.9005167435575435f, 0.9005375865096215f, 0.9005584273923122f, 0.9005792662055679f, + 0.9006001029493409f, 0.9006209376235832f, 0.9006417702282468f, 0.9006626007632841f, + 0.9006834292286469f, 0.9007042556242876f, 0.9007250799501583f, 0.9007459022062109f, + 0.9007667223923979f, 0.9007875405086713f, 0.9008083565549831f, 0.9008291705312858f, + 0.9008499824375314f, 0.9008707922736721f, 0.9008916000396600f, 0.9009124057354473f, + 0.9009332093609862f, 0.9009540109162291f, 0.9009748104011278f, 0.9009956078156348f, + 0.9010164031597023f, 0.9010371964332825f, 0.9010579876363274f, 0.9010787767687896f, + 0.9010995638306210f, 0.9011203488217738f, 0.9011411317422007f, 0.9011619125918534f, + 0.9011826913706844f, 0.9012034680786460f, 0.9012242427156903f, 0.9012450152817698f, + 0.9012657857768366f, 0.9012865542008428f, 0.9013073205537411f, 0.9013280848354833f, + 0.9013488470460220f, 0.9013696071853095f, 0.9013903652532979f, 0.9014111212499396f, + 0.9014318751751870f, 0.9014526270289922f, 0.9014733768113077f, 0.9014941245220858f, + 0.9015148701612786f, 0.9015356137288387f, 0.9015563552247184f, 0.9015770946488699f, + 0.9015978320012457f, 0.9016185672817980f, 0.9016393004904791f, 0.9016600316272416f, + 0.9016807606920377f, 0.9017014876848197f, 0.9017222126055402f, 0.9017429354541514f, + 0.9017636562306056f, 0.9017843749348555f, 0.9018050915668532f, 0.9018258061265511f, + 0.9018465186139019f, 0.9018672290288575f, 0.9018879373713707f, 0.9019086436413940f, + 0.9019293478388793f, 0.9019500499637796f, 0.9019707500160471f, 0.9019914479956340f, + 0.9020121439024932f, 0.9020328377365767f, 0.9020535294978372f, 0.9020742191862272f, + 0.9020949068016989f, 0.9021155923442049f, 0.9021362758136978f, 0.9021569572101298f, + 0.9021776365334535f, 0.9021983137836216f, 0.9022189889605862f, 0.9022396620643000f, + 0.9022603330947155f, 0.9022810020517852f, 0.9023016689354615f, 0.9023223337456970f, + 0.9023429964824442f, 0.9023636571456557f, 0.9023843157352838f, 0.9024049722512811f, + 0.9024256266936004f, 0.9024462790621939f, 0.9024669293570142f, 0.9024875775780141f, + 0.9025082237251458f, 0.9025288677983622f, 0.9025495097976156f, 0.9025701497228587f, + 0.9025907875740439f, 0.9026114233511240f, 0.9026320570540514f, 0.9026526886827788f, + 0.9026733182372588f, 0.9026939457174439f, 0.9027145711232868f, 0.9027351944547400f, + 0.9027558157117561f, 0.9027764348942879f, 0.9027970520022879f, 0.9028176670357085f, + 0.9028382799945028f, 0.9028588908786230f, 0.9028794996880219f, 0.9029001064226524f, + 0.9029207110824666f, 0.9029413136674176f, 0.9029619141774580f, 0.9029825126125403f, + 0.9030031089726170f, 0.9030237032576414f, 0.9030442954675655f, 0.9030648856023424f, + 0.9030854736619246f, 0.9031060596462648f, 0.9031266435553158f, 0.9031472253890301f, + 0.9031678051473606f, 0.9031883828302602f, 0.9032089584376810f, 0.9032295319695761f, + 0.9032501034258984f, 0.9032706728066003f, 0.9032912401116346f, 0.9033118053409543f, + 0.9033323684945118f, 0.9033529295722600f, 0.9033734885741517f, 0.9033940455001395f, + 0.9034146003501763f, 0.9034351531242149f, 0.9034557038222079f, 0.9034762524441081f, + 0.9034967989898685f, 0.9035173434594416f, 0.9035378858527804f, 0.9035584261698376f, + 0.9035789644105660f, 0.9035995005749184f, 0.9036200346628477f, 0.9036405666743066f, + 0.9036610966092480f, 0.9036816244676247f, 0.9037021502493894f, 0.9037226739544951f, + 0.9037431955828946f, 0.9037637151345407f, 0.9037842326093865f, 0.9038047480073843f, + 0.9038252613284875f, 0.9038457725726486f, 0.9038662817398206f, 0.9038867888299565f, + 0.9039072938430091f, 0.9039277967789311f, 0.9039482976376756f, 0.9039687964191954f, + 0.9039892931234433f, 0.9040097877503724f, 0.9040302802999355f, 0.9040507707720855f, + 0.9040712591667754f, 0.9040917454839581f, 0.9041122297235863f, 0.9041327118856133f, + 0.9041531919699917f, 0.9041736699766747f, 0.9041941459056150f, 0.9042146197567656f, + 0.9042350915300797f, 0.9042555612255101f, 0.9042760288430096f, 0.9042964943825315f, + 0.9043169578440283f, 0.9043374192274534f, 0.9043578785327596f, 0.9043783357598999f, + 0.9043987909088274f, 0.9044192439794949f, 0.9044396949718555f, 0.9044601438858623f, + 0.9044805907214682f, 0.9045010354786261f, 0.9045214781572894f, 0.9045419187574107f, + 0.9045623572789432f, 0.9045827937218400f, 0.9046032280860541f, 0.9046236603715384f, + 0.9046440905782462f, 0.9046645187061304f, 0.9046849447551439f, 0.9047053687252402f, + 0.9047257906163719f, 0.9047462104284923f, 0.9047666281615546f, 0.9047870438155116f, + 0.9048074573903165f, 0.9048278688859226f, 0.9048482783022826f, 0.9048686856393500f, + 0.9048890908970775f, 0.9049094940754185f, 0.9049298951743261f, 0.9049502941937533f, + 0.9049706911336532f, 0.9049910859939791f, 0.9050114787746840f, 0.9050318694757211f, + 0.9050522580970436f, 0.9050726446386045f, 0.9050930291003570f, 0.9051134114822544f, + 0.9051337917842496f, 0.9051541700062959f, 0.9051745461483467f, 0.9051949202103547f, + 0.9052152921922736f, 0.9052356620940561f, 0.9052560299156557f, 0.9052763956570256f, + 0.9052967593181188f, 0.9053171208988886f, 0.9053374803992883f, 0.9053578378192710f, + 0.9053781931587900f, 0.9053985464177986f, 0.9054188975962497f, 0.9054392466940968f, + 0.9054595937112933f, 0.9054799386477920f, 0.9055002815035464f, 0.9055206222785099f, + 0.9055409609726355f, 0.9055612975858766f, 0.9055816321181864f, 0.9056019645695181f, + 0.9056222949398253f, 0.9056426232290609f, 0.9056629494371783f, 0.9056832735641310f, + 0.9057035956098720f, 0.9057239155743547f, 0.9057442334575326f, 0.9057645492593587f, + 0.9057848629797864f, 0.9058051746187694f, 0.9058254841762604f, 0.9058457916522131f, + 0.9058660970465809f, 0.9058864003593170f, 0.9059067015903747f, 0.9059270007397074f, + 0.9059472978072685f, 0.9059675927930113f, 0.9059878856968892f, 0.9060081765188555f, + 0.9060284652588636f, 0.9060487519168670f, 0.9060690364928188f, 0.9060893189866728f, + 0.9061095993983820f, 0.9061298777279000f, 0.9061501539751802f, 0.9061704281401759f, + 0.9061907002228405f, 0.9062109702231277f, 0.9062312381409906f, 0.9062515039763828f, + 0.9062717677292577f, 0.9062920293995685f, 0.9063122889872690f, 0.9063325464923124f, + 0.9063528019146523f, 0.9063730552542422f, 0.9063933065110353f, 0.9064135556849852f, + 0.9064338027760455f, 0.9064540477841695f, 0.9064742907093106f, 0.9064945315514227f, + 0.9065147703104588f, 0.9065350069863726f, 0.9065552415791177f, 0.9065754740886474f, + 0.9065957045149153f, 0.9066159328578750f, 0.9066361591174799f, 0.9066563832936836f, + 0.9066766053864395f, 0.9066968253957012f, 0.9067170433214223f, 0.9067372591635562f, + 0.9067574729220566f, 0.9067776845968770f, 0.9067978941879709f, 0.9068181016952918f, + 0.9068383071187935f, 0.9068585104584294f, 0.9068787117141530f, 0.9068989108859181f, + 0.9069191079736780f, 0.9069393029773866f, 0.9069594958969974f, 0.9069796867324638f, + 0.9069998754837396f, 0.9070200621507784f, 0.9070402467335337f, 0.9070604292319592f, + 0.9070806096460085f, 0.9071007879756351f, 0.9071209642207930f, 0.9071411383814354f, + 0.9071613104575162f, 0.9071814804489891f, 0.9072016483558075f, 0.9072218141779251f, + 0.9072419779152959f, 0.9072621395678732f, 0.9072822991356106f, 0.9073024566184622f, + 0.9073226120163813f, 0.9073427653293218f, 0.9073629165572373f, 0.9073830657000815f, + 0.9074032127578081f, 0.9074233577303707f, 0.9074435006177233f, 0.9074636414198194f, + 0.9074837801366126f, 0.9075039167680568f, 0.9075240513141057f, 0.9075441837747131f, + 0.9075643141498325f, 0.9075844424394180f, 0.9076045686434231f, 0.9076246927618015f, + 0.9076448147945071f, 0.9076649347414937f, 0.9076850526027148f, 0.9077051683781245f, + 0.9077252820676763f, 0.9077453936713243f, 0.9077655031890219f, 0.9077856106207232f, + 0.9078057159663819f, 0.9078258192259517f, 0.9078459203993864f, 0.9078660194866400f, + 0.9078861164876662f, 0.9079062114024188f, 0.9079263042308516f, 0.9079463949729185f, + 0.9079664836285732f, 0.9079865701977698f, 0.9080066546804619f, 0.9080267370766034f, + 0.9080468173861483f, 0.9080668956090503f, 0.9080869717452632f, 0.9081070457947410f, + 0.9081271177574376f, 0.9081471876333067f, 0.9081672554223024f, 0.9081873211243784f, + 0.9082073847394887f, 0.9082274462675871f, 0.9082475057086276f, 0.9082675630625641f, + 0.9082876183293505f, 0.9083076715089405f, 0.9083277226012884f, 0.9083477716063478f, + 0.9083678185240728f, 0.9083878633544173f, 0.9084079060973353f, 0.9084279467527807f, + 0.9084479853207073f, 0.9084680218010691f, 0.9084880561938203f, 0.9085080884989146f, + 0.9085281187163061f, 0.9085481468459488f, 0.9085681728877965f, 0.9085881968418033f, + 0.9086082187079232f, 0.9086282384861101f, 0.9086482561763181f, 0.9086682717785013f, + 0.9086882852926134f, 0.9087082967186085f, 0.9087283060564409f, 0.9087483133060643f, + 0.9087683184674329f, 0.9087883215405006f, 0.9088083225252215f, 0.9088283214215497f, + 0.9088483182294391f, 0.9088683129488438f, 0.9088883055797180f, 0.9089082961220155f, + 0.9089282845756906f, 0.9089482709406973f, 0.9089682552169897f, 0.9089882374045216f, + 0.9090082175032475f, 0.9090281955131212f, 0.9090481714340969f, 0.9090681452661287f, + 0.9090881170091706f, 0.9091080866631768f, 0.9091280542281015f, 0.9091480197038986f, + 0.9091679830905224f, 0.9091879443879269f, 0.9092079035960663f, 0.9092278607148948f, + 0.9092478157443663f, 0.9092677686844353f, 0.9092877195350556f, 0.9093076682961816f, + 0.9093276149677673f, 0.9093475595497670f, 0.9093675020421347f, 0.9093874424448247f, + 0.9094073807577913f, 0.9094273169809883f, 0.9094472511143703f, 0.9094671831578912f, + 0.9094871131115054f, 0.9095070409751670f, 0.9095269667488302f, 0.9095468904324492f, + 0.9095668120259783f, 0.9095867315293716f, 0.9096066489425835f, 0.9096265642655681f, + 0.9096464774982795f, 0.9096663886406723f, 0.9096862976927005f, 0.9097062046543183f, + 0.9097261095254802f, 0.9097460123061402f, 0.9097659129962526f, 0.9097858115957719f, + 0.9098057081046522f, 0.9098256025228478f, 0.9098454948503131f, 0.9098653850870020f, + 0.9098852732328692f, 0.9099051592878689f, 0.9099250432519552f, 0.9099449251250827f, + 0.9099648049072057f, 0.9099846825982782f, 0.9100045581982548f, 0.9100244317070898f, + 0.9100443031247374f, 0.9100641724511520f, 0.9100840396862881f, 0.9101039048300998f, + 0.9101237678825416f, 0.9101436288435678f, 0.9101634877131328f, 0.9101833444911910f, + 0.9102031991776965f, 0.9102230517726040f, 0.9102429022758679f, 0.9102627506874422f, + 0.9102825970072818f, 0.9103024412353407f, 0.9103222833715734f, 0.9103421234159343f, + 0.9103619613683780f, 0.9103817972288586f, 0.9104016309973307f, 0.9104214626737488f, + 0.9104412922580671f, 0.9104611197502402f, 0.9104809451502227f, 0.9105007684579686f, + 0.9105205896734327f, 0.9105404087965693f, 0.9105602258273329f, 0.9105800407656780f, + 0.9105998536115589f, 0.9106196643649302f, 0.9106394730257465f, 0.9106592795939621f, + 0.9106790840695316f, 0.9106988864524094f, 0.9107186867425499f, 0.9107384849399077f, + 0.9107582810444376f, 0.9107780750560935f, 0.9107978669748305f, 0.9108176568006028f, + 0.9108374445333650f, 0.9108572301730715f, 0.9108770137196772f, 0.9108967951731362f, + 0.9109165745334034f, 0.9109363518004330f, 0.9109561269741798f, 0.9109759000545984f, + 0.9109956710416431f, 0.9110154399352687f, 0.9110352067354298f, 0.9110549714420808f, + 0.9110747340551762f, 0.9110944945746711f, 0.9111142530005194f, 0.9111340093326762f, + 0.9111537635710959f, 0.9111735157157331f, 0.9111932657665425f, 0.9112130137234786f, + 0.9112327595864962f, 0.9112525033555497f, 0.9112722450305939f, 0.9112919846115833f, + 0.9113117220984728f, 0.9113314574912167f, 0.9113511907897698f, 0.9113709219940869f, + 0.9113906511041223f, 0.9114103781198311f, 0.9114301030411677f, 0.9114498258680868f, + 0.9114695466005430f, 0.9114892652384913f, 0.9115089817818860f, 0.9115286962306819f, + 0.9115484085848340f, 0.9115681188442966f, 0.9115878270090247f, 0.9116075330789728f, + 0.9116272370540957f, 0.9116469389343481f, 0.9116666387196848f, 0.9116863364100605f, + 0.9117060320054299f, 0.9117257255057477f, 0.9117454169109687f, 0.9117651062210478f, + 0.9117847934359394f, 0.9118044785555985f, 0.9118241615799800f, 0.9118438425090384f, + 0.9118635213427285f, 0.9118831980810053f, 0.9119028727238233f, 0.9119225452711376f, + 0.9119422157229026f, 0.9119618840790734f, 0.9119815503396048f, 0.9120012145044515f, + 0.9120208765735682f, 0.9120405365469101f, 0.9120601944244316f, 0.9120798502060877f, + 0.9120995038918335f, 0.9121191554816234f, 0.9121388049754123f, 0.9121584523731554f, + 0.9121780976748071f, 0.9121977408803226f, 0.9122173819896566f, 0.9122370210027640f, + 0.9122566579195998f, 0.9122762927401186f, 0.9122959254642754f, 0.9123155560920252f, + 0.9123351846233227f, 0.9123548110581230f, 0.9123744353963810f, 0.9123940576380513f, + 0.9124136777830890f, 0.9124332958314492f, 0.9124529117830865f, 0.9124725256379560f, + 0.9124921373960126f, 0.9125117470572113f, 0.9125313546215068f, 0.9125509600888544f, + 0.9125705634592087f, 0.9125901647325249f, 0.9126097639087579f, 0.9126293609878625f, + 0.9126489559697940f, 0.9126685488545070f, 0.9126881396419566f, 0.9127077283320980f, + 0.9127273149248859f, 0.9127468994202753f, 0.9127664818182215f, 0.9127860621186792f, + 0.9128056403216035f, 0.9128252164269495f, 0.9128447904346720f, 0.9128643623447262f, + 0.9128839321570672f, 0.9129034998716498f, 0.9129230654884291f, 0.9129426290073602f, + 0.9129621904283981f, 0.9129817497514980f, 0.9130013069766147f, 0.9130208621037034f, + 0.9130404151327193f, 0.9130599660636171f, 0.9130795148963521f, 0.9130990616308795f, + 0.9131186062671541f, 0.9131381488051312f, 0.9131576892447659f, 0.9131772275860132f, + 0.9131967638288282f, 0.9132162979731661f, 0.9132358300189818f, 0.9132553599662306f, + 0.9132748878148678f, 0.9132944135648481f, 0.9133139372161269f, 0.9133334587686592f, + 0.9133529782224002f, 0.9133724955773053f, 0.9133920108333292f, 0.9134115239904272f, + 0.9134310350485547f, 0.9134505440076667f, 0.9134700508677183f, 0.9134895556286647f, + 0.9135090582904611f, 0.9135285588530627f, 0.9135480573164249f, 0.9135675536805025f, + 0.9135870479452508f, 0.9136065401106253f, 0.9136260301765807f, 0.9136455181430728f, + 0.9136650040100563f, 0.9136844877774867f, 0.9137039694453193f, 0.9137234490135091f, + 0.9137429264820114f, 0.9137624018507816f, 0.9137818751197747f, 0.9138013462889460f, + 0.9138208153582511f, 0.9138402823276449f, 0.9138597471970826f, 0.9138792099665199f, + 0.9138986706359117f, 0.9139181292052133f, 0.9139375856743802f, 0.9139570400433674f, + 0.9139764923121306f, 0.9139959424806247f, 0.9140153905488052f, 0.9140348365166274f, + 0.9140542803840465f, 0.9140737221510179f, 0.9140931618174971f, 0.9141125993834391f, + 0.9141320348487995f, 0.9141514682135334f, 0.9141708994775964f, 0.9141903286409436f, + 0.9142097557035307f, 0.9142291806653127f, 0.9142486035262449f, 0.9142680242862832f, + 0.9142874429453824f, 0.9143068595034983f, 0.9143262739605860f, 0.9143456863166008f, + 0.9143650965714986f, 0.9143845047252342f, 0.9144039107777634f, 0.9144233147290415f, + 0.9144427165790239f, 0.9144621163276658f, 0.9144815139749231f, 0.9145009095207508f, + 0.9145203029651044f, 0.9145396943079396f, 0.9145590835492116f, 0.9145784706888758f, + 0.9145978557268878f, 0.9146172386632030f, 0.9146366194977767f, 0.9146559982305649f, + 0.9146753748615224f, 0.9146947493906050f, 0.9147141218177682f, 0.9147334921429674f, + 0.9147528603661582f, 0.9147722264872958f, 0.9147915905063361f, 0.9148109524232344f, + 0.9148303122379461f, 0.9148496699504269f, 0.9148690255606323f, 0.9148883790685176f, + 0.9149077304740386f, 0.9149270797771508f, 0.9149464269778096f, 0.9149657720759705f, + 0.9149851150715893f, 0.9150044559646213f, 0.9150237947550223f, 0.9150431314427475f, + 0.9150624660277528f, 0.9150817985099937f, 0.9151011288894256f, 0.9151204571660042f, + 0.9151397833396853f, 0.9151591074104241f, 0.9151784293781763f, 0.9151977492428978f, + 0.9152170670045437f, 0.9152363826630701f, 0.9152556962184324f, 0.9152750076705861f, + 0.9152943170194870f, 0.9153136242650908f, 0.9153329294073528f, 0.9153522324462290f, + 0.9153715333816748f, 0.9153908322136458f, 0.9154101289420981f, 0.9154294235669868f, + 0.9154487160882678f, 0.9154680065058969f, 0.9154872948198295f, 0.9155065810300215f, + 0.9155258651364285f, 0.9155451471390061f, 0.9155644270377101f, 0.9155837048324963f, + 0.9156029805233202f, 0.9156222541101375f, 0.9156415255929041f, 0.9156607949715756f, + 0.9156800622461077f, 0.9156993274164561f, 0.9157185904825765f, 0.9157378514444249f, + 0.9157571103019567f, 0.9157763670551279f, 0.9157956217038942f, 0.9158148742482112f, + 0.9158341246880347f, 0.9158533730233206f, 0.9158726192540245f, 0.9158918633801023f, + 0.9159111054015099f, 0.9159303453182027f, 0.9159495831301369f, 0.9159688188372680f, + 0.9159880524395518f, 0.9160072839369444f, 0.9160265133294013f, 0.9160457406168785f, + 0.9160649657993317f, 0.9160841888767167f, 0.9161034098489894f, 0.9161226287161057f, + 0.9161418454780214f, 0.9161610601346921f, 0.9161802726860740f, 0.9161994831321227f, + 0.9162186914727941f, 0.9162378977080443f, 0.9162571018378288f, 0.9162763038621037f, + 0.9162955037808248f, 0.9163147015939480f, 0.9163338973014292f, 0.9163530909032244f, + 0.9163722823992891f, 0.9163914717895797f, 0.9164106590740517f, 0.9164298442526612f, + 0.9164490273253642f, 0.9164682082921164f, 0.9164873871528738f, 0.9165065639075924f, + 0.9165257385562281f, 0.9165449110987368f, 0.9165640815350746f, 0.9165832498651972f, + 0.9166024160890607f, 0.9166215802066211f, 0.9166407422178342f, 0.9166599021226560f, + 0.9166790599210427f, 0.9166982156129500f, 0.9167173691983340f, 0.9167365206771506f, + 0.9167556700493560f, 0.9167748173149060f, 0.9167939624737566f, 0.9168131055258639f, + 0.9168322464711839f, 0.9168513853096726f, 0.9168705220412859f, 0.9168896566659801f, + 0.9169087891837110f, 0.9169279195944346f, 0.9169470478981072f, 0.9169661740946846f, + 0.9169852981841229f, 0.9170044201663783f, 0.9170235400414066f, 0.9170426578091642f, + 0.9170617734696068f, 0.9170808870226906f, 0.9170999984683720f, 0.9171191078066065f, + 0.9171382150373507f, 0.9171573201605605f, 0.9171764231761919f, 0.9171955240842010f, + 0.9172146228845443f, 0.9172337195771774f, 0.9172528141620565f, 0.9172719066391380f, + 0.9172909970083779f, 0.9173100852697322f, 0.9173291714231574f, 0.9173482554686091f, + 0.9173673374060439f, 0.9173864172354177f, 0.9174054949566867f, 0.9174245705698072f, + 0.9174436440747352f, 0.9174627154714269f, 0.9174817847598385f, 0.9175008519399263f, + 0.9175199170116463f, 0.9175389799749548f, 0.9175580408298079f, 0.9175770995761618f, + 0.9175961562139729f, 0.9176152107431972f, 0.9176342631637909f, 0.9176533134757104f, + 0.9176723616789118f, 0.9176914077733515f, 0.9177104517589852f, 0.9177294936357698f, + 0.9177485334036612f, 0.9177675710626158f, 0.9177866066125897f, 0.9178056400535393f, + 0.9178246713854206f, 0.9178437006081901f, 0.9178627277218041f, 0.9178817527262187f, + 0.9179007756213904f, 0.9179197964072754f, 0.9179388150838298f, 0.9179578316510102f, + 0.9179768461087727f, 0.9179958584570737f, 0.9180148686958693f, 0.9180338768251162f, + 0.9180528828447704f, 0.9180718867547883f, 0.9180908885551264f, 0.9181098882457408f, + 0.9181288858265880f, 0.9181478812976241f, 0.9181668746588059f, 0.9181858659100893f, + 0.9182048550514309f, 0.9182238420827870f, 0.9182428270041141f, 0.9182618098153683f, + 0.9182807905165061f, 0.9182997691074840f, 0.9183187455882583f, 0.9183377199587853f, + 0.9183566922190217f, 0.9183756623689235f, 0.9183946304084475f, 0.9184135963375497f, + 0.9184325601561868f, 0.9184515218643153f, 0.9184704814618914f, 0.9184894389488715f, + 0.9185083943252123f, 0.9185273475908700f, 0.9185462987458011f, 0.9185652477899622f, + 0.9185841947233095f, 0.9186031395457998f, 0.9186220822573893f, 0.9186410228580344f, + 0.9186599613476919f, 0.9186788977263181f, 0.9186978319938693f, 0.9187167641503023f, + 0.9187356941955735f, 0.9187546221296393f, 0.9187735479524565f, 0.9187924716639810f, + 0.9188113932641699f, 0.9188303127529797f, 0.9188492301303665f, 0.9188681453962870f, + 0.9188870585506980f, 0.9189059695935557f, 0.9189248785248169f, 0.9189437853444380f, + 0.9189626900523756f, 0.9189815926485861f, 0.9190004931330265f, 0.9190193915056528f, + 0.9190382877664220f, 0.9190571819152905f, 0.9190760739522149f, 0.9190949638771518f, + 0.9191138516900578f, 0.9191327373908894f, 0.9191516209796033f, 0.9191705024561562f, + 0.9191893818205045f, 0.9192082590726049f, 0.9192271342124142f, 0.9192460072398887f, + 0.9192648781549853f, 0.9192837469576605f, 0.9193026136478709f, 0.9193214782255733f, + 0.9193403406907242f, 0.9193592010432805f, 0.9193780592831986f, 0.9193969154104351f, + 0.9194157694249471f, 0.9194346213266907f, 0.9194534711156230f, 0.9194723187917007f, + 0.9194911643548801f, 0.9195100078051182f, 0.9195288491423718f, 0.9195476883665973f, + 0.9195665254777515f, 0.9195853604757913f, 0.9196041933606731f, 0.9196230241323540f, + 0.9196418527907905f, 0.9196606793359393f, 0.9196795037677572f, 0.9196983260862009f, + 0.9197171462912274f, 0.9197359643827930f, 0.9197547803608549f, 0.9197735942253695f, + 0.9197924059762939f, 0.9198112156135846f, 0.9198300231371984f, 0.9198488285470924f, + 0.9198676318432230f, 0.9198864330255470f, 0.9199052320940215f, 0.9199240290486032f, + 0.9199428238892486f, 0.9199616166159150f, 0.9199804072285588f, 0.9199991957271371f, + 0.9200179821116066f, 0.9200367663819240f, 0.9200555485380464f, 0.9200743285799304f, + 0.9200931065075331f, 0.9201118823208112f, 0.9201306560197215f, 0.9201494276042209f, + 0.9201681970742664f, 0.9201869644298146f, 0.9202057296708226f, 0.9202244927972473f, + 0.9202432538090454f, 0.9202620127061738f, 0.9202807694885896f, 0.9202995241562495f, + 0.9203182767091105f, 0.9203370271471295f, 0.9203557754702634f, 0.9203745216784691f, + 0.9203932657717036f, 0.9204120077499236f, 0.9204307476130863f, 0.9204494853611485f, + 0.9204682209940671f, 0.9204869545117992f, 0.9205056859143016f, 0.9205244152015314f, + 0.9205431423734455f, 0.9205618674300008f, 0.9205805903711543f, 0.9205993111968630f, + 0.9206180299070839f, 0.9206367465017740f, 0.9206554609808902f, 0.9206741733443895f, + 0.9206928835922291f, 0.9207115917243658f, 0.9207302977407565f, 0.9207490016413586f, + 0.9207677034261288f, 0.9207864030950241f, 0.9208051006480019f, 0.9208237960850189f, + 0.9208424894060321f, 0.9208611806109988f, 0.9208798696998759f, 0.9208985566726203f, + 0.9209172415291895f, 0.9209359242695401f, 0.9209546048936293f, 0.9209732834014145f, + 0.9209919597928523f, 0.9210106340679001f, 0.9210293062265148f, 0.9210479762686536f, + 0.9210666441942736f, 0.9210853100033318f, 0.9211039736957854f, 0.9211226352715915f, + 0.9211412947307073f, 0.9211599520730896f, 0.9211786072986961f, 0.9211972604074833f, + 0.9212159113994087f, 0.9212345602744294f, 0.9212532070325025f, 0.9212718516735851f, + 0.9212904941976345f, 0.9213091346046077f, 0.9213277728944620f, 0.9213464090671545f, + 0.9213650431226423f, 0.9213836750608828f, 0.9214023048818331f, 0.9214209325854501f, + 0.9214395581716914f, 0.9214581816405141f, 0.9214768029918752f, 0.9214954222257321f, + 0.9215140393420419f, 0.9215326543407619f, 0.9215512672218494f, 0.9215698779852615f, + 0.9215884866309554f, 0.9216070931588886f, 0.9216256975690179f, 0.9216442998613008f, + 0.9216629000356947f, 0.9216814980921567f, 0.9217000940306441f, 0.9217186878511140f, + 0.9217372795535238f, 0.9217558691378309f, 0.9217744566039925f, 0.9217930419519658f, + 0.9218116251817081f, 0.9218302062931768f, 0.9218487852863291f, 0.9218673621611224f, + 0.9218859369175140f, 0.9219045095554610f, 0.9219230800749211f, 0.9219416484758514f, + 0.9219602147582091f, 0.9219787789219519f, 0.9219973409670368f, 0.9220159008934213f, + 0.9220344587010628f, 0.9220530143899185f, 0.9220715679599459f, 0.9220901194111023f, + 0.9221086687433451f, 0.9221272159566317f, 0.9221457610509193f, 0.9221643040261654f, + 0.9221828448823276f, 0.9222013836193630f, 0.9222199202372291f, 0.9222384547358833f, + 0.9222569871152830f, 0.9222755173753856f, 0.9222940455161487f, 0.9223125715375294f, + 0.9223310954394854f, 0.9223496172219739f, 0.9223681368849526f, 0.9223866544283789f, + 0.9224051698522099f, 0.9224236831564034f, 0.9224421943409169f, 0.9224607034057076f, + 0.9224792103507331f, 0.9224977151759510f, 0.9225162178813185f, 0.9225347184667932f, + 0.9225532169323328f, 0.9225717132778944f, 0.9225902075034359f, 0.9226086996089146f, + 0.9226271895942878f, 0.9226456774595134f, 0.9226641632045487f, 0.9226826468293512f, + 0.9227011283338786f, 0.9227196077180883f, 0.9227380849819377f, 0.9227565601253847f, + 0.9227750331483864f, 0.9227935040509007f, 0.9228119728328851f, 0.9228304394942970f, + 0.9228489040350941f, 0.9228673664552339f, 0.9228858267546741f, 0.9229042849333721f, + 0.9229227409912857f, 0.9229411949283722f, 0.9229596467445895f, 0.9229780964398949f, + 0.9229965440142462f, 0.9230149894676011f, 0.9230334327999170f, 0.9230518740111515f, + 0.9230703131012624f, 0.9230887500702073f, 0.9231071849179436f, 0.9231256176444294f, + 0.9231440482496218f, 0.9231624767334788f, 0.9231809030959581f, 0.9231993273370170f, + 0.9232177494566135f, 0.9232361694547052f, 0.9232545873312495f, 0.9232730030862045f, + 0.9232914167195276f, 0.9233098282311766f, 0.9233282376211092f, 0.9233466448892830f, + 0.9233650500356556f, 0.9233834530601851f, 0.9234018539628288f, 0.9234202527435447f, + 0.9234386494022904f, 0.9234570439390235f, 0.9234754363537019f, 0.9234938266462834f, + 0.9235122148167255f, 0.9235306008649862f, 0.9235489847910231f, 0.9235673665947940f, + 0.9235857462762566f, 0.9236041238353688f, 0.9236224992720882f, 0.9236408725863727f, + 0.9236592437781800f, 0.9236776128474679f, 0.9236959797941943f, 0.9237143446183167f, + 0.9237327073197932f, 0.9237510678985815f, 0.9237694263546394f, 0.9237877826879248f, + 0.9238061368983954f, 0.9238244889860091f, 0.9238428389507236f, 0.9238611867924970f, + 0.9238795325112867f, 0.9238978761070510f, 0.9239162175797475f, 0.9239345569293341f, + 0.9239528941557686f, 0.9239712292590091f, 0.9239895622390131f, 0.9240078930957388f, + 0.9240262218291438f, 0.9240445484391863f, 0.9240628729258239f, 0.9240811952890146f, + 0.9240995155287163f, 0.9241178336448869f, 0.9241361496374842f, 0.9241544635064664f, + 0.9241727752517912f, 0.9241910848734164f, 0.9242093923713002f, 0.9242276977454004f, + 0.9242460009956749f, 0.9242643021220817f, 0.9242826011245787f, 0.9243008980031239f, + 0.9243191927576753f, 0.9243374853881906f, 0.9243557758946280f, 0.9243740642769456f, + 0.9243923505351010f, 0.9244106346690525f, 0.9244289166787579f, 0.9244471965641753f, + 0.9244654743252626f, 0.9244837499619779f, 0.9245020234742791f, 0.9245202948621242f, + 0.9245385641254714f, 0.9245568312642785f, 0.9245750962785036f, 0.9245933591681048f, + 0.9246116199330400f, 0.9246298785732674f, 0.9246481350887449f, 0.9246663894794305f, + 0.9246846417452825f, 0.9247028918862586f, 0.9247211399023173f, 0.9247393857934164f, + 0.9247576295595139f, 0.9247758712005680f, 0.9247941107165368f, 0.9248123481073784f, + 0.9248305833730508f, 0.9248488165135123f, 0.9248670475287205f, 0.9248852764186341f, + 0.9249035031832109f, 0.9249217278224091f, 0.9249399503361868f, 0.9249581707245020f, + 0.9249763889873130f, 0.9249946051245781f, 0.9250128191362550f, 0.9250310310223021f, + 0.9250492407826776f, 0.9250674484173396f, 0.9250856539262461f, 0.9251038573093555f, + 0.9251220585666258f, 0.9251402576980153f, 0.9251584547034821f, 0.9251766495829845f, + 0.9251948423364804f, 0.9252130329639284f, 0.9252312214652865f, 0.9252494078405128f, + 0.9252675920895655f, 0.9252857742124031f, 0.9253039542089836f, 0.9253221320792653f, + 0.9253403078232062f, 0.9253584814407649f, 0.9253766529318994f, 0.9253948222965680f, + 0.9254129895347291f, 0.9254311546463405f, 0.9254493176313610f, 0.9254674784897485f, + 0.9254856372214615f, 0.9255037938264581f, 0.9255219483046967f, 0.9255401006561353f, + 0.9255582508807327f, 0.9255763989784468f, 0.9255945449492359f, 0.9256126887930585f, + 0.9256308305098727f, 0.9256489700996370f, 0.9256671075623097f, 0.9256852428978489f, + 0.9257033761062131f, 0.9257215071873608f, 0.9257396361412500f, 0.9257577629678392f, + 0.9257758876670867f, 0.9257940102389509f, 0.9258121306833902f, 0.9258302490003628f, + 0.9258483651898273f, 0.9258664792517418f, 0.9258845911860648f, 0.9259027009927547f, + 0.9259208086717701f, 0.9259389142230688f, 0.9259570176466098f, 0.9259751189423512f, + 0.9259932181102515f, 0.9260113151502689f, 0.9260294100623622f, 0.9260475028464895f, + 0.9260655935026093f, 0.9260836820306801f, 0.9261017684306603f, 0.9261198527025082f, + 0.9261379348461826f, 0.9261560148616415f, 0.9261740927488438f, 0.9261921685077474f, + 0.9262102421383113f, 0.9262283136404938f, 0.9262463830142532f, 0.9262644502595482f, + 0.9262825153763372f, 0.9263005783645787f, 0.9263186392242311f, 0.9263366979552530f, + 0.9263547545576029f, 0.9263728090312391f, 0.9263908613761205f, 0.9264089115922053f, + 0.9264269596794521f, 0.9264450056378196f, 0.9264630494672661f, 0.9264810911677501f, + 0.9264991307392305f, 0.9265171681816655f, 0.9265352034950138f, 0.9265532366792338f, + 0.9265712677342842f, 0.9265892966601237f, 0.9266073234567106f, 0.9266253481240035f, + 0.9266433706619612f, 0.9266613910705421f, 0.9266794093497048f, 0.9266974254994081f, + 0.9267154395196103f, 0.9267334514102702f, 0.9267514611713463f, 0.9267694688027973f, + 0.9267874743045817f, 0.9268054776766584f, 0.9268234789189858f, 0.9268414780315225f, + 0.9268594750142272f, 0.9268774698670585f, 0.9268954625899752f, 0.9269134531829358f, + 0.9269314416458991f, 0.9269494279788237f, 0.9269674121816681f, 0.9269853942543912f, + 0.9270033741969517f, 0.9270213520093081f, 0.9270393276914192f, 0.9270573012432436f, + 0.9270752726647401f, 0.9270932419558673f, 0.9271112091165842f, 0.9271291741468490f, + 0.9271471370466209f, 0.9271650978158583f, 0.9271830564545201f, 0.9272010129625651f, + 0.9272189673399518f, 0.9272369195866390f, 0.9272548697025856f, 0.9272728176877503f, + 0.9272907635420917f, 0.9273087072655688f, 0.9273266488581402f, 0.9273445883197646f, + 0.9273625256504011f, 0.9273804608500081f, 0.9273983939185446f, 0.9274163248559695f, + 0.9274342536622413f, 0.9274521803373190f, 0.9274701048811613f, 0.9274880272937270f, + 0.9275059475749752f, 0.9275238657248643f, 0.9275417817433534f, 0.9275596956304013f, + 0.9275776073859667f, 0.9275955170100085f, 0.9276134245024857f, 0.9276313298633569f, + 0.9276492330925812f, 0.9276671341901173f, 0.9276850331559240f, 0.9277029299899603f, + 0.9277208246921852f, 0.9277387172625572f, 0.9277566077010356f, 0.9277744960075790f, + 0.9277923821821463f, 0.9278102662246966f, 0.9278281481351887f, 0.9278460279135814f, + 0.9278639055598338f, 0.9278817810739047f, 0.9278996544557531f, 0.9279175257053378f, + 0.9279353948226179f, 0.9279532618075521f, 0.9279711266600996f, 0.9279889893802192f, + 0.9280068499678700f, 0.9280247084230108f, 0.9280425647456005f, 0.9280604189355983f, + 0.9280782709929631f, 0.9280961209176537f, 0.9281139687096294f, 0.9281318143688487f, + 0.9281496578952712f, 0.9281674992888554f, 0.9281853385495605f, 0.9282031756773454f, + 0.9282210106721694f, 0.9282388435339913f, 0.9282566742627700f, 0.9282745028584649f, + 0.9282923293210346f, 0.9283101536504383f, 0.9283279758466353f, 0.9283457959095842f, + 0.9283636138392444f, 0.9283814296355748f, 0.9283992432985345f, 0.9284170548280826f, + 0.9284348642241780f, 0.9284526714867799f, 0.9284704766158475f, 0.9284882796113396f, + 0.9285060804732155f, 0.9285238792014344f, 0.9285416757959550f, 0.9285594702567368f, + 0.9285772625837388f, 0.9285950527769200f, 0.9286128408362396f, 0.9286306267616568f, + 0.9286484105531305f, 0.9286661922106200f, 0.9286839717340846f, 0.9287017491234830f, + 0.9287195243787748f, 0.9287372974999188f, 0.9287550684868745f, 0.9287728373396008f, + 0.9287906040580570f, 0.9288083686422022f, 0.9288261310919956f, 0.9288438914073963f, + 0.9288616495883637f, 0.9288794056348568f, 0.9288971595468349f, 0.9289149113242571f, + 0.9289326609670828f, 0.9289504084752710f, 0.9289681538487810f, 0.9289858970875721f, + 0.9290036381916034f, 0.9290213771608342f, 0.9290391139952237f, 0.9290568486947310f, + 0.9290745812593159f, 0.9290923116889369f, 0.9291100399835538f, 0.9291277661431256f, + 0.9291454901676117f, 0.9291632120569713f, 0.9291809318111638f, 0.9291986494301482f, + 0.9292163649138839f, 0.9292340782623305f, 0.9292517894754470f, 0.9292694985531925f, + 0.9292872054955268f, 0.9293049103024089f, 0.9293226129737983f, 0.9293403135096540f, + 0.9293580119099355f, 0.9293757081746024f, 0.9293934023036136f, 0.9294110942969286f, + 0.9294287841545068f, 0.9294464718763076f, 0.9294641574622902f, 0.9294818409124140f, + 0.9294995222266386f, 0.9295172014049229f, 0.9295348784472268f, 0.9295525533535093f, + 0.9295702261237299f, 0.9295878967578480f, 0.9296055652558229f, 0.9296232316176143f, + 0.9296408958431813f, 0.9296585579324833f, 0.9296762178854799f, 0.9296938757021305f, + 0.9297115313823944f, 0.9297291849262310f, 0.9297468363335999f, 0.9297644856044605f, + 0.9297821327387722f, 0.9297997777364944f, 0.9298174205975865f, 0.9298350613220082f, + 0.9298526999097187f, 0.9298703363606776f, 0.9298879706748445f, 0.9299056028521786f, + 0.9299232328926396f, 0.9299408607961869f, 0.9299584865627800f, 0.9299761101923784f, + 0.9299937316849415f, 0.9300113510404290f, 0.9300289682588003f, 0.9300465833400149f, + 0.9300641962840324f, 0.9300818070908122f, 0.9300994157603140f, 0.9301170222924972f, + 0.9301346266873214f, 0.9301522289447461f, 0.9301698290647309f, 0.9301874270472354f, + 0.9302050228922191f, 0.9302226165996414f, 0.9302402081694623f, 0.9302577976016410f, + 0.9302753848961371f, 0.9302929700529103f, 0.9303105530719202f, 0.9303281339531265f, + 0.9303457126964885f, 0.9303632893019660f, 0.9303808637695187f, 0.9303984360991059f, + 0.9304160062906875f, 0.9304335743442231f, 0.9304511402596722f, 0.9304687040369946f, + 0.9304862656761498f, 0.9305038251770974f, 0.9305213825397971f, 0.9305389377642087f, + 0.9305564908502918f, 0.9305740417980060f, 0.9305915906073108f, 0.9306091372781662f, + 0.9306266818105318f, 0.9306442242043671f, 0.9306617644596319f, 0.9306793025762859f, + 0.9306968385542889f, 0.9307143723936003f, 0.9307319040941803f, 0.9307494336559881f, + 0.9307669610789837f, 0.9307844863631268f, 0.9308020095083771f, 0.9308195305146942f, + 0.9308370493820382f, 0.9308545661103683f, 0.9308720806996448f, 0.9308895931498271f, + 0.9309071034608750f, 0.9309246116327485f, 0.9309421176654071f, 0.9309596215588106f, + 0.9309771233129189f, 0.9309946229276918f, 0.9310121204030889f, 0.9310296157390702f, + 0.9310471089355952f, 0.9310645999926240f, 0.9310820889101165f, 0.9310995756880320f, + 0.9311170603263308f, 0.9311345428249725f, 0.9311520231839171f, 0.9311695014031243f, + 0.9311869774825537f, 0.9312044514221656f, 0.9312219232219197f, 0.9312393928817756f, + 0.9312568604016934f, 0.9312743257816330f, 0.9312917890215541f, 0.9313092501214166f, + 0.9313267090811804f, 0.9313441659008055f, 0.9313616205802515f, 0.9313790731194787f, + 0.9313965235184466f, 0.9314139717771153f, 0.9314314178954447f, 0.9314488618733947f, + 0.9314663037109251f, 0.9314837434079960f, 0.9315011809645671f, 0.9315186163805986f, + 0.9315360496560503f, 0.9315534807908821f, 0.9315709097850541f, 0.9315883366385259f, + 0.9316057613512578f, 0.9316231839232098f, 0.9316406043543415f, 0.9316580226446131f, + 0.9316754387939846f, 0.9316928528024159f, 0.9317102646698669f, 0.9317276743962980f, + 0.9317450819816687f, 0.9317624874259393f, 0.9317798907290696f, 0.9317972918910197f, + 0.9318146909117497f, 0.9318320877912195f, 0.9318494825293890f, 0.9318668751262187f, + 0.9318842655816681f, 0.9319016538956975f, 0.9319190400682670f, 0.9319364240993364f, + 0.9319538059888659f, 0.9319711857368157f, 0.9319885633431456f, 0.9320059388078158f, + 0.9320233121307865f, 0.9320406833120175f, 0.9320580523514690f, 0.9320754192491012f, + 0.9320927840048741f, 0.9321101466187477f, 0.9321275070906823f, 0.9321448654206377f, + 0.9321622216085744f, 0.9321795756544523f, 0.9321969275582315f, 0.9322142773198723f, + 0.9322316249393345f, 0.9322489704165786f, 0.9322663137515647f, 0.9322836549442526f, + 0.9323009939946026f, 0.9323183309025752f, 0.9323356656681302f, 0.9323529982912279f, + 0.9323703287718285f, 0.9323876571098919f, 0.9324049833053787f, 0.9324223073582487f, + 0.9324396292684624f, 0.9324569490359799f, 0.9324742666607612f, 0.9324915821427667f, + 0.9325088954819567f, 0.9325262066782911f, 0.9325435157317304f, 0.9325608226422348f, + 0.9325781274097644f, 0.9325954300342796f, 0.9326127305157405f, 0.9326300288541073f, + 0.9326473250493403f, 0.9326646191014000f, 0.9326819110102462f, 0.9326992007758397f, + 0.9327164883981403f, 0.9327337738771084f, 0.9327510572127045f, 0.9327683384048885f, + 0.9327856174536210f, 0.9328028943588623f, 0.9328201691205725f, 0.9328374417387120f, + 0.9328547122132412f, 0.9328719805441202f, 0.9328892467313095f, 0.9329065107747694f, + 0.9329237726744601f, 0.9329410324303421f, 0.9329582900423757f, 0.9329755455105212f, + 0.9329927988347388f, 0.9330100500149893f, 0.9330272990512325f, 0.9330445459434291f, + 0.9330617906915394f, 0.9330790332955238f, 0.9330962737553427f, 0.9331135120709563f, + 0.9331307482423251f, 0.9331479822694096f, 0.9331652141521701f, 0.9331824438905670f, + 0.9331996714845607f, 0.9332168969341117f, 0.9332341202391802f, 0.9332513413997269f, + 0.9332685604157120f, 0.9332857772870961f, 0.9333029920138395f, 0.9333202045959027f, + 0.9333374150332462f, 0.9333546233258303f, 0.9333718294736156f, 0.9333890334765625f, + 0.9334062353346315f, 0.9334234350477831f, 0.9334406326159778f, 0.9334578280391759f, + 0.9334750213173379f, 0.9334922124504246f, 0.9335094014383961f, 0.9335265882812132f, + 0.9335437729788362f, 0.9335609555312258f, 0.9335781359383423f, 0.9335953142001464f, + 0.9336124903165985f, 0.9336296642876593f, 0.9336468361132891f, 0.9336640057934487f, + 0.9336811733280984f, 0.9336983387171989f, 0.9337155019607107f, 0.9337326630585945f, + 0.9337498220108106f, 0.9337669788173196f, 0.9337841334780824f, 0.9338012859930593f, + 0.9338184363622110f, 0.9338355845854980f, 0.9338527306628808f, 0.9338698745943202f, + 0.9338870163797769f, 0.9339041560192112f, 0.9339212935125839f, 0.9339384288598555f, + 0.9339555620609867f, 0.9339726931159382f, 0.9339898220246706f, 0.9340069487871444f, + 0.9340240734033205f, 0.9340411958731593f, 0.9340583161966214f, 0.9340754343736678f, + 0.9340925504042589f, 0.9341096642883554f, 0.9341267760259181f, 0.9341438856169075f, + 0.9341609930612844f, 0.9341780983590096f, 0.9341952015100435f, 0.9342123025143471f, + 0.9342294013718808f, 0.9342464980826054f, 0.9342635926464818f, 0.9342806850634706f, + 0.9342977753335325f, 0.9343148634566283f, 0.9343319494327186f, 0.9343490332617641f, + 0.9343661149437259f, 0.9343831944785643f, 0.9344002718662403f, 0.9344173471067146f, + 0.9344344201999480f, 0.9344514911459013f, 0.9344685599445351f, 0.9344856265958105f, + 0.9345026910996879f, 0.9345197534561283f, 0.9345368136650923f, 0.9345538717265410f, + 0.9345709276404350f, 0.9345879814067352f, 0.9346050330254023f, 0.9346220824963972f, + 0.9346391298196808f, 0.9346561749952137f, 0.9346732180229569f, 0.9346902589028712f, + 0.9347072976349174f, 0.9347243342190564f, 0.9347413686552490f, 0.9347584009434562f, + 0.9347754310836387f, 0.9347924590757574f, 0.9348094849197732f, 0.9348265086156469f, + 0.9348435301633395f, 0.9348605495628118f, 0.9348775668140248f, 0.9348945819169392f, + 0.9349115948715161f, 0.9349286056777162f, 0.9349456143355006f, 0.9349626208448302f, + 0.9349796252056658f, 0.9349966274179684f, 0.9350136274816989f, 0.9350306253968182f, + 0.9350476211632874f, 0.9350646147810673f, 0.9350816062501188f, 0.9350985955704031f, + 0.9351155827418809f, 0.9351325677645134f, 0.9351495506382612f, 0.9351665313630856f, + 0.9351835099389476f, 0.9352004863658080f, 0.9352174606436278f, 0.9352344327723682f, + 0.9352514027519898f, 0.9352683705824540f, 0.9352853362637218f, 0.9353022997957539f, + 0.9353192611785115f, 0.9353362204119557f, 0.9353531774960475f, 0.9353701324307477f, + 0.9353870852160178f, 0.9354040358518183f, 0.9354209843381107f, 0.9354379306748558f, + 0.9354548748620146f, 0.9354718168995485f, 0.9354887567874183f, 0.9355056945255850f, + 0.9355226301140099f, 0.9355395635526540f, 0.9355564948414784f, 0.9355734239804442f, + 0.9355903509695124f, 0.9356072758086441f, 0.9356241984978007f, 0.9356411190369428f, + 0.9356580374260320f, 0.9356749536650293f, 0.9356918677538956f, 0.9357087796925923f, + 0.9357256894810804f, 0.9357425971193210f, 0.9357595026072754f, 0.9357764059449046f, + 0.9357933071321699f, 0.9358102061690324f, 0.9358271030554532f, 0.9358439977913935f, + 0.9358608903768146f, 0.9358777808116776f, 0.9358946690959435f, 0.9359115552295739f, + 0.9359284392125297f, 0.9359453210447720f, 0.9359622007262623f, 0.9359790782569617f, + 0.9359959536368313f, 0.9360128268658325f, 0.9360296979439264f, 0.9360465668710745f, + 0.9360634336472375f, 0.9360802982723770f, 0.9360971607464543f, 0.9361140210694305f, + 0.9361308792412669f, 0.9361477352619250f, 0.9361645891313656f, 0.9361814408495501f, + 0.9361982904164401f, 0.9362151378319965f, 0.9362319830961808f, 0.9362488262089543f, + 0.9362656671702783f, 0.9362825059801139f, 0.9362993426384225f, 0.9363161771451656f, + 0.9363330095003043f, 0.9363498397037999f, 0.9363666677556138f, 0.9363834936557075f, + 0.9364003174040421f, 0.9364171390005789f, 0.9364339584452794f, 0.9364507757381050f, + 0.9364675908790169f, 0.9364844038679766f, 0.9365012147049453f, 0.9365180233898844f, + 0.9365348299227555f, 0.9365516343035197f, 0.9365684365321385f, 0.9365852366085734f, + 0.9366020345327856f, 0.9366188303047366f, 0.9366356239243877f, 0.9366524153917004f, + 0.9366692047066362f, 0.9366859918691562f, 0.9367027768792223f, 0.9367195597367957f, + 0.9367363404418376f, 0.9367531189943097f, 0.9367698953941735f, 0.9367866696413903f, + 0.9368034417359216f, 0.9368202116777289f, 0.9368369794667735f, 0.9368537451030170f, + 0.9368705085864210f, 0.9368872699169467f, 0.9369040290945558f, 0.9369207861192097f, + 0.9369375409908699f, 0.9369542937094979f, 0.9369710442750552f, 0.9369877926875032f, + 0.9370045389468037f, 0.9370212830529180f, 0.9370380250058076f, 0.9370547648054341f, + 0.9370715024517592f, 0.9370882379447441f, 0.9371049712843506f, 0.9371217024705401f, + 0.9371384315032741f, 0.9371551583825144f, 0.9371718831082224f, 0.9371886056803598f, + 0.9372053260988880f, 0.9372220443637685f, 0.9372387604749632f, 0.9372554744324334f, + 0.9372721862361409f, 0.9372888958860472f, 0.9373056033821139f, 0.9373223087243026f, + 0.9373390119125750f, 0.9373557129468925f, 0.9373724118272169f, 0.9373891085535099f, + 0.9374058031257329f, 0.9374224955438477f, 0.9374391858078159f, 0.9374558739175992f, + 0.9374725598731593f, 0.9374892436744575f, 0.9375059253214558f, 0.9375226048141159f, + 0.9375392821523992f, 0.9375559573362676f, 0.9375726303656828f, 0.9375893012406064f, + 0.9376059699610000f, 0.9376226365268254f, 0.9376393009380444f, 0.9376559631946184f, + 0.9376726232965095f, 0.9376892812436790f, 0.9377059370360890f, 0.9377225906737011f, + 0.9377392421564770f, 0.9377558914843783f, 0.9377725386573670f, 0.9377891836754046f, + 0.9378058265384531f, 0.9378224672464741f, 0.9378391057994293f, 0.9378557421972807f, + 0.9378723764399899f, 0.9378890085275186f, 0.9379056384598288f, 0.9379222662368820f, + 0.9379388918586402f, 0.9379555153250653f, 0.9379721366361189f, 0.9379887557917628f, + 0.9380053727919588f, 0.9380219876366689f, 0.9380386003258547f, 0.9380552108594783f, + 0.9380718192375012f, 0.9380884254598855f, 0.9381050295265928f, 0.9381216314375852f, + 0.9381382311928244f, 0.9381548287922722f, 0.9381714242358906f, 0.9381880175236414f, + 0.9382046086554865f, 0.9382211976313877f, 0.9382377844513070f, 0.9382543691152061f, + 0.9382709516230471f, 0.9382875319747919f, 0.9383041101704021f, 0.9383206862098398f, + 0.9383372600930669f, 0.9383538318200455f, 0.9383704013907372f, 0.9383869688051041f, + 0.9384035340631081f, 0.9384200971647112f, 0.9384366581098751f, 0.9384532168985620f, + 0.9384697735307338f, 0.9384863280063523f, 0.9385028803253797f, 0.9385194304877779f, + 0.9385359784935086f, 0.9385525243425340f, 0.9385690680348162f, 0.9385856095703170f, + 0.9386021489489983f, 0.9386186861708224f, 0.9386352212357510f, 0.9386517541437464f, + 0.9386682848947702f, 0.9386848134887847f, 0.9387013399257520f, 0.9387178642056339f, + 0.9387343863283925f, 0.9387509062939898f, 0.9387674241023879f, 0.9387839397535489f, + 0.9388004532474348f, 0.9388169645840075f, 0.9388334737632292f, 0.9388499807850621f, + 0.9388664856494681f, 0.9388829883564092f, 0.9388994889058476f, 0.9389159872977453f, + 0.9389324835320646f, 0.9389489776087673f, 0.9389654695278156f, 0.9389819592891717f, + 0.9389984468927975f, 0.9390149323386554f, 0.9390314156267074f, 0.9390478967569155f, + 0.9390643757292420f, 0.9390808525436489f, 0.9390973272000983f, 0.9391137996985525f, + 0.9391302700389736f, 0.9391467382213238f, 0.9391632042455650f, 0.9391796681116598f, + 0.9391961298195699f, 0.9392125893692577f, 0.9392290467606854f, 0.9392455019938152f, + 0.9392619550686092f, 0.9392784059850297f, 0.9392948547430386f, 0.9393113013425985f, + 0.9393277457836714f, 0.9393441880662194f, 0.9393606281902052f, 0.9393770661555904f, + 0.9393935019623375f, 0.9394099356104089f, 0.9394263670997665f, 0.9394427964303728f, + 0.9394592236021899f, 0.9394756486151802f, 0.9394920714693058f, 0.9395084921645290f, + 0.9395249107008121f, 0.9395413270781175f, 0.9395577412964072f, 0.9395741533556436f, + 0.9395905632557893f, 0.9396069709968060f, 0.9396233765786564f, 0.9396397800013027f, + 0.9396561812647071f, 0.9396725803688321f, 0.9396889773136400f, 0.9397053720990929f, + 0.9397217647251533f, 0.9397381551917836f, 0.9397545434989459f, 0.9397709296466028f, + 0.9397873136347166f, 0.9398036954632494f, 0.9398200751321638f, 0.9398364526414221f, + 0.9398528279909867f, 0.9398692011808200f, 0.9398855722108841f, 0.9399019410811417f, + 0.9399183077915551f, 0.9399346723420865f, 0.9399510347326986f, 0.9399673949633536f, + 0.9399837530340139f, 0.9400001089446421f, 0.9400164626952004f, 0.9400328142856514f, + 0.9400491637159574f, 0.9400655109860808f, 0.9400818560959842f, 0.9400981990456299f, + 0.9401145398349803f, 0.9401308784639979f, 0.9401472149326453f, 0.9401635492408847f, + 0.9401798813886788f, 0.9401962113759901f, 0.9402125392027808f, 0.9402288648690136f, + 0.9402451883746509f, 0.9402615097196552f, 0.9402778289039889f, 0.9402941459276147f, + 0.9403104607904951f, 0.9403267734925923f, 0.9403430840338692f, 0.9403593924142881f, + 0.9403756986338115f, 0.9403920026924021f, 0.9404083045900222f, 0.9404246043266347f, + 0.9404409019022018f, 0.9404571973166861f, 0.9404734905700503f, 0.9404897816622568f, + 0.9405060705932683f, 0.9405223573630473f, 0.9405386419715565f, 0.9405549244187582f, + 0.9405712047046152f, 0.9405874828290900f, 0.9406037587921453f, 0.9406200325937436f, + 0.9406363042338476f, 0.9406525737124197f, 0.9406688410294228f, 0.9406851061848193f, + 0.9407013691785719f, 0.9407176300106433f, 0.9407338886809959f, 0.9407501451895928f, + 0.9407663995363961f, 0.9407826517213687f, 0.9407989017444733f, 0.9408151496056725f, + 0.9408313953049289f, 0.9408476388422053f, 0.9408638802174643f, 0.9408801194306685f, + 0.9408963564817808f, 0.9409125913707637f, 0.9409288240975799f, 0.9409450546621922f, + 0.9409612830645633f, 0.9409775093046558f, 0.9409937333824325f, 0.9410099552978560f, + 0.9410261750508893f, 0.9410423926414948f, 0.9410586080696354f, 0.9410748213352739f, + 0.9410910324383728f, 0.9411072413788950f, 0.9411234481568034f, 0.9411396527720605f, + 0.9411558552246292f, 0.9411720555144722f, 0.9411882536415523f, 0.9412044496058324f, + 0.9412206434072752f, 0.9412368350458433f, 0.9412530245214998f, 0.9412692118342073f, + 0.9412853969839287f, 0.9413015799706267f, 0.9413177607942642f, 0.9413339394548039f, + 0.9413501159522090f, 0.9413662902864417f, 0.9413824624574654f, 0.9413986324652426f, + 0.9414148003097362f, 0.9414309659909093f, 0.9414471295087244f, 0.9414632908631445f, + 0.9414794500541326f, 0.9414956070816514f, 0.9415117619456637f, 0.9415279146461326f, + 0.9415440651830208f, 0.9415602135562913f, 0.9415763597659069f, 0.9415925038118306f, + 0.9416086456940251f, 0.9416247854124536f, 0.9416409229670789f, 0.9416570583578638f, + 0.9416731915847714f, 0.9416893226477644f, 0.9417054515468060f, 0.9417215782818589f, + 0.9417377028528862f, 0.9417538252598507f, 0.9417699455027155f, 0.9417860635814435f, + 0.9418021794959976f, 0.9418182932463409f, 0.9418344048324363f, 0.9418505142542468f, + 0.9418666215117353f, 0.9418827266048647f, 0.9418988295335984f, 0.9419149302978990f, + 0.9419310288977295f, 0.9419471253330532f, 0.9419632196038329f, 0.9419793117100317f, + 0.9419954016516126f, 0.9420114894285385f, 0.9420275750407725f, 0.9420436584882779f, + 0.9420597397710173f, 0.9420758188889541f, 0.9420918958420512f, 0.9421079706302716f, + 0.9421240432535786f, 0.9421401137119348f, 0.9421561820053038f, 0.9421722481336484f, + 0.9421883120969318f, 0.9422043738951168f, 0.9422204335281670f, 0.9422364909960449f, + 0.9422525462987140f, 0.9422685994361374f, 0.9422846504082780f, 0.9423006992150991f, + 0.9423167458565638f, 0.9423327903326351f, 0.9423488326432762f, 0.9423648727884503f, + 0.9423809107681205f, 0.9423969465822498f, 0.9424129802308016f, 0.9424290117137388f, + 0.9424450410310249f, 0.9424610681826228f, 0.9424770931684956f, 0.9424931159886067f, + 0.9425091366429192f, 0.9425251551313962f, 0.9425411714540012f, 0.9425571856106969f, + 0.9425731976014469f, 0.9425892074262142f, 0.9426052150849621f, 0.9426212205776537f, + 0.9426372239042525f, 0.9426532250647214f, 0.9426692240590239f, 0.9426852208871229f, + 0.9427012155489819f, 0.9427172080445642f, 0.9427331983738328f, 0.9427491865367512f, + 0.9427651725332825f, 0.9427811563633901f, 0.9427971380270370f, 0.9428131175241868f, + 0.9428290948548027f, 0.9428450700188478f, 0.9428610430162856f, 0.9428770138470793f, + 0.9428929825111921f, 0.9429089490085876f, 0.9429249133392288f, 0.9429408755030793f, + 0.9429568355001021f, 0.9429727933302607f, 0.9429887489935185f, 0.9430047024898387f, + 0.9430206538191847f, 0.9430366029815198f, 0.9430525499768073f, 0.9430684948050108f, + 0.9430844374660935f, 0.9431003779600187f, 0.9431163162867497f, 0.9431322524462503f, + 0.9431481864384834f, 0.9431641182634126f, 0.9431800479210013f, 0.9431959754112128f, + 0.9432119007340106f, 0.9432278238893581f, 0.9432437448772186f, 0.9432596636975557f, + 0.9432755803503325f, 0.9432914948355127f, 0.9433074071530597f, 0.9433233173029369f, + 0.9433392252851077f, 0.9433551310995356f, 0.9433710347461840f, 0.9433869362250163f, + 0.9434028355359962f, 0.9434187326790869f, 0.9434346276542520f, 0.9434505204614551f, + 0.9434664111006593f, 0.9434822995718284f, 0.9434981858749258f, 0.9435140700099149f, + 0.9435299519767595f, 0.9435458317754227f, 0.9435617094058683f, 0.9435775848680596f, + 0.9435934581619604f, 0.9436093292875339f, 0.9436251982447439f, 0.9436410650335538f, + 0.9436569296539271f, 0.9436727921058276f, 0.9436886523892185f, 0.9437045105040635f, + 0.9437203664503262f, 0.9437362202279701f, 0.9437520718369589f, 0.9437679212772561f, + 0.9437837685488251f, 0.9437996136516298f, 0.9438154565856335f, 0.9438312973507998f, + 0.9438471359470927f, 0.9438629723744754f, 0.9438788066329116f, 0.9438946387223650f, + 0.9439104686427991f, 0.9439262963941777f, 0.9439421219764643f, 0.9439579453896225f, + 0.9439737666336160f, 0.9439895857084084f, 0.9440054026139634f, 0.9440212173502446f, + 0.9440370299172158f, 0.9440528403148405f, 0.9440686485430825f, 0.9440844546019053f, + 0.9441002584912727f, 0.9441160602111484f, 0.9441318597614959f, 0.9441476571422792f, + 0.9441634523534618f, 0.9441792453950074f, 0.9441950362668798f, 0.9442108249690427f, + 0.9442266115014598f, 0.9442423958640948f, 0.9442581780569114f, 0.9442739580798734f, + 0.9442897359329444f, 0.9443055116160883f, 0.9443212851292688f, 0.9443370564724498f, + 0.9443528256455948f, 0.9443685926486677f, 0.9443843574816322f, 0.9444001201444521f, + 0.9444158806370913f, 0.9444316389595134f, 0.9444473951116823f, 0.9444631490935617f, + 0.9444789009051155f, 0.9444946505463074f, 0.9445103980171013f, 0.9445261433174611f, + 0.9445418864473504f, 0.9445576274067331f, 0.9445733661955732f, 0.9445891028138342f, + 0.9446048372614803f, 0.9446205695384751f, 0.9446362996447824f, 0.9446520275803663f, + 0.9446677533451905f, 0.9446834769392188f, 0.9446991983624152f, 0.9447149176147436f, + 0.9447306346961678f, 0.9447463496066517f, 0.9447620623461591f, 0.9447777729146539f, + 0.9447934813121003f, 0.9448091875384618f, 0.9448248915937025f, 0.9448405934777864f, + 0.9448562931906772f, 0.9448719907323390f, 0.9448876861027357f, 0.9449033793018310f, + 0.9449190703295892f, 0.9449347591859740f, 0.9449504458709495f, 0.9449661303844796f, + 0.9449818127265281f, 0.9449974928970591f, 0.9450131708960368f, 0.9450288467234247f, + 0.9450445203791871f, 0.9450601918632879f, 0.9450758611756911f, 0.9450915283163606f, + 0.9451071932852606f, 0.9451228560823549f, 0.9451385167076075f, 0.9451541751609827f, + 0.9451698314424442f, 0.9451854855519561f, 0.9452011374894825f, 0.9452167872549875f, + 0.9452324348484350f, 0.9452480802697890f, 0.9452637235190137f, 0.9452793645960731f, + 0.9452950035009311f, 0.9453106402335520f, 0.9453262747938999f, 0.9453419071819386f, + 0.9453575373976323f, 0.9453731654409451f, 0.9453887913118411f, 0.9454044150102844f, + 0.9454200365362391f, 0.9454356558896693f, 0.9454512730705391f, 0.9454668880788125f, + 0.9454825009144537f, 0.9454981115774270f, 0.9455137200676963f, 0.9455293263852258f, + 0.9455449305299797f, 0.9455605325019220f, 0.9455761323010169f, 0.9455917299272286f, + 0.9456073253805213f, 0.9456229186608590f, 0.9456385097682062f, 0.9456540987025266f, + 0.9456696854637847f, 0.9456852700519447f, 0.9457008524669706f, 0.9457164327088267f, + 0.9457320107774772f, 0.9457475866728862f, 0.9457631603950181f, 0.9457787319438369f, + 0.9457943013193069f, 0.9458098685213925f, 0.9458254335500575f, 0.9458409964052666f, + 0.9458565570869839f, 0.9458721155951735f, 0.9458876719297997f, 0.9459032260908269f, + 0.9459187780782191f, 0.9459343278919407f, 0.9459498755319561f, 0.9459654209982293f, + 0.9459809642907249f, 0.9459965054094067f, 0.9460120443542395f, 0.9460275811251874f, + 0.9460431157222146f, 0.9460586481452855f, 0.9460741783943645f, 0.9460897064694156f, + 0.9461052323704033f, 0.9461207560972922f, 0.9461362776500462f, 0.9461517970286297f, + 0.9461673142330074f, 0.9461828292631431f, 0.9461983421190016f, 0.9462138528005470f, + 0.9462293613077438f, 0.9462448676405564f, 0.9462603717989488f, 0.9462758737828858f, + 0.9462913735923316f, 0.9463068712272505f, 0.9463223666876071f, 0.9463378599733657f, + 0.9463533510844906f, 0.9463688400209462f, 0.9463843267826971f, 0.9463998113697076f, + 0.9464152937819421f, 0.9464307740193650f, 0.9464462520819408f, 0.9464617279696338f, + 0.9464772016824087f, 0.9464926732202297f, 0.9465081425830613f, 0.9465236097708679f, + 0.9465390747836141f, 0.9465545376212644f, 0.9465699982837830f, 0.9465854567711346f, + 0.9466009130832836f, 0.9466163672201945f, 0.9466318191818317f, 0.9466472689681599f, + 0.9466627165791434f, 0.9466781620147467f, 0.9466936052749345f, 0.9467090463596711f, + 0.9467244852689212f, 0.9467399220026492f, 0.9467553565608197f, 0.9467707889433971f, + 0.9467862191503460f, 0.9468016471816311f, 0.9468170730372167f, 0.9468324967170675f, + 0.9468479182211480f, 0.9468633375494229f, 0.9468787547018566f, 0.9468941696784136f, + 0.9469095824790588f, 0.9469249931037564f, 0.9469404015524713f, 0.9469558078251680f, + 0.9469712119218109f, 0.9469866138423648f, 0.9470020135867944f, 0.9470174111550641f, + 0.9470328065471386f, 0.9470481997629826f, 0.9470635908025605f, 0.9470789796658372f, + 0.9470943663527772f, 0.9471097508633451f, 0.9471251331975058f, 0.9471405133552235f, + 0.9471558913364633f, 0.9471712671411897f, 0.9471866407693672f, 0.9472020122209607f, + 0.9472173814959348f, 0.9472327485942542f, 0.9472481135158834f, 0.9472634762607876f, + 0.9472788368289309f, 0.9472941952202782f, 0.9473095514347945f, 0.9473249054724442f, + 0.9473402573331920f, 0.9473556070170028f, 0.9473709545238412f, 0.9473862998536721f, + 0.9474016430064599f, 0.9474169839821697f, 0.9474323227807662f, 0.9474476594022139f, + 0.9474629938464777f, 0.9474783261135225f, 0.9474936562033128f, 0.9475089841158135f, + 0.9475243098509896f, 0.9475396334088055f, 0.9475549547892262f, 0.9475702739922165f, + 0.9475855910177411f, 0.9476009058657650f, 0.9476162185362527f, 0.9476315290291691f, + 0.9476468373444793f, 0.9476621434821478f, 0.9476774474421396f, 0.9476927492244194f, + 0.9477080488289521f, 0.9477233462557026f, 0.9477386415046358f, 0.9477539345757163f, + 0.9477692254689092f, 0.9477845141841792f, 0.9477998007214913f, 0.9478150850808102f, + 0.9478303672621010f, 0.9478456472653285f, 0.9478609250904575f, 0.9478762007374529f, + 0.9478914742062797f, 0.9479067454969029f, 0.9479220146092870f, 0.9479372815433973f, + 0.9479525462991987f, 0.9479678088766559f, 0.9479830692757338f, 0.9479983274963977f, + 0.9480135835386122f, 0.9480288374023423f, 0.9480440890875531f, 0.9480593385942094f, + 0.9480745859222762f, 0.9480898310717185f, 0.9481050740425012f, 0.9481203148345894f, + 0.9481355534479480f, 0.9481507898825418f, 0.9481660241383361f, 0.9481812562152957f, + 0.9481964861133856f, 0.9482117138325710f, 0.9482269393728165f, 0.9482421627340876f, + 0.9482573839163491f, 0.9482726029195658f, 0.9482878197437031f, 0.9483030343887259f, + 0.9483182468545991f, 0.9483334571412879f, 0.9483486652487574f, 0.9483638711769724f, + 0.9483790749258981f, 0.9483942764954997f, 0.9484094758857420f, 0.9484246730965903f, + 0.9484398681280096f, 0.9484550609799649f, 0.9484702516524214f, 0.9484854401453442f, + 0.9485006264586983f, 0.9485158105924488f, 0.9485309925465609f, 0.9485461723209997f, + 0.9485613499157303f, 0.9485765253307178f, 0.9485916985659273f, 0.9486068696213240f, + 0.9486220384968730f, 0.9486372051925395f, 0.9486523697082886f, 0.9486675320440854f, + 0.9486826921998951f, 0.9486978501756830f, 0.9487130059714139f, 0.9487281595870535f, + 0.9487433110225665f, 0.9487584602779183f, 0.9487736073530741f, 0.9487887522479991f, + 0.9488038949626584f, 0.9488190354970173f, 0.9488341738510410f, 0.9488493100246945f, + 0.9488644440179433f, 0.9488795758307526f, 0.9488947054630874f, 0.9489098329149133f, + 0.9489249581861952f, 0.9489400812768984f, 0.9489552021869883f, 0.9489703209164299f, + 0.9489854374651888f, 0.9490005518332300f, 0.9490156640205187f, 0.9490307740270206f, + 0.9490458818527006f, 0.9490609874975240f, 0.9490760909614563f, 0.9490911922444626f, + 0.9491062913465083f, 0.9491213882675587f, 0.9491364830075789f, 0.9491515755665345f, + 0.9491666659443907f, 0.9491817541411128f, 0.9491968401566663f, 0.9492119239910163f, + 0.9492270056441282f, 0.9492420851159674f, 0.9492571624064992f, 0.9492722375156889f, + 0.9492873104435021f, 0.9493023811899038f, 0.9493174497548598f, 0.9493325161383350f, + 0.9493475803402952f, 0.9493626423607054f, 0.9493777021995314f, 0.9493927598567382f, + 0.9494078153322915f, 0.9494228686261565f, 0.9494379197382988f, 0.9494529686686836f, + 0.9494680154172765f, 0.9494830599840428f, 0.9494981023689479f, 0.9495131425719574f, + 0.9495281805930367f, 0.9495432164321511f, 0.9495582500892661f, 0.9495732815643473f, + 0.9495883108573600f, 0.9496033379682697f, 0.9496183628970418f, 0.9496333856436420f, + 0.9496484062080355f, 0.9496634245901879f, 0.9496784407900649f, 0.9496934548076317f, + 0.9497084666428538f, 0.9497234762956970f, 0.9497384837661264f, 0.9497534890541078f, + 0.9497684921596067f, 0.9497834930825885f, 0.9497984918230188f, 0.9498134883808631f, + 0.9498284827560870f, 0.9498434749486561f, 0.9498584649585358f, 0.9498734527856916f, + 0.9498884384300893f, 0.9499034218916943f, 0.9499184031704722f, 0.9499333822663886f, + 0.9499483591794090f, 0.9499633339094991f, 0.9499783064566244f, 0.9499932768207504f, + 0.9500082450018430f, 0.9500232109998676f, 0.9500381748147898f, 0.9500531364465753f, + 0.9500680958951896f, 0.9500830531605984f, 0.9500980082427674f, 0.9501129611416620f, + 0.9501279118572481f, 0.9501428603894913f, 0.9501578067383570f, 0.9501727509038111f, + 0.9501876928858193f, 0.9502026326843471f, 0.9502175702993603f, 0.9502325057308244f, + 0.9502474389787052f, 0.9502623700429685f, 0.9502772989235797f, 0.9502922256205047f, + 0.9503071501337093f, 0.9503220724631589f, 0.9503369926088193f, 0.9503519105706565f, + 0.9503668263486358f, 0.9503817399427232f, 0.9503966513528844f, 0.9504115605790850f, + 0.9504264676212909f, 0.9504413724794678f, 0.9504562751535813f, 0.9504711756435974f, + 0.9504860739494817f, 0.9505009700712000f, 0.9505158640087181f, 0.9505307557620016f, + 0.9505456453310166f, 0.9505605327157287f, 0.9505754179161036f, 0.9505903009321072f, + 0.9506051817637053f, 0.9506200604108638f, 0.9506349368735483f, 0.9506498111517248f, + 0.9506646832453589f, 0.9506795531544167f, 0.9506944208788638f, 0.9507092864186661f, + 0.9507241497737896f, 0.9507390109442000f, 0.9507538699298631f, 0.9507687267307449f, + 0.9507835813468111f, 0.9507984337780276f, 0.9508132840243605f, 0.9508281320857753f, + 0.9508429779622382f, 0.9508578216537149f, 0.9508726631601713f, 0.9508875024815734f, + 0.9509023396178871f, 0.9509171745690781f, 0.9509320073351125f, 0.9509468379159562f, + 0.9509616663115751f, 0.9509764925219351f, 0.9509913165470021f, 0.9510061383867421f, + 0.9510209580411211f, 0.9510357755101049f, 0.9510505907936595f, 0.9510654038917510f, + 0.9510802148043450f, 0.9510950235314078f, 0.9511098300729054f, 0.9511246344288035f, + 0.9511394365990682f, 0.9511542365836656f, 0.9511690343825615f, 0.9511838299957220f, + 0.9511986234231132f, 0.9512134146647010f, 0.9512282037204514f, 0.9512429905903304f, + 0.9512577752743040f, 0.9512725577723382f, 0.9512873380843994f, 0.9513021162104530f, + 0.9513168921504656f, 0.9513316659044029f, 0.9513464374722311f, 0.9513612068539163f, + 0.9513759740494244f, 0.9513907390587216f, 0.9514055018817740f, 0.9514202625185475f, + 0.9514350209690083f, 0.9514497772331226f, 0.9514645313108562f, 0.9514792832021755f, + 0.9514940329070464f, 0.9515087804254350f, 0.9515235257573075f, 0.9515382689026299f, + 0.9515530098613686f, 0.9515677486334895f, 0.9515824852189587f, 0.9515972196177425f, + 0.9516119518298068f, 0.9516266818551180f, 0.9516414096936421f, 0.9516561353453453f, + 0.9516708588101939f, 0.9516855800881537f, 0.9517002991791913f, 0.9517150160832726f, + 0.9517297308003637f, 0.9517444433304312f, 0.9517591536734409f, 0.9517738618293591f, + 0.9517885677981521f, 0.9518032715797861f, 0.9518179731742272f, 0.9518326725814417f, + 0.9518473698013956f, 0.9518620648340556f, 0.9518767576793874f, 0.9518914483373576f, + 0.9519061368079323f, 0.9519208230910778f, 0.9519355071867602f, 0.9519501890949461f, + 0.9519648688156014f, 0.9519795463486925f, 0.9519942216941858f, 0.9520088948520473f, + 0.9520235658222436f, 0.9520382346047407f, 0.9520529011995050f, 0.9520675656065030f, + 0.9520822278257006f, 0.9520968878570645f, 0.9521115457005608f, 0.9521262013561558f, + 0.9521408548238158f, 0.9521555061035074f, 0.9521701551951965f, 0.9521848020988498f, + 0.9521994468144336f, 0.9522140893419140f, 0.9522287296812576f, 0.9522433678324307f, + 0.9522580037953996f, 0.9522726375701306f, 0.9522872691565903f, 0.9523018985547449f, + 0.9523165257645608f, 0.9523311507860046f, 0.9523457736190424f, 0.9523603942636407f, + 0.9523750127197659f, 0.9523896289873843f, 0.9524042430664627f, 0.9524188549569671f, + 0.9524334646588640f, 0.9524480721721200f, 0.9524626774967014f, 0.9524772806325748f, + 0.9524918815797063f, 0.9525064803380627f, 0.9525210769076102f, 0.9525356712883155f, + 0.9525502634801449f, 0.9525648534830649f, 0.9525794412970420f, 0.9525940269220426f, + 0.9526086103580333f, 0.9526231916049804f, 0.9526377706628507f, 0.9526523475316104f, + 0.9526669222112262f, 0.9526814947016644f, 0.9526960650028917f, 0.9527106331148746f, + 0.9527251990375796f, 0.9527397627709732f, 0.9527543243150218f, 0.9527688836696923f, + 0.9527834408349509f, 0.9527979958107643f, 0.9528125485970990f, 0.9528270991939216f, + 0.9528416476011987f, 0.9528561938188967f, 0.9528707378469824f, 0.9528852796854222f, + 0.9528998193341829f, 0.9529143567932308f, 0.9529288920625326f, 0.9529434251420551f, + 0.9529579560317647f, 0.9529724847316280f, 0.9529870112416117f, 0.9530015355616822f, + 0.9530160576918065f, 0.9530305776319510f, 0.9530450953820824f, 0.9530596109421672f, + 0.9530741243121722f, 0.9530886354920640f, 0.9531031444818093f, 0.9531176512813747f, + 0.9531321558907268f, 0.9531466583098325f, 0.9531611585386581f, 0.9531756565771706f, + 0.9531901524253367f, 0.9532046460831228f, 0.9532191375504958f, 0.9532336268274225f, + 0.9532481139138693f, 0.9532625988098031f, 0.9532770815151907f, 0.9532915620299988f, + 0.9533060403541938f, 0.9533205164877429f, 0.9533349904306124f, 0.9533494621827693f, + 0.9533639317441803f, 0.9533783991148121f, 0.9533928642946317f, 0.9534073272836054f, + 0.9534217880817003f, 0.9534362466888832f, 0.9534507031051206f, 0.9534651573303795f, + 0.9534796093646266f, 0.9534940592078288f, 0.9535085068599527f, 0.9535229523209653f, + 0.9535373955908333f, 0.9535518366695235f, 0.9535662755570028f, 0.9535807122532379f, + 0.9535951467581957f, 0.9536095790718431f, 0.9536240091941467f, 0.9536384371250736f, + 0.9536528628645905f, 0.9536672864126643f, 0.9536817077692619f, 0.9536961269343500f, + 0.9537105439078956f, 0.9537249586898656f, 0.9537393712802268f, 0.9537537816789460f, + 0.9537681898859903f, 0.9537825959013264f, 0.9537969997249214f, 0.9538114013567419f, + 0.9538258007967551f, 0.9538401980449277f, 0.9538545931012268f, 0.9538689859656191f, + 0.9538833766380718f, 0.9538977651185516f, 0.9539121514070255f, 0.9539265355034605f, + 0.9539409174078235f, 0.9539552971200813f, 0.9539696746402012f, 0.9539840499681499f, + 0.9539984231038945f, 0.9540127940474019f, 0.9540271627986391f, 0.9540415293575729f, + 0.9540558937241707f, 0.9540702558983991f, 0.9540846158802252f, 0.9540989736696162f, + 0.9541133292665388f, 0.9541276826709603f, 0.9541420338828475f, 0.9541563829021674f, + 0.9541707297288873f, 0.9541850743629740f, 0.9541994168043946f, 0.9542137570531162f, + 0.9542280951091057f, 0.9542424309723302f, 0.9542567646427569f, 0.9542710961203527f, + 0.9542854254050847f, 0.9542997524969200f, 0.9543140773958256f, 0.9543284001017688f, + 0.9543427206147165f, 0.9543570389346357f, 0.9543713550614938f, 0.9543856689952577f, + 0.9543999807358945f, 0.9544142902833714f, 0.9544285976376554f, 0.9544429027987138f, + 0.9544572057665136f, 0.9544715065410219f, 0.9544858051222058f, 0.9545001015100327f, + 0.9545143957044695f, 0.9545286877054834f, 0.9545429775130417f, 0.9545572651271114f, + 0.9545715505476596f, 0.9545858337746538f, 0.9546001148080608f, 0.9546143936478481f, + 0.9546286702939827f, 0.9546429447464317f, 0.9546572170051627f, 0.9546714870701424f, + 0.9546857549413383f, 0.9547000206187177f, 0.9547142841022476f, 0.9547285453918951f, + 0.9547428044876279f, 0.9547570613894129f, 0.9547713160972173f, 0.9547855686110085f, + 0.9547998189307537f, 0.9548140670564201f, 0.9548283129879751f, 0.9548425567253858f, + 0.9548567982686196f, 0.9548710376176436f, 0.9548852747724252f, 0.9548995097329318f, + 0.9549137424991305f, 0.9549279730709886f, 0.9549422014484735f, 0.9549564276315525f, + 0.9549706516201928f, 0.9549848734143618f, 0.9549990930140269f, 0.9550133104191552f, + 0.9550275256297142f, 0.9550417386456711f, 0.9550559494669933f, 0.9550701580936484f, + 0.9550843645256034f, 0.9550985687628257f, 0.9551127708052829f, 0.9551269706529421f, + 0.9551411683057708f, 0.9551553637637362f, 0.9551695570268059f, 0.9551837480949473f, + 0.9551979369681277f, 0.9552121236463144f, 0.9552263081294750f, 0.9552404904175766f, + 0.9552546705105870f, 0.9552688484084734f, 0.9552830241112031f, 0.9552971976187438f, + 0.9553113689310627f, 0.9553255380481274f, 0.9553397049699053f, 0.9553538696963638f, + 0.9553680322274702f, 0.9553821925631925f, 0.9553963507034974f, 0.9554105066483529f, + 0.9554246603977263f, 0.9554388119515852f, 0.9554529613098968f, 0.9554671084726289f, + 0.9554812534397488f, 0.9554953962112240f, 0.9555095367870221f, 0.9555236751671106f, + 0.9555378113514568f, 0.9555519453400285f, 0.9555660771327931f, 0.9555802067297181f, + 0.9555943341307711f, 0.9556084593359195f, 0.9556225823451311f, 0.9556367031583731f, + 0.9556508217756132f, 0.9556649381968192f, 0.9556790524219583f, 0.9556931644509983f, + 0.9557072742839066f, 0.9557213819206509f, 0.9557354873611987f, 0.9557495906055177f, + 0.9557636916535754f, 0.9557777905053394f, 0.9557918871607773f, 0.9558059816198567f, + 0.9558200738825454f, 0.9558341639488107f, 0.9558482518186204f, 0.9558623374919422f, + 0.9558764209687436f, 0.9558905022489922f, 0.9559045813326558f, 0.9559186582197019f, + 0.9559327329100982f, 0.9559468054038125f, 0.9559608757008121f, 0.9559749438010651f, + 0.9559890097045389f, 0.9560030734112013f, 0.9560171349210198f, 0.9560311942339623f, + 0.9560452513499964f, 0.9560593062690899f, 0.9560733589912103f, 0.9560874095163254f, + 0.9561014578444030f, 0.9561155039754108f, 0.9561295479093164f, 0.9561435896460876f, + 0.9561576291856921f, 0.9561716665280977f, 0.9561857016732722f, 0.9561997346211831f, + 0.9562137653717985f, 0.9562277939250858f, 0.9562418202810130f, 0.9562558444395478f, + 0.9562698664006581f, 0.9562838861643114f, 0.9562979037304757f, 0.9563119190991187f, + 0.9563259322702082f, 0.9563399432437121f, 0.9563539520195982f, 0.9563679585978340f, + 0.9563819629783877f, 0.9563959651612269f, 0.9564099651463195f, 0.9564239629336334f, + 0.9564379585231362f, 0.9564519519147959f, 0.9564659431085805f, 0.9564799321044576f, + 0.9564939189023950f, 0.9565079035023609f, 0.9565218859043229f, 0.9565358661082488f, + 0.9565498441141068f, 0.9565638199218645f, 0.9565777935314898f, 0.9565917649429507f, + 0.9566057341562151f, 0.9566197011712507f, 0.9566336659880257f, 0.9566476286065078f, + 0.9566615890266651f, 0.9566755472484653f, 0.9566895032718763f, 0.9567034570968663f, + 0.9567174087234031f, 0.9567313581514546f, 0.9567453053809888f, 0.9567592504119735f, + 0.9567731932443769f, 0.9567871338781668f, 0.9568010723133112f, 0.9568150085497781f, + 0.9568289425875354f, 0.9568428744265511f, 0.9568568040667934f, 0.9568707315082299f, + 0.9568846567508289f, 0.9568985797945583f, 0.9569125006393860f, 0.9569264192852802f, + 0.9569403357322089f, 0.9569542499801399f, 0.9569681620290414f, 0.9569820718788816f, + 0.9569959795296282f, 0.9570098849812494f, 0.9570237882337133f, 0.9570376892869877f, + 0.9570515881410410f, 0.9570654847958411f, 0.9570793792513560f, 0.9570932715075539f, + 0.9571071615644028f, 0.9571210494218707f, 0.9571349350799260f, 0.9571488185385364f, + 0.9571626997976701f, 0.9571765788572955f, 0.9571904557173803f, 0.9572043303778928f, + 0.9572182028388012f, 0.9572320731000735f, 0.9572459411616778f, 0.9572598070235824f, + 0.9572736706857552f, 0.9572875321481645f, 0.9573013914107785f, 0.9573152484735652f, + 0.9573291033364928f, 0.9573429559995296f, 0.9573568064626435f, 0.9573706547258030f, + 0.9573845007889759f, 0.9573983446521307f, 0.9574121863152355f, 0.9574260257782584f, + 0.9574398630411676f, 0.9574536981039315f, 0.9574675309665182f, 0.9574813616288957f, + 0.9574951900910326f, 0.9575090163528968f, 0.9575228404144567f, 0.9575366622756806f, + 0.9575504819365365f, 0.9575642993969927f, 0.9575781146570176f, 0.9575919277165794f, + 0.9576057385756463f, 0.9576195472341866f, 0.9576333536921685f, 0.9576471579495605f, + 0.9576609600063306f, 0.9576747598624472f, 0.9576885575178786f, 0.9577023529725931f, + 0.9577161462265589f, 0.9577299372797444f, 0.9577437261321180f, 0.9577575127836477f, + 0.9577712972343023f, 0.9577850794840497f, 0.9577988595328584f, 0.9578126373806967f, + 0.9578264130275329f, 0.9578401864733355f, 0.9578539577180726f, 0.9578677267617127f, + 0.9578814936042244f, 0.9578952582455756f, 0.9579090206857349f, 0.9579227809246708f, + 0.9579365389623514f, 0.9579502947987454f, 0.9579640484338209f, 0.9579777998675464f, + 0.9579915490998904f, 0.9580052961308212f, 0.9580190409603071f, 0.9580327835883168f, + 0.9580465240148186f, 0.9580602622397807f, 0.9580739982631720f, 0.9580877320849603f, + 0.9581014637051146f, 0.9581151931236033f, 0.9581289203403944f, 0.9581426453554568f, + 0.9581563681687588f, 0.9581700887802689f, 0.9581838071899554f, 0.9581975233977872f, + 0.9582112374037323f, 0.9582249492077594f, 0.9582386588098371f, 0.9582523662099336f, + 0.9582660714080177f, 0.9582797744040578f, 0.9582934751980222f, 0.9583071737898798f, + 0.9583208701795989f, 0.9583345643671480f, 0.9583482563524958f, 0.9583619461356107f, + 0.9583756337164612f, 0.9583893190950159f, 0.9584030022712434f, 0.9584166832451122f, + 0.9584303620165910f, 0.9584440385856482f, 0.9584577129522523f, 0.9584713851163722f, + 0.9584850550779761f, 0.9584987228370329f, 0.9585123883935111f, 0.9585260517473790f, + 0.9585397128986057f, 0.9585533718471596f, 0.9585670285930091f, 0.9585806831361232f, + 0.9585943354764702f, 0.9586079856140188f, 0.9586216335487379f, 0.9586352792805957f, + 0.9586489228095610f, 0.9586625641356028f, 0.9586762032586893f, 0.9586898401787893f, + 0.9587034748958716f, 0.9587171074099047f, 0.9587307377208573f, 0.9587443658286980f, + 0.9587579917333957f, 0.9587716154349190f, 0.9587852369332366f, 0.9587988562283171f, + 0.9588124733201293f, 0.9588260882086419f, 0.9588397008938235f, 0.9588533113756430f, + 0.9588669196540690f, 0.9588805257290703f, 0.9588941296006156f, 0.9589077312686737f, + 0.9589213307332131f, 0.9589349279942029f, 0.9589485230516116f, 0.9589621159054080f, + 0.9589757065555611f, 0.9589892950020393f, 0.9590028812448116f, 0.9590164652838469f, + 0.9590300471191135f, 0.9590436267505809f, 0.9590572041782172f, 0.9590707794019916f, + 0.9590843524218728f, 0.9590979232378296f, 0.9591114918498308f, 0.9591250582578453f, + 0.9591386224618419f, 0.9591521844617894f, 0.9591657442576567f, 0.9591793018494125f, + 0.9591928572370257f, 0.9592064104204653f, 0.9592199613996999f, 0.9592335101746985f, + 0.9592470567454301f, 0.9592606011118633f, 0.9592741432739672f, 0.9592876832317105f, + 0.9593012209850622f, 0.9593147565339912f, 0.9593282898784664f, 0.9593418210184566f, + 0.9593553499539308f, 0.9593688766848578f, 0.9593824012112067f, 0.9593959235329463f, + 0.9594094436500455f, 0.9594229615624733f, 0.9594364772701987f, 0.9594499907731904f, + 0.9594635020714175f, 0.9594770111648491f, 0.9594905180534539f, 0.9595040227372010f, + 0.9595175252160593f, 0.9595310254899978f, 0.9595445235589856f, 0.9595580194229915f, + 0.9595715130819845f, 0.9595850045359338f, 0.9595984937848081f, 0.9596119808285766f, + 0.9596254656672083f, 0.9596389483006721f, 0.9596524287289371f, 0.9596659069519723f, + 0.9596793829697468f, 0.9596928567822295f, 0.9597063283893895f, 0.9597197977911959f, + 0.9597332649876177f, 0.9597467299786239f, 0.9597601927641837f, 0.9597736533442660f, + 0.9597871117188399f, 0.9598005678878746f, 0.9598140218513391f, 0.9598274736092024f, + 0.9598409231614337f, 0.9598543705080022f, 0.9598678156488766f, 0.9598812585840264f, + 0.9598946993134205f, 0.9599081378370282f, 0.9599215741548184f, 0.9599350082667605f, + 0.9599484401728232f, 0.9599618698729760f, 0.9599752973671880f, 0.9599887226554282f, + 0.9600021457376660f, 0.9600155666138701f, 0.9600289852840100f, 0.9600424017480550f, + 0.9600558160059739f, 0.9600692280577361f, 0.9600826379033107f, 0.9600960455426669f, + 0.9601094509757739f, 0.9601228542026010f, 0.9601362552231172f, 0.9601496540372918f, + 0.9601630506450940f, 0.9601764450464930f, 0.9601898372414581f, 0.9602032272299585f, + 0.9602166150119634f, 0.9602300005874421f, 0.9602433839563637f, 0.9602567651186975f, + 0.9602701440744128f, 0.9602835208234788f, 0.9602968953658648f, 0.9603102677015402f, + 0.9603236378304739f, 0.9603370057526356f, 0.9603503714679943f, 0.9603637349765194f, + 0.9603770962781801f, 0.9603904553729459f, 0.9604038122607859f, 0.9604171669416693f, + 0.9604305194155658f, 0.9604438696824444f, 0.9604572177422747f, 0.9604705635950256f, + 0.9604839072406668f, 0.9604972486791674f, 0.9605105879104970f, 0.9605239249346247f, + 0.9605372597515200f, 0.9605505923611523f, 0.9605639227634908f, 0.9605772509585050f, + 0.9605905769461641f, 0.9606039007264376f, 0.9606172222992950f, 0.9606305416647055f, + 0.9606438588226385f, 0.9606571737730636f, 0.9606704865159499f, 0.9606837970512672f, + 0.9606971053789845f, 0.9607104114990713f, 0.9607237154114973f, 0.9607370171162317f, + 0.9607503166132439f, 0.9607636139025035f, 0.9607769089839799f, 0.9607902018576424f, + 0.9608034925234608f, 0.9608167809814041f, 0.9608300672314420f, 0.9608433512735440f, + 0.9608566331076797f, 0.9608699127338182f, 0.9608831901519292f, 0.9608964653619823f, + 0.9609097383639468f, 0.9609230091577923f, 0.9609362777434883f, 0.9609495441210043f, + 0.9609628082903098f, 0.9609760702513742f, 0.9609893300041673f, 0.9610025875486585f, + 0.9610158428848172f, 0.9610290960126132f, 0.9610423469320157f, 0.9610555956429946f, + 0.9610688421455194f, 0.9610820864395594f, 0.9610953285250844f, 0.9611085684020638f, + 0.9611218060704674f, 0.9611350415302646f, 0.9611482747814251f, 0.9611615058239183f, + 0.9611747346577142f, 0.9611879612827819f, 0.9612011856990913f, 0.9612144079066119f, + 0.9612276279053135f, 0.9612408456951654f, 0.9612540612761376f, 0.9612672746481994f, + 0.9612804858113206f, 0.9612936947654709f, 0.9613069015106198f, 0.9613201060467370f, + 0.9613333083737923f, 0.9613465084917551f, 0.9613597064005952f, 0.9613729021002825f, + 0.9613860955907862f, 0.9613992868720763f, 0.9614124759441225f, 0.9614256628068943f, + 0.9614388474603617f, 0.9614520299044941f, 0.9614652101392612f, 0.9614783881646330f, + 0.9614915639805790f, 0.9615047375870689f, 0.9615179089840726f, 0.9615310781715597f, + 0.9615442451495000f, 0.9615574099178632f, 0.9615705724766191f, 0.9615837328257374f, + 0.9615968909651879f, 0.9616100468949402f, 0.9616232006149644f, 0.9616363521252299f, + 0.9616495014257068f, 0.9616626485163647f, 0.9616757933971734f, 0.9616889360681027f, + 0.9617020765291225f, 0.9617152147802025f, 0.9617283508213126f, 0.9617414846524225f, + 0.9617546162735020f, 0.9617677456845211f, 0.9617808728854494f, 0.9617939978762570f, + 0.9618071206569135f, 0.9618202412273890f, 0.9618333595876529f, 0.9618464757376757f, + 0.9618595896774266f, 0.9618727014068759f, 0.9618858109259933f, 0.9618989182347488f, + 0.9619120233331121f, 0.9619251262210533f, 0.9619382268985421f, 0.9619513253655485f, + 0.9619644216220423f, 0.9619775156679935f, 0.9619906075033720f, 0.9620036971281477f, + 0.9620167845422906f, 0.9620298697457704f, 0.9620429527385572f, 0.9620560335206210f, + 0.9620691120919317f, 0.9620821884524591f, 0.9620952626021732f, 0.9621083345410441f, + 0.9621214042690416f, 0.9621344717861358f, 0.9621475370922966f, 0.9621606001874939f, + 0.9621736610716978f, 0.9621867197448783f, 0.9621997762070054f, 0.9622128304580490f, + 0.9622258824979790f, 0.9622389323267657f, 0.9622519799443789f, 0.9622650253507887f, + 0.9622780685459651f, 0.9622911095298782f, 0.9623041483024979f, 0.9623171848637943f, + 0.9623302192137374f, 0.9623432513522974f, 0.9623562812794441f, 0.9623693089951478f, + 0.9623823344993784f, 0.9623953577921061f, 0.9624083788733009f, 0.9624213977429328f, + 0.9624344144009720f, 0.9624474288473887f, 0.9624604410821527f, 0.9624734511052342f, + 0.9624864589166034f, 0.9624994645162305f, 0.9625124679040853f, 0.9625254690801383f, + 0.9625384680443592f, 0.9625514647967184f, 0.9625644593371859f, 0.9625774516657321f, + 0.9625904417823269f, 0.9626034296869405f, 0.9626164153795430f, 0.9626293988601047f, + 0.9626423801285957f, 0.9626553591849861f, 0.9626683360292462f, 0.9626813106613461f, + 0.9626942830812559f, 0.9627072532889460f, 0.9627202212843865f, 0.9627331870675475f, + 0.9627461506383994f, 0.9627591119969122f, 0.9627720711430564f, 0.9627850280768019f, + 0.9627979827981190f, 0.9628109353069781f, 0.9628238856033493f, 0.9628368336872029f, + 0.9628497795585090f, 0.9628627232172381f, 0.9628756646633602f, 0.9628886038968458f, + 0.9629015409176650f, 0.9629144757257881f, 0.9629274083211855f, 0.9629403387038273f, + 0.9629532668736839f, 0.9629661928307255f, 0.9629791165749225f, 0.9629920381062452f, + 0.9630049574246639f, 0.9630178745301488f, 0.9630307894226703f, 0.9630437021021987f, + 0.9630566125687043f, 0.9630695208221576f, 0.9630824268625287f, 0.9630953306897881f, + 0.9631082323039062f, 0.9631211317048531f, 0.9631340288925994f, 0.9631469238671154f, + 0.9631598166283714f, 0.9631727071763379f, 0.9631855955109850f, 0.9631984816322835f, + 0.9632113655402035f, 0.9632242472347154f, 0.9632371267157898f, 0.9632500039833968f, + 0.9632628790375071f, 0.9632757518780909f, 0.9632886225051187f, 0.9633014909185610f, + 0.9633143571183881f, 0.9633272211045706f, 0.9633400828770787f, 0.9633529424358831f, + 0.9633657997809540f, 0.9633786549122620f, 0.9633915078297777f, 0.9634043585334713f, + 0.9634172070233133f, 0.9634300532992743f, 0.9634428973613248f, 0.9634557392094352f, + 0.9634685788435760f, 0.9634814162637176f, 0.9634942514698307f, 0.9635070844618857f, + 0.9635199152398531f, 0.9635327438037035f, 0.9635455701534072f, 0.9635583942889350f, + 0.9635712162102572f, 0.9635840359173447f, 0.9635968534101675f, 0.9636096686886965f, + 0.9636224817529022f, 0.9636352926027552f, 0.9636481012382260f, 0.9636609076592851f, + 0.9636737118659032f, 0.9636865138580508f, 0.9636993136356985f, 0.9637121111988168f, + 0.9637249065473765f, 0.9637376996813480f, 0.9637504906007019f, 0.9637632793054091f, + 0.9637760657954398f, 0.9637888500707650f, 0.9638016321313549f, 0.9638144119771805f, + 0.9638271896082123f, 0.9638399650244209f, 0.9638527382257770f, 0.9638655092122512f, + 0.9638782779838142f, 0.9638910445404366f, 0.9639038088820892f, 0.9639165710087425f, + 0.9639293309203671f, 0.9639420886169341f, 0.9639548440984137f, 0.9639675973647768f, + 0.9639803484159941f, 0.9639930972520363f, 0.9640058438728740f, 0.9640185882784782f, + 0.9640313304688193f, 0.9640440704438680f, 0.9640568082035953f, 0.9640695437479717f, + 0.9640822770769681f, 0.9640950081905552f, 0.9641077370887036f, 0.9641204637713842f, + 0.9641331882385676f, 0.9641459104902247f, 0.9641586305263263f, 0.9641713483468430f, + 0.9641840639517457f, 0.9641967773410053f, 0.9642094885145923f, 0.9642221974724776f, + 0.9642349042146322f, 0.9642476087410266f, 0.9642603110516317f, 0.9642730111464184f, + 0.9642857090253574f, 0.9642984046884197f, 0.9643110981355759f, 0.9643237893667970f, + 0.9643364783820537f, 0.9643491651813170f, 0.9643618497645575f, 0.9643745321317464f, + 0.9643872122828543f, 0.9643998902178521f, 0.9644125659367108f, 0.9644252394394011f, + 0.9644379107258939f, 0.9644505797961601f, 0.9644632466501707f, 0.9644759112878964f, + 0.9644885737093084f, 0.9645012339143774f, 0.9645138919030741f, 0.9645265476753698f, + 0.9645392012312352f, 0.9645518525706412f, 0.9645645016935589f, 0.9645771485999590f, + 0.9645897932898128f, 0.9646024357630908f, 0.9646150760197642f, 0.9646277140598040f, + 0.9646403498831809f, 0.9646529834898662f, 0.9646656148798306f, 0.9646782440530453f, + 0.9646908710094809f, 0.9647034957491090f, 0.9647161182719000f, 0.9647287385778250f, + 0.9647413566668553f, 0.9647539725389618f, 0.9647665861941153f, 0.9647791976322870f, + 0.9647918068534479f, 0.9648044138575690f, 0.9648170186446212f, 0.9648296212145757f, + 0.9648422215674036f, 0.9648548197030757f, 0.9648674156215633f, 0.9648800093228374f, + 0.9648926008068689f, 0.9649051900736290f, 0.9649177771230887f, 0.9649303619552192f, + 0.9649429445699914f, 0.9649555249673767f, 0.9649681031473457f, 0.9649806791098700f, + 0.9649932528549203f, 0.9650058243824681f, 0.9650183936924841f, 0.9650309607849397f, + 0.9650435256598059f, 0.9650560883170538f, 0.9650686487566547f, 0.9650812069785796f, + 0.9650937629827996f, 0.9651063167692859f, 0.9651188683380097f, 0.9651314176889423f, + 0.9651439648220544f, 0.9651565097373176f, 0.9651690524347030f, 0.9651815929141816f, + 0.9651941311757247f, 0.9652066672193035f, 0.9652192010448891f, 0.9652317326524529f, + 0.9652442620419658f, 0.9652567892133993f, 0.9652693141667245f, 0.9652818369019125f, + 0.9652943574189347f, 0.9653068757177622f, 0.9653193917983663f, 0.9653319056607184f, + 0.9653444173047894f, 0.9653569267305507f, 0.9653694339379737f, 0.9653819389270295f, + 0.9653944416976894f, 0.9654069422499246f, 0.9654194405837065f, 0.9654319366990064f, + 0.9654444305957954f, 0.9654569222740450f, 0.9654694117337262f, 0.9654818989748107f, + 0.9654943839972695f, 0.9655068668010741f, 0.9655193473861957f, 0.9655318257526055f, + 0.9655443019002751f, 0.9655567758291758f, 0.9655692475392786f, 0.9655817170305552f, + 0.9655941843029768f, 0.9656066493565149f, 0.9656191121911405f, 0.9656315728068253f, + 0.9656440312035406f, 0.9656564873812576f, 0.9656689413399480f, 0.9656813930795829f, + 0.9656938426001338f, 0.9657062899015719f, 0.9657187349838690f, 0.9657311778469961f, + 0.9657436184909248f, 0.9657560569156265f, 0.9657684931210726f, 0.9657809271072345f, + 0.9657933588740836f, 0.9658057884215915f, 0.9658182157497295f, 0.9658306408584689f, + 0.9658430637477815f, 0.9658554844176385f, 0.9658679028680114f, 0.9658803190988717f, + 0.9658927331101909f, 0.9659051449019403f, 0.9659175544740917f, 0.9659299618266162f, + 0.9659423669594855f, 0.9659547698726711f, 0.9659671705661445f, 0.9659795690398771f, + 0.9659919652938406f, 0.9660043593280063f, 0.9660167511423459f, 0.9660291407368307f, + 0.9660415281114324f, 0.9660539132661226f, 0.9660662962008726f, 0.9660786769156542f, + 0.9660910554104388f, 0.9661034316851980f, 0.9661158057399034f, 0.9661281775745264f, + 0.9661405471890387f, 0.9661529145834120f, 0.9661652797576176f, 0.9661776427116272f, + 0.9661900034454126f, 0.9662023619589450f, 0.9662147182521964f, 0.9662270723251382f, + 0.9662394241777419f, 0.9662517738099793f, 0.9662641212218219f, 0.9662764664132415f, + 0.9662888093842096f, 0.9663011501346980f, 0.9663134886646779f, 0.9663258249741216f, + 0.9663381590630001f, 0.9663504909312854f, 0.9663628205789493f, 0.9663751480059632f, + 0.9663874732122988f, 0.9663997961979279f, 0.9664121169628221f, 0.9664244355069531f, + 0.9664367518302927f, 0.9664490659328124f, 0.9664613778144840f, 0.9664736874752793f, + 0.9664859949151698f, 0.9664983001341274f, 0.9665106031321238f, 0.9665229039091306f, + 0.9665352024651197f, 0.9665474988000627f, 0.9665597929139315f, 0.9665720848066977f, + 0.9665843744783331f, 0.9665966619288094f, 0.9666089471580986f, 0.9666212301661722f, + 0.9666335109530021f, 0.9666457895185601f, 0.9666580658628179f, 0.9666703399857473f, + 0.9666826118873202f, 0.9666948815675082f, 0.9667071490262833f, 0.9667194142636173f, + 0.9667316772794818f, 0.9667439380738490f, 0.9667561966466903f, 0.9667684529979779f, + 0.9667807071276834f, 0.9667929590357786f, 0.9668052087222355f, 0.9668174561870260f, + 0.9668297014301218f, 0.9668419444514949f, 0.9668541852511170f, 0.9668664238289600f, + 0.9668786601849959f, 0.9668908943191965f, 0.9669031262315337f, 0.9669153559219794f, + 0.9669275833905057f, 0.9669398086370840f, 0.9669520316616866f, 0.9669642524642854f, + 0.9669764710448521f, 0.9669886874033589f, 0.9670009015397774f, 0.9670131134540798f, + 0.9670253231462380f, 0.9670375306162238f, 0.9670497358640092f, 0.9670619388895664f, + 0.9670741396928670f, 0.9670863382738831f, 0.9670985346325868f, 0.9671107287689499f, + 0.9671229206829444f, 0.9671351103745424f, 0.9671472978437157f, 0.9671594830904364f, + 0.9671716661146766f, 0.9671838469164081f, 0.9671960254956031f, 0.9672082018522336f, + 0.9672203759862713f, 0.9672325478976888f, 0.9672447175864575f, 0.9672568850525498f, + 0.9672690502959378f, 0.9672812133165933f, 0.9672933741144886f, 0.9673055326895956f, + 0.9673176890418863f, 0.9673298431713329f, 0.9673419950779074f, 0.9673541447615819f, + 0.9673662922223285f, 0.9673784374601193f, 0.9673905804749263f, 0.9674027212667217f, + 0.9674148598354775f, 0.9674269961811659f, 0.9674391303037589f, 0.9674512622032287f, + 0.9674633918795474f, 0.9674755193326873f, 0.9674876445626203f, 0.9674997675693184f, + 0.9675118883527541f, 0.9675240069128994f, 0.9675361232497265f, 0.9675482373632074f, + 0.9675603492533144f, 0.9675724589200196f, 0.9675845663632953f, 0.9675966715831135f, + 0.9676087745794465f, 0.9676208753522664f, 0.9676329739015455f, 0.9676450702272559f, + 0.9676571643293699f, 0.9676692562078596f, 0.9676813458626973f, 0.9676934332938552f, + 0.9677055185013055f, 0.9677176014850204f, 0.9677296822449722f, 0.9677417607811332f, + 0.9677538370934755f, 0.9677659111819713f, 0.9677779830465931f, 0.9677900526873130f, + 0.9678021201041033f, 0.9678141852969362f, 0.9678262482657840f, 0.9678383090106191f, + 0.9678503675314136f, 0.9678624238281400f, 0.9678744779007704f, 0.9678865297492772f, + 0.9678985793736327f, 0.9679106267738091f, 0.9679226719497790f, 0.9679347149015144f, + 0.9679467556289878f, 0.9679587941321715f, 0.9679708304110378f, 0.9679828644655590f, + 0.9679948962957077f, 0.9680069259014559f, 0.9680189532827762f, 0.9680309784396409f, + 0.9680430013720223f, 0.9680550220798928f, 0.9680670405632249f, 0.9680790568219908f, + 0.9680910708561630f, 0.9681030826657139f, 0.9681150922506158f, 0.9681270996108412f, + 0.9681391047463623f, 0.9681511076571520f, 0.9681631083431822f, 0.9681751068044255f, + 0.9681871030408544f, 0.9681990970524413f, 0.9682110888391586f, 0.9682230784009788f, + 0.9682350657378743f, 0.9682470508498175f, 0.9682590337367811f, 0.9682710143987373f, + 0.9682829928356587f, 0.9682949690475177f, 0.9683069430342868f, 0.9683189147959385f, + 0.9683308843324453f, 0.9683428516437796f, 0.9683548167299141f, 0.9683667795908212f, + 0.9683787402264733f, 0.9683906986368430f, 0.9684026548219029f, 0.9684146087816254f, + 0.9684265605159832f, 0.9684385100249487f, 0.9684504573084944f, 0.9684624023665930f, + 0.9684743451992168f, 0.9684862858063387f, 0.9684982241879310f, 0.9685101603439663f, + 0.9685220942744173f, 0.9685340259792565f, 0.9685459554584565f, 0.9685578827119897f, + 0.9685698077398289f, 0.9685817305419467f, 0.9685936511183157f, 0.9686055694689084f, + 0.9686174855936975f, 0.9686293994926556f, 0.9686413111657552f, 0.9686532206129692f, + 0.9686651278342701f, 0.9686770328296304f, 0.9686889355990228f, 0.9687008361424201f, + 0.9687127344597948f, 0.9687246305511196f, 0.9687365244163673f, 0.9687484160555102f, + 0.9687603054685214f, 0.9687721926553734f, 0.9687840776160388f, 0.9687959603504904f, + 0.9688078408587010f, 0.9688197191406430f, 0.9688315951962893f, 0.9688434690256126f, + 0.9688553406285856f, 0.9688672100051809f, 0.9688790771553715f, 0.9688909420791298f, + 0.9689028047764289f, 0.9689146652472412f, 0.9689265234915396f, 0.9689383795092970f, + 0.9689502333004858f, 0.9689620848650790f, 0.9689739342030493f, 0.9689857813143695f, + 0.9689976261990123f, 0.9690094688569507f, 0.9690213092881572f, 0.9690331474926048f, + 0.9690449834702662f, 0.9690568172211143f, 0.9690686487451217f, 0.9690804780422614f, + 0.9690923051125061f, 0.9691041299558288f, 0.9691159525722022f, 0.9691277729615990f, + 0.9691395911239923f, 0.9691514070593548f, 0.9691632207676593f, 0.9691750322488788f, + 0.9691868415029860f, 0.9691986485299539f, 0.9692104533297553f, 0.9692222559023630f, + 0.9692340562477501f, 0.9692458543658892f, 0.9692576502567534f, 0.9692694439203156f, + 0.9692812353565485f, 0.9692930245654251f, 0.9693048115469185f, 0.9693165963010013f, + 0.9693283788276467f, 0.9693401591268275f, 0.9693519371985164f, 0.9693637130426868f, + 0.9693754866593113f, 0.9693872580483629f, 0.9693990272098146f, 0.9694107941436395f, + 0.9694225588498103f, 0.9694343213283001f, 0.9694460815790819f, 0.9694578396021285f, + 0.9694695953974130f, 0.9694813489649085f, 0.9694931003045878f, 0.9695048494164240f, + 0.9695165963003900f, 0.9695283409564589f, 0.9695400833846038f, 0.9695518235847975f, + 0.9695635615570132f, 0.9695752973012238f, 0.9695870308174025f, 0.9695987621055221f, + 0.9696104911655559f, 0.9696222179974767f, 0.9696339426012577f, 0.9696456649768719f, + 0.9696573851242924f, 0.9696691030434923f, 0.9696808187344447f, 0.9696925321971224f, + 0.9697042434314989f, 0.9697159524375469f, 0.9697276592152397f, 0.9697393637645505f, + 0.9697510660854521f, 0.9697627661779179f, 0.9697744640419209f, 0.9697861596774342f, + 0.9697978530844309f, 0.9698095442628842f, 0.9698212332127671f, 0.9698329199340530f, + 0.9698446044267148f, 0.9698562866907258f, 0.9698679667260590f, 0.9698796445326878f, + 0.9698913201105851f, 0.9699029934597242f, 0.9699146645800782f, 0.9699263334716205f, + 0.9699380001343240f, 0.9699496645681620f, 0.9699613267731078f, 0.9699729867491345f, + 0.9699846444962152f, 0.9699963000143234f, 0.9700079533034321f, 0.9700196043635145f, + 0.9700312531945440f, 0.9700428997964937f, 0.9700545441693368f, 0.9700661863130466f, + 0.9700778262275964f, 0.9700894639129595f, 0.9701010993691088f, 0.9701127325960180f, + 0.9701243635936603f, 0.9701359923620088f, 0.9701476189010367f, 0.9701592432107174f, + 0.9701708652910245f, 0.9701824851419307f, 0.9701941027634098f, 0.9702057181554349f, + 0.9702173313179792f, 0.9702289422510162f, 0.9702405509545191f, 0.9702521574284613f, + 0.9702637616728161f, 0.9702753636875568f, 0.9702869634726569f, 0.9702985610280895f, + 0.9703101563538281f, 0.9703217494498461f, 0.9703333403161167f, 0.9703449289526134f, + 0.9703565153593094f, 0.9703680995361783f, 0.9703796814831933f, 0.9703912612003279f, + 0.9704028386875555f, 0.9704144139448494f, 0.9704259869721830f, 0.9704375577695298f, + 0.9704491263368631f, 0.9704606926741565f, 0.9704722567813832f, 0.9704838186585167f, + 0.9704953783055305f, 0.9705069357223980f, 0.9705184909090926f, 0.9705300438655878f, + 0.9705415945918571f, 0.9705531430878738f, 0.9705646893536115f, 0.9705762333890436f, + 0.9705877751941436f, 0.9705993147688851f, 0.9706108521132412f, 0.9706223872271857f, + 0.9706339201106922f, 0.9706454507637339f, 0.9706569791862845f, 0.9706685053783174f, + 0.9706800293398061f, 0.9706915510707242f, 0.9707030705710453f, 0.9707145878407427f, + 0.9707261028797902f, 0.9707376156881611f, 0.9707491262658290f, 0.9707606346127676f, + 0.9707721407289504f, 0.9707836446143507f, 0.9707951462689424f, 0.9708066456926989f, + 0.9708181428855939f, 0.9708296378476008f, 0.9708411305786934f, 0.9708526210788450f, + 0.9708641093480295f, 0.9708755953862203f, 0.9708870791933911f, 0.9708985607695155f, + 0.9709100401145671f, 0.9709215172285195f, 0.9709329921113464f, 0.9709444647630213f, + 0.9709559351835180f, 0.9709674033728100f, 0.9709788693308710f, 0.9709903330576747f, + 0.9710017945531947f, 0.9710132538174047f, 0.9710247108502783f, 0.9710361656517892f, + 0.9710476182219111f, 0.9710590685606176f, 0.9710705166678826f, 0.9710819625436796f, + 0.9710934061879825f, 0.9711048476007647f, 0.9711162867820000f, 0.9711277237316622f, + 0.9711391584497251f, 0.9711505909361623f, 0.9711620211909475f, 0.9711734492140546f, + 0.9711848750054571f, 0.9711962985651289f, 0.9712077198930437f, 0.9712191389891753f, + 0.9712305558534974f, 0.9712419704859838f, 0.9712533828866082f, 0.9712647930553445f, + 0.9712762009921665f, 0.9712876066970478f, 0.9712990101699623f, 0.9713104114108838f, + 0.9713218104197862f, 0.9713332071966431f, 0.9713446017414284f, 0.9713559940541160f, + 0.9713673841346795f, 0.9713787719830930f, 0.9713901575993301f, 0.9714015409833648f, + 0.9714129221351709f, 0.9714243010547222f, 0.9714356777419926f, 0.9714470521969558f, + 0.9714584244195860f, 0.9714697944098567f, 0.9714811621677421f, 0.9714925276932157f, + 0.9715038909862518f, 0.9715152520468240f, 0.9715266108749062f, 0.9715379674704725f, + 0.9715493218334966f, 0.9715606739639525f, 0.9715720238618142f, 0.9715833715270554f, + 0.9715947169596502f, 0.9716060601595725f, 0.9716174011267961f, 0.9716287398612951f, + 0.9716400763630434f, 0.9716514106320150f, 0.9716627426681836f, 0.9716740724715236f, + 0.9716854000420085f, 0.9716967253796126f, 0.9717080484843098f, 0.9717193693560739f, + 0.9717306879948792f, 0.9717420044006994f, 0.9717533185735086f, 0.9717646305132809f, + 0.9717759402199901f, 0.9717872476936104f, 0.9717985529341158f, 0.9718098559414802f, + 0.9718211567156777f, 0.9718324552566824f, 0.9718437515644681f, 0.9718550456390092f, + 0.9718663374802794f, 0.9718776270882529f, 0.9718889144629038f, 0.9719001996042061f, + 0.9719114825121340f, 0.9719227631866614f, 0.9719340416277624f, 0.9719453178354112f, + 0.9719565918095817f, 0.9719678635502481f, 0.9719791330573846f, 0.9719904003309652f, + 0.9720016653709639f, 0.9720129281773550f, 0.9720241887501125f, 0.9720354470892106f, + 0.9720467031946235f, 0.9720579570663251f, 0.9720692087042897f, 0.9720804581084914f, + 0.9720917052789044f, 0.9721029502155029f, 0.9721141929182608f, 0.9721254333871525f, + 0.9721366716221521f, 0.9721479076232339f, 0.9721591413903720f, 0.9721703729235404f, + 0.9721816022227134f, 0.9721928292878654f, 0.9722040541189704f, 0.9722152767160026f, + 0.9722264970789363f, 0.9722377152077456f, 0.9722489311024050f, 0.9722601447628882f, + 0.9722713561891700f, 0.9722825653812244f, 0.9722937723390255f, 0.9723049770625477f, + 0.9723161795517653f, 0.9723273798066525f, 0.9723385778271835f, 0.9723497736133326f, + 0.9723609671650741f, 0.9723721584823823f, 0.9723833475652315f, 0.9723945344135958f, + 0.9724057190274498f, 0.9724169014067675f, 0.9724280815515234f, 0.9724392594616917f, + 0.9724504351372468f, 0.9724616085781630f, 0.9724727797844146f, 0.9724839487559759f, + 0.9724951154928212f, 0.9725062799949250f, 0.9725174422622614f, 0.9725286022948051f, + 0.9725397600925302f, 0.9725509156554111f, 0.9725620689834221f, 0.9725732200765377f, + 0.9725843689347322f, 0.9725955155579801f, 0.9726066599462556f, 0.9726178020995332f, + 0.9726289420177873f, 0.9726400797009922f, 0.9726512151491225f, 0.9726623483621524f, + 0.9726734793400564f, 0.9726846080828090f, 0.9726957345903846f, 0.9727068588627575f, + 0.9727179808999024f, 0.9727291007017933f, 0.9727402182684051f, 0.9727513335997120f, + 0.9727624466956886f, 0.9727735575563091f, 0.9727846661815485f, 0.9727957725713806f, + 0.9728068767257804f, 0.9728179786447221f, 0.9728290783281803f, 0.9728401757761295f, + 0.9728512709885442f, 0.9728623639653988f, 0.9728734547066680f, 0.9728845432123261f, + 0.9728956294823478f, 0.9729067135167074f, 0.9729177953153797f, 0.9729288748783391f, + 0.9729399522055602f, 0.9729510272970173f, 0.9729621001526854f, 0.9729731707725386f, + 0.9729842391565517f, 0.9729953053046992f, 0.9730063692169558f, 0.9730174308932960f, + 0.9730284903336941f, 0.9730395475381252f, 0.9730506025065635f, 0.9730616552389837f, + 0.9730727057353605f, 0.9730837539956684f, 0.9730948000198821f, 0.9731058438079762f, + 0.9731168853599251f, 0.9731279246757037f, 0.9731389617552866f, 0.9731499965986483f, + 0.9731610292057635f, 0.9731720595766070f, 0.9731830877111532f, 0.9731941136093769f, + 0.9732051372712528f, 0.9732161586967555f, 0.9732271778858597f, 0.9732381948385400f, + 0.9732492095547711f, 0.9732602220345279f, 0.9732712322777848f, 0.9732822402845167f, + 0.9732932460546982f, 0.9733042495883041f, 0.9733152508853090f, 0.9733262499456876f, + 0.9733372467694148f, 0.9733482413564652f, 0.9733592337068137f, 0.9733702238204347f, + 0.9733812116973033f, 0.9733921973373940f, 0.9734031807406817f, 0.9734141619071411f, + 0.9734251408367470f, 0.9734361175294742f, 0.9734470919852974f, 0.9734580642041915f, + 0.9734690341861310f, 0.9734800019310911f, 0.9734909674390462f, 0.9735019307099714f, + 0.9735128917438414f, 0.9735238505406310f, 0.9735348071003149f, 0.9735457614228682f, + 0.9735567135082656f, 0.9735676633564818f, 0.9735786109674918f, 0.9735895563412703f, + 0.9736004994777924f, 0.9736114403770326f, 0.9736223790389661f, 0.9736333154635676f, + 0.9736442496508119f, 0.9736551816006740f, 0.9736661113131287f, 0.9736770387881510f, + 0.9736879640257157f, 0.9736988870257977f, 0.9737098077883718f, 0.9737207263134131f, + 0.9737316426008964f, 0.9737425566507966f, 0.9737534684630886f, 0.9737643780377475f, + 0.9737752853747480f, 0.9737861904740652f, 0.9737970933356740f, 0.9738079939595493f, + 0.9738188923456661f, 0.9738297884939994f, 0.9738406824045239f, 0.9738515740772150f, + 0.9738624635120473f, 0.9738733507089959f, 0.9738842356680358f, 0.9738951183891420f, + 0.9739059988722896f, 0.9739168771174532f, 0.9739277531246082f, 0.9739386268937296f, + 0.9739494984247922f, 0.9739603677177711f, 0.9739712347726414f, 0.9739820995893779f, + 0.9739929621679558f, 0.9740038225083503f, 0.9740146806105362f, 0.9740255364744886f, + 0.9740363901001826f, 0.9740472414875933f, 0.9740580906366956f, 0.9740689375474647f, + 0.9740797822198757f, 0.9740906246539036f, 0.9741014648495234f, 0.9741123028067105f, + 0.9741231385254396f, 0.9741339720056861f, 0.9741448032474249f, 0.9741556322506314f, + 0.9741664590152803f, 0.9741772835413471f, 0.9741881058288068f, 0.9741989258776343f, + 0.9742097436878051f, 0.9742205592592942f, 0.9742313725920767f, 0.9742421836861277f, + 0.9742529925414225f, 0.9742637991579363f, 0.9742746035356440f, 0.9742854056745209f, + 0.9742962055745423f, 0.9743070032356834f, 0.9743177986579191f, 0.9743285918412249f, + 0.9743393827855759f, 0.9743501714909472f, 0.9743609579573140f, 0.9743717421846517f, + 0.9743825241729355f, 0.9743933039221404f, 0.9744040814322419f, 0.9744148567032149f, + 0.9744256297350350f, 0.9744364005276772f, 0.9744471690811169f, 0.9744579353953293f, + 0.9744686994702896f, 0.9744794613059732f, 0.9744902209023552f, 0.9745009782594110f, + 0.9745117333771157f, 0.9745224862554449f, 0.9745332368943737f, 0.9745439852938773f, + 0.9745547314539312f, 0.9745654753745105f, 0.9745762170555908f, 0.9745869564971472f, + 0.9745976936991551f, 0.9746084286615896f, 0.9746191613844264f, 0.9746298918676406f, + 0.9746406201112077f, 0.9746513461151027f, 0.9746620698793014f, 0.9746727914037789f, + 0.9746835106885107f, 0.9746942277334720f, 0.9747049425386383f, 0.9747156551039849f, + 0.9747263654294873f, 0.9747370735151207f, 0.9747477793608608f, 0.9747584829666825f, + 0.9747691843325618f, 0.9747798834584737f, 0.9747905803443937f, 0.9748012749902973f, + 0.9748119673961598f, 0.9748226575619569f, 0.9748333454876635f, 0.9748440311732556f, + 0.9748547146187084f, 0.9748653958239973f, 0.9748760747890980f, 0.9748867515139856f, + 0.9748974259986358f, 0.9749080982430240f, 0.9749187682471259f, 0.9749294360109166f, + 0.9749401015343717f, 0.9749507648174669f, 0.9749614258601775f, 0.9749720846624791f, + 0.9749827412243471f, 0.9749933955457571f, 0.9750040476266846f, 0.9750146974671051f, + 0.9750253450669941f, 0.9750359904263273f, 0.9750466335450799f, 0.9750572744232279f, + 0.9750679130607465f, 0.9750785494576112f, 0.9750891836137978f, 0.9750998155292819f, + 0.9751104452040389f, 0.9751210726380443f, 0.9751316978312738f, 0.9751423207837031f, + 0.9751529414953076f, 0.9751635599660631f, 0.9751741761959448f, 0.9751847901849288f, + 0.9751954019329904f, 0.9752060114401052f, 0.9752166187062490f, 0.9752272237313974f, + 0.9752378265155258f, 0.9752484270586101f, 0.9752590253606258f, 0.9752696214215486f, + 0.9752802152413542f, 0.9752908068200181f, 0.9753013961575161f, 0.9753119832538238f, + 0.9753225681089169f, 0.9753331507227712f, 0.9753437310953621f, 0.9753543092266654f, + 0.9753648851166569f, 0.9753754587653123f, 0.9753860301726072f, 0.9753965993385173f, + 0.9754071662630183f, 0.9754177309460860f, 0.9754282933876961f, 0.9754388535878243f, + 0.9754494115464464f, 0.9754599672635381f, 0.9754705207390750f, 0.9754810719730331f, + 0.9754916209653881f, 0.9755021677161155f, 0.9755127122251914f, 0.9755232544925915f, + 0.9755337945182914f, 0.9755443323022669f, 0.9755548678444940f, 0.9755654011449483f, + 0.9755759322036057f, 0.9755864610204419f, 0.9755969875954328f, 0.9756075119285541f, + 0.9756180340197818f, 0.9756285538690914f, 0.9756390714764591f, 0.9756495868418605f, + 0.9756600999652716f, 0.9756706108466681f, 0.9756811194860258f, 0.9756916258833206f, + 0.9757021300385286f, 0.9757126319516253f, 0.9757231316225867f, 0.9757336290513888f, + 0.9757441242380073f, 0.9757546171824182f, 0.9757651078845974f, 0.9757755963445206f, + 0.9757860825621639f, 0.9757965665375031f, 0.9758070482705142f, 0.9758175277611731f, + 0.9758280050094555f, 0.9758384800153377f, 0.9758489527787954f, 0.9758594232998045f, + 0.9758698915783410f, 0.9758803576143810f, 0.9758908214079001f, 0.9759012829588745f, + 0.9759117422672802f, 0.9759221993330930f, 0.9759326541562890f, 0.9759431067368440f, + 0.9759535570747343f, 0.9759640051699356f, 0.9759744510224240f, 0.9759848946321754f, + 0.9759953359991660f, 0.9760057751233716f, 0.9760162120047683f, 0.9760266466433322f, + 0.9760370790390390f, 0.9760475091918651f, 0.9760579371017866f, 0.9760683627687791f, + 0.9760787861928188f, 0.9760892073738821f, 0.9760996263119446f, 0.9761100430069825f, + 0.9761204574589719f, 0.9761308696678889f, 0.9761412796337096f, 0.9761516873564099f, + 0.9761620928359661f, 0.9761724960723541f, 0.9761828970655502f, 0.9761932958155303f, + 0.9762036923222706f, 0.9762140865857472f, 0.9762244786059361f, 0.9762348683828136f, + 0.9762452559163558f, 0.9762556412065387f, 0.9762660242533386f, 0.9762764050567315f, + 0.9762867836166936f, 0.9762971599332011f, 0.9763075340062302f, 0.9763179058357568f, + 0.9763282754217573f, 0.9763386427642078f, 0.9763490078630845f, 0.9763593707183635f, + 0.9763697313300211f, 0.9763800896980335f, 0.9763904458223768f, 0.9764007997030272f, + 0.9764111513399610f, 0.9764215007331544f, 0.9764318478825835f, 0.9764421927882246f, + 0.9764525354500541f, 0.9764628758680478f, 0.9764732140421825f, 0.9764835499724339f, + 0.9764938836587786f, 0.9765042151011928f, 0.9765145442996526f, 0.9765248712541345f, + 0.9765351959646145f, 0.9765455184310690f, 0.9765558386534744f, 0.9765661566318068f, + 0.9765764723660426f, 0.9765867858561581f, 0.9765970971021296f, 0.9766074061039333f, + 0.9766177128615456f, 0.9766280173749428f, 0.9766383196441012f, 0.9766486196689972f, + 0.9766589174496070f, 0.9766692129859070f, 0.9766795062778736f, 0.9766897973254831f, + 0.9767000861287118f, 0.9767103726875361f, 0.9767206570019324f, 0.9767309390718771f, + 0.9767412188973466f, 0.9767514964783169f, 0.9767617718147649f, 0.9767720449066666f, + 0.9767823157539987f, 0.9767925843567373f, 0.9768028507148591f, 0.9768131148283402f, + 0.9768233766971572f, 0.9768336363212866f, 0.9768438937007047f, 0.9768541488353879f, + 0.9768644017253126f, 0.9768746523704555f, 0.9768849007707927f, 0.9768951469263009f, + 0.9769053908369565f, 0.9769156325027358f, 0.9769258719236155f, 0.9769361090995720f, + 0.9769463440305816f, 0.9769565767166210f, 0.9769668071576666f, 0.9769770353536948f, + 0.9769872613046824f, 0.9769974850106056f, 0.9770077064714410f, 0.9770179256871651f, + 0.9770281426577544f, 0.9770383573831855f, 0.9770485698634348f, 0.9770587800984789f, + 0.9770689880882945f, 0.9770791938328578f, 0.9770893973321456f, 0.9770995985861345f, + 0.9771097975948009f, 0.9771199943581214f, 0.9771301888760725f, 0.9771403811486310f, + 0.9771505711757732f, 0.9771607589574758f, 0.9771709444937156f, 0.9771811277844688f, + 0.9771913088297123f, 0.9772014876294226f, 0.9772116641835762f, 0.9772218384921499f, + 0.9772320105551203f, 0.9772421803724639f, 0.9772523479441575f, 0.9772625132701775f, + 0.9772726763505009f, 0.9772828371851040f, 0.9772929957739636f, 0.9773031521170562f, + 0.9773133062143587f, 0.9773234580658476f, 0.9773336076714997f, 0.9773437550312917f, + 0.9773539001452000f, 0.9773640430132016f, 0.9773741836352730f, 0.9773843220113910f, + 0.9773944581415323f, 0.9774045920256735f, 0.9774147236637915f, 0.9774248530558628f, + 0.9774349802018643f, 0.9774451051017725f, 0.9774552277555645f, 0.9774653481632167f, + 0.9774754663247061f, 0.9774855822400093f, 0.9774956959091030f, 0.9775058073319640f, + 0.9775159165085693f, 0.9775260234388953f, 0.9775361281229190f, 0.9775462305606172f, + 0.9775563307519665f, 0.9775664286969439f, 0.9775765243955260f, 0.9775866178476897f, + 0.9775967090534119f, 0.9776067980126693f, 0.9776168847254386f, 0.9776269691916969f, + 0.9776370514114208f, 0.9776471313845871f, 0.9776572091111730f, 0.9776672845911549f, + 0.9776773578245099f, 0.9776874288112148f, 0.9776974975512465f, 0.9777075640445817f, + 0.9777176282911976f, 0.9777276902910705f, 0.9777377500441780f, 0.9777478075504963f, + 0.9777578628100028f, 0.9777679158226741f, 0.9777779665884871f, 0.9777880151074190f, + 0.9777980613794464f, 0.9778081054045463f, 0.9778181471826957f, 0.9778281867138714f, + 0.9778382239980504f, 0.9778482590352097f, 0.9778582918253260f, 0.9778683223683766f, + 0.9778783506643381f, 0.9778883767131877f, 0.9778984005149023f, 0.9779084220694589f, + 0.9779184413768344f, 0.9779284584370056f, 0.9779384732499499f, 0.9779484858156440f, + 0.9779584961340648f, 0.9779685042051897f, 0.9779785100289953f, 0.9779885136054587f, + 0.9779985149345571f, 0.9780085140162673f, 0.9780185108505665f, 0.9780285054374316f, + 0.9780384977768396f, 0.9780484878687676f, 0.9780584757131928f, 0.9780684613100920f, + 0.9780784446594424f, 0.9780884257612209f, 0.9780984046154048f, 0.9781083812219711f, + 0.9781183555808967f, 0.9781283276921587f, 0.9781382975557344f, 0.9781482651716009f, + 0.9781582305397351f, 0.9781681936601141f, 0.9781781545327151f, 0.9781881131575151f, + 0.9781980695344914f, 0.9782080236636210f, 0.9782179755448811f, 0.9782279251782487f, + 0.9782378725637011f, 0.9782478177012153f, 0.9782577605907685f, 0.9782677012323379f, + 0.9782776396259005f, 0.9782875757714337f, 0.9782975096689144f, 0.9783074413183200f, + 0.9783173707196277f, 0.9783272978728144f, 0.9783372227778575f, 0.9783471454347342f, + 0.9783570658434216f, 0.9783669840038971f, 0.9783768999161376f, 0.9783868135801205f, + 0.9783967249958231f, 0.9784066341632224f, 0.9784165410822958f, 0.9784264457530205f, + 0.9784363481753737f, 0.9784462483493328f, 0.9784561462748748f, 0.9784660419519771f, + 0.9784759353806168f, 0.9784858265607714f, 0.9784957154924181f, 0.9785056021755342f, + 0.9785154866100969f, 0.9785253687960834f, 0.9785352487334712f, 0.9785451264222375f, + 0.9785550018623596f, 0.9785648750538148f, 0.9785747459965805f, 0.9785846146906337f, + 0.9785944811359523f, 0.9786043453325131f, 0.9786142072802936f, 0.9786240669792712f, + 0.9786339244294231f, 0.9786437796307269f, 0.9786536325831597f, 0.9786634832866991f, + 0.9786733317413222f, 0.9786831779470065f, 0.9786930219037294f, 0.9787028636114683f, + 0.9787127030702004f, 0.9787225402799034f, 0.9787323752405543f, 0.9787422079521310f, + 0.9787520384146103f, 0.9787618666279702f, 0.9787716925921877f, 0.9787815163072404f, + 0.9787913377731057f, 0.9788011569897610f, 0.9788109739571837f, 0.9788207886753514f, + 0.9788306011442415f, 0.9788404113638313f, 0.9788502193340983f, 0.9788600250550201f, + 0.9788698285265741f, 0.9788796297487378f, 0.9788894287214884f, 0.9788992254448039f, + 0.9789090199186613f, 0.9789188121430383f, 0.9789286021179125f, 0.9789383898432613f, + 0.9789481753190622f, 0.9789579585452927f, 0.9789677395219303f, 0.9789775182489526f, + 0.9789872947263371f, 0.9789970689540612f, 0.9790068409321028f, 0.9790166106604390f, + 0.9790263781390476f, 0.9790361433679062f, 0.9790459063469922f, 0.9790556670762832f, + 0.9790654255557569f, 0.9790751817853908f, 0.9790849357651623f, 0.9790946874950494f, + 0.9791044369750292f, 0.9791141842050797f, 0.9791239291851782f, 0.9791336719153025f, + 0.9791434123954302f, 0.9791531506255389f, 0.9791628866056061f, 0.9791726203356097f, + 0.9791823518155269f, 0.9791920810453357f, 0.9792018080250138f, 0.9792115327545385f, + 0.9792212552338877f, 0.9792309754630389f, 0.9792406934419700f, 0.9792504091706584f, + 0.9792601226490820f, 0.9792698338772184f, 0.9792795428550451f, 0.9792892495825402f, + 0.9792989540596810f, 0.9793086562864454f, 0.9793183562628109f, 0.9793280539887556f, + 0.9793377494642569f, 0.9793474426892925f, 0.9793571336638403f, 0.9793668223878779f, + 0.9793765088613832f, 0.9793861930843336f, 0.9793958750567073f, 0.9794055547784818f, + 0.9794152322496348f, 0.9794249074701442f, 0.9794345804399877f, 0.9794442511591431f, + 0.9794539196275882f, 0.9794635858453007f, 0.9794732498122585f, 0.9794829115284391f, + 0.9794925709938207f, 0.9795022282083810f, 0.9795118831720976f, 0.9795215358849485f, + 0.9795311863469115f, 0.9795408345579644f, 0.9795504805180849f, 0.9795601242272510f, + 0.9795697656854405f, 0.9795794048926313f, 0.9795890418488011f, 0.9795986765539280f, + 0.9796083090079895f, 0.9796179392109637f, 0.9796275671628285f, 0.9796371928635618f, + 0.9796468163131412f, 0.9796564375115449f, 0.9796660564587507f, 0.9796756731547364f, + 0.9796852875994799f, 0.9796948997929593f, 0.9797045097351523f, 0.9797141174260370f, + 0.9797237228655912f, 0.9797333260537928f, 0.9797429269906197f, 0.9797525256760501f, + 0.9797621221100616f, 0.9797717162926325f, 0.9797813082237404f, 0.9797908979033636f, + 0.9798004853314797f, 0.9798100705080670f, 0.9798196534331033f, 0.9798292341065665f, + 0.9798388125284347f, 0.9798483886986861f, 0.9798579626172983f, 0.9798675342842494f, + 0.9798771036995176f, 0.9798866708630808f, 0.9798962357749170f, 0.9799057984350042f, + 0.9799153588433205f, 0.9799249169998439f, 0.9799344729045523f, 0.9799440265574240f, + 0.9799535779584367f, 0.9799631271075688f, 0.9799726740047983f, 0.9799822186501029f, + 0.9799917610434612f, 0.9800013011848510f, 0.9800108390742502f, 0.9800203747116373f, + 0.9800299080969900f, 0.9800394392302866f, 0.9800489681115052f, 0.9800584947406238f, + 0.9800680191176206f, 0.9800775412424737f, 0.9800870611151612f, 0.9800965787356611f, + 0.9801060941039518f, 0.9801156072200112f, 0.9801251180838175f, 0.9801346266953489f, + 0.9801441330545836f, 0.9801536371614996f, 0.9801631390160751f, 0.9801726386182883f, + 0.9801821359681174f, 0.9801916310655405f, 0.9802011239105358f, 0.9802106145030817f, + 0.9802201028431560f, 0.9802295889307372f, 0.9802390727658034f, 0.9802485543483327f, + 0.9802580336783036f, 0.9802675107556940f, 0.9802769855804823f, 0.9802864581526466f, + 0.9802959284721653f, 0.9803053965390165f, 0.9803148623531786f, 0.9803243259146296f, + 0.9803337872233480f, 0.9803432462793119f, 0.9803527030824997f, 0.9803621576328895f, + 0.9803716099304598f, 0.9803810599751885f, 0.9803905077670544f, 0.9803999533060354f, + 0.9804093965921099f, 0.9804188376252562f, 0.9804282764054526f, 0.9804377129326775f, + 0.9804471472069091f, 0.9804565792281257f, 0.9804660089963058f, 0.9804754365114275f, + 0.9804848617734694f, 0.9804942847824095f, 0.9805037055382265f, 0.9805131240408985f, + 0.9805225402904041f, 0.9805319542867214f, 0.9805413660298289f, 0.9805507755197049f, + 0.9805601827563279f, 0.9805695877396762f, 0.9805789904697282f, 0.9805883909464622f, + 0.9805977891698568f, 0.9806071851398902f, 0.9806165788565411f, 0.9806259703197875f, + 0.9806353595296081f, 0.9806447464859813f, 0.9806541311888854f, 0.9806635136382991f, + 0.9806728938342005f, 0.9806822717765683f, 0.9806916474653808f, 0.9807010209006166f, + 0.9807103920822540f, 0.9807197610102716f, 0.9807291276846477f, 0.9807384921053609f, + 0.9807478542723898f, 0.9807572141857126f, 0.9807665718453080f, 0.9807759272511545f, + 0.9807852804032304f, 0.9807946313015145f, 0.9808039799459851f, 0.9808133263366208f, + 0.9808226704734001f, 0.9808320123563015f, 0.9808413519853035f, 0.9808506893603849f, + 0.9808600244815239f, 0.9808693573486992f, 0.9808786879618894f, 0.9808880163210729f, + 0.9808973424262284f, 0.9809066662773345f, 0.9809159878743696f, 0.9809253072173125f, + 0.9809346243061416f, 0.9809439391408357f, 0.9809532517213732f, 0.9809625620477327f, + 0.9809718701198928f, 0.9809811759378324f, 0.9809904795015297f, 0.9809997808109636f, + 0.9810090798661126f, 0.9810183766669555f, 0.9810276712134706f, 0.9810369635056368f, + 0.9810462535434328f, 0.9810555413268370f, 0.9810648268558284f, 0.9810741101303854f, + 0.9810833911504866f, 0.9810926699161110f, 0.9811019464272369f, 0.9811112206838433f, + 0.9811204926859087f, 0.9811297624334119f, 0.9811390299263315f, 0.9811482951646463f, + 0.9811575581483348f, 0.9811668188773761f, 0.9811760773517486f, 0.9811853335714311f, + 0.9811945875364023f, 0.9812038392466411f, 0.9812130887021261f, 0.9812223359028360f, + 0.9812315808487497f, 0.9812408235398458f, 0.9812500639761031f, 0.9812593021575006f, + 0.9812685380840167f, 0.9812777717556305f, 0.9812870031723204f, 0.9812962323340656f, + 0.9813054592408447f, 0.9813146838926364f, 0.9813239062894197f, 0.9813331264311732f, + 0.9813423443178759f, 0.9813515599495066f, 0.9813607733260441f, 0.9813699844474671f, + 0.9813791933137546f, 0.9813883999248852f, 0.9813976042808381f, 0.9814068063815919f, + 0.9814160062271255f, 0.9814252038174178f, 0.9814343991524477f, 0.9814435922321940f, + 0.9814527830566355f, 0.9814619716257512f, 0.9814711579395200f, 0.9814803419979207f, + 0.9814895238009321f, 0.9814987033485334f, 0.9815078806407034f, 0.9815170556774208f, + 0.9815262284586647f, 0.9815353989844140f, 0.9815445672546477f, 0.9815537332693446f, + 0.9815628970284836f, 0.9815720585320438f, 0.9815812177800041f, 0.9815903747723435f, + 0.9815995295090407f, 0.9816086819900749f, 0.9816178322154251f, 0.9816269801850701f, + 0.9816361258989891f, 0.9816452693571608f, 0.9816544105595644f, 0.9816635495061788f, + 0.9816726861969831f, 0.9816818206319562f, 0.9816909528110772f, 0.9817000827343251f, + 0.9817092104016788f, 0.9817183358131174f, 0.9817274589686199f, 0.9817365798681654f, + 0.9817456985117330f, 0.9817548148993016f, 0.9817639290308503f, 0.9817730409063582f, + 0.9817821505258043f, 0.9817912578891678f, 0.9818003629964276f, 0.9818094658475628f, + 0.9818185664425525f, 0.9818276647813758f, 0.9818367608640119f, 0.9818458546904398f, + 0.9818549462606386f, 0.9818640355745873f, 0.9818731226322653f, 0.9818822074336515f, + 0.9818912899787250f, 0.9819003702674651f, 0.9819094482998507f, 0.9819185240758612f, + 0.9819275975954755f, 0.9819366688586730f, 0.9819457378654327f, 0.9819548046157337f, + 0.9819638691095552f, 0.9819729313468766f, 0.9819819913276767f, 0.9819910490519350f, + 0.9820001045196305f, 0.9820091577307425f, 0.9820182086852500f, 0.9820272573831326f, + 0.9820363038243690f, 0.9820453480089388f, 0.9820543899368211f, 0.9820634296079951f, + 0.9820724670224399f, 0.9820815021801350f, 0.9820905350810595f, 0.9820995657251925f, + 0.9821085941125136f, 0.9821176202430016f, 0.9821266441166363f, 0.9821356657333965f, + 0.9821446850932616f, 0.9821537021962110f, 0.9821627170422238f, 0.9821717296312794f, + 0.9821807399633572f, 0.9821897480384362f, 0.9821987538564959f, 0.9822077574175155f, + 0.9822167587214745f, 0.9822257577683520f, 0.9822347545581275f, 0.9822437490907802f, + 0.9822527413662894f, 0.9822617313846346f, 0.9822707191457949f, 0.9822797046497500f, + 0.9822886878964788f, 0.9822976688859610f, 0.9823066476181760f, 0.9823156240931029f, + 0.9823245983107212f, 0.9823335702710103f, 0.9823425399739496f, 0.9823515074195184f, + 0.9823604726076962f, 0.9823694355384622f, 0.9823783962117961f, 0.9823873546276771f, + 0.9823963107860847f, 0.9824052646869983f, 0.9824142163303973f, 0.9824231657162611f, + 0.9824321128445692f, 0.9824410577153010f, 0.9824500003284359f, 0.9824589406839536f, + 0.9824678787818332f, 0.9824768146220544f, 0.9824857482045966f, 0.9824946795294391f, + 0.9825036085965617f, 0.9825125354059437f, 0.9825214599575647f, 0.9825303822514040f, + 0.9825393022874412f, 0.9825482200656559f, 0.9825571355860274f, 0.9825660488485354f, + 0.9825749598531592f, 0.9825838685998787f, 0.9825927750886729f, 0.9826016793195218f, + 0.9826105812924048f, 0.9826194810073013f, 0.9826283784641910f, 0.9826372736630534f, + 0.9826461666038681f, 0.9826550572866146f, 0.9826639457112725f, 0.9826728318778214f, + 0.9826817157862409f, 0.9826905974365104f, 0.9826994768286097f, 0.9827083539625184f, + 0.9827172288382160f, 0.9827261014556821f, 0.9827349718148963f, 0.9827438399158384f, + 0.9827527057584878f, 0.9827615693428242f, 0.9827704306688273f, 0.9827792897364767f, + 0.9827881465457520f, 0.9827970010966328f, 0.9828058533890989f, 0.9828147034231298f, + 0.9828235511987052f, 0.9828323967158049f, 0.9828412399744085f, 0.9828500809744958f, + 0.9828589197160461f, 0.9828677561990394f, 0.9828765904234554f, 0.9828854223892738f, + 0.9828942520964741f, 0.9829030795450362f, 0.9829119047349397f, 0.9829207276661645f, + 0.9829295483386901f, 0.9829383667524965f, 0.9829471829075630f, 0.9829559968038698f, + 0.9829648084413964f, 0.9829736178201227f, 0.9829824249400283f, 0.9829912298010930f, + 0.9830000324032966f, 0.9830088327466189f, 0.9830176308310397f, 0.9830264266565386f, + 0.9830352202230956f, 0.9830440115306904f, 0.9830528005793028f, 0.9830615873689127f, + 0.9830703718994996f, 0.9830791541710437f, 0.9830879341835247f, 0.9830967119369223f, + 0.9831054874312163f, 0.9831142606663867f, 0.9831230316424133f, 0.9831318003592759f, + 0.9831405668169545f, 0.9831493310154288f, 0.9831580929546785f, 0.9831668526346838f, + 0.9831756100554244f, 0.9831843652168802f, 0.9831931181190311f, 0.9832018687618570f, + 0.9832106171453376f, 0.9832193632694531f, 0.9832281071341833f, 0.9832368487395080f, + 0.9832455880854071f, 0.9832543251718606f, 0.9832630599988486f, 0.9832717925663507f, + 0.9832805228743470f, 0.9832892509228174f, 0.9832979767117419f, 0.9833067002411003f, + 0.9833154215108728f, 0.9833241405210392f, 0.9833328572715794f, 0.9833415717624735f, + 0.9833502839937015f, 0.9833589939652433f, 0.9833677016770788f, 0.9833764071291881f, + 0.9833851103215512f, 0.9833938112541482f, 0.9834025099269588f, 0.9834112063399633f, + 0.9834199004931415f, 0.9834285923864736f, 0.9834372820199396f, 0.9834459693935195f, + 0.9834546545071933f, 0.9834633373609410f, 0.9834720179547428f, 0.9834806962885787f, + 0.9834893723624287f, 0.9834980461762729f, 0.9835067177300914f, 0.9835153870238641f, + 0.9835240540575713f, 0.9835327188311930f, 0.9835413813447093f, 0.9835500415981001f, + 0.9835586995913459f, 0.9835673553244265f, 0.9835760087973220f, 0.9835846600100128f, + 0.9835933089624787f, 0.9836019556546999f, 0.9836106000866567f, 0.9836192422583291f, + 0.9836278821696972f, 0.9836365198207412f, 0.9836451552114412f, 0.9836537883417776f, + 0.9836624192117303f, 0.9836710478212795f, 0.9836796741704054f, 0.9836882982590882f, + 0.9836969200873080f, 0.9837055396550453f, 0.9837141569622798f, 0.9837227720089921f, + 0.9837313847951621f, 0.9837399953207703f, 0.9837486035857966f, 0.9837572095902216f, + 0.9837658133340252f, 0.9837744148171877f, 0.9837830140396896f, 0.9837916110015107f, + 0.9838002057026316f, 0.9838087981430323f, 0.9838173883226932f, 0.9838259762415946f, + 0.9838345618997166f, 0.9838431452970396f, 0.9838517264335439f, 0.9838603053092096f, + 0.9838688819240172f, 0.9838774562779469f, 0.9838860283709789f, 0.9838945982030937f, + 0.9839031657742715f, 0.9839117310844925f, 0.9839202941337373f, 0.9839288549219859f, + 0.9839374134492189f, 0.9839459697154165f, 0.9839545237205590f, 0.9839630754646268f, + 0.9839716249476004f, 0.9839801721694598f, 0.9839887171301857f, 0.9839972598297582f, + 0.9840058002681579f, 0.9840143384453649f, 0.9840228743613599f, 0.9840314080161231f, + 0.9840399394096350f, 0.9840484685418758f, 0.9840569954128261f, 0.9840655200224662f, + 0.9840740423707764f, 0.9840825624577375f, 0.9840910802833295f, 0.9840995958475330f, + 0.9841081091503285f, 0.9841166201916964f, 0.9841251289716171f, 0.9841336354900709f, + 0.9841421397470386f, 0.9841506417425003f, 0.9841591414764368f, 0.9841676389488283f, + 0.9841761341596553f, 0.9841846271088985f, 0.9841931177965382f, 0.9842016062225548f, + 0.9842100923869290f, 0.9842185762896413f, 0.9842270579306720f, 0.9842355373100018f, + 0.9842440144276111f, 0.9842524892834805f, 0.9842609618775905f, 0.9842694322099216f, + 0.9842779002804544f, 0.9842863660891693f, 0.9842948296360470f, 0.9843032909210679f, + 0.9843117499442128f, 0.9843202067054621f, 0.9843286612047962f, 0.9843371134421960f, + 0.9843455634176419f, 0.9843540111311145f, 0.9843624565825945f, 0.9843708997720623f, + 0.9843793406994985f, 0.9843877793648840f, 0.9843962157681990f, 0.9844046499094244f, + 0.9844130817885407f, 0.9844215114055286f, 0.9844299387603687f, 0.9844383638530416f, + 0.9844467866835279f, 0.9844552072518085f, 0.9844636255578636f, 0.9844720416016742f, + 0.9844804553832209f, 0.9844888669024844f, 0.9844972761594452f, 0.9845056831540842f, + 0.9845140878863818f, 0.9845224903563189f, 0.9845308905638762f, 0.9845392885090343f, + 0.9845476841917740f, 0.9845560776120759f, 0.9845644687699208f, 0.9845728576652892f, + 0.9845812442981622f, 0.9845896286685203f, 0.9845980107763442f, 0.9846063906216147f, + 0.9846147682043126f, 0.9846231435244186f, 0.9846315165819134f, 0.9846398873767778f, + 0.9846482559089926f, 0.9846566221785386f, 0.9846649861853963f, 0.9846733479295469f, + 0.9846817074109709f, 0.9846900646296493f, 0.9846984195855626f, 0.9847067722786917f, + 0.9847151227090176f, 0.9847234708765210f, 0.9847318167811827f, 0.9847401604229835f, + 0.9847485018019042f, 0.9847568409179257f, 0.9847651777710289f, 0.9847735123611945f, + 0.9847818446884034f, 0.9847901747526364f, 0.9847985025538745f, 0.9848068280920984f, + 0.9848151513672891f, 0.9848234723794275f, 0.9848317911284943f, 0.9848401076144705f, + 0.9848484218373370f, 0.9848567337970747f, 0.9848650434936644f, 0.9848733509270871f, + 0.9848816560973237f, 0.9848899590043551f, 0.9848982596481621f, 0.9849065580287260f, + 0.9849148541460272f, 0.9849231480000471f, 0.9849314395907663f, 0.9849397289181661f, + 0.9849480159822270f, 0.9849563007829304f, 0.9849645833202570f, 0.9849728635941878f, + 0.9849811416047040f, 0.9849894173517861f, 0.9849976908354156f, 0.9850059620555731f, + 0.9850142310122398f, 0.9850224977053967f, 0.9850307621350247f, 0.9850390243011049f, + 0.9850472842036182f, 0.9850555418425457f, 0.9850637972178685f, 0.9850720503295676f, + 0.9850803011776238f, 0.9850885497620184f, 0.9850967960827324f, 0.9851050401397468f, + 0.9851132819330426f, 0.9851215214626011f, 0.9851297587284030f, 0.9851379937304298f, + 0.9851462264686622f, 0.9851544569430815f, 0.9851626851536687f, 0.9851709111004048f, + 0.9851791347832710f, 0.9851873562022486f, 0.9851955753573184f, 0.9852037922484616f, + 0.9852120068756595f, 0.9852202192388928f, 0.9852284293381431f, 0.9852366371733913f, + 0.9852448427446185f, 0.9852530460518060f, 0.9852612470949349f, 0.9852694458739862f, + 0.9852776423889412f, 0.9852858366397811f, 0.9852940286264870f, 0.9853022183490401f, + 0.9853104058074216f, 0.9853185910016126f, 0.9853267739315943f, 0.9853349545973480f, + 0.9853431329988548f, 0.9853513091360959f, 0.9853594830090527f, 0.9853676546177061f, + 0.9853758239620377f, 0.9853839910420285f, 0.9853921558576596f, 0.9854003184089126f, + 0.9854084786957684f, 0.9854166367182084f, 0.9854247924762140f, 0.9854329459697660f, + 0.9854410971988462f, 0.9854492461634355f, 0.9854573928635154f, 0.9854655372990672f, + 0.9854736794700718f, 0.9854818193765109f, 0.9854899570183657f, 0.9854980923956174f, + 0.9855062255082473f, 0.9855143563562369f, 0.9855224849395673f, 0.9855306112582198f, + 0.9855387353121761f, 0.9855468571014171f, 0.9855549766259243f, 0.9855630938856791f, + 0.9855712088806627f, 0.9855793216108567f, 0.9855874320762422f, 0.9855955402768006f, + 0.9856036462125134f, 0.9856117498833620f, 0.9856198512893275f, 0.9856279504303915f, + 0.9856360473065354f, 0.9856441419177406f, 0.9856522342639884f, 0.9856603243452603f, + 0.9856684121615376f, 0.9856764977128017f, 0.9856845809990342f, 0.9856926620202164f, + 0.9857007407763299f, 0.9857088172673557f, 0.9857168914932757f, 0.9857249634540711f, + 0.9857330331497235f, 0.9857411005802142f, 0.9857491657455248f, 0.9857572286456366f, + 0.9857652892805313f, 0.9857733476501903f, 0.9857814037545949f, 0.9857894575937268f, + 0.9857975091675674f, 0.9858055584760982f, 0.9858136055193008f, 0.9858216502971565f, + 0.9858296928096471f, 0.9858377330567538f, 0.9858457710384584f, 0.9858538067547423f, + 0.9858618402055870f, 0.9858698713909740f, 0.9858779003108852f, 0.9858859269653016f, + 0.9858939513542052f, 0.9859019734775774f, 0.9859099933353997f, 0.9859180109276537f, + 0.9859260262543211f, 0.9859340393153834f, 0.9859420501108221f, 0.9859500586406189f, + 0.9859580649047555f, 0.9859660689032131f, 0.9859740706359738f, 0.9859820701030189f, + 0.9859900673043301f, 0.9859980622398891f, 0.9860060549096773f, 0.9860140453136766f, + 0.9860220334518686f, 0.9860300193242347f, 0.9860380029307568f, 0.9860459842714165f, + 0.9860539633461954f, 0.9860619401550753f, 0.9860699146980376f, 0.9860778869750643f, + 0.9860858569861368f, 0.9860938247312370f, 0.9861017902103464f, 0.9861097534234469f, + 0.9861177143705201f, 0.9861256730515476f, 0.9861336294665113f, 0.9861415836153928f, + 0.9861495354981739f, 0.9861574851148361f, 0.9861654324653615f, 0.9861733775497317f, + 0.9861813203679283f, 0.9861892609199331f, 0.9861971992057279f, 0.9862051352252944f, + 0.9862130689786145f, 0.9862210004656699f, 0.9862289296864423f, 0.9862368566409135f, + 0.9862447813290655f, 0.9862527037508797f, 0.9862606239063382f, 0.9862685417954228f, + 0.9862764574181150f, 0.9862843707743970f, 0.9862922818642503f, 0.9863001906876570f, + 0.9863080972445987f, 0.9863160015350573f, 0.9863239035590146f, 0.9863318033164525f, + 0.9863397008073530f, 0.9863475960316976f, 0.9863554889894685f, 0.9863633796806474f, + 0.9863712681052160f, 0.9863791542631565f, 0.9863870381544506f, 0.9863949197790801f, + 0.9864027991370272f, 0.9864106762282735f, 0.9864185510528010f, 0.9864264236105915f, + 0.9864342939016271f, 0.9864421619258896f, 0.9864500276833610f, 0.9864578911740230f, + 0.9864657523978579f, 0.9864736113548473f, 0.9864814680449734f, 0.9864893224682179f, + 0.9864971746245629f, 0.9865050245139902f, 0.9865128721364821f, 0.9865207174920202f, + 0.9865285605805867f, 0.9865364014021635f, 0.9865442399567326f, 0.9865520762442759f, + 0.9865599102647754f, 0.9865677420182133f, 0.9865755715045714f, 0.9865833987238318f, + 0.9865912236759764f, 0.9865990463609874f, 0.9866068667788467f, 0.9866146849295364f, + 0.9866225008130385f, 0.9866303144293349f, 0.9866381257784078f, 0.9866459348602393f, + 0.9866537416748113f, 0.9866615462221061f, 0.9866693485021055f, 0.9866771485147917f, + 0.9866849462601467f, 0.9866927417381527f, 0.9867005349487916f, 0.9867083258920458f, + 0.9867161145678971f, 0.9867239009763277f, 0.9867316851173198f, 0.9867394669908554f, + 0.9867472465969165f, 0.9867550239354855f, 0.9867627990065444f, 0.9867705718100753f, + 0.9867783423460604f, 0.9867861106144818f, 0.9867938766153217f, 0.9868016403485622f, + 0.9868094018141854f, 0.9868171610121736f, 0.9868249179425090f, 0.9868326726051736f, + 0.9868404250001497f, 0.9868481751274194f, 0.9868559229869650f, 0.9868636685787686f, + 0.9868714119028125f, 0.9868791529590787f, 0.9868868917475497f, 0.9868946282682075f, + 0.9869023625210345f, 0.9869100945060127f, 0.9869178242231245f, 0.9869255516723521f, + 0.9869332768536777f, 0.9869409997670836f, 0.9869487204125521f, 0.9869564387900653f, + 0.9869641548996057f, 0.9869718687411553f, 0.9869795803146966f, 0.9869872896202116f, + 0.9869949966576830f, 0.9870027014270927f, 0.9870104039284232f, 0.9870181041616567f, + 0.9870258021267756f, 0.9870334978237622f, 0.9870411912525987f, 0.9870488824132675f, + 0.9870565713057510f, 0.9870642579300315f, 0.9870719422860912f, 0.9870796243739125f, + 0.9870873041934779f, 0.9870949817447696f, 0.9871026570277700f, 0.9871103300424614f, + 0.9871180007888263f, 0.9871256692668470f, 0.9871333354765057f, 0.9871409994177851f, + 0.9871486610906676f, 0.9871563204951352f, 0.9871639776311706f, 0.9871716324987563f, + 0.9871792850978743f, 0.9871869354285074f, 0.9871945834906379f, 0.9872022292842483f, + 0.9872098728093208f, 0.9872175140658380f, 0.9872251530537824f, 0.9872327897731363f, + 0.9872404242238823f, 0.9872480564060027f, 0.9872556863194800f, 0.9872633139642968f, + 0.9872709393404354f, 0.9872785624478785f, 0.9872861832866082f, 0.9872938018566074f, + 0.9873014181578584f, 0.9873090321903436f, 0.9873166439540457f, 0.9873242534489471f, + 0.9873318606750304f, 0.9873394656322780f, 0.9873470683206726f, 0.9873546687401965f, + 0.9873622668908324f, 0.9873698627725628f, 0.9873774563853701f, 0.9873850477292372f, + 0.9873926368041462f, 0.9874002236100801f, 0.9874078081470211f, 0.9874153904149521f, + 0.9874229704138554f, 0.9874305481437137f, 0.9874381236045096f, 0.9874456967962256f, + 0.9874532677188446f, 0.9874608363723487f, 0.9874684027567209f, 0.9874759668719437f, + 0.9874835287179997f, 0.9874910882948716f, 0.9874986456025419f, 0.9875062006409933f, + 0.9875137534102084f, 0.9875213039101699f, 0.9875288521408605f, 0.9875363981022627f, + 0.9875439417943592f, 0.9875514832171328f, 0.9875590223705661f, 0.9875665592546418f, + 0.9875740938693424f, 0.9875816262146507f, 0.9875891562905496f, 0.9875966840970214f, + 0.9876042096340492f, 0.9876117329016153f, 0.9876192538997027f, 0.9876267726282941f, + 0.9876342890873722f, 0.9876418032769196f, 0.9876493151969192f, 0.9876568248473536f, + 0.9876643322282057f, 0.9876718373394582f, 0.9876793401810936f, 0.9876868407530951f, + 0.9876943390554451f, 0.9877018350881265f, 0.9877093288511222f, 0.9877168203444147f, + 0.9877243095679870f, 0.9877317965218219f, 0.9877392812059020f, 0.9877467636202103f, + 0.9877542437647295f, 0.9877617216394425f, 0.9877691972443321f, 0.9877766705793810f, + 0.9877841416445722f, 0.9877916104398884f, 0.9877990769653124f, 0.9878065412208271f, + 0.9878140032064155f, 0.9878214629220603f, 0.9878289203677444f, 0.9878363755434506f, + 0.9878438284491617f, 0.9878512790848608f, 0.9878587274505307f, 0.9878661735461542f, + 0.9878736173717142f, 0.9878810589271937f, 0.9878884982125755f, 0.9878959352278426f, + 0.9879033699729778f, 0.9879108024479640f, 0.9879182326527842f, 0.9879256605874214f, + 0.9879330862518584f, 0.9879405096460782f, 0.9879479307700636f, 0.9879553496237977f, + 0.9879627662072634f, 0.9879701805204438f, 0.9879775925633216f, 0.9879850023358800f, + 0.9879924098381019f, 0.9879998150699701f, 0.9880072180314678f, 0.9880146187225780f, + 0.9880220171432835f, 0.9880294132935675f, 0.9880368071734129f, 0.9880441987828028f, + 0.9880515881217201f, 0.9880589751901478f, 0.9880663599880690f, 0.9880737425154668f, + 0.9880811227723241f, 0.9880885007586240f, 0.9880958764743496f, 0.9881032499194838f, + 0.9881106210940098f, 0.9881179899979106f, 0.9881253566311693f, 0.9881327209937689f, + 0.9881400830856926f, 0.9881474429069232f, 0.9881548004574442f, 0.9881621557372384f, + 0.9881695087462891f, 0.9881768594845792f, 0.9881842079520919f, 0.9881915541488103f, + 0.9881988980747176f, 0.9882062397297968f, 0.9882135791140311f, 0.9882209162274036f, + 0.9882282510698974f, 0.9882355836414959f, 0.9882429139421819f, 0.9882502419719387f, + 0.9882575677307495f, 0.9882648912185974f, 0.9882722124354657f, 0.9882795313813374f, + 0.9882868480561957f, 0.9882941624600240f, 0.9883014745928053f, 0.9883087844545227f, + 0.9883160920451598f, 0.9883233973646993f, 0.9883307004131248f, 0.9883380011904194f, + 0.9883452996965661f, 0.9883525959315486f, 0.9883598898953497f, 0.9883671815879529f, + 0.9883744710093413f, 0.9883817581594981f, 0.9883890430384068f, 0.9883963256460504f, + 0.9884036059824124f, 0.9884108840474758f, 0.9884181598412242f, 0.9884254333636405f, + 0.9884327046147083f, 0.9884399735944108f, 0.9884472403027312f, 0.9884545047396529f, + 0.9884617669051593f, 0.9884690267992334f, 0.9884762844218589f, 0.9884835397730188f, + 0.9884907928526966f, 0.9884980436608757f, 0.9885052921975392f, 0.9885125384626706f, + 0.9885197824562533f, 0.9885270241782704f, 0.9885342636287057f, 0.9885415008075421f, + 0.9885487357147632f, 0.9885559683503524f, 0.9885631987142930f, 0.9885704268065684f, + 0.9885776526271620f, 0.9885848761760573f, 0.9885920974532375f, 0.9885993164586860f, + 0.9886065331923864f, 0.9886137476543222f, 0.9886209598444764f, 0.9886281697628329f, + 0.9886353774093748f, 0.9886425827840856f, 0.9886497858869489f, 0.9886569867179479f, + 0.9886641852770663f, 0.9886713815642874f, 0.9886785755795947f, 0.9886857673229718f, + 0.9886929567944019f, 0.9887001439938687f, 0.9887073289213556f, 0.9887145115768461f, + 0.9887216919603238f, 0.9887288700717720f, 0.9887360459111744f, 0.9887432194785143f, + 0.9887503907737754f, 0.9887575597969411f, 0.9887647265479950f, 0.9887718910269206f, + 0.9887790532337015f, 0.9887862131683212f, 0.9887933708307632f, 0.9888005262210111f, + 0.9888076793390485f, 0.9888148301848587f, 0.9888219787584257f, 0.9888291250597327f, + 0.9888362690887635f, 0.9888434108455016f, 0.9888505503299306f, 0.9888576875420341f, + 0.9888648224817956f, 0.9888719551491990f, 0.9888790855442275f, 0.9888862136668650f, + 0.9888933395170951f, 0.9889004630949013f, 0.9889075844002673f, 0.9889147034331768f, + 0.9889218201936132f, 0.9889289346815605f, 0.9889360468970021f, 0.9889431568399216f, + 0.9889502645103030f, 0.9889573699081297f, 0.9889644730333853f, 0.9889715738860537f, + 0.9889786724661185f, 0.9889857687735634f, 0.9889928628083720f, 0.9889999545705280f, + 0.9890070440600153f, 0.9890141312768175f, 0.9890212162209181f, 0.9890282988923011f, + 0.9890353792909503f, 0.9890424574168490f, 0.9890495332699815f, 0.9890566068503310f, + 0.9890636781578815f, 0.9890707471926169f, 0.9890778139545207f, 0.9890848784435767f, + 0.9890919406597688f, 0.9890990006030806f, 0.9891060582734960f, 0.9891131136709987f, + 0.9891201667955727f, 0.9891272176472015f, 0.9891342662258691f, 0.9891413125315591f, + 0.9891483565642556f, 0.9891553983239422f, 0.9891624378106026f, 0.9891694750242210f, + 0.9891765099647810f, 0.9891835426322664f, 0.9891905730266611f, 0.9891976011479489f, + 0.9892046269961138f, 0.9892116505711395f, 0.9892186718730098f, 0.9892256909017088f, + 0.9892327076572200f, 0.9892397221395278f, 0.9892467343486157f, 0.9892537442844677f, + 0.9892607519470676f, 0.9892677573363994f, 0.9892747604524470f, 0.9892817612951943f, + 0.9892887598646252f, 0.9892957561607235f, 0.9893027501834734f, 0.9893097419328585f, + 0.9893167314088630f, 0.9893237186114706f, 0.9893307035406655f, 0.9893376861964315f, + 0.9893446665787526f, 0.9893516446876127f, 0.9893586205229958f, 0.9893655940848859f, + 0.9893725653732670f, 0.9893795343881230f, 0.9893865011294378f, 0.9893934655971957f, + 0.9894004277913804f, 0.9894073877119760f, 0.9894143453589664f, 0.9894213007323359f, + 0.9894282538320683f, 0.9894352046581476f, 0.9894421532105580f, 0.9894490994892833f, + 0.9894560434943077f, 0.9894629852256152f, 0.9894699246831898f, 0.9894768618670157f, + 0.9894837967770768f, 0.9894907294133573f, 0.9894976597758410f, 0.9895045878645123f, + 0.9895115136793552f, 0.9895184372203537f, 0.9895253584874919f, 0.9895322774807540f, + 0.9895391942001239f, 0.9895461086455859f, 0.9895530208171240f, 0.9895599307147224f, + 0.9895668383383651f, 0.9895737436880364f, 0.9895806467637203f, 0.9895875475654009f, + 0.9895944460930625f, 0.9896013423466891f, 0.9896082363262649f, 0.9896151280317741f, + 0.9896220174632008f, 0.9896289046205293f, 0.9896357895037435f, 0.9896426721128280f, + 0.9896495524477665f, 0.9896564305085436f, 0.9896633062951432f, 0.9896701798075497f, + 0.9896770510457472f, 0.9896839200097199f, 0.9896907866994522f, 0.9896976511149280f, + 0.9897045132561318f, 0.9897113731230477f, 0.9897182307156600f, 0.9897250860339529f, + 0.9897319390779106f, 0.9897387898475174f, 0.9897456383427576f, 0.9897524845636155f, + 0.9897593285100752f, 0.9897661701821211f, 0.9897730095797375f, 0.9897798467029086f, + 0.9897866815516186f, 0.9897935141258520f, 0.9898003444255932f, 0.9898071724508261f, + 0.9898139982015353f, 0.9898208216777049f, 0.9898276428793195f, 0.9898344618063633f, + 0.9898412784588205f, 0.9898480928366756f, 0.9898549049399129f, 0.9898617147685168f, + 0.9898685223224716f, 0.9898753276017616f, 0.9898821306063712f, 0.9898889313362847f, + 0.9898957297914867f, 0.9899025259719613f, 0.9899093198776930f, 0.9899161115086663f, + 0.9899229008648655f, 0.9899296879462749f, 0.9899364727528791f, 0.9899432552846623f, + 0.9899500355416090f, 0.9899568135237037f, 0.9899635892309308f, 0.9899703626632745f, + 0.9899771338207196f, 0.9899839027032503f, 0.9899906693108511f, 0.9899974336435066f, + 0.9900041957012009f, 0.9900109554839188f, 0.9900177129916446f, 0.9900244682243629f, + 0.9900312211820580f, 0.9900379718647144f, 0.9900447202723168f, 0.9900514664048495f, + 0.9900582102622971f, 0.9900649518446440f, 0.9900716911518748f, 0.9900784281839740f, + 0.9900851629409260f, 0.9900918954227155f, 0.9900986256293269f, 0.9901053535607448f, + 0.9901120792169538f, 0.9901188025979383f, 0.9901255237036829f, 0.9901322425341721f, + 0.9901389590893906f, 0.9901456733693229f, 0.9901523853739537f, 0.9901590951032673f, + 0.9901658025572484f, 0.9901725077358816f, 0.9901792106391516f, 0.9901859112670429f, + 0.9901926096195400f, 0.9901993056966277f, 0.9902059994982906f, 0.9902126910245131f, + 0.9902193802752800f, 0.9902260672505759f, 0.9902327519503855f, 0.9902394343746933f, + 0.9902461145234840f, 0.9902527923967424f, 0.9902594679944529f, 0.9902661413166002f, + 0.9902728123631691f, 0.9902794811341442f, 0.9902861476295103f, 0.9902928118492518f, + 0.9902994737933536f, 0.9903061334618004f, 0.9903127908545768f, 0.9903194459716675f, + 0.9903260988130573f, 0.9903327493787309f, 0.9903393976686730f, 0.9903460436828683f, + 0.9903526874213013f, 0.9903593288839573f, 0.9903659680708204f, 0.9903726049818758f, + 0.9903792396171082f, 0.9903858719765021f, 0.9903925020600424f, 0.9903991298677138f, + 0.9904057553995013f, 0.9904123786553894f, 0.9904189996353631f, 0.9904256183394070f, + 0.9904322347675060f, 0.9904388489196448f, 0.9904454607958083f, 0.9904520703959814f, + 0.9904586777201486f, 0.9904652827682950f, 0.9904718855404053f, 0.9904784860364644f, + 0.9904850842564571f, 0.9904916802003682f, 0.9904982738681825f, 0.9905048652598849f, + 0.9905114543754603f, 0.9905180412148935f, 0.9905246257781695f, 0.9905312080652728f, + 0.9905377880761888f, 0.9905443658109020f, 0.9905509412693975f, 0.9905575144516598f, + 0.9905640853576744f, 0.9905706539874257f, 0.9905772203408989f, 0.9905837844180787f, + 0.9905903462189501f, 0.9905969057434981f, 0.9906034629917077f, 0.9906100179635634f, + 0.9906165706590506f, 0.9906231210781541f, 0.9906296692208587f, 0.9906362150871496f, + 0.9906427586770116f, 0.9906492999904296f, 0.9906558390273887f, 0.9906623757878739f, + 0.9906689102718700f, 0.9906754424793622f, 0.9906819724103354f, 0.9906885000647745f, + 0.9906950254426646f, 0.9907015485439907f, 0.9907080693687379f, 0.9907145879168909f, + 0.9907211041884352f, 0.9907276181833554f, 0.9907341299016367f, 0.9907406393432641f, + 0.9907471465082227f, 0.9907536513964975f, 0.9907601540080736f, 0.9907666543429360f, + 0.9907731524010698f, 0.9907796481824601f, 0.9907861416870919f, 0.9907926329149502f, + 0.9907991218660204f, 0.9908056085402872f, 0.9908120929377360f, 0.9908185750583517f, + 0.9908250549021195f, 0.9908315324690244f, 0.9908380077590517f, 0.9908444807721863f, + 0.9908509515084136f, 0.9908574199677186f, 0.9908638861500862f, 0.9908703500555019f, + 0.9908768116839508f, 0.9908832710354177f, 0.9908897281098882f, 0.9908961829073473f, + 0.9909026354277800f, 0.9909090856711716f, 0.9909155336375075f, 0.9909219793267725f, + 0.9909284227389520f, 0.9909348638740311f, 0.9909413027319951f, 0.9909477393128292f, + 0.9909541736165185f, 0.9909606056430482f, 0.9909670353924038f, 0.9909734628645702f, + 0.9909798880595327f, 0.9909863109772767f, 0.9909927316177873f, 0.9909991499810498f, + 0.9910055660670494f, 0.9910119798757713f, 0.9910183914072009f, 0.9910248006613235f, + 0.9910312076381241f, 0.9910376123375882f, 0.9910440147597012f, 0.9910504149044481f, + 0.9910568127718143f, 0.9910632083617853f, 0.9910696016743460f, 0.9910759927094821f, + 0.9910823814671786f, 0.9910887679474211f, 0.9910951521501947f, 0.9911015340754848f, + 0.9911079137232768f, 0.9911142910935560f, 0.9911206661863078f, 0.9911270390015173f, + 0.9911334095391702f, 0.9911397777992517f, 0.9911461437817470f, 0.9911525074866419f, + 0.9911588689139214f, 0.9911652280635710f, 0.9911715849355760f, 0.9911779395299219f, + 0.9911842918465942f, 0.9911906418855781f, 0.9911969896468591f, 0.9912033351304226f, + 0.9912096783362541f, 0.9912160192643388f, 0.9912223579146623f, 0.9912286942872101f, + 0.9912350283819674f, 0.9912413601989200f, 0.9912476897380529f, 0.9912540169993519f, + 0.9912603419828024f, 0.9912666646883898f, 0.9912729851160995f, 0.9912793032659172f, + 0.9912856191378282f, 0.9912919327318180f, 0.9912982440478721f, 0.9913045530859761f, + 0.9913108598461154f, 0.9913171643282755f, 0.9913234665324420f, 0.9913297664586004f, + 0.9913360641067361f, 0.9913423594768347f, 0.9913486525688818f, 0.9913549433828629f, + 0.9913612319187635f, 0.9913675181765692f, 0.9913738021562655f, 0.9913800838578380f, + 0.9913863632812723f, 0.9913926404265540f, 0.9913989152936684f, 0.9914051878826015f, + 0.9914114581933385f, 0.9914177262258653f, 0.9914239919801673f, 0.9914302554562301f, + 0.9914365166540394f, 0.9914427755735808f, 0.9914490322148399f, 0.9914552865778024f, + 0.9914615386624538f, 0.9914677884687797f, 0.9914740359967659f, 0.9914802812463979f, + 0.9914865242176615f, 0.9914927649105422f, 0.9914990033250257f, 0.9915052394610978f, + 0.9915114733187439f, 0.9915177048979500f, 0.9915239341987016f, 0.9915301612209843f, + 0.9915363859647839f, 0.9915426084300861f, 0.9915488286168765f, 0.9915550465251410f, + 0.9915612621548653f, 0.9915674755060349f, 0.9915736865786356f, 0.9915798953726532f, + 0.9915861018880735f, 0.9915923061248820f, 0.9915985080830647f, 0.9916047077626072f, + 0.9916109051634954f, 0.9916171002857148f, 0.9916232931292512f, 0.9916294836940908f, + 0.9916356719802187f, 0.9916418579876213f, 0.9916480417162840f, 0.9916542231661927f, + 0.9916604023373332f, 0.9916665792296914f, 0.9916727538432529f, 0.9916789261780037f, + 0.9916850962339295f, 0.9916912640110161f, 0.9916974295092494f, 0.9917035927286153f, + 0.9917097536690995f, 0.9917159123306879f, 0.9917220687133663f, 0.9917282228171207f, + 0.9917343746419368f, 0.9917405241878006f, 0.9917466714546977f, 0.9917528164426144f, + 0.9917589591515361f, 0.9917650995814491f, 0.9917712377323390f, 0.9917773736041918f, + 0.9917835071969935f, 0.9917896385107299f, 0.9917957675453869f, 0.9918018943009504f, + 0.9918080187774064f, 0.9918141409747409f, 0.9918202608929396f, 0.9918263785319885f, + 0.9918324938918738f, 0.9918386069725811f, 0.9918447177740964f, 0.9918508262964060f, + 0.9918569325394955f, 0.9918630365033509f, 0.9918691381879583f, 0.9918752375933038f, + 0.9918813347193730f, 0.9918874295661523f, 0.9918935221336274f, 0.9918996124217844f, + 0.9919057004306093f, 0.9919117861600882f, 0.9919178696102070f, 0.9919239507809517f, + 0.9919300296723085f, 0.9919361062842632f, 0.9919421806168021f, 0.9919482526699109f, + 0.9919543224435760f, 0.9919603899377832f, 0.9919664551525187f, 0.9919725180877684f, + 0.9919785787435186f, 0.9919846371197553f, 0.9919906932164644f, 0.9919967470336321f, + 0.9920027985712445f, 0.9920088478292878f, 0.9920148948077480f, 0.9920209395066111f, + 0.9920269819258634f, 0.9920330220654908f, 0.9920390599254796f, 0.9920450955058159f, + 0.9920511288064857f, 0.9920571598274753f, 0.9920631885687708f, 0.9920692150303584f, + 0.9920752392122241f, 0.9920812611143541f, 0.9920872807367346f, 0.9920932980793518f, + 0.9920993131421918f, 0.9921053259252408f, 0.9921113364284849f, 0.9921173446519106f, + 0.9921233505955037f, 0.9921293542592506f, 0.9921353556431376f, 0.9921413547471506f, + 0.9921473515712761f, 0.9921533461155002f, 0.9921593383798092f, 0.9921653283641892f, + 0.9921713160686265f, 0.9921773014931075f, 0.9921832846376182f, 0.9921892655021449f, + 0.9921952440866739f, 0.9922012203911915f, 0.9922071944156839f, 0.9922131661601374f, + 0.9922191356245385f, 0.9922251028088730f, 0.9922310677131275f, 0.9922370303372884f, + 0.9922429906813417f, 0.9922489487452738f, 0.9922549045290712f, 0.9922608580327199f, + 0.9922668092562066f, 0.9922727581995172f, 0.9922787048626384f, 0.9922846492455563f, + 0.9922905913482574f, 0.9922965311707278f, 0.9923024687129541f, 0.9923084039749226f, + 0.9923143369566196f, 0.9923202676580315f, 0.9923261960791447f, 0.9923321222199455f, + 0.9923380460804204f, 0.9923439676605557f, 0.9923498869603377f, 0.9923558039797530f, + 0.9923617187187879f, 0.9923676311774288f, 0.9923735413556620f, 0.9923794492534742f, + 0.9923853548708517f, 0.9923912582077808f, 0.9923971592642481f, 0.9924030580402400f, + 0.9924089545357428f, 0.9924148487507432f, 0.9924207406852275f, 0.9924266303391821f, + 0.9924325177125936f, 0.9924384028054485f, 0.9924442856177330f, 0.9924501661494340f, + 0.9924560444005377f, 0.9924619203710306f, 0.9924677940608994f, 0.9924736654701303f, + 0.9924795345987100f, 0.9924854014466250f, 0.9924912660138618f, 0.9924971283004069f, + 0.9925029883062469f, 0.9925088460313682f, 0.9925147014757576f, 0.9925205546394014f, + 0.9925264055222861f, 0.9925322541243985f, 0.9925381004457250f, 0.9925439444862522f, + 0.9925497862459666f, 0.9925556257248549f, 0.9925614629229037f, 0.9925672978400994f, + 0.9925731304764288f, 0.9925789608318784f, 0.9925847889064348f, 0.9925906147000845f, + 0.9925964382128143f, 0.9926022594446108f, 0.9926080783954604f, 0.9926138950653500f, + 0.9926197094542661f, 0.9926255215621955f, 0.9926313313891246f, 0.9926371389350401f, + 0.9926429441999288f, 0.9926487471837773f, 0.9926545478865723f, 0.9926603463083002f, + 0.9926661424489480f, 0.9926719363085023f, 0.9926777278869496f, 0.9926835171842769f, + 0.9926893042004707f, 0.9926950889355177f, 0.9927008713894048f, 0.9927066515621185f, + 0.9927124294536455f, 0.9927182050639726f, 0.9927239783930866f, 0.9927297494409740f, + 0.9927355182076218f, 0.9927412846930167f, 0.9927470488971454f, 0.9927528108199946f, + 0.9927585704615511f, 0.9927643278218017f, 0.9927700829007331f, 0.9927758356983322f, + 0.9927815862145857f, 0.9927873344494802f, 0.9927930804030028f, 0.9927988240751402f, + 0.9928045654658791f, 0.9928103045752065f, 0.9928160414031090f, 0.9928217759495734f, + 0.9928275082145868f, 0.9928332381981358f, 0.9928389659002073f, 0.9928446913207881f, + 0.9928504144598651f, 0.9928561353174251f, 0.9928618538934549f, 0.9928675701879416f, + 0.9928732842008717f, 0.9928789959322325f, 0.9928847053820105f, 0.9928904125501927f, + 0.9928961174367660f, 0.9929018200417173f, 0.9929075203650336f, 0.9929132184067015f, + 0.9929189141667083f, 0.9929246076450406f, 0.9929302988416855f, 0.9929359877566298f, + 0.9929416743898605f, 0.9929473587413644f, 0.9929530408111287f, 0.9929587205991401f, + 0.9929643981053856f, 0.9929700733298523f, 0.9929757462725270f, 0.9929814169333967f, + 0.9929870853124484f, 0.9929927514096691f, 0.9929984152250456f, 0.9930040767585652f, + 0.9930097360102146f, 0.9930153929799809f, 0.9930210476678512f, 0.9930267000738123f, + 0.9930323501978514f, 0.9930379980399554f, 0.9930436436001113f, 0.9930492868783063f, + 0.9930549278745273f, 0.9930605665887614f, 0.9930662030209955f, 0.9930718371712168f, + 0.9930774690394123f, 0.9930830986255691f, 0.9930887259296741f, 0.9930943509517146f, + 0.9930999736916776f, 0.9931055941495500f, 0.9931112123253191f, 0.9931168282189720f, + 0.9931224418304956f, 0.9931280531598772f, 0.9931336622071038f, 0.9931392689721624f, + 0.9931448734550404f, 0.9931504756557247f, 0.9931560755742026f, 0.9931616732104610f, + 0.9931672685644872f, 0.9931728616362683f, 0.9931784524257915f, 0.9931840409330439f, + 0.9931896271580126f, 0.9931952111006849f, 0.9932007927610479f, 0.9932063721390887f, + 0.9932119492347945f, 0.9932175240481527f, 0.9932230965791502f, 0.9932286668277743f, + 0.9932342347940123f, 0.9932398004778512f, 0.9932453638792784f, 0.9932509249982812f, + 0.9932564838348464f, 0.9932620403889617f, 0.9932675946606140f, 0.9932731466497907f, + 0.9932786963564790f, 0.9932842437806662f, 0.9932897889223394f, 0.9932953317814860f, + 0.9933008723580933f, 0.9933064106521484f, 0.9933119466636388f, 0.9933174803925514f, + 0.9933230118388739f, 0.9933285410025934f, 0.9933340678836972f, 0.9933395924821726f, + 0.9933451147980069f, 0.9933506348311875f, 0.9933561525817015f, 0.9933616680495365f, + 0.9933671812346796f, 0.9933726921371182f, 0.9933782007568397f, 0.9933837070938314f, + 0.9933892111480807f, 0.9933947129195748f, 0.9934002124083011f, 0.9934057096142471f, + 0.9934112045374001f, 0.9934166971777474f, 0.9934221875352764f, 0.9934276756099747f, + 0.9934331614018294f, 0.9934386449108279f, 0.9934441261369578f, 0.9934496050802063f, + 0.9934550817405610f, 0.9934605561180092f, 0.9934660282125384f, 0.9934714980241359f, + 0.9934769655527892f, 0.9934824307984857f, 0.9934878937612130f, 0.9934933544409584f, + 0.9934988128377094f, 0.9935042689514534f, 0.9935097227821778f, 0.9935151743298702f, + 0.9935206235945181f, 0.9935260705761089f, 0.9935315152746301f, 0.9935369576900692f, + 0.9935423978224137f, 0.9935478356716509f, 0.9935532712377687f, 0.9935587045207543f, + 0.9935641355205953f, 0.9935695642372793f, 0.9935749906707937f, 0.9935804148211260f, + 0.9935858366882639f, 0.9935912562721949f, 0.9935966735729065f, 0.9936020885903861f, + 0.9936075013246216f, 0.9936129117756003f, 0.9936183199433098f, 0.9936237258277377f, + 0.9936291294288717f, 0.9936345307466993f, 0.9936399297812080f, 0.9936453265323854f, + 0.9936507210002191f, 0.9936561131846969f, 0.9936615030858061f, 0.9936668907035348f, + 0.9936722760378700f, 0.9936776590887997f, 0.9936830398563115f, 0.9936884183403929f, + 0.9936937945410317f, 0.9936991684582155f, 0.9937045400919319f, 0.9937099094421686f, + 0.9937152765089132f, 0.9937206412921534f, 0.9937260037918770f, 0.9937313640080715f, + 0.9937367219407246f, 0.9937420775898241f, 0.9937474309553576f, 0.9937527820373128f, + 0.9937581308356774f, 0.9937634773504392f, 0.9937688215815859f, 0.9937741635291051f, + 0.9937795031929846f, 0.9937848405732120f, 0.9937901756697753f, 0.9937955084826621f, + 0.9938008390118601f, 0.9938061672573572f, 0.9938114932191409f, 0.9938168168971991f, + 0.9938221382915197f, 0.9938274574020902f, 0.9938327742288987f, 0.9938380887719327f, + 0.9938434010311802f, 0.9938487110066287f, 0.9938540186982664f, 0.9938593241060808f, + 0.9938646272300597f, 0.9938699280701911f, 0.9938752266264628f, 0.9938805228988625f, + 0.9938858168873781f, 0.9938911085919974f, 0.9938963980127082f, 0.9939016851494985f, + 0.9939069700023561f, 0.9939122525712687f, 0.9939175328562243f, 0.9939228108572107f, + 0.9939280865742158f, 0.9939333600072277f, 0.9939386311562338f, 0.9939439000212223f, + 0.9939491666021811f, 0.9939544308990982f, 0.9939596929119612f, 0.9939649526407581f, + 0.9939702100854769f, 0.9939754652461056f, 0.9939807181226319f, 0.9939859687150439f, + 0.9939912170233294f, 0.9939964630474765f, 0.9940017067874730f, 0.9940069482433069f, + 0.9940121874149662f, 0.9940174243024389f, 0.9940226589057128f, 0.9940278912247760f, + 0.9940331212596164f, 0.9940383490102220f, 0.9940435744765810f, 0.9940487976586810f, + 0.9940540185565102f, 0.9940592371700567f, 0.9940644534993084f, 0.9940696675442533f, + 0.9940748793048794f, 0.9940800887811748f, 0.9940852959731274f, 0.9940905008807255f, + 0.9940957035039569f, 0.9941009038428097f, 0.9941061018972720f, 0.9941112976673318f, + 0.9941164911529771f, 0.9941216823541961f, 0.9941268712709768f, 0.9941320579033073f, + 0.9941372422511757f, 0.9941424243145700f, 0.9941476040934785f, 0.9941527815878889f, + 0.9941579567977897f, 0.9941631297231689f, 0.9941683003640145f, 0.9941734687203146f, + 0.9941786347920576f, 0.9941837985792312f, 0.9941889600818240f, 0.9941941192998238f, + 0.9941992762332189f, 0.9942044308819974f, 0.9942095832461475f, 0.9942147333256572f, + 0.9942198811205150f, 0.9942250266307087f, 0.9942301698562266f, 0.9942353107970570f, + 0.9942404494531879f, 0.9942455858246078f, 0.9942507199113044f, 0.9942558517132665f, + 0.9942609812304818f, 0.9942661084629387f, 0.9942712334106255f, 0.9942763560735304f, + 0.9942814764516416f, 0.9942865945449472f, 0.9942917103534356f, 0.9942968238770949f, + 0.9943019351159136f, 0.9943070440698797f, 0.9943121507389816f, 0.9943172551232076f, + 0.9943223572225458f, 0.9943274570369847f, 0.9943325545665123f, 0.9943376498111171f, + 0.9943427427707873f, 0.9943478334455113f, 0.9943529218352772f, 0.9943580079400736f, + 0.9943630917598886f, 0.9943681732947105f, 0.9943732525445278f, 0.9943783295093287f, + 0.9943834041891014f, 0.9943884765838346f, 0.9943935466935163f, 0.9943986145181350f, + 0.9944036800576791f, 0.9944087433121368f, 0.9944138042814966f, 0.9944188629657469f, + 0.9944239193648760f, 0.9944289734788723f, 0.9944340253077241f, 0.9944390748514199f, + 0.9944441221099480f, 0.9944491670832969f, 0.9944542097714550f, 0.9944592501744107f, + 0.9944642882921524f, 0.9944693241246685f, 0.9944743576719475f, 0.9944793889339777f, + 0.9944844179107476f, 0.9944894446022458f, 0.9944944690084605f, 0.9944994911293803f, + 0.9945045109649936f, 0.9945095285152890f, 0.9945145437802548f, 0.9945195567598795f, + 0.9945245674541517f, 0.9945295758630598f, 0.9945345819865922f, 0.9945395858247376f, + 0.9945445873774843f, 0.9945495866448210f, 0.9945545836267360f, 0.9945595783232180f, + 0.9945645707342554f, 0.9945695608598368f, 0.9945745486999508f, 0.9945795342545858f, + 0.9945845175237303f, 0.9945894985073731f, 0.9945944772055025f, 0.9945994536181072f, + 0.9946044277451757f, 0.9946093995866966f, 0.9946143691426584f, 0.9946193364130498f, + 0.9946243013978594f, 0.9946292640970756f, 0.9946342245106872f, 0.9946391826386827f, + 0.9946441384810507f, 0.9946490920377798f, 0.9946540433088588f, 0.9946589922942760f, + 0.9946639389940204f, 0.9946688834080802f, 0.9946738255364445f, 0.9946787653791016f, + 0.9946837029360402f, 0.9946886382072492f, 0.9946935711927170f, 0.9946985018924324f, + 0.9947034303063839f, 0.9947083564345602f, 0.9947132802769503f, 0.9947182018335425f, + 0.9947231211043257f, 0.9947280380892886f, 0.9947329527884198f, 0.9947378652017080f, + 0.9947427753291420f, 0.9947476831707104f, 0.9947525887264020f, 0.9947574919962057f, + 0.9947623929801099f, 0.9947672916781035f, 0.9947721880901753f, 0.9947770822163140f, + 0.9947819740565083f, 0.9947868636107470f, 0.9947917508790188f, 0.9947966358613126f, + 0.9948015185576171f, 0.9948063989679211f, 0.9948112770922134f, 0.9948161529304826f, + 0.9948210264827179f, 0.9948258977489077f, 0.9948307667290410f, 0.9948356334231065f, + 0.9948404978310932f, 0.9948453599529898f, 0.9948502197887852f, 0.9948550773384680f, + 0.9948599326020273f, 0.9948647855794519f, 0.9948696362707306f, 0.9948744846758522f, + 0.9948793307948056f, 0.9948841746275797f, 0.9948890161741634f, 0.9948938554345454f, + 0.9948986924087149f, 0.9949035270966604f, 0.9949083594983711f, 0.9949131896138357f, + 0.9949180174430432f, 0.9949228429859824f, 0.9949276662426424f, 0.9949324872130120f, + 0.9949373058970801f, 0.9949421222948356f, 0.9949469364062675f, 0.9949517482313648f, + 0.9949565577701164f, 0.9949613650225111f, 0.9949661699885379f, 0.9949709726681860f, + 0.9949757730614441f, 0.9949805711683013f, 0.9949853669887465f, 0.9949901605227688f, + 0.9949949517703570f, 0.9949997407315002f, 0.9950045274061874f, 0.9950093117944075f, + 0.9950140938961497f, 0.9950188737114029f, 0.9950236512401561f, 0.9950284264823983f, + 0.9950331994381186f, 0.9950379701073060f, 0.9950427384899495f, 0.9950475045860382f, + 0.9950522683955612f, 0.9950570299185073f, 0.9950617891548658f, 0.9950665461046257f, + 0.9950713007677762f, 0.9950760531443060f, 0.9950808032342047f, 0.9950855510374609f, + 0.9950902965540640f, 0.9950950397840029f, 0.9950997807272668f, 0.9951045193838449f, + 0.9951092557537261f, 0.9951139898368997f, 0.9951187216333547f, 0.9951234511430802f, + 0.9951281783660655f, 0.9951329033022996f, 0.9951376259517718f, 0.9951423463144710f, + 0.9951470643903865f, 0.9951517801795075f, 0.9951564936818230f, 0.9951612048973224f, + 0.9951659138259946f, 0.9951706204678290f, 0.9951753248228148f, 0.9951800268909410f, + 0.9951847266721969f, 0.9951894241665716f, 0.9951941193740546f, 0.9951988122946348f, + 0.9952035029283015f, 0.9952081912750440f, 0.9952128773348515f, 0.9952175611077132f, + 0.9952222425936182f, 0.9952269217925561f, 0.9952315987045158f, 0.9952362733294867f, + 0.9952409456674581f, 0.9952456157184192f, 0.9952502834823592f, 0.9952549489592675f, + 0.9952596121491334f, 0.9952642730519460f, 0.9952689316676947f, 0.9952735879963688f, + 0.9952782420379577f, 0.9952828937924505f, 0.9952875432598366f, 0.9952921904401054f, + 0.9952968353332461f, 0.9953014779392481f, 0.9953061182581007f, 0.9953107562897933f, + 0.9953153920343151f, 0.9953200254916555f, 0.9953246566618040f, 0.9953292855447498f, + 0.9953339121404823f, 0.9953385364489908f, 0.9953431584702649f, 0.9953477782042937f, + 0.9953523956510668f, 0.9953570108105735f, 0.9953616236828031f, 0.9953662342677451f, + 0.9953708425653890f, 0.9953754485757240f, 0.9953800522987397f, 0.9953846537344254f, + 0.9953892528827707f, 0.9953938497437648f, 0.9953984443173972f, 0.9954030366036575f, + 0.9954076266025349f, 0.9954122143140191f, 0.9954167997380994f, 0.9954213828747652f, + 0.9954259637240062f, 0.9954305422858117f, 0.9954351185601712f, 0.9954396925470743f, + 0.9954442642465103f, 0.9954488336584688f, 0.9954534007829393f, 0.9954579656199114f, + 0.9954625281693744f, 0.9954670884313179f, 0.9954716464057315f, 0.9954762020926047f, + 0.9954807554919269f, 0.9954853066036878f, 0.9954898554278769f, 0.9954944019644837f, + 0.9954989462134978f, 0.9955034881749086f, 0.9955080278487060f, 0.9955125652348793f, + 0.9955171003334181f, 0.9955216331443120f, 0.9955261636675506f, 0.9955306919031236f, + 0.9955352178510204f, 0.9955397415112307f, 0.9955442628837440f, 0.9955487819685501f, + 0.9955532987656385f, 0.9955578132749988f, 0.9955623254966207f, 0.9955668354304938f, + 0.9955713430766078f, 0.9955758484349522f, 0.9955803515055166f, 0.9955848522882910f, + 0.9955893507832646f, 0.9955938469904274f, 0.9955983409097690f, 0.9956028325412790f, + 0.9956073218849470f, 0.9956118089407630f, 0.9956162937087163f, 0.9956207761887969f, + 0.9956252563809943f, 0.9956297342852983f, 0.9956342099016986f, 0.9956386832301849f, + 0.9956431542707469f, 0.9956476230233744f, 0.9956520894880571f, 0.9956565536647847f, + 0.9956610155535469f, 0.9956654751543336f, 0.9956699324671344f, 0.9956743874919392f, + 0.9956788402287375f, 0.9956832906775194f, 0.9956877388382745f, 0.9956921847109926f, + 0.9956966282956635f, 0.9957010695922769f, 0.9957055086008227f, 0.9957099453212908f, + 0.9957143797536706f, 0.9957188118979524f, 0.9957232417541257f, 0.9957276693221805f, + 0.9957320946021064f, 0.9957365175938935f, 0.9957409382975314f, 0.9957453567130101f, + 0.9957497728403194f, 0.9957541866794493f, 0.9957585982303893f, 0.9957630074931295f, + 0.9957674144676598f, 0.9957718191539700f, 0.9957762215520499f, 0.9957806216618896f, + 0.9957850194834788f, 0.9957894150168074f, 0.9957938082618655f, 0.9957981992186427f, + 0.9958025878871292f, 0.9958069742673147f, 0.9958113583591892f, 0.9958157401627427f, + 0.9958201196779649f, 0.9958244969048460f, 0.9958288718433759f, 0.9958332444935444f, + 0.9958376148553416f, 0.9958419829287574f, 0.9958463487137816f, 0.9958507122104044f, + 0.9958550734186158f, 0.9958594323384056f, 0.9958637889697638f, 0.9958681433126806f, + 0.9958724953671457f, 0.9958768451331493f, 0.9958811926106813f, 0.9958855377997318f, + 0.9958898807002907f, 0.9958942213123482f, 0.9958985596358941f, 0.9959028956709186f, + 0.9959072294174117f, 0.9959115608753634f, 0.9959158900447638f, 0.9959202169256028f, + 0.9959245415178707f, 0.9959288638215574f, 0.9959331838366531f, 0.9959375015631476f, + 0.9959418170010313f, 0.9959461301502941f, 0.9959504410109261f, 0.9959547495829175f, + 0.9959590558662583f, 0.9959633598609386f, 0.9959676615669485f, 0.9959719609842782f, + 0.9959762581129178f, 0.9959805529528574f, 0.9959848455040871f, 0.9959891357665970f, + 0.9959934237403774f, 0.9959977094254183f, 0.9960019928217099f, 0.9960062739292423f, + 0.9960105527480059f, 0.9960148292779906f, 0.9960191035191867f, 0.9960233754715843f, + 0.9960276451351736f, 0.9960319125099448f, 0.9960361775958881f, 0.9960404403929938f, + 0.9960447009012520f, 0.9960489591206528f, 0.9960532150511867f, 0.9960574686928436f, + 0.9960617200456140f, 0.9960659691094880f, 0.9960702158844558f, 0.9960744603705077f, + 0.9960787025676340f, 0.9960829424758247f, 0.9960871800950705f, 0.9960914154253612f, + 0.9960956484666873f, 0.9960998792190391f, 0.9961041076824069f, 0.9961083338567808f, + 0.9961125577421511f, 0.9961167793385084f, 0.9961209986458427f, 0.9961252156641444f, + 0.9961294303934037f, 0.9961336428336112f, 0.9961378529847569f, 0.9961420608468313f, + 0.9961462664198246f, 0.9961504697037273f, 0.9961546706985298f, 0.9961588694042222f, + 0.9961630658207949f, 0.9961672599482384f, 0.9961714517865430f, 0.9961756413356990f, + 0.9961798285956970f, 0.9961840135665270f, 0.9961881962481797f, 0.9961923766406453f, + 0.9961965547439142f, 0.9962007305579770f, 0.9962049040828240f, 0.9962090753184455f, + 0.9962132442648320f, 0.9962174109219739f, 0.9962215752898618f, 0.9962257373684857f, + 0.9962298971578365f, 0.9962340546579044f, 0.9962382098686799f, 0.9962423627901534f, + 0.9962465134223155f, 0.9962506617651565f, 0.9962548078186670f, 0.9962589515828374f, + 0.9962630930576581f, 0.9962672322431197f, 0.9962713691392127f, 0.9962755037459274f, + 0.9962796360632546f, 0.9962837660911846f, 0.9962878938297081f, 0.9962920192788153f, + 0.9962961424384968f, 0.9963002633087434f, 0.9963043818895455f, 0.9963084981808935f, + 0.9963126121827780f, 0.9963167238951897f, 0.9963208333181188f, 0.9963249404515563f, + 0.9963290452954924f, 0.9963331478499179f, 0.9963372481148233f, 0.9963413460901991f, + 0.9963454417760359f, 0.9963495351723244f, 0.9963536262790551f, 0.9963577150962187f, + 0.9963618016238057f, 0.9963658858618067f, 0.9963699678102124f, 0.9963740474690134f, + 0.9963781248382002f, 0.9963821999177636f, 0.9963862727076941f, 0.9963903432079825f, + 0.9963944114186193f, 0.9963984773395952f, 0.9964025409709009f, 0.9964066023125270f, + 0.9964106613644641f, 0.9964147181267031f, 0.9964187725992345f, 0.9964228247820489f, + 0.9964268746751372f, 0.9964309222784901f, 0.9964349675920982f, 0.9964390106159521f, + 0.9964430513500426f, 0.9964470897943605f, 0.9964511259488965f, 0.9964551598136412f, + 0.9964591913885854f, 0.9964632206737198f, 0.9964672476690354f, 0.9964712723745225f, + 0.9964752947901722f, 0.9964793149159751f, 0.9964833327519220f, 0.9964873482980037f, + 0.9964913615542109f, 0.9964953725205344f, 0.9964993811969650f, 0.9965033875834935f, + 0.9965073916801108f, 0.9965113934868075f, 0.9965153930035744f, 0.9965193902304025f, + 0.9965233851672824f, 0.9965273778142052f, 0.9965313681711615f, 0.9965353562381420f, + 0.9965393420151379f, 0.9965433255021399f, 0.9965473066991387f, 0.9965512856061253f, + 0.9965552622230905f, 0.9965592365500252f, 0.9965632085869203f, 0.9965671783337665f, + 0.9965711457905548f, 0.9965751109572761f, 0.9965790738339213f, 0.9965830344204814f, + 0.9965869927169470f, 0.9965909487233091f, 0.9965949024395587f, 0.9965988538656868f, + 0.9966028030016841f, 0.9966067498475417f, 0.9966106944032505f, 0.9966146366688012f, + 0.9966185766441851f, 0.9966225143293930f, 0.9966264497244157f, 0.9966303828292444f, + 0.9966343136438699f, 0.9966382421682833f, 0.9966421684024754f, 0.9966460923464374f, + 0.9966500140001601f, 0.9966539333636345f, 0.9966578504368516f, 0.9966617652198025f, + 0.9966656777124782f, 0.9966695879148695f, 0.9966734958269676f, 0.9966774014487636f, + 0.9966813047802483f, 0.9966852058214130f, 0.9966891045722484f, 0.9966930010327457f, + 0.9966968952028961f, 0.9967007870826904f, 0.9967046766721198f, 0.9967085639711754f, + 0.9967124489798480f, 0.9967163316981290f, 0.9967202121260095f, 0.9967240902634802f, + 0.9967279661105325f, 0.9967318396671574f, 0.9967357109333461f, 0.9967395799090896f, + 0.9967434465943789f, 0.9967473109892053f, 0.9967511730935599f, 0.9967550329074337f, + 0.9967588904308180f, 0.9967627456637038f, 0.9967665986060824f, 0.9967704492579448f, + 0.9967742976192820f, 0.9967781436900855f, 0.9967819874703464f, 0.9967858289600556f, + 0.9967896681592046f, 0.9967935050677843f, 0.9967973396857861f, 0.9968011720132011f, + 0.9968050020500204f, 0.9968088297962353f, 0.9968126552518370f, 0.9968164784168168f, + 0.9968202992911657f, 0.9968241178748751f, 0.9968279341679361f, 0.9968317481703400f, + 0.9968355598820782f, 0.9968393693031415f, 0.9968431764335216f, 0.9968469812732095f, + 0.9968507838221966f, 0.9968545840804740f, 0.9968583820480330f, 0.9968621777248651f, + 0.9968659711109613f, 0.9968697622063130f, 0.9968735510109115f, 0.9968773375247479f, + 0.9968811217478138f, 0.9968849036801004f, 0.9968886833215990f, 0.9968924606723008f, + 0.9968962357321972f, 0.9969000085012796f, 0.9969037789795393f, 0.9969075471669675f, + 0.9969113130635557f, 0.9969150766692952f, 0.9969188379841774f, 0.9969225970081935f, + 0.9969263537413351f, 0.9969301081835933f, 0.9969338603349596f, 0.9969376101954255f, + 0.9969413577649822f, 0.9969451030436211f, 0.9969488460313336f, 0.9969525867281113f, + 0.9969563251339453f, 0.9969600612488272f, 0.9969637950727485f, 0.9969675266057003f, + 0.9969712558476743f, 0.9969749827986618f, 0.9969787074586544f, 0.9969824298276433f, + 0.9969861499056202f, 0.9969898676925764f, 0.9969935831885033f, 0.9969972963933924f, + 0.9970010073072353f, 0.9970047159300233f, 0.9970084222617480f, 0.9970121263024009f, + 0.9970158280519733f, 0.9970195275104570f, 0.9970232246778431f, 0.9970269195541235f, + 0.9970306121392895f, 0.9970343024333326f, 0.9970379904362444f, 0.9970416761480164f, + 0.9970453595686400f, 0.9970490406981071f, 0.9970527195364088f, 0.9970563960835369f, + 0.9970600703394830f, 0.9970637423042384f, 0.9970674119777949f, 0.9970710793601441f, + 0.9970747444512773f, 0.9970784072511862f, 0.9970820677598625f, 0.9970857259772977f, + 0.9970893819034834f, 0.9970930355384112f, 0.9970966868820728f, 0.9971003359344596f, + 0.9971039826955633f, 0.9971076271653756f, 0.9971112693438881f, 0.9971149092310923f, + 0.9971185468269800f, 0.9971221821315428f, 0.9971258151447723f, 0.9971294458666602f, + 0.9971330742971981f, 0.9971367004363777f, 0.9971403242841907f, 0.9971439458406287f, + 0.9971475651056835f, 0.9971511820793466f, 0.9971547967616098f, 0.9971584091524648f, + 0.9971620192519033f, 0.9971656270599170f, 0.9971692325764975f, 0.9971728358016366f, + 0.9971764367353262f, 0.9971800353775576f, 0.9971836317283230f, 0.9971872257876139f, + 0.9971908175554219f, 0.9971944070317390f, 0.9971979942165569f, 0.9972015791098673f, + 0.9972051617116620f, 0.9972087420219325f, 0.9972123200406711f, 0.9972158957678692f, + 0.9972194692035187f, 0.9972230403476113f, 0.9972266092001389f, 0.9972301757610933f, + 0.9972337400304662f, 0.9972373020082496f, 0.9972408616944350f, 0.9972444190890145f, + 0.9972479741919799f, 0.9972515270033228f, 0.9972550775230353f, 0.9972586257511091f, + 0.9972621716875362f, 0.9972657153323082f, 0.9972692566854171f, 0.9972727957468548f, + 0.9972763325166132f, 0.9972798669946840f, 0.9972833991810591f, 0.9972869290757306f, + 0.9972904566786902f, 0.9972939819899298f, 0.9972975050094415f, 0.9973010257372169f, + 0.9973045441732480f, 0.9973080603175268f, 0.9973115741700453f, 0.9973150857307953f, + 0.9973185949997686f, 0.9973221019769574f, 0.9973256066623535f, 0.9973291090559488f, + 0.9973326091577355f, 0.9973361069677052f, 0.9973396024858501f, 0.9973430957121621f, + 0.9973465866466332f, 0.9973500752892553f, 0.9973535616400204f, 0.9973570456989207f, + 0.9973605274659479f, 0.9973640069410942f, 0.9973674841243514f, 0.9973709590157117f, + 0.9973744316151670f, 0.9973779019227095f, 0.9973813699383310f, 0.9973848356620237f, + 0.9973882990937795f, 0.9973917602335906f, 0.9973952190814488f, 0.9973986756373464f, + 0.9974021299012753f, 0.9974055818732276f, 0.9974090315531955f, 0.9974124789411709f, + 0.9974159240371460f, 0.9974193668411127f, 0.9974228073530632f, 0.9974262455729898f, + 0.9974296815008842f, 0.9974331151367388f, 0.9974365464805456f, 0.9974399755322968f, + 0.9974434022919844f, 0.9974468267596005f, 0.9974502489351375f, 0.9974536688185872f, + 0.9974570864099419f, 0.9974605017091938f, 0.9974639147163349f, 0.9974673254313574f, + 0.9974707338542537f, 0.9974741399850157f, 0.9974775438236355f, 0.9974809453701056f, + 0.9974843446244179f, 0.9974877415865647f, 0.9974911362565383f, 0.9974945286343307f, + 0.9974979187199342f, 0.9975013065133410f, 0.9975046920145434f, 0.9975080752235335f, + 0.9975114561403035f, 0.9975148347648457f, 0.9975182110971523f, 0.9975215851372157f, + 0.9975249568850280f, 0.9975283263405814f, 0.9975316935038683f, 0.9975350583748808f, + 0.9975384209536112f, 0.9975417812400520f, 0.9975451392341953f, 0.9975484949360333f, + 0.9975518483455584f, 0.9975551994627629f, 0.9975585482876391f, 0.9975618948201793f, + 0.9975652390603758f, 0.9975685810082208f, 0.9975719206637067f, 0.9975752580268260f, + 0.9975785930975708f, 0.9975819258759335f, 0.9975852563619065f, 0.9975885845554820f, + 0.9975919104566526f, 0.9975952340654105f, 0.9975985553817480f, 0.9976018744056576f, + 0.9976051911371316f, 0.9976085055761624f, 0.9976118177227424f, 0.9976151275768640f, + 0.9976184351385196f, 0.9976217404077015f, 0.9976250433844021f, 0.9976283440686139f, + 0.9976316424603293f, 0.9976349385595408f, 0.9976382323662406f, 0.9976415238804214f, + 0.9976448131020754f, 0.9976481000311953f, 0.9976513846677733f, 0.9976546670118019f, + 0.9976579470632737f, 0.9976612248221810f, 0.9976645002885164f, 0.9976677734622722f, + 0.9976710443434410f, 0.9976743129320154f, 0.9976775792279876f, 0.9976808432313504f, + 0.9976841049420960f, 0.9976873643602172f, 0.9976906214857063f, 0.9976938763185559f, + 0.9976971288587585f, 0.9977003791063066f, 0.9977036270611929f, 0.9977068727234096f, + 0.9977101160929496f, 0.9977133571698051f, 0.9977165959539690f, 0.9977198324454336f, + 0.9977230666441916f, 0.9977262985502355f, 0.9977295281635580f, 0.9977327554841514f, + 0.9977359805120086f, 0.9977392032471221f, 0.9977424236894843f, 0.9977456418390880f, + 0.9977488576959257f, 0.9977520712599901f, 0.9977552825312739f, 0.9977584915097694f, + 0.9977616981954696f, 0.9977649025883668f, 0.9977681046884538f, 0.9977713044957233f, + 0.9977745020101678f, 0.9977776972317801f, 0.9977808901605528f, 0.9977840807964785f, + 0.9977872691395500f, 0.9977904551897597f, 0.9977936389471007f, 0.9977968204115654f, + 0.9977999995831465f, 0.9978031764618367f, 0.9978063510476287f, 0.9978095233405153f, + 0.9978126933404893f, 0.9978158610475431f, 0.9978190264616696f, 0.9978221895828615f, + 0.9978253504111116f, 0.9978285089464126f, 0.9978316651887572f, 0.9978348191381382f, + 0.9978379707945483f, 0.9978411201579802f, 0.9978442672284269f, 0.9978474120058809f, + 0.9978505544903351f, 0.9978536946817823f, 0.9978568325802153f, 0.9978599681856267f, + 0.9978631014980095f, 0.9978662325173565f, 0.9978693612436603f, 0.9978724876769139f, + 0.9978756118171102f, 0.9978787336642417f, 0.9978818532183016f, 0.9978849704792824f, + 0.9978880854471771f, 0.9978911981219786f, 0.9978943085036796f, 0.9978974165922729f, + 0.9979005223877516f, 0.9979036258901085f, 0.9979067270993364f, 0.9979098260154281f, + 0.9979129226383766f, 0.9979160169681748f, 0.9979191090048154f, 0.9979221987482916f, + 0.9979252861985960f, 0.9979283713557217f, 0.9979314542196616f, 0.9979345347904084f, + 0.9979376130679553f, 0.9979406890522950f, 0.9979437627434207f, 0.9979468341413251f, + 0.9979499032460012f, 0.9979529700574420f, 0.9979560345756404f, 0.9979590968005895f, + 0.9979621567322819f, 0.9979652143707110f, 0.9979682697158695f, 0.9979713227677505f, + 0.9979743735263470f, 0.9979774219916518f, 0.9979804681636582f, 0.9979835120423588f, + 0.9979865536277470f, 0.9979895929198156f, 0.9979926299185577f, 0.9979956646239663f, + 0.9979986970360344f, 0.9980017271547550f, 0.9980047549801212f, 0.9980077805121260f, + 0.9980108037507625f, 0.9980138246960236f, 0.9980168433479026f, 0.9980198597063925f, + 0.9980228737714862f, 0.9980258855431769f, 0.9980288950214578f, 0.9980319022063217f, + 0.9980349070977618f, 0.9980379096957713f, 0.9980409100003432f, 0.9980439080114707f, + 0.9980469037291468f, 0.9980498971533648f, 0.9980528882841175f, 0.9980558771213983f, + 0.9980588636652002f, 0.9980618479155166f, 0.9980648298723401f, 0.9980678095356643f, + 0.9980707869054823f, 0.9980737619817871f, 0.9980767347645720f, 0.9980797052538301f, + 0.9980826734495546f, 0.9980856393517387f, 0.9980886029603754f, 0.9980915642754582f, + 0.9980945232969800f, 0.9980974800249343f, 0.9981004344593141f, 0.9981033866001126f, + 0.9981063364473231f, 0.9981092840009387f, 0.9981122292609528f, 0.9981151722273586f, + 0.9981181129001492f, 0.9981210512793179f, 0.9981239873648581f, 0.9981269211567629f, + 0.9981298526550256f, 0.9981327818596394f, 0.9981357087705977f, 0.9981386333878935f, + 0.9981415557115205f, 0.9981444757414717f, 0.9981473934777404f, 0.9981503089203200f, + 0.9981532220692036f, 0.9981561329243849f, 0.9981590414858568f, 0.9981619477536128f, + 0.9981648517276462f, 0.9981677534079504f, 0.9981706527945186f, 0.9981735498873442f, + 0.9981764446864205f, 0.9981793371917409f, 0.9981822274032988f, 0.9981851153210874f, + 0.9981880009451003f, 0.9981908842753306f, 0.9981937653117720f, 0.9981966440544174f, + 0.9981995205032607f, 0.9982023946582950f, 0.9982052665195137f, 0.9982081360869103f, + 0.9982110033604782f, 0.9982138683402106f, 0.9982167310261013f, 0.9982195914181434f, + 0.9982224495163305f, 0.9982253053206559f, 0.9982281588311132f, 0.9982310100476957f, + 0.9982338589703968f, 0.9982367055992103f, 0.9982395499341292f, 0.9982423919751472f, + 0.9982452317222579f, 0.9982480691754544f, 0.9982509043347305f, 0.9982537372000796f, + 0.9982565677714952f, 0.9982593960489706f, 0.9982622220324997f, 0.9982650457220756f, + 0.9982678671176921f, 0.9982706862193426f, 0.9982735030270206f, 0.9982763175407195f, + 0.9982791297604332f, 0.9982819396861550f, 0.9982847473178783f, 0.9982875526555970f, + 0.9982903556993044f, 0.9982931564489941f, 0.9982959549046597f, 0.9982987510662947f, + 0.9983015449338929f, 0.9983043365074475f, 0.9983071257869525f, 0.9983099127724012f, + 0.9983126974637873f, 0.9983154798611044f, 0.9983182599643460f, 0.9983210377735059f, + 0.9983238132885776f, 0.9983265865095546f, 0.9983293574364309f, 0.9983321260691997f, + 0.9983348924078550f, 0.9983376564523903f, 0.9983404182027991f, 0.9983431776590752f, + 0.9983459348212124f, 0.9983486896892040f, 0.9983514422630440f, 0.9983541925427259f, + 0.9983569405282434f, 0.9983596862195904f, 0.9983624296167602f, 0.9983651707197468f, + 0.9983679095285438f, 0.9983706460431448f, 0.9983733802635438f, 0.9983761121897343f, + 0.9983788418217100f, 0.9983815691594647f, 0.9983842942029921f, 0.9983870169522860f, + 0.9983897374073402f, 0.9983924555681483f, 0.9983951714347040f, 0.9983978850070012f, + 0.9984005962850336f, 0.9984033052687952f, 0.9984060119582794f, 0.9984087163534802f, + 0.9984114184543913f, 0.9984141182610065f, 0.9984168157733196f, 0.9984195109913246f, + 0.9984222039150150f, 0.9984248945443849f, 0.9984275828794278f, 0.9984302689201378f, + 0.9984329526665084f, 0.9984356341185339f, 0.9984383132762077f, 0.9984409901395239f, + 0.9984436647084763f, 0.9984463369830587f, 0.9984490069632650f, 0.9984516746490891f, + 0.9984543400405248f, 0.9984570031375659f, 0.9984596639402065f, 0.9984623224484404f, + 0.9984649786622612f, 0.9984676325816633f, 0.9984702842066403f, 0.9984729335371861f, + 0.9984755805732948f, 0.9984782253149601f, 0.9984808677621759f, 0.9984835079149365f, + 0.9984861457732354f, 0.9984887813370666f, 0.9984914146064243f, 0.9984940455813024f, + 0.9984966742616946f, 0.9984993006475951f, 0.9985019247389978f, 0.9985045465358966f, + 0.9985071660382855f, 0.9985097832461585f, 0.9985123981595097f, 0.9985150107783328f, + 0.9985176211026222f, 0.9985202291323715f, 0.9985228348675750f, 0.9985254383082266f, + 0.9985280394543202f, 0.9985306383058501f, 0.9985332348628101f, 0.9985358291251942f, + 0.9985384210929967f, 0.9985410107662115f, 0.9985435981448325f, 0.9985461832288540f, + 0.9985487660182699f, 0.9985513465130743f, 0.9985539247132613f, 0.9985565006188249f, + 0.9985590742297593f, 0.9985616455460585f, 0.9985642145677167f, 0.9985667812947279f, + 0.9985693457270861f, 0.9985719078647856f, 0.9985744677078203f, 0.9985770252561846f, + 0.9985795805098725f, 0.9985821334688780f, 0.9985846841331955f, 0.9985872325028188f, + 0.9985897785777422f, 0.9985923223579600f, 0.9985948638434662f, 0.9985974030342549f, + 0.9985999399303204f, 0.9986024745316568f, 0.9986050068382584f, 0.9986075368501192f, + 0.9986100645672333f, 0.9986125899895952f, 0.9986151131171990f, 0.9986176339500388f, + 0.9986201524881089f, 0.9986226687314034f, 0.9986251826799166f, 0.9986276943336427f, + 0.9986302036925760f, 0.9986327107567107f, 0.9986352155260408f, 0.9986377180005610f, + 0.9986402181802653f, 0.9986427160651478f, 0.9986452116552030f, 0.9986477049504251f, + 0.9986501959508083f, 0.9986526846563470f, 0.9986551710670354f, 0.9986576551828678f, + 0.9986601370038385f, 0.9986626165299417f, 0.9986650937611719f, 0.9986675686975232f, + 0.9986700413389901f, 0.9986725116855668f, 0.9986749797372476f, 0.9986774454940269f, + 0.9986799089558991f, 0.9986823701228583f, 0.9986848289948992f, 0.9986872855720158f, + 0.9986897398542026f, 0.9986921918414541f, 0.9986946415337644f, 0.9986970889311280f, + 0.9986995340335393f, 0.9987019768409927f, 0.9987044173534825f, 0.9987068555710031f, + 0.9987092914935490f, 0.9987117251211145f, 0.9987141564536940f, 0.9987165854912821f, + 0.9987190122338729f, 0.9987214366814611f, 0.9987238588340410f, 0.9987262786916070f, + 0.9987286962541537f, 0.9987311115216754f, 0.9987335244941665f, 0.9987359351716217f, + 0.9987383435540352f, 0.9987407496414017f, 0.9987431534337154f, 0.9987455549309711f, + 0.9987479541331629f, 0.9987503510402856f, 0.9987527456523335f, 0.9987551379693013f, + 0.9987575279911833f, 0.9987599157179741f, 0.9987623011496682f, 0.9987646842862602f, + 0.9987670651277444f, 0.9987694436741156f, 0.9987718199253681f, 0.9987741938814966f, + 0.9987765655424956f, 0.9987789349083597f, 0.9987813019790833f, 0.9987836667546611f, + 0.9987860292350876f, 0.9987883894203574f, 0.9987907473104651f, 0.9987931029054052f, + 0.9987954562051724f, 0.9987978072097612f, 0.9988001559191663f, 0.9988025023333821f, + 0.9988048464524034f, 0.9988071882762247f, 0.9988095278048408f, 0.9988118650382461f, + 0.9988141999764354f, 0.9988165326194032f, 0.9988188629671442f, 0.9988211910196531f, + 0.9988235167769245f, 0.9988258402389529f, 0.9988281614057333f, 0.9988304802772601f, + 0.9988327968535280f, 0.9988351111345317f, 0.9988374231202660f, 0.9988397328107255f, + 0.9988420402059048f, 0.9988443453057988f, 0.9988466481104020f, 0.9988489486197093f, + 0.9988512468337152f, 0.9988535427524146f, 0.9988558363758021f, 0.9988581277038725f, + 0.9988604167366205f, 0.9988627034740408f, 0.9988649879161283f, 0.9988672700628777f, + 0.9988695499142836f, 0.9988718274703409f, 0.9988741027310443f, 0.9988763756963887f, + 0.9988786463663687f, 0.9988809147409792f, 0.9988831808202149f, 0.9988854446040707f, + 0.9988877060925413f, 0.9988899652856216f, 0.9988922221833063f, 0.9988944767855904f, + 0.9988967290924684f, 0.9988989791039354f, 0.9989012268199862f, 0.9989034722406155f, + 0.9989057153658183f, 0.9989079561955893f, 0.9989101947299234f, 0.9989124309688154f, + 0.9989146649122604f, 0.9989168965602530f, 0.9989191259127882f, 0.9989213529698608f, + 0.9989235777314658f, 0.9989258001975979f, 0.9989280203682522f, 0.9989302382434235f, + 0.9989324538231067f, 0.9989346671072967f, 0.9989368780959885f, 0.9989390867891769f, + 0.9989412931868569f, 0.9989434972890233f, 0.9989456990956712f, 0.9989478986067956f, + 0.9989500958223912f, 0.9989522907424532f, 0.9989544833669762f, 0.9989566736959556f, + 0.9989588617293861f, 0.9989610474672628f, 0.9989632309095805f, 0.9989654120563344f, + 0.9989675909075193f, 0.9989697674631303f, 0.9989719417231624f, 0.9989741136876106f, + 0.9989762833564698f, 0.9989784507297351f, 0.9989806158074016f, 0.9989827785894643f, + 0.9989849390759180f, 0.9989870972667581f, 0.9989892531619793f, 0.9989914067615768f, + 0.9989935580655457f, 0.9989957070738811f, 0.9989978537865778f, 0.9989999982036311f, + 0.9990021403250360f, 0.9990042801507876f, 0.9990064176808809f, 0.9990085529153112f, + 0.9990106858540734f, 0.9990128164971626f, 0.9990149448445739f, 0.9990170708963025f, + 0.9990191946523435f, 0.9990213161126920f, 0.9990234352773431f, 0.9990255521462920f, + 0.9990276667195337f, 0.9990297789970634f, 0.9990318889788763f, 0.9990339966649676f, + 0.9990361020553323f, 0.9990382051499657f, 0.9990403059488628f, 0.9990424044520190f, + 0.9990445006594293f, 0.9990465945710890f, 0.9990486861869932f, 0.9990507755071371f, + 0.9990528625315159f, 0.9990549472601249f, 0.9990570296929592f, 0.9990591098300140f, + 0.9990611876712846f, 0.9990632632167662f, 0.9990653364664540f, 0.9990674074203434f, + 0.9990694760784293f, 0.9990715424407073f, 0.9990736065071725f, 0.9990756682778200f, + 0.9990777277526454f, 0.9990797849316437f, 0.9990818398148102f, 0.9990838924021403f, + 0.9990859426936293f, 0.9990879906892723f, 0.9990900363890648f, 0.9990920797930020f, + 0.9990941209010791f, 0.9990961597132916f, 0.9990981962296347f, 0.9991002304501038f, + 0.9991022623746941f, 0.9991042920034010f, 0.9991063193362200f, 0.9991083443731461f, + 0.9991103671141749f, 0.9991123875593017f, 0.9991144057085218f, 0.9991164215618307f, + 0.9991184351192235f, 0.9991204463806959f, 0.9991224553462430f, 0.9991244620158605f, + 0.9991264663895434f, 0.9991284684672873f, 0.9991304682490877f, 0.9991324657349399f, + 0.9991344609248392f, 0.9991364538187811f, 0.9991384444167611f, 0.9991404327187746f, + 0.9991424187248169f, 0.9991444024348837f, 0.9991463838489700f, 0.9991483629670718f, + 0.9991503397891841f, 0.9991523143153026f, 0.9991542865454226f, 0.9991562564795398f, + 0.9991582241176494f, 0.9991601894597471f, 0.9991621525058283f, 0.9991641132558884f, + 0.9991660717099230f, 0.9991680278679277f, 0.9991699817298977f, 0.9991719332958288f, + 0.9991738825657164f, 0.9991758295395560f, 0.9991777742173432f, 0.9991797165990735f, + 0.9991816566847423f, 0.9991835944743453f, 0.9991855299678781f, 0.9991874631653361f, + 0.9991893940667149f, 0.9991913226720102f, 0.9991932489812174f, 0.9991951729943320f, + 0.9991970947113499f, 0.9991990141322664f, 0.9992009312570771f, 0.9992028460857778f, + 0.9992047586183639f, 0.9992066688548311f, 0.9992085767951749f, 0.9992104824393911f, + 0.9992123857874753f, 0.9992142868394229f, 0.9992161855952297f, 0.9992180820548914f, + 0.9992199762184035f, 0.9992218680857617f, 0.9992237576569617f, 0.9992256449319992f, + 0.9992275299108696f, 0.9992294125935689f, 0.9992312929800925f, 0.9992331710704363f, + 0.9992350468645959f, 0.9992369203625668f, 0.9992387915643450f, 0.9992406604699261f, + 0.9992425270793058f, 0.9992443913924797f, 0.9992462534094436f, 0.9992481131301933f, + 0.9992499705547244f, 0.9992518256830327f, 0.9992536785151139f, 0.9992555290509638f, + 0.9992573772905781f, 0.9992592232339526f, 0.9992610668810830f, 0.9992629082319650f, + 0.9992647472865944f, 0.9992665840449672f, 0.9992684185070789f, 0.9992702506729254f, + 0.9992720805425026f, 0.9992739081158061f, 0.9992757333928317f, 0.9992775563735753f, + 0.9992793770580327f, 0.9992811954461998f, 0.9992830115380723f, 0.9992848253336459f, + 0.9992866368329167f, 0.9992884460358805f, 0.9992902529425330f, 0.9992920575528702f, + 0.9992938598668878f, 0.9992956598845817f, 0.9992974576059478f, 0.9992992530309819f, + 0.9993010461596801f, 0.9993028369920379f, 0.9993046255280515f, 0.9993064117677167f, + 0.9993081957110295f, 0.9993099773579855f, 0.9993117567085809f, 0.9993135337628114f, + 0.9993153085206731f, 0.9993170809821618f, 0.9993188511472735f, 0.9993206190160041f, + 0.9993223845883495f, 0.9993241478643057f, 0.9993259088438686f, 0.9993276675270343f, + 0.9993294239137984f, 0.9993311780041573f, 0.9993329297981067f, 0.9993346792956427f, + 0.9993364264967612f, 0.9993381714014582f, 0.9993399140097297f, 0.9993416543215717f, + 0.9993433923369802f, 0.9993451280559512f, 0.9993468614784807f, 0.9993485926045648f, + 0.9993503214341994f, 0.9993520479673805f, 0.9993537722041044f, 0.9993554941443669f, + 0.9993572137881640f, 0.9993589311354919f, 0.9993606461863466f, 0.9993623589407241f, + 0.9993640693986205f, 0.9993657775600321f, 0.9993674834249545f, 0.9993691869933842f, + 0.9993708882653171f, 0.9993725872407493f, 0.9993742839196770f, 0.9993759783020961f, + 0.9993776703880028f, 0.9993793601773934f, 0.9993810476702637f, 0.9993827328666101f, + 0.9993844157664286f, 0.9993860963697152f, 0.9993877746764662f, 0.9993894506866777f, + 0.9993911244003461f, 0.9993927958174671f, 0.9993944649380371f, 0.9993961317620522f, + 0.9993977962895086f, 0.9993994585204027f, 0.9994011184547302f, 0.9994027760924877f, + 0.9994044314336713f, 0.9994060844782771f, 0.9994077352263012f, 0.9994093836777401f, + 0.9994110298325898f, 0.9994126736908466f, 0.9994143152525067f, 0.9994159545175663f, + 0.9994175914860217f, 0.9994192261578690f, 0.9994208585331047f, 0.9994224886117248f, + 0.9994241163937256f, 0.9994257418791035f, 0.9994273650678546f, 0.9994289859599753f, + 0.9994306045554617f, 0.9994322208543104f, 0.9994338348565173f, 0.9994354465620789f, + 0.9994370559709915f, 0.9994386630832514f, 0.9994402678988549f, 0.9994418704177982f, + 0.9994434706400778f, 0.9994450685656898f, 0.9994466641946307f, 0.9994482575268968f, + 0.9994498485624845f, 0.9994514373013901f, 0.9994530237436098f, 0.9994546078891401f, + 0.9994561897379773f, 0.9994577692901180f, 0.9994593465455581f, 0.9994609215042944f, + 0.9994624941663232f, 0.9994640645316407f, 0.9994656326002435f, 0.9994671983721277f, + 0.9994687618472901f, 0.9994703230257268f, 0.9994718819074344f, 0.9994734384924092f, + 0.9994749927806478f, 0.9994765447721463f, 0.9994780944669014f, 0.9994796418649095f, + 0.9994811869661669f, 0.9994827297706703f, 0.9994842702784159f, 0.9994858084894004f, + 0.9994873444036201f, 0.9994888780210714f, 0.9994904093417510f, 0.9994919383656552f, + 0.9994934650927806f, 0.9994949895231237f, 0.9994965116566809f, 0.9994980314934486f, + 0.9994995490334236f, 0.9995010642766022f, 0.9995025772229811f, 0.9995040878725566f, + 0.9995055962253253f, 0.9995071022812839f, 0.9995086060404287f, 0.9995101075027564f, + 0.9995116066682634f, 0.9995131035369466f, 0.9995145981088021f, 0.9995160903838267f, + 0.9995175803620170f, 0.9995190680433695f, 0.9995205534278809f, 0.9995220365155476f, + 0.9995235173063663f, 0.9995249958003336f, 0.9995264719974462f, 0.9995279458977004f, + 0.9995294175010931f, 0.9995308868076209f, 0.9995323538172803f, 0.9995338185300680f, + 0.9995352809459805f, 0.9995367410650147f, 0.9995381988871670f, 0.9995396544124342f, + 0.9995411076408129f, 0.9995425585722998f, 0.9995440072068914f, 0.9995454535445847f, + 0.9995468975853760f, 0.9995483393292622f, 0.9995497787762400f, 0.9995512159263060f, + 0.9995526507794570f, 0.9995540833356896f, 0.9995555135950005f, 0.9995569415573865f, + 0.9995583672228443f, 0.9995597905913706f, 0.9995612116629621f, 0.9995626304376156f, + 0.9995640469153277f, 0.9995654610960955f, 0.9995668729799153f, 0.9995682825667841f, + 0.9995696898566986f, 0.9995710948496556f, 0.9995724975456518f, 0.9995738979446841f, + 0.9995752960467492f, 0.9995766918518439f, 0.9995780853599651f, 0.9995794765711093f, + 0.9995808654852737f, 0.9995822521024548f, 0.9995836364226495f, 0.9995850184458547f, + 0.9995863981720671f, 0.9995877756012835f, 0.9995891507335010f, 0.9995905235687161f, + 0.9995918941069259f, 0.9995932623481273f, 0.9995946282923168f, 0.9995959919394916f, + 0.9995973532896484f, 0.9995987123427841f, 0.9996000690988955f, 0.9996014235579798f, + 0.9996027757200335f, 0.9996041255850537f, 0.9996054731530373f, 0.9996068184239811f, + 0.9996081613978821f, 0.9996095020747371f, 0.9996108404545432f, 0.9996121765372972f, + 0.9996135103229959f, 0.9996148418116366f, 0.9996161710032160f, 0.9996174978977309f, + 0.9996188224951786f, 0.9996201447955558f, 0.9996214647988596f, 0.9996227825050868f, + 0.9996240979142346f, 0.9996254110262999f, 0.9996267218412794f, 0.9996280303591706f, + 0.9996293365799701f, 0.9996306405036750f, 0.9996319421302823f, 0.9996332414597892f, + 0.9996345384921923f, 0.9996358332274891f, 0.9996371256656762f, 0.9996384158067509f, + 0.9996397036507102f, 0.9996409891975511f, 0.9996422724472706f, 0.9996435533998658f, + 0.9996448320553336f, 0.9996461084136714f, 0.9996473824748761f, 0.9996486542389447f, + 0.9996499237058742f, 0.9996511908756620f, 0.9996524557483049f, 0.9996537183238001f, + 0.9996549786021447f, 0.9996562365833358f, 0.9996574922673706f, 0.9996587456542460f, + 0.9996599967439592f, 0.9996612455365075f, 0.9996624920318878f, 0.9996637362300974f, + 0.9996649781311333f, 0.9996662177349928f, 0.9996674550416729f, 0.9996686900511708f, + 0.9996699227634838f, 0.9996711531786088f, 0.9996723812965432f, 0.9996736071172841f, + 0.9996748306408287f, 0.9996760518671742f, 0.9996772707963177f, 0.9996784874282566f, + 0.9996797017629879f, 0.9996809138005089f, 0.9996821235408168f, 0.9996833309839087f, + 0.9996845361297821f, 0.9996857389784340f, 0.9996869395298618f, 0.9996881377840625f, + 0.9996893337410336f, 0.9996905274007722f, 0.9996917187632757f, 0.9996929078285411f, + 0.9996940945965660f, 0.9996952790673475f, 0.9996964612408827f, 0.9996976411171693f, + 0.9996988186962042f, 0.9996999939779849f, 0.9997011669625087f, 0.9997023376497728f, + 0.9997035060397746f, 0.9997046721325114f, 0.9997058359279805f, 0.9997069974261792f, + 0.9997081566271049f, 0.9997093135307548f, 0.9997104681371264f, 0.9997116204462170f, + 0.9997127704580239f, 0.9997139181725445f, 0.9997150635897762f, 0.9997162067097163f, + 0.9997173475323622f, 0.9997184860577112f, 0.9997196222857608f, 0.9997207562165085f, + 0.9997218878499513f, 0.9997230171860870f, 0.9997241442249127f, 0.9997252689664261f, + 0.9997263914106245f, 0.9997275115575052f, 0.9997286294070657f, 0.9997297449593036f, + 0.9997308582142160f, 0.9997319691718006f, 0.9997330778320548f, 0.9997341841949761f, + 0.9997352882605617f, 0.9997363900288093f, 0.9997374894997164f, 0.9997385866732804f, + 0.9997396815494987f, 0.9997407741283688f, 0.9997418644098884f, 0.9997429523940548f, + 0.9997440380808654f, 0.9997451214703179f, 0.9997462025624099f, 0.9997472813571386f, + 0.9997483578545018f, 0.9997494320544968f, 0.9997505039571213f, 0.9997515735623728f, + 0.9997526408702488f, 0.9997537058807469f, 0.9997547685938646f, 0.9997558290095995f, + 0.9997568871279491f, 0.9997579429489111f, 0.9997589964724829f, 0.9997600476986622f, + 0.9997610966274466f, 0.9997621432588336f, 0.9997631875928209f, 0.9997642296294059f, + 0.9997652693685865f, 0.9997663068103601f, 0.9997673419547243f, 0.9997683748016769f, + 0.9997694053512153f, 0.9997704336033373f, 0.9997714595580405f, 0.9997724832153225f, + 0.9997735045751810f, 0.9997745236376137f, 0.9997755404026181f, 0.9997765548701920f, + 0.9997775670403329f, 0.9997785769130387f, 0.9997795844883069f, 0.9997805897661354f, + 0.9997815927465217f, 0.9997825934294635f, 0.9997835918149585f, 0.9997845879030045f, + 0.9997855816935992f, 0.9997865731867402f, 0.9997875623824254f, 0.9997885492806523f, + 0.9997895338814188f, 0.9997905161847226f, 0.9997914961905615f, 0.9997924738989331f, + 0.9997934493098353f, 0.9997944224232658f, 0.9997953932392223f, 0.9997963617577027f, + 0.9997973279787047f, 0.9997982919022260f, 0.9997992535282645f, 0.9998002128568180f, + 0.9998011698878843f, 0.9998021246214610f, 0.9998030770575462f, 0.9998040271961375f, + 0.9998049750372329f, 0.9998059205808300f, 0.9998068638269267f, 0.9998078047755210f, + 0.9998087434266105f, 0.9998096797801932f, 0.9998106138362669f, 0.9998115455948295f, + 0.9998124750558788f, 0.9998134022194126f, 0.9998143270854289f, 0.9998152496539255f, + 0.9998161699249004f, 0.9998170878983512f, 0.9998180035742762f, 0.9998189169526729f, + 0.9998198280335394f, 0.9998207368168737f, 0.9998216433026734f, 0.9998225474909368f, + 0.9998234493816616f, 0.9998243489748456f, 0.9998252462704870f, 0.9998261412685836f, + 0.9998270339691334f, 0.9998279243721344f, 0.9998288124775844f, 0.9998296982854814f, + 0.9998305817958234f, 0.9998314630086084f, 0.9998323419238344f, 0.9998332185414992f, + 0.9998340928616010f, 0.9998349648841377f, 0.9998358346091073f, 0.9998367020365078f, + 0.9998375671663371f, 0.9998384299985934f, 0.9998392905332747f, 0.9998401487703789f, + 0.9998410047099040f, 0.9998418583518482f, 0.9998427096962095f, 0.9998435587429858f, + 0.9998444054921752f, 0.9998452499437760f, 0.9998460920977860f, 0.9998469319542033f, + 0.9998477695130259f, 0.9998486047742521f, 0.9998494377378798f, 0.9998502684039071f, + 0.9998510967723322f, 0.9998519228431532f, 0.9998527466163679f, 0.9998535680919748f, + 0.9998543872699719f, 0.9998552041503571f, 0.9998560187331288f, 0.9998568310182850f, + 0.9998576410058239f, 0.9998584486957435f, 0.9998592540880420f, 0.9998600571827176f, + 0.9998608579797685f, 0.9998616564791928f, 0.9998624526809886f, 0.9998632465851542f, + 0.9998640381916877f, 0.9998648275005872f, 0.9998656145118511f, 0.9998663992254774f, + 0.9998671816414644f, 0.9998679617598102f, 0.9998687395805130f, 0.9998695151035712f, + 0.9998702883289829f, 0.9998710592567464f, 0.9998718278868597f, 0.9998725942193213f, + 0.9998733582541293f, 0.9998741199912820f, 0.9998748794307775f, 0.9998756365726142f, + 0.9998763914167904f, 0.9998771439633043f, 0.9998778942121541f, 0.9998786421633382f, + 0.9998793878168549f, 0.9998801311727024f, 0.9998808722308788f, 0.9998816109913828f, + 0.9998823474542126f, 0.9998830816193662f, 0.9998838134868422f, 0.9998845430566389f, + 0.9998852703287545f, 0.9998859953031874f, 0.9998867179799360f, 0.9998874383589985f, + 0.9998881564403733f, 0.9998888722240589f, 0.9998895857100534f, 0.9998902968983553f, + 0.9998910057889629f, 0.9998917123818747f, 0.9998924166770889f, 0.9998931186746041f, + 0.9998938183744185f, 0.9998945157765305f, 0.9998952108809387f, 0.9998959036876413f, + 0.9998965941966367f, 0.9998972824079234f, 0.9998979683214998f, 0.9998986519373643f, + 0.9998993332555154f, 0.9999000122759514f, 0.9999006889986709f, 0.9999013634236722f, + 0.9999020355509539f, 0.9999027053805143f, 0.9999033729123520f, 0.9999040381464653f, + 0.9999047010828529f, 0.9999053617215130f, 0.9999060200624443f, 0.9999066761056452f, + 0.9999073298511143f, 0.9999079812988499f, 0.9999086304488507f, 0.9999092773011150f, + 0.9999099218556415f, 0.9999105641124286f, 0.9999112040714749f, 0.9999118417327790f, + 0.9999124770963392f, 0.9999131101621542f, 0.9999137409302227f, 0.9999143694005429f, + 0.9999149955731135f, 0.9999156194479332f, 0.9999162410250004f, 0.9999168603043137f, + 0.9999174772858718f, 0.9999180919696731f, 0.9999187043557163f, 0.9999193144440000f, + 0.9999199222345228f, 0.9999205277272831f, 0.9999211309222799f, 0.9999217318195114f, + 0.9999223304189765f, 0.9999229267206737f, 0.9999235207246017f, 0.9999241124307591f, + 0.9999247018391445f, 0.9999252889497566f, 0.9999258737625941f, 0.9999264562776555f, + 0.9999270364949396f, 0.9999276144144451f, 0.9999281900361705f, 0.9999287633601146f, + 0.9999293343862761f, 0.9999299031146536f, 0.9999304695452458f, 0.9999310336780514f, + 0.9999315955130692f, 0.9999321550502979f, 0.9999327122897360f, 0.9999332672313825f, + 0.9999338198752360f, 0.9999343702212952f, 0.9999349182695588f, 0.9999354640200258f, + 0.9999360074726946f, 0.9999365486275641f, 0.9999370874846332f, 0.9999376240439004f, + 0.9999381583053646f, 0.9999386902690246f, 0.9999392199348791f, 0.9999397473029270f, + 0.9999402723731670f, 0.9999407951455979f, 0.9999413156202184f, 0.9999418337970275f, + 0.9999423496760239f, 0.9999428632572065f, 0.9999433745405739f, 0.9999438835261252f, + 0.9999443902138591f, 0.9999448946037744f, 0.9999453966958700f, 0.9999458964901448f, + 0.9999463939865975f, 0.9999468891852270f, 0.9999473820860323f, 0.9999478726890121f, + 0.9999483609941654f, 0.9999488470014909f, 0.9999493307109877f, 0.9999498121226547f, + 0.9999502912364905f, 0.9999507680524942f, 0.9999512425706647f, 0.9999517147910010f, + 0.9999521847135018f, 0.9999526523381662f, 0.9999531176649931f, 0.9999535806939812f, + 0.9999540414251298f, 0.9999544998584377f, 0.9999549559939036f, 0.9999554098315268f, + 0.9999558613713061f, 0.9999563106132405f, 0.9999567575573289f, 0.9999572022035704f, + 0.9999576445519639f, 0.9999580846025083f, 0.9999585223552028f, 0.9999589578100462f, + 0.9999593909670375f, 0.9999598218261758f, 0.9999602503874602f, 0.9999606766508895f, + 0.9999611006164628f, 0.9999615222841792f, 0.9999619416540376f, 0.9999623587260372f, + 0.9999627735001769f, 0.9999631859764558f, 0.9999635961548730f, 0.9999640040354275f, + 0.9999644096181183f, 0.9999648129029446f, 0.9999652138899054f, 0.9999656125789999f, + 0.9999660089702269f, 0.9999664030635858f, 0.9999667948590754f, 0.9999671843566951f, + 0.9999675715564438f, 0.9999679564583206f, 0.9999683390623249f, 0.9999687193684554f, + 0.9999690973767116f, 0.9999694730870924f, 0.9999698464995970f, 0.9999702176142244f, + 0.9999705864309741f, 0.9999709529498449f, 0.9999713171708363f, 0.9999716790939471f, + 0.9999720387191767f, 0.9999723960465242f, 0.9999727510759888f, 0.9999731038075697f, + 0.9999734542412659f, 0.9999738023770769f, 0.9999741482150017f, 0.9999744917550397f, + 0.9999748329971898f, 0.9999751719414515f, 0.9999755085878238f, 0.9999758429363061f, + 0.9999761749868976f, 0.9999765047395974f, 0.9999768321944049f, 0.9999771573513193f, + 0.9999774802103399f, 0.9999778007714659f, 0.9999781190346965f, 0.9999784350000310f, + 0.9999787486674688f, 0.9999790600370091f, 0.9999793691086512f, 0.9999796758823942f, + 0.9999799803582377f, 0.9999802825361808f, 0.9999805824162229f, 0.9999808799983632f, + 0.9999811752826011f, 0.9999814682689360f, 0.9999817589573671f, 0.9999820473478938f, + 0.9999823334405153f, 0.9999826172352312f, 0.9999828987320406f, 0.9999831779309430f, + 0.9999834548319377f, 0.9999837294350241f, 0.9999840017402015f, 0.9999842717474693f, + 0.9999845394568270f, 0.9999848048682738f, 0.9999850679818092f, 0.9999853287974325f, + 0.9999855873151432f, 0.9999858435349407f, 0.9999860974568244f, 0.9999863490807938f, + 0.9999865984068480f, 0.9999868454349867f, 0.9999870901652094f, 0.9999873325975154f, + 0.9999875727319041f, 0.9999878105683750f, 0.9999880461069277f, 0.9999882793475614f, + 0.9999885102902757f, 0.9999887389350701f, 0.9999889652819440f, 0.9999891893308970f, + 0.9999894110819284f, 0.9999896305350378f, 0.9999898476902247f, 0.9999900625474886f, + 0.9999902751068289f, 0.9999904853682453f, 0.9999906933317372f, 0.9999908989973041f, + 0.9999911023649456f, 0.9999913034346612f, 0.9999915022064505f, 0.9999916986803129f, + 0.9999918928562480f, 0.9999920847342555f, 0.9999922743143348f, 0.9999924615964855f, + 0.9999926465807072f, 0.9999928292669994f, 0.9999930096553618f, 0.9999931877457938f, + 0.9999933635382952f, 0.9999935370328654f, 0.9999937082295043f, 0.9999938771282112f, + 0.9999940437289858f, 0.9999942080318278f, 0.9999943700367367f, 0.9999945297437123f, + 0.9999946871527541f, 0.9999948422638617f, 0.9999949950770348f, 0.9999951455922731f, + 0.9999952938095762f, 0.9999954397289438f, 0.9999955833503754f, 0.9999957246738710f, + 0.9999958636994299f, 0.9999960004270521f, 0.9999961348567371f, 0.9999962669884847f, + 0.9999963968222944f, 0.9999965243581661f, 0.9999966495960994f, 0.9999967725360941f, + 0.9999968931781499f, 0.9999970115222664f, 0.9999971275684435f, 0.9999972413166809f, + 0.9999973527669782f, 0.9999974619193353f, 0.9999975687737518f, 0.9999976733302276f, + 0.9999977755887623f, 0.9999978755493559f, 0.9999979732120081f, 0.9999980685767185f, + 0.9999981616434870f, 0.9999982524123134f, 0.9999983408831975f, 0.9999984270561389f, + 0.9999985109311378f, 0.9999985925081937f, 0.9999986717873064f, 0.9999987487684759f, + 0.9999988234517019f, 0.9999988958369843f, 0.9999989659243228f, 0.9999990337137175f, + 0.9999990992051678f, 0.9999991623986740f, 0.9999992232942359f, 0.9999992818918531f, + 0.9999993381915255f, 0.9999993921932533f, 0.9999994438970360f, 0.9999994933028736f, + 0.9999995404107661f, 0.9999995852207133f, 0.9999996277327151f, 0.9999996679467715f, + 0.9999997058628822f, 0.9999997414810473f, 0.9999997748012666f, 0.9999998058235401f, + 0.9999998345478677f, 0.9999998609742493f, 0.9999998851026849f, 0.9999999069331744f, + 0.9999999264657179f, 0.9999999437003151f, 0.9999999586369661f, 0.9999999712756709f, + 0.9999999816164293f, 0.9999999896592414f, 0.9999999954041073f, 0.9999999988510269f, + 1.0000000000000000f}; + +} // namespace autoware_utils diff --git a/autoware_utils/src/math/trigonometry.cpp b/autoware_utils/src/math/trigonometry.cpp new file mode 100644 index 0000000..f7e5a9f --- /dev/null +++ b/autoware_utils/src/math/trigonometry.cpp @@ -0,0 +1,125 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/math/trigonometry.hpp" + +#include "autoware_utils/math/constants.hpp" +#include "autoware_utils/math/sin_table.hpp" + +#include +#include + +namespace autoware_utils +{ + +float sin(float radian) +{ + float degree = + radian * (180.f / static_cast(autoware_utils::pi)) * (discrete_arcs_num_360 / 360.f); + size_t idx = + (static_cast(std::round(degree)) % discrete_arcs_num_360 + discrete_arcs_num_360) % + discrete_arcs_num_360; + + float mul = 1.f; + if (discrete_arcs_num_90 <= idx && idx < 2 * discrete_arcs_num_90) { + idx = 2 * discrete_arcs_num_90 - idx; + } else if (2 * discrete_arcs_num_90 <= idx && idx < 3 * discrete_arcs_num_90) { + mul = -1.f; + idx = idx - 2 * discrete_arcs_num_90; + } else if (3 * discrete_arcs_num_90 <= idx && idx < 4 * discrete_arcs_num_90) { + mul = -1.f; + idx = 4 * discrete_arcs_num_90 - idx; + } + + return mul * g_sin_table[idx]; +} + +float cos(float radian) +{ + return sin(radian + static_cast(autoware_utils::pi) / 2.f); +} + +std::pair sin_and_cos(float radian) +{ + constexpr float tmp = + (180.f / static_cast(autoware_utils::pi)) * (discrete_arcs_num_360 / 360.f); + const float degree = radian * tmp; + size_t idx = + (static_cast(std::round(degree)) % discrete_arcs_num_360 + discrete_arcs_num_360) % + discrete_arcs_num_360; + + if (idx < discrete_arcs_num_90) { + return {g_sin_table[idx], g_sin_table[discrete_arcs_num_90 - idx]}; + } else if (discrete_arcs_num_90 <= idx && idx < 2 * discrete_arcs_num_90) { + idx = 2 * discrete_arcs_num_90 - idx; + return {g_sin_table[idx], -g_sin_table[discrete_arcs_num_90 - idx]}; + } else if (2 * discrete_arcs_num_90 <= idx && idx < 3 * discrete_arcs_num_90) { + idx = idx - 2 * discrete_arcs_num_90; + return {-g_sin_table[idx], -g_sin_table[discrete_arcs_num_90 - idx]}; + } else { // 3 * discrete_arcs_num_90 <= idx && idx < 4 * discrete_arcs_num_90 + idx = 4 * discrete_arcs_num_90 - idx; + return {-g_sin_table[idx], g_sin_table[discrete_arcs_num_90 - idx]}; + } +} + +// This code is modified from a part of the OpenCV project +// (https://github.com/opencv/opencv/blob/4.x/modules/core/src/mathfuncs_core.simd.hpp). It is +// subject to the license terms in the LICENSE file found in the top-level directory of this +// distribution and at http://opencv.org/license.html. +// The license can be found in +// autoware_utils/third_party_licenses/opencv-license.md +// and https://github.com/opencv/opencv/blob/master/LICENSE + +// Modification: +// 1. use autoware defined PI +// 2. output of the function is changed from degrees to radians. +namespace detail_fast_atan2 +{ +static const float atan2_p1 = 0.9997878412794807f * static_cast(180) / autoware_utils::pi; +static const float atan2_p3 = -0.3258083974640975f * static_cast(180) / autoware_utils::pi; +static const float atan2_p5 = 0.1555786518463281f * static_cast(180) / autoware_utils::pi; +static const float atan2_p7 = -0.04432655554792128f * static_cast(180) / autoware_utils::pi; +static const float atan2_DBL_EPSILON = 2.2204460492503131e-016f; +} // namespace detail_fast_atan2 + +float opencv_fast_atan2(float dy, float dx) +{ + float ax = std::abs(dx); + float ay = std::abs(dy); + float a, c, c2; + if (ax >= ay) { + c = ay / (ax + detail_fast_atan2::atan2_DBL_EPSILON); + c2 = c * c; + a = (((detail_fast_atan2::atan2_p7 * c2 + detail_fast_atan2::atan2_p5) * c2 + + detail_fast_atan2::atan2_p3) * + c2 + + detail_fast_atan2::atan2_p1) * + c; + } else { + c = ax / (ay + detail_fast_atan2::atan2_DBL_EPSILON); + c2 = c * c; + a = 90.f - (((detail_fast_atan2::atan2_p7 * c2 + detail_fast_atan2::atan2_p5) * c2 + + detail_fast_atan2::atan2_p3) * + c2 + + detail_fast_atan2::atan2_p1) * + c; + } + if (dx < 0) a = 180.f - a; + if (dy < 0) a = 360.f - a; + + a = a * autoware_utils::pi / 180.f; + return a; +} + +} // namespace autoware_utils diff --git a/autoware_utils/src/ros/diagnostics_interface.cpp b/autoware_utils/src/ros/diagnostics_interface.cpp new file mode 100644 index 0000000..060482f --- /dev/null +++ b/autoware_utils/src/ros/diagnostics_interface.cpp @@ -0,0 +1,106 @@ +// Copyright 2023 Autoware Foundation +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/ros/diagnostics_interface.hpp" + +#include + +#include + +#include +#include + +namespace autoware_utils +{ +DiagnosticsInterface::DiagnosticsInterface(rclcpp::Node * node, const std::string & diagnostic_name) +: clock_(node->get_clock()) +{ + diagnostics_pub_ = + node->create_publisher("/diagnostics", 10); + + diagnostics_status_msg_.name = + std::string(node->get_name()) + std::string(": ") + diagnostic_name; + diagnostics_status_msg_.hardware_id = node->get_name(); +} + +void DiagnosticsInterface::clear() +{ + diagnostics_status_msg_.values.clear(); + diagnostics_status_msg_.values.shrink_to_fit(); + + diagnostics_status_msg_.level = diagnostic_msgs::msg::DiagnosticStatus::OK; + diagnostics_status_msg_.message = ""; +} + +void DiagnosticsInterface::add_key_value(const diagnostic_msgs::msg::KeyValue & key_value_msg) +{ + auto it = std::find_if( + std::begin(diagnostics_status_msg_.values), std::end(diagnostics_status_msg_.values), + [key_value_msg](const auto & arg) { return arg.key == key_value_msg.key; }); + + if (it != std::cend(diagnostics_status_msg_.values)) { + it->value = key_value_msg.value; + } else { + diagnostics_status_msg_.values.push_back(key_value_msg); + } +} + +void DiagnosticsInterface::add_key_value(const std::string & key, const std::string & value) +{ + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = key; + key_value.value = value; + add_key_value(key_value); +} + +void DiagnosticsInterface::add_key_value(const std::string & key, bool value) +{ + diagnostic_msgs::msg::KeyValue key_value; + key_value.key = key; + key_value.value = value ? "True" : "False"; + add_key_value(key_value); +} + +void DiagnosticsInterface::update_level_and_message(const int8_t level, const std::string & message) +{ + if ((level > diagnostic_msgs::msg::DiagnosticStatus::OK)) { + if (!diagnostics_status_msg_.message.empty()) { + diagnostics_status_msg_.message += "; "; + } + diagnostics_status_msg_.message += message; + } + if (level > diagnostics_status_msg_.level) { + diagnostics_status_msg_.level = level; + } +} + +void DiagnosticsInterface::publish(const rclcpp::Time & publish_time_stamp) +{ + diagnostics_pub_->publish(create_diagnostics_array(publish_time_stamp)); +} + +diagnostic_msgs::msg::DiagnosticArray DiagnosticsInterface::create_diagnostics_array( + const rclcpp::Time & publish_time_stamp) const +{ + diagnostic_msgs::msg::DiagnosticArray diagnostics_msg; + diagnostics_msg.header.stamp = publish_time_stamp; + diagnostics_msg.status.push_back(diagnostics_status_msg_); + + if (diagnostics_msg.status.at(0).level == diagnostic_msgs::msg::DiagnosticStatus::OK) { + diagnostics_msg.status.at(0).message = "OK"; + } + + return diagnostics_msg; +} +} // namespace autoware_utils diff --git a/autoware_utils/src/ros/logger_level_configure.cpp b/autoware_utils/src/ros/logger_level_configure.cpp new file mode 100644 index 0000000..c1ad9d2 --- /dev/null +++ b/autoware_utils/src/ros/logger_level_configure.cpp @@ -0,0 +1,61 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/ros/logger_level_configure.hpp" + +#include + +namespace autoware_utils +{ +LoggerLevelConfigure::LoggerLevelConfigure(rclcpp::Node * node) : ros_logger_(node->get_logger()) +{ + using std::placeholders::_1; + using std::placeholders::_2; + + srv_config_logger_ = node->create_service( + "~/config_logger", std::bind(&LoggerLevelConfigure::on_logger_config_service, this, _1, _2)); +} + +void LoggerLevelConfigure::on_logger_config_service( + const ConfigLogger::Request::SharedPtr request, const ConfigLogger::Response::SharedPtr response) +{ + int logging_severity; + const auto ret_level = rcutils_logging_severity_level_from_string( + request->level.c_str(), rcl_get_default_allocator(), &logging_severity); + + if (ret_level != RCUTILS_RET_OK) { + response->success = false; + RCLCPP_WARN_STREAM( + ros_logger_, "Failed to change logger level for " + << request->logger_name + << " due to an invalid logging severity: " << request->level); + return; + } + + const auto ret_set = + rcutils_logging_set_logger_level(request->logger_name.c_str(), logging_severity); + + if (ret_set != RCUTILS_RET_OK) { + response->success = false; + RCLCPP_WARN_STREAM(ros_logger_, "Failed to set logger level for " << request->logger_name); + return; + } + + response->success = true; + RCLCPP_INFO_STREAM( + ros_logger_, "Logger level [" << request->level << "] is set for " << request->logger_name); + return; +} + +} // namespace autoware_utils diff --git a/autoware_utils/src/ros/marker_helper.cpp b/autoware_utils/src/ros/marker_helper.cpp new file mode 100644 index 0000000..a6c2fa6 --- /dev/null +++ b/autoware_utils/src/ros/marker_helper.cpp @@ -0,0 +1,72 @@ +// Copyright 2023 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/ros/marker_helper.hpp" + +#include + +namespace autoware_utils +{ +visualization_msgs::msg::Marker create_default_marker( + const std::string & frame_id, const rclcpp::Time & now, const std::string & ns, const int32_t id, + const int32_t type, const geometry_msgs::msg::Vector3 & scale, + const std_msgs::msg::ColorRGBA & color) +{ + visualization_msgs::msg::Marker marker; + + marker.header.frame_id = frame_id; + marker.header.stamp = now; + marker.ns = ns; + marker.id = id; + marker.type = type; + marker.action = visualization_msgs::msg::Marker::ADD; + marker.lifetime = rclcpp::Duration::from_seconds(0.5); + + marker.pose.position = create_marker_position(0.0, 0.0, 0.0); + marker.pose.orientation = create_marker_orientation(0.0, 0.0, 0.0, 1.0); + marker.scale = scale; + marker.color = color; + marker.frame_locked = true; + + return marker; +} + +visualization_msgs::msg::Marker create_deleted_default_marker( + const rclcpp::Time & now, const std::string & ns, const int32_t id) +{ + visualization_msgs::msg::Marker marker; + + marker.header.stamp = now; + marker.ns = ns; + marker.id = id; + marker.action = visualization_msgs::msg::Marker::DELETE; + + return marker; +} + +void append_marker_array( + const visualization_msgs::msg::MarkerArray & additional_marker_array, + visualization_msgs::msg::MarkerArray * marker_array, + const std::optional & current_time) +{ + for (const auto & marker : additional_marker_array.markers) { + marker_array->markers.push_back(marker); + + if (current_time) { + marker_array->markers.back().header.stamp = current_time.value(); + } + } +} + +} // namespace autoware_utils diff --git a/autoware_utils/src/ros/msg_operation.cpp b/autoware_utils/src/ros/msg_operation.cpp new file mode 100644 index 0000000..73aa6bf --- /dev/null +++ b/autoware_utils/src/ros/msg_operation.cpp @@ -0,0 +1,55 @@ +// Copyright 2022 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/ros/msg_operation.hpp" + +#include + +#ifdef ROS_DISTRO_GALACTIC +#include +#else +#include +#endif + +// NOTE: Do not use autoware_utils namespace +namespace geometry_msgs +{ +namespace msg +{ +Quaternion operator+(Quaternion a, Quaternion b) noexcept +{ + tf2::Quaternion quat_a; + tf2::Quaternion quat_b; + tf2::fromMsg(a, quat_a); + tf2::fromMsg(b, quat_b); + return tf2::toMsg(quat_a + quat_b); +} + +Quaternion operator-(Quaternion a) noexcept +{ + tf2::Quaternion quat_a; + tf2::fromMsg(a, quat_a); + return tf2::toMsg(quat_a * -1.0); +} + +Quaternion operator-(Quaternion a, Quaternion b) noexcept +{ + tf2::Quaternion quat_a; + tf2::Quaternion quat_b; + tf2::fromMsg(a, quat_a); + tf2::fromMsg(b, quat_b); + return tf2::toMsg(quat_a * quat_b.inverse()); +} +} // namespace msg +} // namespace geometry_msgs diff --git a/autoware_utils/src/system/backtrace.cpp b/autoware_utils/src/system/backtrace.cpp new file mode 100644 index 0000000..3657af1 --- /dev/null +++ b/autoware_utils/src/system/backtrace.cpp @@ -0,0 +1,53 @@ +// Copyright 2023 Tier IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/system/backtrace.hpp" + +#include "rclcpp/rclcpp.hpp" + +#include + +#include +#include +#include +#include + +namespace autoware_utils +{ + +// cppcheck-suppress unusedFunction +void print_backtrace() +{ + constexpr size_t max_frames = 100; + void * addrlist[max_frames + 1]; + + int addrlen = backtrace(addrlist, sizeof(addrlist) / sizeof(void *)); + + if (addrlen == 0) { + return; + } + + char ** symbol_list = backtrace_symbols(addrlist, addrlen); + + std::stringstream ss; + ss << "\n @ ********** back trace **********" << std::endl; + for (int i = 1; i < addrlen; i++) { + ss << " @ " << symbol_list[i] << std::endl; + } + RCLCPP_DEBUG_STREAM(rclcpp::get_logger("autoware_utils"), ss.str()); + + free(symbol_list); +} + +} // namespace autoware_utils diff --git a/autoware_utils/src/system/time_keeper.cpp b/autoware_utils/src/system/time_keeper.cpp new file mode 100644 index 0000000..78d5e0e --- /dev/null +++ b/autoware_utils/src/system/time_keeper.cpp @@ -0,0 +1,205 @@ +// Copyright 2024 TIER IV, Inc. +// +// Licensed under the Apache License, Version 2.0 (the "License"); +// you may not use this file except in compliance with the License. +// You may obtain a copy of the License at +// +// http://www.apache.org/licenses/LICENSE-2.0 +// +// Unless required by applicable law or agreed to in writing, software +// distributed under the License is distributed on an "AS IS" BASIS, +// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. +// See the License for the specific language governing permissions and +// limitations under the License. + +#include "autoware_utils/system/time_keeper.hpp" + +#include +#include + +#include + +#include +#include +#include +#include + +namespace autoware_utils +{ + +ProcessingTimeNode::ProcessingTimeNode(const std::string & name) : name_(name) +{ +} + +std::shared_ptr ProcessingTimeNode::add_child(const std::string & name) +{ + auto new_child_node = std::make_shared(name); + new_child_node->parent_node_ = weak_from_this(); + child_nodes_.push_back(new_child_node); + return new_child_node; +} + +std::string ProcessingTimeNode::to_string() const +{ + std::function + construct_string = [&]( + const ProcessingTimeNode & node, std::ostringstream & oss, + const std::string & prefix, bool is_last, bool is_root) { + if (!is_root) { + oss << prefix << (is_last ? "└── " : "├── "); + } + if (!node.comment_.empty()) { + oss << node.name_ << " (" << node.processing_time_ << "ms) : " << node.comment_ << "\n"; + } else { + oss << node.name_ << " (" << node.processing_time_ << "ms)\n"; + } + for (size_t i = 0; i < node.child_nodes_.size(); ++i) { + const auto & child = node.child_nodes_[i]; + construct_string( + *child, oss, prefix + (is_last ? " " : "│ "), i == node.child_nodes_.size() - 1, + false); + } + }; + + std::ostringstream oss; + construct_string(*this, oss, "", true, true); + return oss.str(); +} + +autoware_internal_debug_msgs::msg::ProcessingTimeTree ProcessingTimeNode::to_msg() const +{ + autoware_internal_debug_msgs::msg::ProcessingTimeTree time_tree_msg; + + std::function + construct_msg = [&]( + const ProcessingTimeNode & node, + autoware_internal_debug_msgs::msg::ProcessingTimeTree & tree_msg, + int parent_id) { + autoware_internal_debug_msgs::msg::ProcessingTimeNode time_node_msg; + time_node_msg.name = node.name_; + time_node_msg.processing_time = node.processing_time_; + time_node_msg.id = static_cast(tree_msg.nodes.size() + 1); + time_node_msg.parent_id = parent_id; + time_node_msg.comment = node.comment_; + tree_msg.nodes.emplace_back(time_node_msg); + + for (const auto & child : node.child_nodes_) { + construct_msg(*child, tree_msg, time_node_msg.id); + } + }; + construct_msg(*this, time_tree_msg, 0); + + return time_tree_msg; +} + +std::weak_ptr ProcessingTimeNode::get_parent_node() const +{ + return parent_node_; +} +std::vector> ProcessingTimeNode::get_child_nodes() const +{ + return child_nodes_; +} +void ProcessingTimeNode::set_time(const double processing_time) +{ + processing_time_ = processing_time; +} + +void ProcessingTimeNode::set_comment(const std::string & comment) +{ + comment_ = comment; +} + +std::string ProcessingTimeNode::get_name() const +{ + return name_; +} + +void TimeKeeper::add_reporter(std::ostream * os) +{ + reporters_.emplace_back([os](const std::shared_ptr & node) { + *os << "==========================" << std::endl; + *os << node->to_string() << std::endl; + }); +} + +void TimeKeeper::add_reporter(rclcpp::Publisher::SharedPtr publisher) +{ + reporters_.emplace_back([publisher](const std::shared_ptr & node) { + publisher->publish(node->to_msg()); + }); +} + +void TimeKeeper::start_track(const std::string & func_name) +{ + if (current_time_node_ == nullptr) { + current_time_node_ = std::make_shared(func_name); + root_node_ = current_time_node_; + root_node_thread_id_ = std::this_thread::get_id(); + } else { + if (root_node_thread_id_ != std::this_thread::get_id()) { + const auto warning_msg = fmt::format( + "TimeKeeper::start_track({}) is called from a different thread. Ignoring the call.", + func_name); + RCLCPP_WARN(rclcpp::get_logger("TimeKeeper"), "%s", warning_msg.c_str()); + return; + } + current_time_node_ = current_time_node_->add_child(func_name); + } + stop_watch_.tic(func_name); +} + +void TimeKeeper::comment(const std::string & comment) +{ + if (current_time_node_ == nullptr) { + throw std::runtime_error("You must call start_track() first, but comment() is called"); + } + current_time_node_->set_comment(comment); +} + +void TimeKeeper::end_track(const std::string & func_name) +{ + if (root_node_thread_id_ != std::this_thread::get_id()) { + return; + } + if (current_time_node_->get_name() != func_name) { + throw std::runtime_error(fmt::format( + "You must call end_track({}) first, but end_track({}) is called", + current_time_node_->get_name(), func_name)); + } + const double processing_time = stop_watch_.toc(func_name); + current_time_node_->set_time(processing_time); + current_time_node_ = current_time_node_->get_parent_node().lock(); + + if (current_time_node_ == nullptr) { + report(); + } +} + +void TimeKeeper::report() +{ + if (current_time_node_ != nullptr) { + throw std::runtime_error(fmt::format( + "You must call end_track({}) first, but report() is called", current_time_node_->get_name())); + } + for (const auto & reporter : reporters_) { + reporter(root_node_); + } + current_time_node_.reset(); + root_node_.reset(); +} + +ScopedTimeTrack::ScopedTimeTrack(const std::string & func_name, TimeKeeper & time_keeper) +: func_name_(func_name), time_keeper_(time_keeper) +{ + time_keeper_.start_track(func_name_); +} + +ScopedTimeTrack::~ScopedTimeTrack() // NOLINT +{ + time_keeper_.end_track(func_name_); +} + +} // namespace autoware_utils diff --git a/build_depends.repos b/build_depends.repos new file mode 100644 index 0000000..6bab4a0 --- /dev/null +++ b/build_depends.repos @@ -0,0 +1,9 @@ +repositories: + autoware_msgs: + type: git + url: https://github.com/autowarefoundation/autoware_msgs.git + version: main + autoware_internal_msgs: + type: git + url: https://github.com/autowarefoundation/autoware_internal_msgs.git + version: main